]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/umbmark.py
f031a675b9bf1e25855e27b16100509795a5dd96
[ros_wild_thumper.git] / scripts / umbmark.py
1 #!/usr/bin/env python
2 # -*- coding: iso-8859-15 -*-
3 #
4 # Gazebo Position: rostopic echo -n 1 /gazebo/model_states
5 #
6 # x_err = x_real - x_odom
7 # y_err = y_real - y_odom
8 # phi_err = phi_real - phi_odom
9 #
10 # x_cg_cw/ccw: avg x_err
11 # y_cg_cw/ccw: avg y_err
12 #
13 # r_cg_cw = sqrt(x_cg_cw**2 + y_cg_cw**2)
14 # r_cg_ccw = sqrt(x_cg_ccw**2 + y_cg_ccw**2)
15 #
16 # L: length (2)
17 # D(l/r): Wheel diameter left/right
18 # b: wheelbase
19 #
20 # Wheel diameter correction:
21 # beta = (y_cg_cw + y_cg_ccw)/(-4*L)
22 # R = (L/2)/sin(beta/2)
23 # Ed = Dr/Dl*(R+b/2)/(R-b/2)
24 # Da = (Dr + Dl)/2
25 # Dl = 2/(Ed + 1) * Da
26 # Dr = 2/((1/Ed) + 1) * Da
27
28 # Wheelbase correction:
29 # alpha = (y_cg_cw - y_cg_ccw)/(-4*L) * 180/pi
30 # Eb = (90)/(90-alpha)
31 # b_new = Eb*b
32
33 import sys
34 import rospy
35 import tf
36 import actionlib
37 import operator
38 from time import sleep
39 from math import *
40 from nav_msgs.msg import Odometry
41 from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
42 from actionlib_msgs.msg import GoalStatus
43
44 class UMBMark:
45         def __init__(self):
46                 rospy.init_node('umbmark')
47                 self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
48                 rospy.Subscriber("odom", Odometry, self.odom_received)
49                 self.odom_pose = None
50                 while not self.move_base.wait_for_server(rospy.Duration(5)):
51                         rospy.loginfo("Waiting for the move_base action server to come up")
52
53         def odom_received(self, msg):
54                 orientation = tf.transformations.euler_from_quaternion(msg.pose.pose.orientation.__getstate__())
55                 self.odom_pose = (msg.pose.pose.position.x, msg.pose.pose.position.y, orientation[2])
56
57         def next_pos(self, x, y, angle):
58                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
59
60                 rospy.loginfo("Moving to (%.2f, %2f), %d°.." % (x, y, angle*180/pi))
61
62                 goal = MoveBaseGoal()
63                 goal.target_pose.header.frame_id = "base_footprint"
64                 goal.target_pose.header.stamp = rospy.Time.now()
65                 goal.target_pose.pose.position.x = x
66                 goal.target_pose.pose.position.y = y
67                 goal.target_pose.pose.orientation.x = odom_quat[0]
68                 goal.target_pose.pose.orientation.y = odom_quat[1]
69                 goal.target_pose.pose.orientation.z = odom_quat[2]
70                 goal.target_pose.pose.orientation.w = odom_quat[3]
71                 self.move_base.send_goal(goal)
72
73                 self.move_base.wait_for_result()
74
75                 if self.move_base.get_state() == GoalStatus.SUCCEEDED:
76                         rospy.loginfo("The base moved to (%.2f, %2f), %d°" % (x, y, angle*180/pi))
77                 else:
78                         rospy.logerr("The base failed to (%.2f, %2f), %d°" % (x, y, angle*180/pi))
79                         raise
80
81         def run(self, direction=-1):
82                 while self.odom_pose is None:
83                         sleep(0.1)
84                 init_pose = self.odom_pose
85                 for i in range(4):
86                         self.next_pos(2, 0, 0)
87                         self.next_pos(0, 0, direction*90*pi/180)
88                 final_pose = map(operator.sub, self.odom_pose, init_pose)
89                 print "Odom Pose: x=%.3f, y=%.3f, angle=%.3f°" % (final_pose[0], final_pose[1], final_pose[2]*180/pi)
90
91         def run_cw(self):
92                 self.run(-1)
93
94         def run_ccw(self):
95                 self.run(1)
96
97 if __name__ == "__main__":
98         p = UMBMark()
99         if len(sys.argv) > 1 and sys.argv[1] == "ccw":
100                 p.run_ccw()
101         else:
102                 p.run_cw()