odom_out_and_back.py 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176
  1. #!/usr/bin/env python
  2. """ odom_out_and_back.py - Version 1.1 2013-12-20
  3. A basic demo of using the /odom topic to move a robot a given distance
  4. or rotate through a given angle.
  5. Created for the Pi Robot Project: http://www.pirobot.org
  6. Copyright (c) 2012 Patrick Goebel. All rights reserved.
  7. This program is free software; you can redistribute it and/or modify
  8. it under the terms of the GNU General Public License as published by
  9. the Free Software Foundation; either version 2 of the License, or
  10. (at your option) any later version.5
  11. This program is distributed in the hope that it will be useful,
  12. but WITHOUT ANY WARRANTY; without even the implied warranty of
  13. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  14. GNU General Public License for more details at:
  15. http://www.gnu.org/licenses/gpl.html
  16. """
  17. import rospy
  18. from geometry_msgs.msg import Twist, Point, Quaternion
  19. import tf
  20. from rbx1_nav.transform_utils import quat_to_angle, normalize_angle
  21. from math import radians, copysign, sqrt, pow, pi
  22. class OutAndBack():
  23. def __init__(self):
  24. # Give the node a name
  25. rospy.init_node('out_and_back', anonymous=False)
  26. # Set rospy to execute a shutdown function when exiting
  27. rospy.on_shutdown(self.shutdown)
  28. # Publisher to control the robot's speed
  29. self.cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=5)
  30. # How fast will we update the robot's movement?
  31. rate = 20
  32. # Set the equivalent ROS rate variable
  33. r = rospy.Rate(rate)
  34. # Set the forward linear speed to 0.15 meters per second
  35. linear_speed = 0.15
  36. # Set the travel distance in meters
  37. goal_distance = 1.0
  38. # Set the rotation speed in radians per second
  39. angular_speed = 0.5
  40. # Set the angular tolerance in degrees converted to radians
  41. angular_tolerance = radians(1.0)
  42. # Set the rotation angle to Pi radians (180 degrees)
  43. goal_angle = pi
  44. # Initialize the tf listener
  45. self.tf_listener = tf.TransformListener()
  46. # Give tf some time to fill its buffer
  47. rospy.sleep(2)
  48. # Set the odom frame
  49. self.odom_frame = '/odom'
  50. # Find out if the robot uses /base_link or /base_footprint
  51. try:
  52. self.tf_listener.waitForTransform(self.odom_frame, '/base_footprint', rospy.Time(), rospy.Duration(1.0))
  53. self.base_frame = '/base_footprint'
  54. except (tf.Exception, tf.ConnectivityException, tf.LookupException):
  55. try:
  56. self.tf_listener.waitForTransform(self.odom_frame, '/base_link', rospy.Time(), rospy.Duration(1.0))
  57. self.base_frame = '/base_link'
  58. except (tf.Exception, tf.ConnectivityException, tf.LookupException):
  59. rospy.loginfo("Cannot find transform between /odom and /base_link or /base_footprint")
  60. rospy.signal_shutdown("tf Exception")
  61. # Initialize the position variable as a Point type
  62. position = Point()
  63. # Loop once for each leg of the trip
  64. for i in range(2):
  65. # Initialize the movement command
  66. move_cmd = Twist()
  67. # Set the movement command to forward motion
  68. move_cmd.linear.x = linear_speed
  69. # Get the starting position values
  70. (position, rotation) = self.get_odom()
  71. x_start = position.x
  72. y_start = position.y
  73. # Keep track of the distance traveled
  74. distance = 0
  75. # Enter the loop to move along a side
  76. while distance < goal_distance and not rospy.is_shutdown():
  77. # Publish the Twist message and sleep 1 cycle
  78. self.cmd_vel.publish(move_cmd)
  79. r.sleep()
  80. # Get the current position
  81. (position, rotation) = self.get_odom()
  82. # Compute the Euclidean distance from the start
  83. distance = sqrt(pow((position.x - x_start), 2) +
  84. pow((position.y - y_start), 2))
  85. # Stop the robot before the rotation
  86. move_cmd = Twist()
  87. self.cmd_vel.publish(move_cmd)
  88. rospy.sleep(1)
  89. # Set the movement command to a rotation
  90. move_cmd.angular.z = angular_speed
  91. # Track the last angle measured
  92. last_angle = rotation
  93. # Track how far we have turned
  94. turn_angle = 0
  95. while abs(turn_angle + angular_tolerance) < abs(goal_angle) and not rospy.is_shutdown():
  96. # Publish the Twist message and sleep 1 cycle
  97. self.cmd_vel.publish(move_cmd)
  98. r.sleep()
  99. # Get the current rotation
  100. (position, rotation) = self.get_odom()
  101. # Compute the amount of rotation since the last loop
  102. delta_angle = normalize_angle(rotation - last_angle)
  103. # Add to the running total
  104. turn_angle += delta_angle
  105. last_angle = rotation
  106. # Stop the robot before the next leg
  107. move_cmd = Twist()
  108. self.cmd_vel.publish(move_cmd)
  109. rospy.sleep(1)
  110. # Stop the robot for good
  111. self.cmd_vel.publish(Twist())
  112. def get_odom(self):
  113. # Get the current transform between the odom and base frames
  114. try:
  115. (trans, rot) = self.tf_listener.lookupTransform(self.odom_frame, self.base_frame, rospy.Time(0))
  116. except (tf.Exception, tf.ConnectivityException, tf.LookupException):
  117. rospy.loginfo("TF Exception")
  118. return
  119. return (Point(*trans), quat_to_angle(Quaternion(*rot)))
  120. def shutdown(self):
  121. # Always stop the robot when shutting down the node.
  122. rospy.loginfo("Stopping the robot...")
  123. self.cmd_vel.publish(Twist())
  124. rospy.sleep(1)
  125. if __name__ == '__main__':
  126. try:
  127. OutAndBack()
  128. except:
  129. rospy.loginfo("Out-and-Back node terminated.")