X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fmove_base.py;h=0d68ce93aa9ecbdd0308982c3f6c8ad9561b46fd;hp=6c066f391f9b50a70c24f2a77a8ac335894f263b;hb=67442b2a9cc0d3110380fba786b4e9291db7f615;hpb=1e0954c7b50dcb6211cfee54fda35cbb36cf6b40 diff --git a/scripts/move_base.py b/scripts/move_base.py index 6c066f3..0d68ce9 100755 --- a/scripts/move_base.py +++ b/scripts/move_base.py @@ -9,7 +9,7 @@ from math import * from geometry_msgs.msg import Twist from nav_msgs.msg import Odometry from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue -from sensor_msgs.msg import Imu +from sensor_msgs.msg import Imu, Range WHEEL_DIST = 0.248 @@ -18,12 +18,21 @@ class MoveBase: rospy.init_node('wild_thumper_move_base') rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived) rospy.Subscriber("imu", Imu, self.imuReceived) - self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() + enable_odom_tf = rospy.get_param("~enable_odom_tf", True) + if enable_odom_tf: + self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() + else: + self.tf_broadcaster = None self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16) self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16) + self.pub_range_fwd = rospy.Publisher("range_forward", Range, queue_size=16) + self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16) + self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16) + self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16) self.set_speed(0, 0) rospy.loginfo("Init done") i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction + self.handicap_last = (-1, -1) self.run() def run(self): @@ -35,25 +44,25 @@ class MoveBase: self.get_tle_err() self.get_odom() self.get_voltage() - #self.get_dist_forward() - #self.get_dist_backward() - #self.get_dist_left() - #self.get_dist_right() + self.get_dist_forward() + self.get_dist_backward() + self.get_dist_left() + self.get_dist_right() rate.sleep() def set_motor_handicap(self, front, aft): # percent - i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft)) + if self.handicap_last != (front, aft): + i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft)) + self.handicap_last = (front, aft) def imuReceived(self, msg): (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__()) if pitch > 30*pi/180: - val = (100/90)*abs(pitch)*180/pi - print "aft handicap", val - self.set_motor_handicap(0, val) + val = (100.0/65)*abs(pitch)*180/pi + self.set_motor_handicap(0, int(val)) elif pitch < -30*pi/180: - val = (100/90)*abs(pitch)*180/pi - print "front handicap", val - self.set_motor_handicap(val, 0) + val = (100.0/65)*abs(pitch)*180/pi + self.set_motor_handicap(int(val), 0) else: self.set_motor_handicap(0, 0) @@ -118,7 +127,8 @@ class MoveBase: odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle) # first, we'll publish the transform over tf - self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_link", "odom") + if self.tf_broadcaster is not None: + self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom") # next, we'll publish the odometry message over ROS odom = Odometry() @@ -133,12 +143,24 @@ class MoveBase: odom.pose.pose.orientation.y = odom_quat[1] odom.pose.pose.orientation.z = odom_quat[2] odom.pose.pose.orientation.w = odom_quat[3] + odom.pose.covariance[0] = 1e-3 # x + odom.pose.covariance[7] = 1e-3 # y + odom.pose.covariance[14] = 1e6 # z + odom.pose.covariance[21] = 1e6 # rotation about X axis + odom.pose.covariance[28] = 1e6 # rotation about Y axis + odom.pose.covariance[35] = 0.1 # rotation about Z axis # set the velocity - odom.child_frame_id = "base_link" + odom.child_frame_id = "base_footprint" odom.twist.twist.linear.x = speed_trans odom.twist.twist.linear.y = 0.0 odom.twist.twist.angular.z = speed_rot + odom.twist.covariance[0] = 1e-3 # x + odom.twist.covariance[7] = 1e-3 # y + odom.twist.covariance[14] = 1e6 # z + odom.twist.covariance[21] = 1e6 # rotation about X axis + odom.twist.covariance[28] = 1e6 # rotation about Y axis + odom.twist.covariance[35] = 0.1 # rotation about Z axis # publish the message self.pub_odom.publish(odom) @@ -166,7 +188,7 @@ class MoveBase: dev.close() val = struct.unpack(">H", s)[0] - return 15221/(val - -276.42)/100; + return val def get_dist_srf(self, num): dev = i2c(0x52) @@ -182,18 +204,37 @@ class MoveBase: return struct.unpack(">H", s)[0]/1000.0 + def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg): + msg = Range() + msg.header.stamp = rospy.Time.now() + msg.header.frame_id = frame_id + msg.radiation_type = typ + msg.field_of_view = fov_deg*pi/180 + msg.min_range = min_range + msg.max_range = max_range + msg.range = dist + pub.publish(msg) + def get_dist_left(self): - dist = self.get_dist_ir(0x1) + if self.pub_range_left.get_num_connections() > 0: + dist = 30.553/(self.get_dist_ir(0x1) - -67.534) + self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, dist, 0.04, 0.3, 5) def get_dist_right(self): - dist = self.get_dist_ir(0x3) + if self.pub_range_right.get_num_connections() > 0: + dist = 17.4/(self.get_dist_ir(0x3) - 69) + self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, dist, 0.04, 0.3, 5) def get_dist_forward(self): - dist = self.get_dist_srf(0x5) + if self.pub_range_fwd.get_num_connections() > 0: + dist = self.get_dist_srf(0x5) + self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 60) def get_dist_backward(self): - dist = self.get_dist_srf(0x7) - + if self.pub_range_bwd.get_num_connections() > 0: + dist = self.get_dist_srf(0x7) + self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 60) + if __name__ == "__main__": MoveBase()