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 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
18 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
20 self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
21 self.pub_scan = rospy.Publisher("scan", LaserScan)
22 self.pub_odom = rospy.Publisher("odom", Odometry)
24 self.wheel_dist = 0.188 # 18.8cm
25 self.wheel_size = 0.052*0.5 # 5.1cm gear ration=0.5
31 self.tf_broadcaster = tf.TransformBroadcaster()
32 self.last_time = rospy.Time.now()
36 def inputsReceived(self, msg):
37 current_time = rospy.Time.now()
39 self.tf_broadcaster.sendTransform((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "map", "base_link");
40 self.send_odometry(msg, current_time)
41 self.send_laser_scan(msg, current_time)
43 self.last_time = current_time
45 def send_odometry(self, msg, current_time):
46 dt = (current_time - self.last_time).to_sec();
47 in_now = msg.input[1:3]
48 in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
50 in_diff[0] = -in_diff[0]
52 in_diff[1] = -in_diff[1]
54 dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8 # steps_changed in different direction => m
55 delta_alpha = dist_dir/self.wheel_dist
57 dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
59 delta_x = cos(self.alpha + delta_alpha/2)*dist
60 delta_y = sin(self.alpha + delta_alpha/2)*dist
62 self.alpha += delta_alpha
65 elif self.alpha < -2*pi:
74 valpha = delta_alpha / dt
76 # first, we'll publish the transform over tf
77 self.tf_broadcaster.sendTransform((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "odom", "base_link");
79 # next, we'll publish the odometry message over ROS
81 odom.header.stamp = current_time
82 odom.header.frame_id = "/odom"
84 # since all odometry is 6DOF we'll need a quaternion created from yaw
85 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
88 odom.pose.pose.position.x = self.x
89 odom.pose.pose.position.y = self.y
90 odom.pose.pose.position.z = 0.0
91 odom.pose.pose.orientation.x = odom_quat[0]
92 odom.pose.pose.orientation.y = odom_quat[1]
93 odom.pose.pose.orientation.z = odom_quat[2]
94 odom.pose.pose.orientation.w = odom_quat[3]
97 odom.child_frame_id = "base_link";
98 odom.twist.twist.linear.x = vx
99 odom.twist.twist.linear.y = vy
100 odom.twist.twist.angular.z = valpha
102 # publish the message
103 self.pub_odom.publish(odom)
105 def send_laser_scan(self, msg, current_time):
106 # first, we'll publish the transform over tf
107 self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "base_link", "scan");
109 # actually ultra sonic range finder
111 scan.header.stamp = current_time
112 scan.header.frame_id = "/scan"
113 scan.angle_min = -pi/4;
114 scan.angle_max = pi/4;
115 scan.angle_increment = pi/4;
116 scan.time_increment = 0.01;
117 scan.range_min = 0.0;
118 scan.range_max = 4.0;
120 scan.ranges.append(msg.d1/100.0)
121 scan.intensities.append(0.5)
122 scan.intensities.append(1.0)
123 scan.intensities.append(0.5)
124 self.pub_scan.publish(scan)
126 # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
127 def cmdVelReceived(self, msg):
129 rot = msg.angular.z # rad/s
131 # handle rotation as offset to speeds
132 speed_offset = (rot * self.wheel_dist)/2.0 # m/s
136 wish_speed_left = trans - speed_offset
137 if abs(wish_speed_left) > 1.7/64.3:
138 speed_l = 64.3*abs(wish_speed_left) - 1.7
139 if wish_speed_left < 0:
142 wish_speed_right = trans + speed_offset
143 if abs(wish_speed_right) > 1.7/64.3:
144 speed_r = 64.3*abs(wish_speed_right) - 1.7
145 if wish_speed_right < 0:
149 if speed_l < -7: speed_l = -7
150 elif speed_l > 7: speed_l = 7
151 if speed_r < -7: speed_r = -7
152 elif speed_r > 7: speed_r = 7
156 outmsg.speed = round(speed_l)
157 self.pub_motor.publish(outmsg)
161 outmsg.speed = round(speed_r)
162 self.pub_motor.publish(outmsg)
164 self.speed = (speed_l, speed_r)
166 if __name__ == '__main__':