timed_out_and_back.py 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115
  1. #!/usr/bin/env python
  2. """ timed_out_and_back.py - Version 1.2 2014-12-14
  3. A basic demo of the using odometry data to move the robot along
  4. and out-and-back trajectory.
  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
  19. from math import pi
  20. class OutAndBack():
  21. def __init__(self):
  22. # Give the node a name
  23. rospy.init_node('out_and_back', anonymous=False)
  24. # Set rospy to execute a shutdown function when exiting
  25. rospy.on_shutdown(self.shutdown)
  26. # Publisher to control the robot's speed
  27. self.cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=1)
  28. # How fast will we update the robot's movement?
  29. rate = 50
  30. # Set the equivalent ROS rate variable
  31. r = rospy.Rate(rate)
  32. # Set the forward linear speed to 0.2 meters per second
  33. linear_speed = 0.2
  34. # Set the travel distance to 1.0 meters
  35. goal_distance = 1.0
  36. # How long should it take us to get there?
  37. linear_duration = goal_distance / linear_speed
  38. # Set the rotation speed to 1.0 radians per second
  39. angular_speed = 1.0
  40. # Set the rotation angle to Pi radians (180 degrees)
  41. goal_angle = pi
  42. # How long should it take to rotate?
  43. angular_duration = goal_angle / angular_speed
  44. # Loop through the two legs of the trip
  45. for i in range(2):
  46. # Initialize the movement command
  47. move_cmd = Twist()
  48. # Set the forward speed
  49. move_cmd.linear.x = linear_speed
  50. # Move forward for a time to go the desired distance
  51. ticks = int(linear_duration * rate)
  52. for t in range(ticks):
  53. self.cmd_vel.publish(move_cmd)
  54. r.sleep()
  55. # Stop the robot before the rotation
  56. move_cmd = Twist()
  57. self.cmd_vel.publish(move_cmd)
  58. rospy.sleep(1)
  59. # Now rotate left roughly 180 degrees
  60. # Set the angular speed
  61. move_cmd.angular.z = angular_speed
  62. # Rotate for a time to go 180 degrees
  63. ticks = int(goal_angle * rate)
  64. for t in range(ticks):
  65. self.cmd_vel.publish(move_cmd)
  66. r.sleep()
  67. # Stop the robot before the next leg
  68. move_cmd = Twist()
  69. self.cmd_vel.publish(move_cmd)
  70. rospy.sleep(1)
  71. # Stop the robot
  72. self.cmd_vel.publish(Twist())
  73. def shutdown(self):
  74. # Always stop the robot when shutting down the node.
  75. rospy.loginfo("Stopping the robot...")
  76. self.cmd_vel.publish(Twist())
  77. rospy.sleep(1)
  78. if __name__ == '__main__':
  79. try:
  80. OutAndBack()
  81. except:
  82. rospy.loginfo("Out-and-Back node terminated.")