22 from typing
import Optional
24 from action_msgs.msg
import GoalStatus
25 from geometry_msgs.msg
import Pose
26 from geometry_msgs.msg
import PoseStamped
27 from geometry_msgs.msg
import PoseWithCovarianceStamped
28 from lifecycle_msgs.srv
import GetState
29 from nav2_msgs.action
import NavigateToPose
30 from nav2_msgs.srv
import ManageLifecycleNodes
34 from rclpy.action
import ActionClient
35 from rclpy.node
import Node
36 from rclpy.qos
import QoSDurabilityPolicy, QoSHistoryPolicy, QoSReliabilityPolicy
37 from rclpy.qos
import QoSProfile
42 def __init__(self, initial_pose: Pose, goal_pose: Pose, namespace: str =
''):
43 super().__init__(node_name=
'nav2_tester', namespace=namespace)
45 PoseWithCovarianceStamped,
'initialpose', 10
47 self.
goal_pubgoal_pub = self.create_publisher(PoseStamped,
'goal_pose', 10)
49 pose_qos = QoSProfile(
50 durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
51 reliability=QoSReliabilityPolicy.RELIABLE,
52 history=QoSHistoryPolicy.KEEP_LAST,
57 PoseWithCovarianceStamped,
'amcl_pose', self.
poseCallbackposeCallback, pose_qos
62 self.
action_clientaction_client = ActionClient(self, NavigateToPose,
'navigate_to_pose')
64 def info_msg(self, msg: str):
65 self.get_logger().info(
'\033[1;37;44m' + msg +
'\033[0m')
67 def warn_msg(self, msg: str):
68 self.get_logger().warn(
'\033[1;37;43m' + msg +
'\033[0m')
70 def error_msg(self, msg: str):
71 self.get_logger().error(
'\033[1;37;41m' + msg +
'\033[0m')
73 def setInitialPose(self):
74 msg = PoseWithCovarianceStamped()
76 msg.header.frame_id =
'map'
77 self.
info_msginfo_msg(
'Publishing Initial Pose')
81 def getStampedPoseMsg(self, pose: Pose):
83 msg.header.frame_id =
'map'
87 def publishGoalPose(self, goal_pose: Optional[Pose] =
None):
88 self.
goal_posegoal_pose = goal_pose
if goal_pose
is not None else self.
goal_posegoal_pose
91 def runNavigateAction(self, goal_pose: Optional[Pose] =
None):
93 self.
info_msginfo_msg(
"Waiting for 'NavigateToPose' action server")
94 while not self.
action_clientaction_client.wait_for_server(timeout_sec=1.0):
95 self.
info_msginfo_msg(
"'NavigateToPose' action server not available, waiting...")
97 self.
goal_posegoal_pose = goal_pose
if goal_pose
is not None else self.
goal_posegoal_pose
98 goal_msg = NavigateToPose.Goal()
101 self.
info_msginfo_msg(
'Sending goal request...')
102 send_goal_future = self.
action_clientaction_client.send_goal_async(goal_msg)
104 rclpy.spin_until_future_complete(self, send_goal_future)
105 goal_handle = send_goal_future.result()
107 if not goal_handle.accepted:
111 self.
info_msginfo_msg(
'Goal accepted')
112 get_result_future = goal_handle.get_result_async()
116 self.
info_msginfo_msg(
"Waiting for 'NavigateToPose' action to complete")
117 rclpy.spin_until_future_complete(self, get_result_future)
118 status = get_result_future.result().status
119 if status != GoalStatus.STATUS_SUCCEEDED:
120 self.
info_msginfo_msg(f
'Goal failed with status code: {status}')
123 if not future_return:
126 self.
info_msginfo_msg(
'Goal succeeded!')
129 def poseCallback(self, msg):
130 self.
info_msginfo_msg(
'Received amcl_pose')
134 def reachesGoal(self, timeout, distance):
136 start_time = time.time()
138 while not goalReached:
139 rclpy.spin_once(self, timeout_sec=1)
142 self.
info_msginfo_msg(
'*** GOAL REACHED ***')
144 elif timeout
is not None:
145 if (time.time() - start_time) > timeout:
146 self.
error_msgerror_msg(
'Robot timed out reaching its goal!')
149 def distanceFromGoal(self):
152 distance = math.sqrt(d_x * d_x + d_y * d_y)
153 self.
info_msginfo_msg(f
'Distance from goal is: {distance}')
156 def wait_for_node_active(self, node_name: str):
158 self.
info_msginfo_msg(f
'Waiting for {node_name} to become active')
159 node_service = f
'{node_name}/get_state'
160 state_client = self.create_client(GetState, node_service)
161 while not state_client.wait_for_service(timeout_sec=1.0):
162 self.
info_msginfo_msg(f
'{node_service} service not available, waiting...')
163 req = GetState.Request()
165 while state !=
'active':
166 self.
info_msginfo_msg(f
'Getting {node_name} state...')
167 future = state_client.call_async(req)
168 rclpy.spin_until_future_complete(self, future)
169 if future.result()
is not None:
170 state = future.result().current_state.label
171 self.
info_msginfo_msg(f
'Result of get_state: {state}')
174 f
'Exception while calling service: {future.exception()!r}'
179 self.
info_msginfo_msg(
'Shutting down')
182 transition_service =
'lifecycle_manager_navigation/manage_nodes'
183 mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
184 while not mgr_client.wait_for_service(timeout_sec=1.0):
185 self.
info_msginfo_msg(f
'{transition_service} service not available, waiting...')
187 req = ManageLifecycleNodes.Request()
188 req.command = ManageLifecycleNodes.Request().SHUTDOWN
189 future = mgr_client.call_async(req)
191 self.
info_msginfo_msg(
'Shutting down navigation lifecycle manager...')
192 rclpy.spin_until_future_complete(self, future)
194 self.
info_msginfo_msg(
'Shutting down navigation lifecycle manager complete.')
195 except Exception
as e:
196 self.
error_msgerror_msg(f
'Service call failed {e!r}')
197 transition_service =
'lifecycle_manager_localization/manage_nodes'
198 mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
199 while not mgr_client.wait_for_service(timeout_sec=1.0):
200 self.
info_msginfo_msg(f
'{transition_service} service not available, waiting...')
202 req = ManageLifecycleNodes.Request()
203 req.command = ManageLifecycleNodes.Request().SHUTDOWN
204 future = mgr_client.call_async(req)
206 self.
info_msginfo_msg(
'Shutting down localization lifecycle manager...')
207 rclpy.spin_until_future_complete(self, future)
209 self.
info_msginfo_msg(
'Shutting down localization lifecycle manager complete')
210 except Exception
as e:
211 self.
error_msgerror_msg(f
'Service call failed {e!r}')
213 def wait_for_initial_pose(self):
216 self.
info_msginfo_msg(
'Setting initial pose')
218 self.
info_msginfo_msg(
'Waiting for amcl_pose to be received')
219 rclpy.spin_once(self, timeout_sec=1)
222 def test_RobotMovesToGoal(robot_tester):
223 robot_tester.info_msg(
'Setting goal pose')
224 robot_tester.publishGoalPose()
225 robot_tester.info_msg(
'Waiting 60 seconds for robot to reach goal')
226 return robot_tester.reachesGoal(timeout=60, distance=0.5)
229 def run_all_tests(robot_tester):
233 robot_tester.wait_for_node_active(
'amcl')
234 robot_tester.wait_for_initial_pose()
235 robot_tester.wait_for_node_active(
'bt_navigator')
236 result = robot_tester.runNavigateAction()
239 result = test_RobotMovesToGoal(robot_tester)
244 robot_tester.info_msg(
'Test PASSED')
246 robot_tester.error_msg(
'Test FAILED')
251 def fwd_pose(x=0.0, y=0.0, z=0.01):
252 initial_pose = Pose()
253 initial_pose.position.x = x
254 initial_pose.position.y = y
255 initial_pose.position.z = z
256 initial_pose.orientation.x = 0.0
257 initial_pose.orientation.y = 0.0
258 initial_pose.orientation.z = 0.0
259 initial_pose.orientation.w = 1.0
263 def get_testers(args):
268 init_x, init_y, final_x, final_y = args.robot[0]
270 initial_pose=fwd_pose(float(init_x), float(init_y)),
271 goal_pose=fwd_pose(float(final_x), float(final_y)),
274 'Starting tester, robot going from '
284 testers.append(tester)
288 for robot
in args.robots:
289 namespace, init_x, init_y, final_x, final_y = robot
292 initial_pose=fwd_pose(float(init_x), float(init_y)),
293 goal_pose=fwd_pose(float(final_x), float(final_y)),
296 'Starting tester for '
307 testers.append(tester)
311 def check_args(expect_failure: str):
313 if expect_failure !=
'True' and expect_failure !=
'False':
315 '\033[1;37;41m' +
' -e flag must be set to True or False only. ' +
'\033[0m'
319 return eval(expect_failure)
322 def main(argv=sys.argv[1:]):
324 parser = argparse.ArgumentParser(description=
'System-level navigation tester node')
325 parser.add_argument(
'-e',
'--expect_failure')
326 group = parser.add_mutually_exclusive_group(required=
True)
332 metavar=(
'init_x',
'init_y',
'final_x',
'final_y'),
333 help=
'The robot starting and final positions.',
340 metavar=(
'name',
'init_x',
'init_y',
'final_x',
'final_y'),
341 help=
"The robot's namespace and starting and final positions. "
342 +
'Repeating the argument for multiple robots is supported.',
345 args, unknown = parser.parse_known_args()
347 expect_failure = check_args(args.expect_failure)
352 testers = get_testers(args)
357 for tester
in testers:
358 passed = run_all_tests(tester)
359 if passed != expect_failure:
362 for tester
in testers:
366 testers[0].info_msg(
'Done Shutting Down.')
368 if passed != expect_failure:
369 testers[0].info_msg(
'Exiting failed')
372 testers[0].info_msg(
'Exiting passed')
376 if __name__ ==
'__main__':
def info_msg(self, str msg)
def distanceFromGoal(self)
def error_msg(self, str msg)
def poseCallback(self, msg)
def getStampedPoseMsg(self, Pose pose)