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()
+ #self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, 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):
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)
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")
+ #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()
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] = 1e-3 # z
+ odom.pose.covariance[21] = 0.1 # rotation about X axis
+ odom.pose.covariance[28] = 0.1 # 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] = 1e-3 # z
+ odom.twist.covariance[21] = 0.1 # rotation about X axis
+ odom.twist.covariance[28] = 0.1 # rotation about Y axis
+ odom.twist.covariance[35] = 0.1 # rotation about Z axis
# publish the message
self.pub_odom.publish(odom)