23 from typing
import Optional
25 from action_msgs.msg
import GoalStatus
27 from lifecycle_msgs.srv
import GetState
28 from nav2_msgs.action
import NavigateToPose
30 from nav2_msgs.srv
import ManageLifecycleNodes
33 from rclpy.action
import ActionClient
34 from rclpy.node
import Node
35 from rclpy.qos
import QoSDurabilityPolicy, QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy
36 from sensor_msgs.msg
import PointCloud2
46 def __init__(self, filter_mask: OccupancyGrid):
47 self.filter_mask: OccupancyGrid = filter_mask
52 def worldToMap(self, wx: float, wy: float) -> tuple[int, int]:
53 origin_x = self.filter_mask.info.origin.position.x
54 origin_y = self.filter_mask.info.origin.position.y
55 size_x = self.filter_mask.info.width
56 size_y = self.filter_mask.info.height
57 resolution = self.filter_mask.info.resolution
59 if wx < origin_x
or wy < origin_y:
62 mx = int((wx - origin_x) / resolution)
63 my = int((wy - origin_y) / resolution)
65 if mx < size_x
and my < size_y:
71 def getValue(self, mx: int, my: int):
72 size_x = self.filter_mask.info.width
73 return self.filter_mask.data[mx + my * size_x]
84 super().__init__(node_name=
'nav2_tester', namespace=namespace)
86 PoseWithCovarianceStamped,
'initialpose', 10
88 self.
goal_pubgoal_pub = self.create_publisher(PoseStamped,
'goal_pose', 10)
90 transient_local_qos = QoSProfile(
91 durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
92 reliability=QoSReliabilityPolicy.RELIABLE,
93 history=QoSHistoryPolicy.KEEP_LAST,
97 volatile_qos = QoSProfile(
98 durability=QoSDurabilityPolicy.VOLATILE,
99 reliability=QoSReliabilityPolicy.RELIABLE,
100 history=QoSHistoryPolicy.KEEP_LAST,
105 PoseWithCovarianceStamped,
112 'local_costmap/clearing_endpoints',
123 if self.
test_typetest_type == TestType.KEEPOUT:
124 self.
plan_subplan_sub = self.create_subscription(
125 Path,
'plan', self.
planCallbackplanCallback, volatile_qos
136 elif self.
test_typetest_type == TestType.SPEED:
139 self.
limitslimits = [50.0, 0.0]
142 self.
plan_subplan_sub = self.create_subscription(
147 self.
mask_submask_sub = self.create_subscription(
148 OccupancyGrid,
'filter_mask', self.
maskCallbackmaskCallback, transient_local_qos
154 self.
action_clientaction_client = ActionClient(self, NavigateToPose,
'navigate_to_pose')
156 def info_msg(self, msg: str) ->
None:
157 self.get_logger().info(
'\033[1;37;44m' + msg +
'\033[0m')
159 def warn_msg(self, msg: str) ->
None:
160 self.get_logger().warn(
'\033[1;37;43m' + msg +
'\033[0m')
162 def error_msg(self, msg: str) ->
None:
163 self.get_logger().error(
'\033[1;37;41m' + msg +
'\033[0m')
165 def setInitialPose(self) -> None:
166 msg = PoseWithCovarianceStamped()
168 msg.header.frame_id =
'map'
173 def getStampedPoseMsg(self, pose: Pose) -> PoseStamped:
175 msg.header.frame_id =
'map'
179 def publishGoalPose(self, goal_pose: Optional[Pose] =
None) ->
None:
180 self.
goal_posegoal_pose = goal_pose
if goal_pose
is not None else self.
goal_posegoal_pose
183 def runNavigateAction(self, goal_pose: Optional[Pose] =
None) -> bool:
186 while not self.
action_clientaction_client.wait_for_server(timeout_sec=1.0):
187 self.
info_msginfo_msginfo_msg(
"'NavigateToPose' action server not available, waiting...")
189 self.
goal_posegoal_pose = goal_pose
if goal_pose
is not None else self.
goal_posegoal_pose
190 goal_msg = NavigateToPose.Goal()
194 send_goal_future = self.
action_clientaction_client.send_goal_async(goal_msg)
196 rclpy.spin_until_future_complete(self, send_goal_future)
197 goal_handle = send_goal_future.result()
199 if not goal_handle
or not goal_handle.accepted:
204 get_result_future = goal_handle.get_result_async()
206 self.
info_msginfo_msginfo_msg(
"Waiting for 'NavigateToPose' action to complete")
207 rclpy.spin_until_future_complete(self, get_result_future)
208 status = get_result_future.result().status
209 if status != GoalStatus.STATUS_SUCCEEDED:
216 def isInKeepout(self, x: float, y: float) -> bool:
217 mx, my = self.
filter_maskfilter_mask.worldToMap(x, y)
218 if mx == -1
and my == -1:
220 if self.
filter_maskfilter_mask.getValue(mx, my) == 100:
225 def checkKeepout(self, x: float, y: float) -> bool:
241 def checkSpeed(self, it: int, speed_limit: float) ->
None:
242 if it >= len(self.
limitslimits):
246 if speed_limit == self.
limitslimits[it]:
250 'Incorrect speed limit received: '
252 +
', but should be: '
253 + str(self.
limitslimits[it])
256 def poseCallback(self, msg: PoseWithCovarianceStamped) ->
None:
260 if self.
test_typetest_type == TestType.KEEPOUT:
262 msg.pose.pose.position.x, msg.pose.pose.position.y
266 def planCallback(self, msg: Path) ->
None:
268 for pose
in msg.poses:
269 if not self.
checkKeepoutcheckKeepout(pose.pose.position.x, pose.pose.position.y):
273 def clearingEndpointsCallback(self, msg: PointCloud2) ->
None:
274 if len(msg.data) > 0:
277 def voxelMarkedCallback(self, msg: PointCloud2) ->
None:
278 if len(msg.data) > 0:
281 def voxelUnknownCallback(self, msg: PointCloud2) ->
None:
282 if len(msg.data) > 0:
285 def dwbCostCloudCallback(self, msg: PointCloud2) ->
None:
287 if len(msg.data) > 0:
290 def speedLimitCallback(self, msg: SpeedLimit) ->
None:
295 def maskCallback(self, msg: OccupancyGrid) ->
None:
300 def wait_for_filter_mask(self, timeout: float) -> bool:
301 start_time = time.time()
305 rclpy.spin_once(self, timeout_sec=1)
306 if (time.time() - start_time) > timeout:
311 def wait_for_pointcloud_subscribers(self, timeout: float) -> bool:
312 start_time = time.time()
319 'Waiting for voxel_marked_cloud/voxel_unknown_cloud/\
320 clearing_endpoints msg to be received ...'
322 rclpy.spin_once(self, timeout_sec=1)
323 if (time.time() - start_time) > timeout:
325 'Time out to waiting for voxel_marked_cloud/voxel_unknown_cloud/\
326 clearing_endpoints msgs'
331 def reachesGoal(self, timeout: float, distance: float) -> bool:
333 start_time = time.time()
335 while not goalReached:
336 rclpy.spin_once(self, timeout_sec=1)
341 elif timeout
is not None:
342 if (time.time() - start_time) > timeout:
349 def distanceFromGoal(self) -> float:
352 distance = math.sqrt(d_x * d_x + d_y * d_y)
356 def wait_for_node_active(self, node_name: str) ->
None:
359 node_service = f
'{node_name}/get_state'
360 state_client = self.create_client(GetState, node_service)
361 while not state_client.wait_for_service(timeout_sec=1.0):
362 self.
info_msginfo_msginfo_msg(f
'{node_service} service not available, waiting...')
363 req = GetState.Request()
365 while state !=
'active':
367 future = state_client.call_async(req)
368 rclpy.spin_until_future_complete(self, future)
369 if future.result()
is not None:
370 state = future.result().current_state.label
374 f
'Exception while calling service: {future.exception()!r}'
378 def shutdown(self) -> None:
382 transition_service =
'lifecycle_manager_navigation/manage_nodes'
383 mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
384 while not mgr_client.wait_for_service(timeout_sec=1.0):
385 self.
info_msginfo_msginfo_msg(f
'{transition_service} service not available, waiting...')
387 req = ManageLifecycleNodes.Request()
388 req.command = ManageLifecycleNodes.Request().SHUTDOWN
389 future = mgr_client.call_async(req)
391 self.
info_msginfo_msginfo_msg(
'Shutting down navigation lifecycle manager...')
392 rclpy.spin_until_future_complete(self, future)
394 self.
info_msginfo_msginfo_msg(
'Shutting down navigation lifecycle manager complete.')
395 except Exception
as e:
397 transition_service =
'lifecycle_manager_localization/manage_nodes'
398 mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
399 while not mgr_client.wait_for_service(timeout_sec=1.0):
400 self.
info_msginfo_msginfo_msg(f
'{transition_service} service not available, waiting...')
402 req = ManageLifecycleNodes.Request()
403 req.command = ManageLifecycleNodes.Request().SHUTDOWN
404 future = mgr_client.call_async(req)
406 self.
info_msginfo_msginfo_msg(
'Shutting down localization lifecycle manager...')
407 rclpy.spin_until_future_complete(self, future)
409 self.
info_msginfo_msginfo_msg(
'Shutting down localization lifecycle manager complete')
410 except Exception
as e:
413 def wait_for_initial_pose(self) -> None:
419 rclpy.spin_once(self, timeout_sec=1)
422 def test_RobotMovesToGoal(robot_tester: NavTester) -> bool:
423 robot_tester.info_msg(
'Setting goal pose')
424 robot_tester.publishGoalPose()
425 robot_tester.info_msg(
'Waiting 60 seconds for robot to reach goal')
426 return robot_tester.reachesGoal(timeout=60, distance=0.5)
434 def test_SpeedLimitsAllCorrect(robot_tester: NavTester) -> bool:
435 if not robot_tester.filter_test_result:
437 for passed
in robot_tester.limit_passed:
439 robot_tester.error_msg(
'Did not meet one of the speed limit')
444 def run_all_tests(robot_tester: NavTester) -> bool:
448 robot_tester.wait_for_node_active(
'amcl')
449 robot_tester.wait_for_initial_pose()
450 robot_tester.wait_for_node_active(
'bt_navigator')
451 result = robot_tester.wait_for_filter_mask(10)
453 result = robot_tester.runNavigateAction()
455 if robot_tester.test_type == TestType.KEEPOUT:
456 result = result
and robot_tester.wait_for_pointcloud_subscribers(10)
459 result = test_RobotMovesToGoal(robot_tester)
462 if robot_tester.test_type == TestType.KEEPOUT:
463 result = robot_tester.filter_test_result
464 result = result
and robot_tester.cost_cloud_received
465 elif robot_tester.test_type == TestType.SPEED:
466 result = test_SpeedLimitsAllCorrect(robot_tester)
471 robot_tester.info_msg(
'Test PASSED')
473 robot_tester.error_msg(
'Test FAILED')
478 def fwd_pose(x: float = 0.0, y: float = 0.0, z: float = 0.01) -> Pose:
479 initial_pose = Pose()
480 initial_pose.position.x = x
481 initial_pose.position.y = y
482 initial_pose.position.z = z
483 initial_pose.orientation.x = 0.0
484 initial_pose.orientation.y = 0.0
485 initial_pose.orientation.z = 0.0
486 initial_pose.orientation.w = 1.0
490 def get_tester(args: argparse.Namespace) -> NavTester:
494 init_x, init_y, final_x, final_y = args.robot[0]
495 test_type = TestType.KEEPOUT
496 if type_str ==
'speed':
497 test_type = TestType.SPEED
501 initial_pose=fwd_pose(float(init_x), float(init_y)),
502 goal_pose=fwd_pose(float(final_x), float(final_y)),
505 'Starting tester, robot going from '
518 def main(argv: list[str] = sys.argv[1:]):
520 parser = argparse.ArgumentParser(
521 description=
'System-level costmap filters tester node'
529 help=
'Type of costmap filter being tested.',
531 group = parser.add_mutually_exclusive_group(required=
True)
537 metavar=(
'init_x',
'init_y',
'final_x',
'final_y'),
538 help=
'The robot starting and final positions.',
541 args, unknown = parser.parse_known_args()
546 tester = get_tester(args)
551 passed = run_all_tests(tester)
555 tester.info_msg(
'Done Shutting Down.')
558 tester.info_msg(
'Exiting failed')
561 tester.info_msg(
'Exiting passed')
565 if __name__ ==
'__main__':
PoseStamped getStampedPoseMsg(self, Pose pose)
clearing_endpoints_received
None voxelUnknownCallback(self, PointCloud2 msg)
None checkSpeed(self, int it, float speed_limit)
None setInitialPose(self)
bool isInKeepout(self, float x, float y)
None clearingEndpointsCallback(self, PointCloud2 msg)
None poseCallback(self, PoseWithCovarianceStamped msg)
float distanceFromGoal(self)
None warn_msg(self, str msg)
None maskCallback(self, OccupancyGrid msg)
None dwbCostCloudCallback(self, PointCloud2 msg)
None voxelMarkedCallback(self, PointCloud2 msg)
None speedLimitCallback(self, SpeedLimit msg)
None planCallback(self, Path msg)
None error_msg(self, str msg)
bool checkKeepout(self, float x, float y)
None info_msg(self, str msg)