]> defiant.homedns.org Git - ros_roboint.git/blob - scripts/robo_explorer.py
wip Odometry
[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 PointCloud
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_cloud = rospy.Publisher("point_cloud", PointCloud)
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.odom_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                 dt = (current_time - self.last_time).to_sec();
40                 in_now = msg.input[1:3]
41                 in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
42                 if self.speed[0] < 0:
43                         in_diff[0] = -in_diff[0]
44                 if self.speed[1] < 0:
45                         in_diff[1] = -in_diff[1]
46
47                 dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8
48                 delta_alpha = dist_dir/self.wheel_dist
49
50                 dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8
51
52                 delta_x = cos(self.alpha + delta_alpha/2)*dist
53                 delta_y = sin(self.alpha + delta_alpha/2)*dist
54
55                 self.alpha += delta_alpha
56                 if self.alpha > 2*pi:
57                         self.alpha -= 2*pi
58                 elif self.alpha < -2*pi:
59                         self.alpha += 2*pi
60                 self.x += delta_x
61                 self.y += delta_y
62
63                 # speeds
64                 vx = delta_x / dt
65                 vy = delta_y / dt
66                 valpha = delta_alpha / dt
67
68                 # since all odometry is 6DOF we'll need a quaternion created from yaw
69                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
70
71                 # first, we'll publish the transform over tf
72                 self.odom_broadcaster.sendTransform((0.0, 0.0, 0.0), odom_quat, current_time, "odom", "base_link");
73
74                 # next, we'll publish the odometry message over ROS
75                 odom = Odometry()
76                 odom.header.stamp = current_time
77                 odom.header.frame_id = "odom"
78
79                 # set the position
80                 odom.pose.pose.position.x = self.x
81                 odom.pose.pose.position.y = self.y
82                 odom.pose.pose.position.z = 0.0
83                 odom.pose.pose.orientation = odom_quat
84
85                 # set the velocity
86                 odom.child_frame_id = "base_link";
87                 odom.twist.twist.linear.x = vx
88                 odom.twist.twist.linear.y = vy
89                 odom.twist.twist.angular.z = valpha
90
91                 # publish the message
92                 self.pub_odom.publish(odom)
93                 
94                 # sent PointCloud
95                 cloud = PointCloud()
96                 cloud.header.stamp = current_time
97                 cloud.header.frame_id = "sensor_frame"
98                 cloud.points.append(Point32(msg.d1/10.0, 0, 0))
99                 self.pub_cloud.publish(cloud)
100
101                 self.last_time = current_time
102                 self.last_in = in_now
103
104
105         def cmdVelReceived(self, msg):
106                 trans = msg.linear.x
107                 rot = msg.angular.z
108
109                 # speed steps = 7
110                 # max trans = 0.1m/s
111                 # max rot = 0.29rad/s
112
113                 speed_l = int(trans*7/0.1 - rot*7/0.29)
114                 speed_r = int(trans*7/0.1 + rot*7/0.29)
115                 if speed_l < -7: speed_l = -7
116                 elif speed_l > 7: speed_l = 7
117                 if speed_r < -7: speed_r = -7
118                 elif speed_r > 7: speed_r = 7
119
120                 outmsg = Motor()
121                 outmsg.num = 1
122                 outmsg.speed = speed_l
123                 self.pub_motor.publish(outmsg)
124                 
125                 outmsg = Motor()
126                 outmsg.num = 2
127                 outmsg.speed = speed_r
128                 self.pub_motor.publish(outmsg)
129
130                 self.speed = (speed_l, speed_r)
131
132 if __name__ == '__main__':
133         RoboExplorer()