calibrate_angular.py 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163
  1. #!/usr/bin/env python
  2. """ calibrate_angular.py - Version 1.1 2013-12-20
  3. Rotate the robot 360 degrees to check the odometry parameters of the base controller.
  4. Created for the Pi Robot Project: http://www.pirobot.org
  5. Copyright (c) 2012 Patrick Goebel. All rights reserved.
  6. This program is free software; you can redistribute it and/or modify
  7. it under the terms of the GNU General Public License as published by
  8. the Free Software Foundation; either version 2 of the License, or
  9. (at your option) any later version.5
  10. This program is distributed in the hope that it will be useful,
  11. but WITHOUT ANY WARRANTY; without even the implied warranty of
  12. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. GNU General Public License for more details at:
  14. http://www.gnu.org/licenses/gpl.html
  15. """
  16. import rospy
  17. from geometry_msgs.msg import Twist, Quaternion
  18. from nav_msgs.msg import Odometry
  19. from dynamic_reconfigure.server import Server
  20. import dynamic_reconfigure.client
  21. from rbx1_nav.cfg import CalibrateAngularConfig
  22. import tf
  23. from math import radians, copysign
  24. from rbx1_nav.transform_utils import quat_to_angle, normalize_angle
  25. class CalibrateAngular():
  26. def __init__(self):
  27. # Give the node a name
  28. rospy.init_node('calibrate_angular', anonymous=False)
  29. # Set rospy to execute a shutdown function when terminating the script
  30. rospy.on_shutdown(self.shutdown)
  31. # How fast will we check the odometry values?
  32. self.rate = rospy.get_param('~rate', 20)
  33. r = rospy.Rate(self.rate)
  34. # The test angle is 360 degrees
  35. self.test_angle = radians(rospy.get_param('~test_angle', 360.0))
  36. self.speed = rospy.get_param('~speed', 0.5) # radians per second
  37. self.tolerance = radians(rospy.get_param('tolerance', 1)) # degrees converted to radians
  38. self.odom_angular_scale_correction = rospy.get_param('~odom_angular_scale_correction', 1.0)
  39. self.start_test = rospy.get_param('~start_test', True)
  40. # Publisher to control the robot's speed
  41. self.cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=5)
  42. # Fire up the dynamic_reconfigure server
  43. dyn_server = Server(CalibrateAngularConfig, self.dynamic_reconfigure_callback)
  44. # Connect to the dynamic_reconfigure server
  45. dyn_client = dynamic_reconfigure.client.Client("calibrate_angular", timeout=60)
  46. # The base frame is usually base_link or base_footprint
  47. self.base_frame = rospy.get_param('~base_frame', '/base_link')
  48. # The odom frame is usually just /odom
  49. self.odom_frame = rospy.get_param('~odom_frame', '/odom')
  50. # Initialize the tf listener
  51. self.tf_listener = tf.TransformListener()
  52. # Give tf some time to fill its buffer
  53. rospy.sleep(2)
  54. # Make sure we see the odom and base frames
  55. self.tf_listener.waitForTransform(self.odom_frame, self.base_frame, rospy.Time(), rospy.Duration(60.0))
  56. rospy.loginfo("Bring up rqt_reconfigure to control the test.")
  57. reverse = 1
  58. while not rospy.is_shutdown():
  59. if self.start_test:
  60. # Get the current rotation angle from tf
  61. self.odom_angle = self.get_odom_angle()
  62. last_angle = self.odom_angle
  63. turn_angle = 0
  64. self.test_angle *= reverse
  65. error = self.test_angle - turn_angle
  66. # Alternate directions between tests
  67. reverse = -reverse
  68. while abs(error) > self.tolerance and self.start_test:
  69. if rospy.is_shutdown():
  70. return
  71. # Rotate the robot to reduce the error
  72. move_cmd = Twist()
  73. move_cmd.angular.z = copysign(self.speed, error)
  74. self.cmd_vel.publish(move_cmd)
  75. r.sleep()
  76. # Get the current rotation angle from tf
  77. self.odom_angle = self.get_odom_angle()
  78. # Compute how far we have gone since the last measurement
  79. delta_angle = self.odom_angular_scale_correction * normalize_angle(self.odom_angle - last_angle)
  80. # Add to our total angle so far
  81. turn_angle += delta_angle
  82. # Compute the new error
  83. error = self.test_angle - turn_angle
  84. # Store the current angle for the next comparison
  85. last_angle = self.odom_angle
  86. # Stop the robot
  87. self.cmd_vel.publish(Twist())
  88. # Update the status flag
  89. self.start_test = False
  90. params = {'start_test': False}
  91. dyn_client.update_configuration(params)
  92. rospy.sleep(0.5)
  93. # Stop the robot
  94. self.cmd_vel.publish(Twist())
  95. def get_odom_angle(self):
  96. # Get the current transform between the odom and base frames
  97. try:
  98. (trans, rot) = self.tf_listener.lookupTransform(self.odom_frame, self.base_frame, rospy.Time(0))
  99. except (tf.Exception, tf.ConnectivityException, tf.LookupException):
  100. rospy.loginfo("TF Exception")
  101. return
  102. # Convert the rotation from a quaternion to an Euler angle
  103. return quat_to_angle(Quaternion(*rot))
  104. def dynamic_reconfigure_callback(self, config, level):
  105. self.test_angle = radians(config['test_angle'])
  106. self.speed = config['speed']
  107. self.tolerance = radians(config['tolerance'])
  108. self.odom_angular_scale_correction = config['odom_angular_scale_correction']
  109. self.start_test = config['start_test']
  110. return config
  111. def shutdown(self):
  112. # Always stop the robot when shutting down the node
  113. rospy.loginfo("Stopping the robot...")
  114. self.cmd_vel.publish(Twist())
  115. rospy.sleep(1)
  116. if __name__ == '__main__':
  117. try:
  118. CalibrateAngular()
  119. except:
  120. rospy.loginfo("Calibration terminated.")