2 import roslib; roslib.load_manifest('roboint')
6 import tf.transformations
7 from math import sin, cos, pi
8 from geometry_msgs.msg import Twist, TransformStamped, Point32
9 from sensor_msgs.msg import LaserScan
10 from nav_msgs.msg import Odometry
11 from roboint.msg import Motor
12 from roboint.msg import Inputs
17 rospy.init_node('robo_explorer')
23 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
24 self.last_time = rospy.Time.now()
29 # fake laser scan with ultra sonic range finder
30 self.enable_ultrasonic_laser = bool(rospy.get_param('~ultrasonic_laser', "True"))
31 # Distance between both wheels in meter (18.55cm)
32 self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.1855"))
33 # Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm
34 self.wheel_size = float(rospy.get_param('~wheel_size', "0.02575"))
35 # Speed to PWM equation gradiant (The m in pwm = speed*m+b)
36 self.speed_gradiant = float(rospy.get_param('~speed_gradiant', "64.3"))
37 # Speed to PWM equation constant (The b in pwm = speed*m+b)
38 self.speed_constant = float(rospy.get_param('~speed_constant', "-1.7"))
40 self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
41 if self.enable_ultrasonic_laser:
42 self.pub_scan = rospy.Publisher("scan", LaserScan)
43 self.pub_odom = rospy.Publisher("odom", Odometry)
45 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
46 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
50 def inputsReceived(self, msg):
51 current_time = rospy.Time.now()
53 self.update_odometry(msg, current_time)
54 if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms
55 self.send_odometry(msg, current_time)
56 if self.enable_ultrasonic_laser:
57 self.send_laser_scan(msg, current_time)
58 self.last_time = current_time
60 def update_odometry(self, msg, current_time):
61 in_now = msg.input[:2]
62 if self.last_in is not None:
63 in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
64 print "update", in_diff, msg.output
65 # fix in_diff from actual motor direction
66 if msg.output[1] > 0: # left reverse
67 in_diff[0] = -in_diff[0]
68 elif msg.output[0] == 0 and msg.output[1] == 0: # left stop
70 if msg.output[3] > 0: # right reverse
71 in_diff[1] = -in_diff[1]
72 elif msg.output[2] == 0 and msg.output[3] == 0: # right stop
75 dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8 # steps_changed in different direction => m
76 delta_alpha = dist_dir/self.wheel_dist
78 dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
80 delta_x = cos(self.alpha + delta_alpha/2)*dist
81 delta_y = sin(self.alpha + delta_alpha/2)*dist
83 self.alpha += delta_alpha
86 elif self.alpha < -2*pi:
93 def send_odometry(self, msg, current_time):
95 dt = (current_time - self.last_time).to_sec()
96 vx = (self.x - self.x_last) / dt
97 vy = (self.y - self.y_last) / dt
98 valpha = (self.alpha - self.alpha_last) / dt
101 self.alpha_last = self.alpha
103 # since all odometry is 6DOF we'll need a quaternion created from yaw
104 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
106 # first, we'll publish the transform over tf
107 self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
109 # next, we'll publish the odometry message over ROS
111 odom.header.stamp = current_time
112 odom.header.frame_id = "/odom"
115 odom.pose.pose.position.x = self.x
116 odom.pose.pose.position.y = self.y
117 odom.pose.pose.position.z = 0.0
118 odom.pose.pose.orientation.x = odom_quat[0]
119 odom.pose.pose.orientation.y = odom_quat[1]
120 odom.pose.pose.orientation.z = odom_quat[2]
121 odom.pose.pose.orientation.w = odom_quat[3]
124 odom.child_frame_id = "base_link"
125 odom.twist.twist.linear.x = vx
126 odom.twist.twist.linear.y = vy
127 odom.twist.twist.angular.z = valpha
129 # publish the message
130 self.pub_odom.publish(odom)
132 def send_laser_scan(self, msg, current_time):
133 # first, we'll publish the transform over tf
134 self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link")
136 # actually ultra sonic range finder
137 num_points = 60 # The base planner needs at least 30 points to work in the default config
138 opening_angle = 30*pi/180 # each side
140 scan.header.stamp = current_time
141 scan.header.frame_id = "/scan"
142 scan.angle_min = -opening_angle
143 scan.angle_max = opening_angle
144 scan.angle_increment = (2*opening_angle)/num_points
145 scan.time_increment = 0.0
148 for i in range(num_points):
149 scan.ranges.append(msg.d1/100.0)
150 #scan.intensities.append(0.5)
151 #scan.intensities.append(1.0)
152 #scan.intensities.append(0.5)
153 self.pub_scan.publish(scan)
155 # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
156 def cmdVelReceived(self, msg):
158 rot = msg.angular.z # rad/s
160 # handle rotation as offset to speeds
161 speed_offset = (rot * self.wheel_dist)/2.0 # m/s
165 wish_speed_left = trans - speed_offset
166 if abs(wish_speed_left) > 0:
167 speed_l = self.speed_gradiant*abs(wish_speed_left) + self.speed_constant
168 if wish_speed_left < 0:
171 wish_speed_right = trans + speed_offset
172 if abs(wish_speed_right) > 0:
173 speed_r = self.speed_gradiant*abs(wish_speed_right) + self.speed_constant
174 if wish_speed_right < 0:
178 if speed_l < -7: speed_l = -7
179 elif speed_l > 7: speed_l = 7
180 if speed_r < -7: speed_r = -7
181 elif speed_r > 7: speed_r = 7
183 print "Speed wanted: %.2f m/s %.2f rad/s, set: %d %d" % (trans, rot, round(speed_l), round(speed_r))
187 outmsg.speed = round(speed_l)
188 self.pub_motor.publish(outmsg)
192 outmsg.speed = round(speed_r)
193 self.pub_motor.publish(outmsg)
195 if __name__ == '__main__':