2 import roslib; roslib.load_manifest('roboint')
6 from geometry_msgs.msg import Twist, TransformStamped, Point32, PoseWithCovarianceStamped
7 from sensor_msgs.msg import LaserScan
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 # fake laser scan with ultra sonic range finder
28 self.enable_ultrasonic_laser = bool(rospy.get_param('~ultrasonic_laser', "True"))
29 # Distance between both wheels in meter (18.55cm)
30 self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.1855"))
31 # Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm
32 self.wheel_size = float(rospy.get_param('~wheel_size', "0.02575"))
33 # Speed to PWM equation gradiant (The m in pwm = speed*m+b)
34 self.speed_gradiant = float(rospy.get_param('~speed_gradiant', "64.3"))
35 # Speed to PWM equation constant (The b in pwm = speed*m+b)
36 self.speed_constant = float(rospy.get_param('~speed_constant', "-1.7"))
38 self.pub_motor = rospy.Publisher("ft/set_motor", Motor, queue_size=16)
39 if self.enable_ultrasonic_laser:
40 self.pub_scan = rospy.Publisher("scan", LaserScan, queue_size=16)
41 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
43 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
44 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
45 rospy.Subscriber("initialpose", PoseWithCovarianceStamped, self.posReceived)
49 def posReceived(self, msg):
50 self.x = msg.pose.pose.position.x
51 self.y = msg.pose.pose.position.y
52 orientation = msg.pose.pose.orientation
53 angles = tf.transformations.euler_from_quaternion([orientation.x, orientation.y, orientation.z, orientation.w])
54 self.alpha = angles[2]
56 def inputsReceived(self, msg):
57 current_time = rospy.Time.now()
59 self.update_odometry(msg, current_time)
60 if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms
61 self.send_odometry(msg, current_time)
62 if self.enable_ultrasonic_laser:
63 self.send_laser_scan(msg, current_time)
64 self.last_time = current_time
66 def update_odometry(self, msg, current_time):
67 in_now = msg.input[:2]
68 if self.last_in is not None:
69 in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
70 # fix in_diff from actual motor direction
71 if msg.output[1] > 0: # left reverse
72 in_diff[0] = -in_diff[0]
73 elif msg.output[0] == 0 and msg.output[1] == 0: # left stop
75 if msg.output[3] > 0: # right reverse
76 in_diff[1] = -in_diff[1]
77 elif msg.output[2] == 0 and msg.output[3] == 0: # right stop
80 dist_dir = (in_diff[1] - in_diff[0]) * self.wheel_size*pi/8 # steps_changed in different direction => m
81 delta_alpha = dist_dir/self.wheel_dist
83 dist = (in_diff[0] + in_diff[1])/2.0 * self.wheel_size*pi/8 # steps_changed same direction => m
85 delta_x = cos(self.alpha + delta_alpha/2)*dist
86 delta_y = sin(self.alpha + delta_alpha/2)*dist
88 self.alpha += delta_alpha
91 elif self.alpha < -2*pi:
98 def send_odometry(self, msg, current_time):
100 dt = (current_time - self.last_time).to_sec()
101 vx = sqrt((self.x - self.x_last)**2 + (self.y - self.y_last)**2) / dt
102 if (msg.output[0]-msg.output[1] + msg.output[2]-msg.output[3]) < 0:
105 valpha = (self.alpha - self.alpha_last) / dt
108 self.alpha_last = self.alpha
110 # since all odometry is 6DOF we'll need a quaternion created from yaw
111 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
113 # first, we'll publish the transform over tf
114 self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
116 # next, we'll publish the odometry message over ROS
118 odom.header.stamp = current_time
119 odom.header.frame_id = "/odom"
122 odom.pose.pose.position.x = self.x
123 odom.pose.pose.position.y = self.y
124 odom.pose.pose.position.z = 0.0
125 odom.pose.pose.orientation.x = odom_quat[0]
126 odom.pose.pose.orientation.y = odom_quat[1]
127 odom.pose.pose.orientation.z = odom_quat[2]
128 odom.pose.pose.orientation.w = odom_quat[3]
131 odom.child_frame_id = "base_link"
132 odom.twist.twist.linear.x = vx
133 odom.twist.twist.linear.y = 0.0
134 odom.twist.twist.angular.z = valpha
136 # publish the message
137 self.pub_odom.publish(odom)
139 def send_laser_scan(self, msg, current_time):
140 # actually ultra sonic range finder
141 num_points = 60 # The base planner needs at least 30 points to work in the default config
142 opening_angle = 30*pi/180 # each side
144 scan.header.stamp = current_time
145 scan.header.frame_id = "forward_sensor"
146 scan.angle_min = -opening_angle
147 scan.angle_max = opening_angle
148 scan.angle_increment = (2*opening_angle)/num_points
149 scan.time_increment = 0.0
152 for i in range(num_points):
153 scan.ranges.append(msg.d1/100.0)
154 #scan.intensities.append(0.5)
155 #scan.intensities.append(1.0)
156 #scan.intensities.append(0.5)
157 self.pub_scan.publish(scan)
159 # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
160 def cmdVelReceived(self, msg):
162 rot = msg.angular.z # rad/s
164 # handle rotation as offset to speeds
165 speed_offset = (rot * self.wheel_dist)/2.0 # m/s
169 wish_speed_left = trans - speed_offset
170 if abs(wish_speed_left) > 0:
171 speed_l = self.speed_gradiant*abs(wish_speed_left) + self.speed_constant
172 if wish_speed_left < 0:
175 wish_speed_right = trans + speed_offset
176 if abs(wish_speed_right) > 0:
177 speed_r = self.speed_gradiant*abs(wish_speed_right) + self.speed_constant
178 if wish_speed_right < 0:
182 if speed_l < -7: speed_l = -7
183 elif speed_l > 7: speed_l = 7
184 if speed_r < -7: speed_r = -7
185 elif speed_r > 7: speed_r = 7
187 #print "Speed wanted: %.2f m/s %.2f rad/s, set: %d %d" % (trans, rot, round(speed_l), round(speed_r))
191 outmsg.speed = round(speed_l)
192 self.pub_motor.publish(outmsg)
196 outmsg.speed = round(speed_r)
197 self.pub_motor.publish(outmsg)
199 if __name__ == '__main__':