]> defiant.homedns.org Git - ros_roboint.git/blob - scripts/robo_explorer.py
fix velocity message in robo_explorer
[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 *
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.x = 0
20                 self.y = 0
21                 self.alpha = 0
22                 self.last_in = None
23                 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
24                 self.last_time = rospy.Time.now()
25                 self.x_last = 0
26                 self.y_last = 0
27                 self.alpha_last = 0
28
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"))
39
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)
44                 
45                 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
46                 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
47
48                 rospy.spin()
49
50         def inputsReceived(self, msg):
51                 current_time = rospy.Time.now()
52
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
59
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                         # fix in_diff from actual motor direction
65                         if msg.output[1] > 0: # left reverse
66                                 in_diff[0] = -in_diff[0]
67                         elif msg.output[0] == 0 and msg.output[1] == 0: # left stop
68                                 in_diff[0] = 0
69                         if msg.output[3] > 0: # right reverse
70                                 in_diff[1] = -in_diff[1]
71                         elif msg.output[2] == 0 and msg.output[3] == 0: # right stop
72                                 in_diff[1] = 0
73
74                         dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8 # steps_changed in different direction => m
75                         delta_alpha = dist_dir/self.wheel_dist
76
77                         dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
78
79                         delta_x = cos(self.alpha + delta_alpha/2)*dist
80                         delta_y = sin(self.alpha + delta_alpha/2)*dist
81
82                         self.alpha += delta_alpha
83                         if self.alpha > 2*pi:
84                                 self.alpha -= 2*pi
85                         elif self.alpha < -2*pi:
86                                 self.alpha += 2*pi
87                         self.x += delta_x
88                         self.y += delta_y
89
90                 self.last_in = in_now
91
92         def send_odometry(self, msg, current_time):
93                 # speeds
94                 dt = (current_time - self.last_time).to_sec()
95                 vx = sqrt((self.x - self.x_last)**2 + (self.y - self.y_last)**2) / dt
96                 vy = 0.0
97                 valpha = (self.alpha - self.alpha_last) / dt
98                 self.x_last = self.x
99                 self.y_last = self.y
100                 self.alpha_last = self.alpha
101
102                 # since all odometry is 6DOF we'll need a quaternion created from yaw
103                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
104
105                 # first, we'll publish the transform over tf
106                 self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
107
108                 # next, we'll publish the odometry message over ROS
109                 odom = Odometry()
110                 odom.header.stamp = current_time
111                 odom.header.frame_id = "/odom"
112
113                 # set the position
114                 odom.pose.pose.position.x = self.x
115                 odom.pose.pose.position.y = self.y
116                 odom.pose.pose.position.z = 0.0
117                 odom.pose.pose.orientation.x = odom_quat[0]
118                 odom.pose.pose.orientation.y = odom_quat[1]
119                 odom.pose.pose.orientation.z = odom_quat[2]
120                 odom.pose.pose.orientation.w = odom_quat[3]
121
122                 # set the velocity
123                 odom.child_frame_id = "base_link"
124                 odom.twist.twist.linear.x = vx
125                 odom.twist.twist.linear.y = vy
126                 odom.twist.twist.angular.z = valpha
127
128                 # publish the message
129                 self.pub_odom.publish(odom)
130                 
131         def send_laser_scan(self, msg, current_time):
132                 # first, we'll publish the transform over tf
133                 self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link")
134
135                 # actually ultra sonic range finder
136                 num_points = 60 # The base planner needs at least 30 points to work in the default config
137                 opening_angle = 30*pi/180 # each side
138                 scan = LaserScan()
139                 scan.header.stamp = current_time
140                 scan.header.frame_id = "/scan"
141                 scan.angle_min = -opening_angle
142                 scan.angle_max = opening_angle
143                 scan.angle_increment = (2*opening_angle)/num_points
144                 scan.time_increment = 0.0
145                 scan.range_min = 0.0
146                 scan.range_max = 4.0
147                 for i in range(num_points):
148                         scan.ranges.append(msg.d1/100.0)
149                 #scan.intensities.append(0.5)
150                 #scan.intensities.append(1.0)
151                 #scan.intensities.append(0.5)
152                 self.pub_scan.publish(scan)
153
154         # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
155         def cmdVelReceived(self, msg):
156                 trans = msg.linear.x
157                 rot = msg.angular.z # rad/s
158
159                 # handle rotation as offset to speeds
160                 speed_offset = (rot * self.wheel_dist)/2.0 # m/s
161
162                 # handle translation
163                 speed_l = 0
164                 wish_speed_left = trans - speed_offset
165                 if abs(wish_speed_left) > 0:
166                         speed_l = self.speed_gradiant*abs(wish_speed_left) + self.speed_constant
167                         if wish_speed_left < 0:
168                                 speed_l*=-1
169                 speed_r = 0
170                 wish_speed_right = trans + speed_offset
171                 if abs(wish_speed_right) > 0:
172                         speed_r = self.speed_gradiant*abs(wish_speed_right) + self.speed_constant
173                         if wish_speed_right < 0:
174                                 speed_r*=-1
175
176                 # check limits
177                 if speed_l < -7: speed_l = -7
178                 elif speed_l > 7: speed_l = 7
179                 if speed_r < -7: speed_r = -7
180                 elif speed_r > 7: speed_r = 7
181
182                 #print "Speed wanted: %.2f m/s %.2f rad/s, set: %d %d" % (trans, rot, round(speed_l), round(speed_r))
183
184                 outmsg = Motor()
185                 outmsg.num = 0
186                 outmsg.speed = round(speed_l)
187                 self.pub_motor.publish(outmsg)
188                 
189                 outmsg = Motor()
190                 outmsg.num = 1
191                 outmsg.speed = round(speed_r)
192                 self.pub_motor.publish(outmsg)
193
194 if __name__ == '__main__':
195         RoboExplorer()