]> defiant.homedns.org Git - ros_roboint.git/blob - scripts/robo_explorer.py
-Added missing A1,A2,AX,AY to Inputs.msg
[ros_roboint.git] / scripts / robo_explorer.py
1 #!/usr/bin/env python
2 import roslib; roslib.load_manifest('roboint')
3 import rospy
4 import tf
5 import tf.broadcaster
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
13
14
15 class RoboExplorer:
16         def __init__(self):
17                 rospy.init_node('robo_explorer')
18
19                 self.wheel_dist = 0.188 # 18.8cm
20                 self.wheel_size = 0.051*0.5 # 5.1cm; gear ration=0.5
21                 self.speed = (0, 0)
22                 self.x = 0
23                 self.y = 0
24                 self.alpha = 0
25                 self.last_in = None
26                 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
27                 self.last_time = rospy.Time.now()
28                 self.x_last = 0
29                 self.y_last = 0
30                 self.alpha_last = 0
31
32                 self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
33                 self.pub_scan = rospy.Publisher("scan", LaserScan)
34                 self.pub_odom = rospy.Publisher("odom", Odometry)
35                 
36                 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
37                 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
38
39                 rospy.spin()
40
41         def inputsReceived(self, msg):
42                 current_time = rospy.Time.now()
43
44                 self.update_odometry(msg, current_time)
45                 if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms
46                         self.send_odometry(msg, current_time)
47                         self.send_laser_scan(msg, current_time)
48                         self.last_time = current_time
49
50         def update_odometry(self, msg, current_time):
51                 in_now = msg.input[:2]
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
55                         if self.speed[0] < 0:
56                                 in_diff[0] = -in_diff[0]
57                         elif self.speed[0] == 0:
58                                 in_diff[0] = 0
59                         if self.speed[1] < 0:
60                                 in_diff[1] = -in_diff[1]
61                         elif self.speed[1] == 0:
62                                 in_diff[1] = 0
63
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
66
67                         dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
68
69                         delta_x = cos(self.alpha + delta_alpha/2)*dist
70                         delta_y = sin(self.alpha + delta_alpha/2)*dist
71
72                         self.alpha += delta_alpha
73                         if self.alpha > 2*pi:
74                                 self.alpha -= 2*pi
75                         elif self.alpha < -2*pi:
76                                 self.alpha += 2*pi
77                         self.x += delta_x
78                         self.y += delta_y
79
80                 self.last_in = in_now
81
82         def send_odometry(self, msg, current_time):
83                 # speeds
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.x_last = self.x
89                 self.y_last = self.y
90                 self.alpha_last = self.alpha
91
92                 # since all odometry is 6DOF we'll need a quaternion created from yaw
93                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
94
95                 # first, we'll publish the transform over tf
96                 self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
97
98                 # next, we'll publish the odometry message over ROS
99                 odom = Odometry()
100                 odom.header.stamp = current_time
101                 odom.header.frame_id = "/odom"
102
103                 # set the position
104                 odom.pose.pose.position.x = self.x
105                 odom.pose.pose.position.y = self.y
106                 odom.pose.pose.position.z = 0.0
107                 odom.pose.pose.orientation.x = odom_quat[0]
108                 odom.pose.pose.orientation.y = odom_quat[1]
109                 odom.pose.pose.orientation.z = odom_quat[2]
110                 odom.pose.pose.orientation.w = odom_quat[3]
111
112                 # set the velocity
113                 odom.child_frame_id = "base_link"
114                 odom.twist.twist.linear.x = vx
115                 odom.twist.twist.linear.y = vy
116                 odom.twist.twist.angular.z = valpha
117
118                 # publish the message
119                 self.pub_odom.publish(odom)
120                 
121         def send_laser_scan(self, msg, current_time):
122                 # first, we'll publish the transform over tf
123                 self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link")
124
125                 # actually ultra sonic range finder
126                 num_points = 60 # The base planner needs at least 30 points to work in the default config
127                 opening_angle = 30*pi/180 # each side
128                 scan = LaserScan()
129                 scan.header.stamp = current_time
130                 scan.header.frame_id = "/scan"
131                 scan.angle_min = -opening_angle
132                 scan.angle_max = opening_angle
133                 scan.angle_increment = (2*opening_angle)/num_points
134                 scan.time_increment = 0.001/num_points
135                 scan.range_min = 0.0
136                 scan.range_max = 4.0
137                 for i in range(num_points):
138                         scan.ranges.append(msg.d1/100.0)
139                 #scan.intensities.append(0.5)
140                 #scan.intensities.append(1.0)
141                 #scan.intensities.append(0.5)
142                 self.pub_scan.publish(scan)
143
144         # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
145         def cmdVelReceived(self, msg):
146                 trans = msg.linear.x
147                 rot = msg.angular.z # rad/s
148
149                 # handle rotation as offset to speeds
150                 speed_offset = (rot * self.wheel_dist)/2.0 # m/s
151
152                 # handle translation
153                 speed_l = 0
154                 wish_speed_left = trans - speed_offset
155                 if abs(wish_speed_left) > 1.7/64.3:
156                         speed_l = 64.3*abs(wish_speed_left) - 1.7
157                         if wish_speed_left < 0:
158                                 speed_l*=-1
159                 speed_r = 0
160                 wish_speed_right = trans + speed_offset
161                 if abs(wish_speed_right) > 1.7/64.3:
162                         speed_r = 64.3*abs(wish_speed_right) - 1.7
163                         if wish_speed_right < 0:
164                                 speed_r*=-1
165
166                 # check limits
167                 if speed_l < -7: speed_l = -7
168                 elif speed_l > 7: speed_l = 7
169                 if speed_r < -7: speed_r = -7
170                 elif speed_r > 7: speed_r = 7
171
172                 #print "Speed wanted: %.2f %.2f, set: %d %d" % (trans, rot*180/pi, round(speed_l), round(speed_r))
173
174                 outmsg = Motor()
175                 outmsg.num = 1
176                 outmsg.speed = round(speed_l)
177                 self.pub_motor.publish(outmsg)
178                 
179                 outmsg = Motor()
180                 outmsg.num = 2
181                 outmsg.speed = round(speed_r)
182                 self.pub_motor.publish(outmsg)
183
184                 self.speed = (speed_l, speed_r)
185
186 if __name__ == '__main__':
187         RoboExplorer()