2 import roslib; roslib.load_manifest('roboint')
5 from math import sin, cos, pi
6 from geometry_msgs.msg import Twist, TransformStamped, Point32
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')
17 self.wheel_dist = 0.188 # 18.8cm
18 self.wheel_size = 0.052*0.5 # 5.2cm; gear ration=0.5
24 self.tf_broadcaster = tf.TransformBroadcaster()
25 self.last_time = rospy.Time.now()
31 self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
32 self.pub_scan = rospy.Publisher("scan", LaserScan)
33 self.pub_odom = rospy.Publisher("odom", Odometry)
35 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
36 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
40 def inputsReceived(self, msg):
41 current_time = rospy.Time.now()
44 self.update_odometry(msg, current_time)
45 if self.input_count >= 10:
47 self.send_odometry(msg, current_time)
48 self.send_laser_scan(msg, current_time)
50 def update_odometry(self, msg, current_time):
51 in_now = msg.input[1:3]
52 if self.last_in is not None:
53 in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
54 # fix in_diff from actual motor direction
56 in_diff[0] = -in_diff[0]
57 elif self.speed[0] == 0:
60 in_diff[1] = -in_diff[1]
61 elif self.speed[1] == 0:
64 dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8 # steps_changed in different direction => m
65 delta_alpha = dist_dir/self.wheel_dist
67 dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
69 delta_x = cos(self.alpha + delta_alpha/2)*dist
70 delta_y = sin(self.alpha + delta_alpha/2)*dist
72 self.alpha += delta_alpha
75 elif self.alpha < -2*pi:
82 def send_odometry(self, msg, current_time):
84 dt = (current_time - self.last_time).to_sec()
85 vx = (self.x - self.x_last) / dt
86 vy = (self.y - self.y_last) / dt
87 valpha = (self.alpha - self.alpha_last) / dt
88 self.last_time = current_time
91 self.alpha_last = self.alpha
93 # since all odometry is 6DOF we'll need a quaternion created from yaw
94 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
96 # first, we'll publish the transform over tf
97 self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
99 # next, we'll publish the odometry message over ROS
101 odom.header.stamp = current_time
102 odom.header.frame_id = "/odom"
105 odom.pose.pose.position.x = self.x
106 odom.pose.pose.position.y = self.y
107 odom.pose.pose.position.z = 0.0
108 odom.pose.pose.orientation.x = odom_quat[0]
109 odom.pose.pose.orientation.y = odom_quat[1]
110 odom.pose.pose.orientation.z = odom_quat[2]
111 odom.pose.pose.orientation.w = odom_quat[3]
114 odom.child_frame_id = "base_link"
115 odom.twist.twist.linear.x = vx
116 odom.twist.twist.linear.y = vy
117 odom.twist.twist.angular.z = valpha
119 # publish the message
120 self.pub_odom.publish(odom)
122 def send_laser_scan(self, msg, current_time):
123 # first, we'll publish the transform over tf
124 self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link")
126 # actually ultra sonic range finder
128 opening_angle = 30*pi/180 # each side
130 scan.header.stamp = current_time
131 scan.header.frame_id = "/scan"
132 scan.angle_min = -opening_angle
133 scan.angle_max = opening_angle
134 scan.angle_increment = (2*opening_angle)/num_points
135 scan.time_increment = 0.1/num_points
138 for i in range(num_points):
139 scan.ranges.append(msg.d1/100.0)
140 #scan.intensities.append(0.5)
141 #scan.intensities.append(1.0)
142 #scan.intensities.append(0.5)
143 self.pub_scan.publish(scan)
145 # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
146 def cmdVelReceived(self, msg):
148 rot = msg.angular.z # rad/s
150 # handle rotation as offset to speeds
151 speed_offset = (rot * self.wheel_dist)/2.0 # m/s
155 wish_speed_left = trans - speed_offset
156 if abs(wish_speed_left) > 1.7/64.3:
157 speed_l = 64.3*abs(wish_speed_left) - 1.7
158 if wish_speed_left < 0:
161 wish_speed_right = trans + speed_offset
162 if abs(wish_speed_right) > 1.7/64.3:
163 speed_r = 64.3*abs(wish_speed_right) - 1.7
164 if wish_speed_right < 0:
168 if speed_l < -7: speed_l = -7
169 elif speed_l > 7: speed_l = 7
170 if speed_r < -7: speed_r = -7
171 elif speed_r > 7: speed_r = 7
175 outmsg.speed = round(speed_l)
176 self.pub_motor.publish(outmsg)
180 outmsg.speed = round(speed_r)
181 self.pub_motor.publish(outmsg)
183 self.speed = (speed_l, speed_r)
185 if __name__ == '__main__':