]> defiant.homedns.org Git - ros_roboint.git/blob - scripts/robo_explorer.py
fixes
[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
27                 self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
28                 self.pub_scan = rospy.Publisher("scan", LaserScan)
29                 self.pub_odom = rospy.Publisher("odom", Odometry)
30                 
31                 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
32                 rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
33
34                 rospy.spin()
35
36         def inputsReceived(self, msg):
37                 current_time = rospy.Time.now()
38
39                 self.tf_broadcaster.sendTransform((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "odom", "map");
40                 self.send_odometry(msg, current_time)
41                 self.send_laser_scan(msg, current_time)
42
43                 self.last_time = current_time
44
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                 if self.last_in is not None:
49                         in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
50                         if self.speed[0] < 0:
51                                 in_diff[0] = -in_diff[0]
52                         if self.speed[1] < 0:
53                                 in_diff[1] = -in_diff[1]
54
55                         dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8 # steps_changed in different direction => m
56                         delta_alpha = dist_dir/self.wheel_dist
57
58                         dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
59
60                         delta_x = cos(self.alpha + delta_alpha/2)*dist
61                         delta_y = sin(self.alpha + delta_alpha/2)*dist
62
63                         self.alpha += delta_alpha
64                         if self.alpha > 2*pi:
65                                 self.alpha -= 2*pi
66                         elif self.alpha < -2*pi:
67                                 self.alpha += 2*pi
68                         self.x += delta_x
69                         self.y += delta_y
70
71                         # speeds
72                         vx = delta_x / dt
73                         vy = delta_y / dt
74                         valpha = delta_alpha / dt
75
76                         # since all odometry is 6DOF we'll need a quaternion created from yaw
77                         odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
78
79                         # first, we'll publish the transform over tf
80                         self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom");
81
82                         # next, we'll publish the odometry message over ROS
83                         odom = Odometry()
84                         odom.header.stamp = current_time
85                         odom.header.frame_id = "/odom"
86
87                         # set the position
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]
95
96                         # set the velocity
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
101
102                         # publish the message
103                         self.pub_odom.publish(odom)
104                 self.last_in = in_now
105                 
106         def send_laser_scan(self, msg, current_time):
107                 # first, we'll publish the transform over tf
108                 self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link");
109
110                 # actually ultra sonic range finder
111                 scan = LaserScan()
112                 scan.header.stamp = current_time
113                 scan.header.frame_id = "/scan"
114                 scan.angle_min = -pi/4;
115                 scan.angle_max = pi/4;
116                 scan.angle_increment = pi/4;
117                 scan.time_increment = 0.01;
118                 scan.range_min = 0.0;
119                 scan.range_max = 4.0;
120                 for i in range(3):
121                         scan.ranges.append(msg.d1/100.0)
122                 scan.intensities.append(0.5)
123                 scan.intensities.append(1.0)
124                 scan.intensities.append(0.5)
125                 self.pub_scan.publish(scan)
126
127         # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
128         def cmdVelReceived(self, msg):
129                 trans = msg.linear.x
130                 rot = msg.angular.z # rad/s
131
132                 # handle rotation as offset to speeds
133                 speed_offset = (rot * self.wheel_dist)/2.0 # m/s
134
135                 # handle translation
136                 speed_l = 0
137                 wish_speed_left = trans - speed_offset
138                 if abs(wish_speed_left) > 1.7/64.3:
139                         speed_l = 64.3*abs(wish_speed_left) - 1.7
140                         if wish_speed_left < 0:
141                                 speed_l*=-1
142                 speed_r = 0
143                 wish_speed_right = trans + speed_offset
144                 if abs(wish_speed_right) > 1.7/64.3:
145                         speed_r = 64.3*abs(wish_speed_right) - 1.7
146                         if wish_speed_right < 0:
147                                 speed_r*=-1
148
149                 # check limits
150                 if speed_l < -7: speed_l = -7
151                 elif speed_l > 7: speed_l = 7
152                 if speed_r < -7: speed_r = -7
153                 elif speed_r > 7: speed_r = 7
154
155                 outmsg = Motor()
156                 outmsg.num = 1
157                 outmsg.speed = round(speed_l)
158                 self.pub_motor.publish(outmsg)
159                 
160                 outmsg = Motor()
161                 outmsg.num = 2
162                 outmsg.speed = round(speed_r)
163                 self.pub_motor.publish(outmsg)
164
165                 self.speed = (speed_l, speed_r)
166
167 if __name__ == '__main__':
168         RoboExplorer()