]> defiant.homedns.org Git - ros_roboint.git/blob - scripts/robo_explorer.py
36ec82870a4844c2cbd62a358363f1c614ad7118
[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 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
11
12
13 class RoboExplorer:
14         def __init__(self):
15                 rospy.init_node('robo_explorer')
16
17                 self.wheel_dist = 0.188 # 18.8cm
18                 self.wheel_size = 0.052*0.5 # 5.2cm; gear ration=0.5
19                 self.speed = (0, 0)
20                 self.x = 0
21                 self.y = 0
22                 self.alpha = 0
23                 self.last_in = None
24                 self.tf_broadcaster = tf.TransformBroadcaster()
25                 self.last_time = rospy.Time.now()
26                 self.input_count = 0
27                 self.x_last = 0
28                 self.y_last = 0
29                 self.alpha_last = 0
30
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)
34                 
35                 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
36                 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
37
38                 rospy.spin()
39
40         def inputsReceived(self, msg):
41                 current_time = rospy.Time.now()
42                 self.input_count+=1
43
44                 self.update_odometry(msg, current_time)
45                 if self.input_count >= 10:
46                         self.input_count = 0
47                         self.tf_broadcaster.sendTransform((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "odom", "map");
48                         self.send_odometry(msg, current_time)
49                         self.send_laser_scan(msg, current_time)
50
51         def update_odometry(self, msg, current_time):
52                 in_now = msg.input[1:3]
53                 if self.last_in is not None:
54                         in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
55                         # fix in_diff from actual motor direction
56                         if self.speed[0] < 0:
57                                 in_diff[0] = -in_diff[0]
58                         elif self.speed[0] == 0:
59                                 in_diff[0] = 0
60                         if self.speed[1] < 0:
61                                 in_diff[1] = -in_diff[1]
62                         elif self.speed[1] == 0:
63                                 in_diff[1] = 0
64
65                         dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8 # steps_changed in different direction => m
66                         delta_alpha = dist_dir/self.wheel_dist
67
68                         dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
69
70                         delta_x = cos(self.alpha + delta_alpha/2)*dist
71                         delta_y = sin(self.alpha + delta_alpha/2)*dist
72
73                         self.alpha += delta_alpha
74                         if self.alpha > 2*pi:
75                                 self.alpha -= 2*pi
76                         elif self.alpha < -2*pi:
77                                 self.alpha += 2*pi
78                         self.x += delta_x
79                         self.y += delta_y
80
81                 self.last_in = in_now
82
83         def send_odometry(self, msg, current_time):
84                 # speeds
85                 dt = (current_time - self.last_time).to_sec()
86                 vx = (self.x - self.x_last) / dt
87                 vy = (self.y - self.y_last) / dt
88                 valpha = (self.alpha - self.alpha_last) / dt
89                 self.last_time = current_time
90                 self.x_last = self.x
91                 self.y_last = self.y
92                 self.alpha_last = self.alpha
93
94                 # since all odometry is 6DOF we'll need a quaternion created from yaw
95                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
96
97                 # first, we'll publish the transform over tf
98                 self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom");
99
100                 # next, we'll publish the odometry message over ROS
101                 odom = Odometry()
102                 odom.header.stamp = current_time
103                 odom.header.frame_id = "/odom"
104
105                 # set the position
106                 odom.pose.pose.position.x = self.x
107                 odom.pose.pose.position.y = self.y
108                 odom.pose.pose.position.z = 0.0
109                 odom.pose.pose.orientation.x = odom_quat[0]
110                 odom.pose.pose.orientation.y = odom_quat[1]
111                 odom.pose.pose.orientation.z = odom_quat[2]
112                 odom.pose.pose.orientation.w = odom_quat[3]
113
114                 # set the velocity
115                 odom.child_frame_id = "base_link";
116                 odom.twist.twist.linear.x = vx
117                 odom.twist.twist.linear.y = vy
118                 odom.twist.twist.angular.z = valpha
119
120                 # publish the message
121                 self.pub_odom.publish(odom)
122                 
123         def send_laser_scan(self, msg, current_time):
124                 # first, we'll publish the transform over tf
125                 self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link");
126
127                 # actually ultra sonic range finder
128                 scan = LaserScan()
129                 scan.header.stamp = current_time
130                 scan.header.frame_id = "/scan"
131                 scan.angle_min = -pi/4;
132                 scan.angle_max = pi/4;
133                 scan.angle_increment = pi/4;
134                 scan.time_increment = 0.1;
135                 scan.range_min = 0.0;
136                 scan.range_max = 4.0;
137                 for i in range(3):
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                 outmsg = Motor()
173                 outmsg.num = 1
174                 outmsg.speed = round(speed_l)
175                 self.pub_motor.publish(outmsg)
176                 
177                 outmsg = Motor()
178                 outmsg.num = 2
179                 outmsg.speed = round(speed_r)
180                 self.pub_motor.publish(outmsg)
181
182                 self.speed = (speed_l, speed_r)
183
184 if __name__ == '__main__':
185         RoboExplorer()