2 # -*- coding: iso-8859-15 -*-
4 # Gazebo Position: rostopic echo -n 1 /gazebo/model_states
6 # x_err = x_real - x_odom
7 # y_err = y_real - y_odom
8 # phi_err = phi_real - phi_odom
10 # x_cg_cw/ccw: avg x_err
11 # y_cg_cw/ccw: avg y_err
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)
17 # D(l/r): Wheel diameter left/right
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)
25 # Wheelbase correction:
26 # alpha = (y_cg_cw - y_cg_ccw)/(-4*L) * 180/pi
27 # Eb = (90)/(90-alpha)
34 from time import sleep
36 from nav_msgs.msg import Odometry
37 from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
38 from actionlib_msgs.msg import GoalStatus
42 rospy.init_node('umbmark')
43 self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
44 rospy.Subscriber("odom", Odometry, self.odom_received)
46 while not self.move_base.wait_for_server(rospy.Duration(5)):
47 rospy.loginfo("Waiting for the move_base action server to come up")
49 def odom_received(self, msg):
50 orientation = tf.transformations.euler_from_quaternion(msg.pose.pose.orientation.__getstate__())
51 self.odom_pose = (msg.pose.pose.position.x, msg.pose.pose.position.y, orientation[2])
53 def next_pos(self, x, y, angle):
54 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
56 rospy.loginfo("Moving to (%.2f, %2f), %d°.." % (x, y, angle*180/pi))
59 goal.target_pose.header.frame_id = "base_footprint"
60 goal.target_pose.header.stamp = rospy.Time.now()
61 goal.target_pose.pose.position.x = x
62 goal.target_pose.pose.position.y = y
63 goal.target_pose.pose.orientation.x = odom_quat[0]
64 goal.target_pose.pose.orientation.y = odom_quat[1]
65 goal.target_pose.pose.orientation.z = odom_quat[2]
66 goal.target_pose.pose.orientation.w = odom_quat[3]
67 self.move_base.send_goal(goal)
69 self.move_base.wait_for_result()
71 if self.move_base.get_state() == GoalStatus.SUCCEEDED:
72 rospy.loginfo("The base moved to (%.2f, %2f), %d°" % (x, y, angle*180/pi))
74 rospy.logerr("The base failed to (%.2f, %2f), %d°" % (x, y, angle*180/pi))
77 def run(self, direction=-1):
78 while self.odom_pose is None:
80 init_pose = self.odom_pose
82 self.next_pos(2, 0, 0)
83 self.next_pos(0, 0, direction*90*pi/180)
84 final_pose = map(operator.sub, self.odom_pose, init_pose)
85 print "Odom Pose: x=%.3f, y=%.3f, angle=%.3f°" % (final_pose[0], final_pose[1], final_pose[2]*180/pi)
93 if __name__ == "__main__":
95 if len(sys.argv) > 1 and sys.argv[1] == "ccw":