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