nav_test.py 8.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205
  1. #!/usr/bin/env python
  2. """ nav_test.py - Version 1.1 2013-12-20
  3. Command a robot to move autonomously among a number of goal locations defined in the map frame.
  4. On each round, select a new random sequence of locations, then attempt to move to each location
  5. in succession. Keep track of success rate, time elapsed, and total distance traveled.
  6. Created for the Pi Robot Project: http://www.pirobot.org
  7. Copyright (c) 2012 Patrick Goebel. All rights reserved.
  8. This program is free software; you can redistribute it and/or modify
  9. it under the terms of the GNU General Public License as published by
  10. the Free Software Foundation; either version 2 of the License, or
  11. (at your option) any later version.5
  12. This program is distributed in the hope that it will be useful,
  13. but WITHOUT ANY WARRANTY; without even the implied warranty of
  14. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  15. GNU General Public License for more details at:
  16. http://www.gnu.org/licenses/gpl.html
  17. """
  18. import rospy
  19. import actionlib
  20. from actionlib_msgs.msg import *
  21. from geometry_msgs.msg import Pose, PoseWithCovarianceStamped, Point, Quaternion, Twist
  22. from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
  23. from random import sample
  24. from math import pow, sqrt
  25. class NavTest():
  26. def __init__(self):
  27. rospy.init_node('nav_test', anonymous=True)
  28. rospy.on_shutdown(self.shutdown)
  29. # How long in seconds should the robot pause at each location?
  30. self.rest_time = rospy.get_param("~rest_time", 10)
  31. # Are we running in the fake simulator?
  32. self.fake_test = rospy.get_param("~fake_test", False)
  33. # Goal state return values
  34. goal_states = ['PENDING', 'ACTIVE', 'PREEMPTED',
  35. 'SUCCEEDED', 'ABORTED', 'REJECTED',
  36. 'PREEMPTING', 'RECALLING', 'RECALLED',
  37. 'LOST']
  38. # Set up the goal locations. Poses are defined in the map frame.
  39. # An easy way to find the pose coordinates is to point-and-click
  40. # Nav Goals in RViz when running in the simulator.
  41. # Pose coordinates are then displayed in the terminal
  42. # that was used to launch RViz.
  43. locations = dict()
  44. locations['hall_foyer'] = Pose(Point(0.643, 4.720, 0.000), Quaternion(0.000, 0.000, 0.223, 0.975))
  45. locations['hall_kitchen'] = Pose(Point(-1.994, 4.382, 0.000), Quaternion(0.000, 0.000, -0.670, 0.743))
  46. locations['hall_bedroom'] = Pose(Point(-3.719, 4.401, 0.000), Quaternion(0.000, 0.000, 0.733, 0.680))
  47. locations['living_room_1'] = Pose(Point(0.720, 2.229, 0.000), Quaternion(0.000, 0.000, 0.786, 0.618))
  48. locations['living_room_2'] = Pose(Point(1.471, 1.007, 0.000), Quaternion(0.000, 0.000, 0.480, 0.877))
  49. locations['dining_room_1'] = Pose(Point(-0.861, -0.019, 0.000), Quaternion(0.000, 0.000, 0.892, -0.451))
  50. # Publisher to manually control the robot (e.g. to stop it, queue_size=5)
  51. self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=5)
  52. # Subscribe to the move_base action server
  53. self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
  54. rospy.loginfo("Waiting for move_base action server...")
  55. # Wait 60 seconds for the action server to become available
  56. self.move_base.wait_for_server(rospy.Duration(60))
  57. rospy.loginfo("Connected to move base server")
  58. # A variable to hold the initial pose of the robot to be set by
  59. # the user in RViz
  60. initial_pose = PoseWithCovarianceStamped()
  61. # Variables to keep track of success rate, running time,
  62. # and distance traveled
  63. n_locations = len(locations)
  64. n_goals = 0
  65. n_successes = 0
  66. i = n_locations
  67. distance_traveled = 0
  68. start_time = rospy.Time.now()
  69. running_time = 0
  70. location = ""
  71. last_location = ""
  72. # Get the initial pose from the user
  73. rospy.loginfo("*** Click the 2D Pose Estimate button in RViz to set the robot's initial pose...")
  74. rospy.wait_for_message('initialpose', PoseWithCovarianceStamped)
  75. self.last_location = Pose()
  76. rospy.Subscriber('initialpose', PoseWithCovarianceStamped, self.update_initial_pose)
  77. # Make sure we have the initial pose
  78. while initial_pose.header.stamp == "":
  79. rospy.sleep(1)
  80. rospy.loginfo("Starting navigation test")
  81. # Begin the main loop and run through a sequence of locations
  82. while not rospy.is_shutdown():
  83. # If we've gone through the current sequence,
  84. # start with a new random sequence
  85. if i == n_locations:
  86. i = 0
  87. sequence = sample(locations, n_locations)
  88. # Skip over first location if it is the same as
  89. # the last location
  90. if sequence[0] == last_location:
  91. i = 1
  92. # Get the next location in the current sequence
  93. location = sequence[i]
  94. # Keep track of the distance traveled.
  95. # Use updated initial pose if available.
  96. if initial_pose.header.stamp == "":
  97. distance = sqrt(pow(locations[location].position.x -
  98. locations[last_location].position.x, 2) +
  99. pow(locations[location].position.y -
  100. locations[last_location].position.y, 2))
  101. else:
  102. rospy.loginfo("Updating current pose.")
  103. distance = sqrt(pow(locations[location].position.x -
  104. initial_pose.pose.pose.position.x, 2) +
  105. pow(locations[location].position.y -
  106. initial_pose.pose.pose.position.y, 2))
  107. initial_pose.header.stamp = ""
  108. # Store the last location for distance calculations
  109. last_location = location
  110. # Increment the counters
  111. i += 1
  112. n_goals += 1
  113. # Set up the next goal location
  114. self.goal = MoveBaseGoal()
  115. self.goal.target_pose.pose = locations[location]
  116. self.goal.target_pose.header.frame_id = 'map'
  117. self.goal.target_pose.header.stamp = rospy.Time.now()
  118. # Let the user know where the robot is going next
  119. rospy.loginfo("Going to: " + str(location))
  120. # Start the robot toward the next location
  121. self.move_base.send_goal(self.goal)
  122. # Allow 5 minutes to get there
  123. finished_within_time = self.move_base.wait_for_result(rospy.Duration(300))
  124. # Check for success or failure
  125. if not finished_within_time:
  126. self.move_base.cancel_goal()
  127. rospy.loginfo("Timed out achieving goal")
  128. else:
  129. state = self.move_base.get_state()
  130. if state == GoalStatus.SUCCEEDED:
  131. rospy.loginfo("Goal succeeded!")
  132. n_successes += 1
  133. distance_traveled += distance
  134. rospy.loginfo("State:" + str(state))
  135. else:
  136. rospy.loginfo("Goal failed with error code: " + str(goal_states[state]))
  137. # How long have we been running?
  138. running_time = rospy.Time.now() - start_time
  139. running_time = running_time.secs / 60.0
  140. # Print a summary success/failure, distance traveled and time elapsed
  141. rospy.loginfo("Success so far: " + str(n_successes) + "/" +
  142. str(n_goals) + " = " +
  143. str(100 * n_successes/n_goals) + "%")
  144. rospy.loginfo("Running time: " + str(trunc(running_time, 1)) +
  145. " min Distance: " + str(trunc(distance_traveled, 1)) + " m")
  146. rospy.sleep(self.rest_time)
  147. def update_initial_pose(self, initial_pose):
  148. self.initial_pose = initial_pose
  149. def shutdown(self):
  150. rospy.loginfo("Stopping the robot...")
  151. self.move_base.cancel_goal()
  152. rospy.sleep(2)
  153. self.cmd_vel_pub.publish(Twist())
  154. rospy.sleep(1)
  155. def trunc(f, n):
  156. # Truncates/pads a float f to n decimal places without rounding
  157. slen = len('%.*f' % (n, f))
  158. return float(str(f)[:slen])
  159. if __name__ == '__main__':
  160. try:
  161. NavTest()
  162. rospy.spin()
  163. except rospy.ROSInterruptException:
  164. rospy.loginfo("AMCL navigation test finished.")