calibrate_linear.py 5.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155
  1. #!/usr/bin/env python
  2. """ calibrate_linear.py - Version 1.1 2013-12-20
  3. Move the robot 1.0 meter to check on the PID 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, Point
  18. from math import copysign, sqrt, pow
  19. from dynamic_reconfigure.server import Server
  20. import dynamic_reconfigure.client
  21. from rbx1_nav.cfg import CalibrateLinearConfig
  22. import tf
  23. class CalibrateLinear():
  24. def __init__(self):
  25. # Give the node a name
  26. rospy.init_node('calibrate_linear', anonymous=False)
  27. # Set rospy to execute a shutdown function when terminating the script
  28. rospy.on_shutdown(self.shutdown)
  29. # How fast will we check the odometry values?
  30. self.rate = rospy.get_param('~rate', 20)
  31. r = rospy.Rate(self.rate)
  32. # Set the distance to travel
  33. self.test_distance = rospy.get_param('~test_distance', 1.0) # meters
  34. self.speed = rospy.get_param('~speed', 0.15) # meters per second
  35. self.tolerance = rospy.get_param('~tolerance', 0.01) # meters
  36. self.odom_linear_scale_correction = rospy.get_param('~odom_linear_scale_correction', 1.0)
  37. self.start_test = rospy.get_param('~start_test', True)
  38. # Publisher to control the robot's speed
  39. self.cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=5)
  40. # Fire up the dynamic_reconfigure server
  41. dyn_server = Server(CalibrateLinearConfig, self.dynamic_reconfigure_callback)
  42. # Connect to the dynamic_reconfigure server
  43. dyn_client = dynamic_reconfigure.client.Client("calibrate_linear", timeout=60)
  44. # The base frame is base_footprint for the TurtleBot but base_link for Pi Robot
  45. self.base_frame = rospy.get_param('~base_frame', '/base_link')
  46. # The odom frame is usually just /odom
  47. self.odom_frame = rospy.get_param('~odom_frame', '/odom')
  48. # Initialize the tf listener
  49. self.tf_listener = tf.TransformListener()
  50. # Give tf some time to fill its buffer
  51. rospy.sleep(2)
  52. # Make sure we see the odom and base frames
  53. self.tf_listener.waitForTransform(self.odom_frame, self.base_frame, rospy.Time(), rospy.Duration(60.0))
  54. rospy.loginfo("Bring up rqt_reconfigure to control the test.")
  55. self.position = Point()
  56. # Get the starting position from the tf transform between the odom and base frames
  57. self.position = self.get_position()
  58. x_start = self.position.x
  59. y_start = self.position.y
  60. move_cmd = Twist()
  61. while not rospy.is_shutdown():
  62. # Stop the robot by default
  63. move_cmd = Twist()
  64. if self.start_test:
  65. # Get the current position from the tf transform between the odom and base frames
  66. self.position = self.get_position()
  67. # Compute the Euclidean distance from the target point
  68. distance = sqrt(pow((self.position.x - x_start), 2) +
  69. pow((self.position.y - y_start), 2))
  70. # Correct the estimated distance by the correction factor
  71. distance *= self.odom_linear_scale_correction
  72. # How close are we?
  73. error = distance - self.test_distance
  74. # Are we close enough?
  75. if not self.start_test or abs(error) < self.tolerance:
  76. self.start_test = False
  77. params = {'start_test': False}
  78. rospy.loginfo(params)
  79. dyn_client.update_configuration(params)
  80. else:
  81. # If not, move in the appropriate direction
  82. move_cmd.linear.x = copysign(self.speed, -1 * error)
  83. else:
  84. self.position = self.get_position()
  85. x_start = self.position.x
  86. y_start = self.position.y
  87. self.cmd_vel.publish(move_cmd)
  88. r.sleep()
  89. # Stop the robot
  90. self.cmd_vel.publish(Twist())
  91. def dynamic_reconfigure_callback(self, config, level):
  92. self.test_distance = config['test_distance']
  93. self.speed = config['speed']
  94. self.tolerance = config['tolerance']
  95. self.odom_linear_scale_correction = config['odom_linear_scale_correction']
  96. self.start_test = config['start_test']
  97. return config
  98. def get_position(self):
  99. # Get the current transform between the odom and base frames
  100. try:
  101. (trans, rot) = self.tf_listener.lookupTransform(self.odom_frame, self.base_frame, rospy.Time(0))
  102. except (tf.Exception, tf.ConnectivityException, tf.LookupException):
  103. rospy.loginfo("TF Exception")
  104. return
  105. return Point(*trans)
  106. def shutdown(self):
  107. # Always stop the robot when shutting down the node
  108. rospy.loginfo("Stopping the robot...")
  109. self.cmd_vel.publish(Twist())
  110. rospy.sleep(1)
  111. if __name__ == '__main__':
  112. try:
  113. CalibrateLinear()
  114. rospy.spin()
  115. except:
  116. rospy.loginfo("Calibration terminated.")