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')
24 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
25 self.last_time = rospy.Time.now()
30 self.enable_ultrasonic_laser = int(rospy.get_param('~ultrasonic_laser', "1"))
31 self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.188"))
32 self.wheel_size = float(rospy.get_param('~wheel_size', "0.0255"))
34 self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
35 self.pub_scan = rospy.Publisher("scan", LaserScan)
36 self.pub_odom = rospy.Publisher("odom", Odometry)
38 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
39 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
43 def inputsReceived(self, msg):
44 current_time = rospy.Time.now()
46 self.update_odometry(msg, current_time)
47 if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms
48 self.send_odometry(msg, current_time)
49 if self.enable_ultrasonic_laser:
50 self.send_laser_scan(msg, current_time)
51 self.last_time = current_time
53 def update_odometry(self, msg, current_time):
54 in_now = msg.input[:2]
55 if self.last_in is not None:
56 in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
57 # fix in_diff from actual motor direction
59 in_diff[0] = -in_diff[0]
60 elif self.speed[0] == 0:
63 in_diff[1] = -in_diff[1]
64 elif self.speed[1] == 0:
67 dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8 # steps_changed in different direction => m
68 delta_alpha = dist_dir/self.wheel_dist
70 dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
72 delta_x = cos(self.alpha + delta_alpha/2)*dist
73 delta_y = sin(self.alpha + delta_alpha/2)*dist
75 self.alpha += delta_alpha
78 elif self.alpha < -2*pi:
85 def send_odometry(self, msg, current_time):
87 dt = (current_time - self.last_time).to_sec()
88 vx = (self.x - self.x_last) / dt
89 vy = (self.y - self.y_last) / dt
90 valpha = (self.alpha - self.alpha_last) / dt
93 self.alpha_last = self.alpha
95 # since all odometry is 6DOF we'll need a quaternion created from yaw
96 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
98 # first, we'll publish the transform over tf
99 self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
101 # next, we'll publish the odometry message over ROS
103 odom.header.stamp = current_time
104 odom.header.frame_id = "/odom"
107 odom.pose.pose.position.x = self.x
108 odom.pose.pose.position.y = self.y
109 odom.pose.pose.position.z = 0.0
110 odom.pose.pose.orientation.x = odom_quat[0]
111 odom.pose.pose.orientation.y = odom_quat[1]
112 odom.pose.pose.orientation.z = odom_quat[2]
113 odom.pose.pose.orientation.w = odom_quat[3]
116 odom.child_frame_id = "base_link"
117 odom.twist.twist.linear.x = vx
118 odom.twist.twist.linear.y = vy
119 odom.twist.twist.angular.z = valpha
121 # publish the message
122 self.pub_odom.publish(odom)
124 def send_laser_scan(self, msg, current_time):
125 # first, we'll publish the transform over tf
126 self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link")
128 # actually ultra sonic range finder
129 num_points = 60 # The base planner needs at least 30 points to work in the default config
130 opening_angle = 30*pi/180 # each side
132 scan.header.stamp = current_time
133 scan.header.frame_id = "/scan"
134 scan.angle_min = -opening_angle
135 scan.angle_max = opening_angle
136 scan.angle_increment = (2*opening_angle)/num_points
137 scan.time_increment = 0.0
140 for i in range(num_points):
141 scan.ranges.append(msg.d1/100.0)
142 #scan.intensities.append(0.5)
143 #scan.intensities.append(1.0)
144 #scan.intensities.append(0.5)
145 self.pub_scan.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) > 1.7/64.3:
159 speed_l = 64.3*abs(wish_speed_left) - 1.7
160 if wish_speed_left < 0:
163 wish_speed_right = trans + speed_offset
164 if abs(wish_speed_right) > 1.7/64.3:
165 speed_r = 64.3*abs(wish_speed_right) - 1.7
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 %.2f, set: %d %d" % (trans, rot*180/pi, 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 self.speed = (speed_l, speed_r)
189 if __name__ == '__main__':