X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fmove_base.py;h=ae15b380ddd1cb3afc1ae05ad1f162b22fb9377a;hp=5ece2683f6d0ad31cee0dd0cebfd9efdb95b26e2;hb=0640fece763d17314bb1a9878c64309476fa1d4a;hpb=b831b0bddbe43dc6e33251381b2a23016cff58fb diff --git a/scripts/move_base.py b/scripts/move_base.py index 5ece268..ae15b38 100755 --- a/scripts/move_base.py +++ b/scripts/move_base.py @@ -2,10 +2,12 @@ # -*- coding: iso-8859-15 -*- import rospy +import tf import struct from i2c import * from math import * from geometry_msgs.msg import Twist +from nav_msgs.msg import Odometry WHEEL_DIST = 0.248 @@ -13,6 +15,8 @@ class MoveBase: def __init__(self): rospy.init_node('wild_thumper_move_base') rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived) + self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() + self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16) self.set_speed(0, 0) rospy.loginfo("Init done") i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction @@ -21,38 +25,55 @@ class MoveBase: def run(self): rate = rospy.Rate(20.0) while not rospy.is_shutdown(): - self.get_pos() + #self.get_odom() #self.get_dist_forward() #self.get_dist_backward() #self.get_dist_left() #self.get_dist_right() rate.sleep() - def get_pos(self): - s = i2c_read_reg(0x50, 0x10, 8) - hall1, hall2, hall3, hall4 = struct.unpack(">hhhh", s) - print hall1, hall2, hall3, hall4 + def get_odom(self): + posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12)) + speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8)) + current_time = rospy.Time.now() - def set_speed(self, left, right): - if left > 0: left+=80 - elif left < 0: left-=80 - if right > 0: right+=80 - elif right < 0: right-=80 + # since all odometry is 6DOF we'll need a quaternion created from yaw + odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle) - if left > 255: left=255 - elif left < -255: left=-255 - if right > 255: right=255 - elif right < -255: right=-255 + # first, we'll publish the transform over tf + self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_link", "odom") - i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", right, right, left, left)) + # next, we'll publish the odometry message over ROS + odom = Odometry() + odom.header.stamp = current_time + odom.header.frame_id = "/odom" + + # set the position + odom.pose.pose.position.x = posx + odom.pose.pose.position.y = posy + odom.pose.pose.position.z = 0.0 + odom.pose.pose.orientation.x = odom_quat[0] + odom.pose.pose.orientation.y = odom_quat[1] + odom.pose.pose.orientation.z = odom_quat[2] + odom.pose.pose.orientation.w = odom_quat[3] + + # set the velocity + odom.child_frame_id = "base_link" + odom.twist.twist.linear.x = speed_trans + odom.twist.twist.linear.y = 0.0 + odom.twist.twist.angular.z = speed_rot + + # publish the message + self.pub_odom.publish(odom) + + + def set_speed(self, trans, rot): + i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot)) def cmdVelReceived(self, msg): trans = msg.linear.x rot = msg.angular.z # rad/s - - right = rot*pi*WHEEL_DIST + trans - left = trans*2-right - self.set_speed(left, right) + self.set_speed(trans, rot) # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12 def get_dist_ir(self, num):