2 import roslib; roslib.load_manifest('roboint')
6 from geometry_msgs.msg import Twist, TransformStamped, Point32, PoseWithCovarianceStamped
7 from sensor_msgs.msg import Range
8 from nav_msgs.msg import Odometry
9 from roboint.msg import Motor
10 from roboint.msg import Inputs
15 rospy.init_node('robo_explorer')
21 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
22 self.last_time = rospy.Time.now()
27 # Distance between both wheels in meter (18.55cm)
28 self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.1855"))
29 # Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm
30 self.wheel_size = float(rospy.get_param('~wheel_size', "0.02575"))
31 # Speed to PWM equation gradiant (The m in pwm = speed*m+b)
32 self.speed_gradiant = float(rospy.get_param('~speed_gradiant', "64.3"))
33 # Speed to PWM equation constant (The b in pwm = speed*m+b)
34 self.speed_constant = float(rospy.get_param('~speed_constant', "-1.7"))
36 self.pub_motor = rospy.Publisher("ft/set_motor", Motor, queue_size=16)
37 self.pub_sonar = rospy.Publisher("sonar", Range, queue_size=16)
38 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
40 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
41 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
42 rospy.Subscriber("initialpose", PoseWithCovarianceStamped, self.posReceived)
46 def posReceived(self, msg):
47 self.x = msg.pose.pose.position.x
48 self.y = msg.pose.pose.position.y
49 orientation = msg.pose.pose.orientation
50 angles = tf.transformations.euler_from_quaternion([orientation.x, orientation.y, orientation.z, orientation.w])
51 self.alpha = angles[2]
53 def inputsReceived(self, msg):
54 current_time = rospy.Time.now()
56 self.update_odometry(msg, current_time)
57 if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms
58 self.send_odometry(msg, current_time)
59 self.send_range(msg, current_time)
60 self.last_time = current_time
62 def update_odometry(self, msg, current_time):
63 in_now = msg.input[:2]
64 if self.last_in is not None:
65 in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
66 # fix in_diff from actual motor direction
67 if msg.output[1] > 0: # left reverse
68 in_diff[0] = -in_diff[0]
69 elif msg.output[0] == 0 and msg.output[1] == 0: # left stop
71 if msg.output[3] > 0: # right reverse
72 in_diff[1] = -in_diff[1]
73 elif msg.output[2] == 0 and msg.output[3] == 0: # right stop
76 dist_dir = (in_diff[1] - in_diff[0]) * self.wheel_size*pi/8 # steps_changed in different direction => m
77 delta_alpha = dist_dir/self.wheel_dist
79 dist = (in_diff[0] + in_diff[1])/2.0 * self.wheel_size*pi/8 # steps_changed same direction => m
81 delta_x = cos(self.alpha + delta_alpha/2)*dist
82 delta_y = sin(self.alpha + delta_alpha/2)*dist
84 self.alpha += delta_alpha
87 elif self.alpha < -2*pi:
94 def send_odometry(self, msg, current_time):
96 dt = (current_time - self.last_time).to_sec()
97 vx = sqrt((self.x - self.x_last)**2 + (self.y - self.y_last)**2) / dt
98 if (msg.output[0]-msg.output[1] + msg.output[2]-msg.output[3]) < 0:
101 valpha = (self.alpha - self.alpha_last) / dt
104 self.alpha_last = self.alpha
106 # since all odometry is 6DOF we'll need a quaternion created from yaw
107 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
109 # first, we'll publish the transform over tf
110 self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
112 # next, we'll publish the odometry message over ROS
114 odom.header.stamp = current_time
115 odom.header.frame_id = "/odom"
118 odom.pose.pose.position.x = self.x
119 odom.pose.pose.position.y = self.y
120 odom.pose.pose.position.z = 0.0
121 odom.pose.pose.orientation.x = odom_quat[0]
122 odom.pose.pose.orientation.y = odom_quat[1]
123 odom.pose.pose.orientation.z = odom_quat[2]
124 odom.pose.pose.orientation.w = odom_quat[3]
127 odom.child_frame_id = "base_link"
128 odom.twist.twist.linear.x = vx
129 odom.twist.twist.linear.y = 0.0
130 odom.twist.twist.angular.z = valpha
132 # publish the message
133 self.pub_odom.publish(odom)
135 def send_range(self, msg, current_time):
136 # ultra sonic range finder
138 scan.header.stamp = current_time
139 scan.header.frame_id = "forward_sensor"
140 scan.radiation_type = 0
141 scan.field_of_view = 60*pi/180
144 scan.range = msg.d1/100.0
145 self.pub_sonar.publish(scan)
147 # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
148 def cmdVelReceived(self, msg):
150 rot = msg.angular.z # rad/s
152 # handle rotation as offset to speeds
153 speed_offset = (rot * self.wheel_dist)/2.0 # m/s
157 wish_speed_left = trans - speed_offset
158 if abs(wish_speed_left) > 0:
159 speed_l = self.speed_gradiant*abs(wish_speed_left) + self.speed_constant
160 if wish_speed_left < 0:
163 wish_speed_right = trans + speed_offset
164 if abs(wish_speed_right) > 0:
165 speed_r = self.speed_gradiant*abs(wish_speed_right) + self.speed_constant
166 if wish_speed_right < 0:
170 if speed_l < -7: speed_l = -7
171 elif speed_l > 7: speed_l = 7
172 if speed_r < -7: speed_r = -7
173 elif speed_r > 7: speed_r = 7
175 #print "Speed wanted: %.2f m/s %.2f rad/s, set: %d %d" % (trans, rot, round(speed_l), round(speed_r))
179 outmsg.speed = round(speed_l)
180 self.pub_motor.publish(outmsg)
184 outmsg.speed = round(speed_r)
185 self.pub_motor.publish(outmsg)
187 if __name__ == '__main__':