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