Skip to content

Commit b4d41fd

Browse files
Added nav2_msgs path fixes to mypy compliance.
Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com>
1 parent 0c53bb5 commit b4d41fd

File tree

4 files changed

+42
-39
lines changed

4 files changed

+42
-39
lines changed

‎nav2_docking/opennav_docking/test/test_docking_server.py‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -200,12 +200,12 @@ def publish_odometry(self, odom_to_base_link: TransformStamped) -> None:
200200
odom.twist.twist = self.command
201201
self.odom_pub.publish(odom)
202202

203-
def action_feedback_callback(self, msg: DockRobot.Feedback) -> None:
203+
def action_feedback_callback(self, msg: DockRobot.Impl.FeedbackMessage) -> None:
204204
# Force the docking action to run a full recovery loop and then
205205
# make contact with the dock (based on pose of robot) before
206206
# we report that the robot is charging
207207
if msg.feedback.num_retries > 0 and \
208-
msg.feedback.state == msg.feedback.WAIT_FOR_CHARGE:
208+
msg.feedback.state == DockRobot.Feedback.WAIT_FOR_CHARGE:
209209
self.is_charging = True
210210

211211
def nav_execute_callback(

‎nav2_simple_commander/nav2_simple_commander/robot_navigator.py‎

Lines changed: 35 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -28,11 +28,11 @@
2828
ComputePathThroughPoses, ComputePathToPose, ComputeRoute, DockRobot,
2929
DriveOnHeading, FollowGPSWaypoints, FollowPath, FollowWaypoints,
3030
NavigateThroughPoses, NavigateToPose, SmoothPath, Spin, UndockRobot)
31-
from nav2_msgs.msg import Route
31+
from nav2_msgs.msg import Costmap, Route
3232
from nav2_msgs.srv import (ClearCostmapAroundPose, ClearCostmapAroundRobot,
3333
ClearCostmapExceptRegion, ClearEntireCostmap, GetCostmap, LoadMap,
3434
ManageLifecycleNodes, Toggle)
35-
from nav_msgs.msg import Goals, OccupancyGrid, Path
35+
from nav_msgs.msg import Goals, Path
3636
import rclpy
3737
from rclpy.action import ActionClient
3838
from rclpy.action.client import ClientGoalHandle
@@ -305,7 +305,7 @@ def goThroughPoses(self, poses: Goals, behavior_tree: str = '') -> Optional[Runn
305305

306306
if not self.goal_handle or not self.goal_handle.accepted:
307307
msg = f'NavigateThroughPoses request with {len(poses.goals)} was rejected!'
308-
self.setTaskError(NavigateThroughPoses.UNKNOWN, msg)
308+
self.setTaskError(NavigateThroughPoses.Result.UNKNOWN, msg)
309309
self.error(msg)
310310
return None
311311

@@ -344,7 +344,7 @@ def goToPose(self, pose: PoseStamped, behavior_tree: str = '') -> Optional[Runni
344344
+ str(pose.pose.position.y)
345345
+ ' was rejected!'
346346
)
347-
self.setTaskError(NavigateToPose.UNKNOWN, msg)
347+
self.setTaskError(NavigateToPose.Result.UNKNOWN, msg)
348348
self.error(msg)
349349
return None
350350

@@ -370,7 +370,7 @@ def followWaypoints(self, poses: list[PoseStamped]) -> Optional[RunningTask]:
370370

371371
if not self.goal_handle or not self.goal_handle.accepted:
372372
msg = f'Following {len(poses)} waypoints request was rejected!'
373-
self.setTaskError(FollowWaypoints.UNKNOWN, msg)
373+
self.setTaskError(FollowWaypoints.Result.UNKNOWN, msg)
374374
self.error(msg)
375375
return None
376376

@@ -396,7 +396,7 @@ def followGpsWaypoints(self, gps_poses: list[GeoPose]) -> Optional[RunningTask]:
396396

397397
if not self.goal_handle or not self.goal_handle.accepted:
398398
msg = f'Following {len(gps_poses)} gps waypoints request was rejected!'
399-
self.setTaskError(FollowGPSWaypoints.UNKNOWN, msg)
399+
self.setTaskError(FollowGPSWaypoints.Result.UNKNOWN, msg)
400400
self.error(msg)
401401
return None
402402

@@ -424,7 +424,7 @@ def spin(
424424

425425
if not self.goal_handle or not self.goal_handle.accepted:
426426
msg = 'Spin request was rejected!'
427-
self.setTaskError(Spin.UNKNOWN, msg)
427+
self.setTaskError(Spin.Result.UNKNOWN, msg)
428428
self.error(msg)
429429
return None
430430

@@ -454,7 +454,7 @@ def backup(
454454

455455
if not self.goal_handle or not self.goal_handle.accepted:
456456
msg = 'Backup request was rejected!'
457-
self.setTaskError(BackUp.UNKNOWN, msg)
457+
self.setTaskError(BackUp.Result.UNKNOWN, msg)
458458
self.error(msg)
459459
return None
460460

@@ -484,7 +484,7 @@ def driveOnHeading(
484484

485485
if not self.goal_handle or not self.goal_handle.accepted:
486486
msg = 'Drive On Heading request was rejected!'
487-
self.setTaskError(DriveOnHeading.UNKNOWN, msg)
487+
self.setTaskError(DriveOnHeading.Result.UNKNOWN, msg)
488488
self.error(msg)
489489
return None
490490

@@ -510,7 +510,7 @@ def assistedTeleop(self, time_allowance: int = 30) -> Optional[RunningTask]:
510510

511511
if not self.goal_handle or not self.goal_handle.accepted:
512512
msg = 'Assisted Teleop request was rejected!'
513-
self.setTaskError(AssistedTeleop.UNKNOWN, msg)
513+
self.setTaskError(AssistedTeleop.Result.UNKNOWN, msg)
514514
self.error(msg)
515515
return None
516516

@@ -539,7 +539,7 @@ def followPath(self, path: Path, controller_id: str = '',
539539

540540
if not self.goal_handle or not self.goal_handle.accepted:
541541
msg = 'FollowPath goal was rejected!'
542-
self.setTaskError(FollowPath.UNKNOWN, msg)
542+
self.setTaskError(FollowPath.Result.UNKNOWN, msg)
543543
self.error(msg)
544544
return None
545545

@@ -568,7 +568,7 @@ def dockRobotByPose(self, dock_pose: PoseStamped,
568568

569569
if not self.goal_handle or not self.goal_handle.accepted:
570570
msg = 'DockRobot request was rejected!'
571-
self.setTaskError(DockRobot.UNKNOWN, msg)
571+
self.setTaskError(DockRobot.Result.UNKNOWN, msg)
572572
self.error(msg)
573573
return None
574574

@@ -595,7 +595,7 @@ def dockRobotByID(self, dock_id: str, nav_to_dock: bool = True) -> Optional[Runn
595595

596596
if not self.goal_handle or not self.goal_handle.accepted:
597597
msg = 'DockRobot request was rejected!'
598-
self.setTaskError(DockRobot.UNKNOWN, msg)
598+
self.setTaskError(DockRobot.Result.UNKNOWN, msg)
599599
self.error(msg)
600600
return None
601601

@@ -620,7 +620,7 @@ def undockRobot(self, dock_type: str = '') -> Optional[RunningTask]:
620620

621621
if not self.goal_handle or not self.goal_handle.accepted:
622622
msg = 'UndockRobot request was rejected!'
623-
self.setTaskError(UndockRobot.UNKNOWN, msg)
623+
self.setTaskError(UndockRobot.Result.UNKNOWN, msg)
624624
self.error(msg)
625625
return None
626626

@@ -761,7 +761,7 @@ def _getPathImpl(
761761
self.error('Get path was rejected!')
762762
self.status = GoalStatus.STATUS_UNKNOWN
763763
result = ComputePathToPose.Result()
764-
result.error_code = ComputePathToPose.UNKNOWN
764+
result.error_code = ComputePathToPose.Result.UNKNOWN
765765
result.error_msg = 'Get path was rejected'
766766
return result
767767

@@ -809,7 +809,7 @@ def _getPathThroughPosesImpl(
809809
goal_msg.start = start
810810
goal_msg.goals.header.frame_id = 'map'
811811
goal_msg.goals.header.stamp = self.get_clock().now().to_msg()
812-
goal_msg.goals.goals = goals
812+
goal_msg.goals.goals = goals.goals
813813
goal_msg.planner_id = planner_id
814814
goal_msg.use_start = use_start
815815

@@ -823,7 +823,7 @@ def _getPathThroughPosesImpl(
823823
if not self.goal_handle or not self.goal_handle.accepted:
824824
self.error('Get path was rejected!')
825825
result = ComputePathThroughPoses.Result()
826-
result.error_code = ComputePathThroughPoses.UNKNOWN
826+
result.error_code = ComputePathThroughPoses.Result.UNKNOWN
827827
result.error_msg = 'Get path was rejected!'
828828
return result
829829

@@ -878,7 +878,7 @@ def _getRouteImpl(
878878
else:
879879
self.error('Invalid start and goal types. Must be PoseStamped for pose or int for ID')
880880
result = ComputeRoute.Result()
881-
result.error_code = ComputeRoute.UNKNOWN
881+
result.error_code = ComputeRoute.Result.UNKNOWN
882882
result.error_msg = 'Request type fields were invalid!'
883883
return result
884884

@@ -890,7 +890,7 @@ def _getRouteImpl(
890890
if not self.goal_handle or not self.goal_handle.accepted:
891891
self.error('Get route was rejected!')
892892
result = ComputeRoute.Result()
893-
result.error_code = ComputeRoute.UNKNOWN
893+
result.error_code = ComputeRoute.Result.UNKNOWN
894894
result.error_msg = 'Get route was rejected!'
895895
return result
896896

@@ -942,7 +942,8 @@ def getAndTrackRoute(
942942
goal_msg.goal = goal
943943
goal_msg.use_poses = True
944944
else:
945-
self.setTaskError(ComputeAndTrackRoute.UNKNOWN, 'Request type fields were invalid!')
945+
self.setTaskError(ComputeAndTrackRoute.Result.UNKNOWN,
946+
'Request type fields were invalid!')
946947
self.error('Invalid start and goal types. Must be PoseStamped for pose or int for ID')
947948
return None
948949

@@ -954,7 +955,7 @@ def getAndTrackRoute(
954955

955956
if not self.route_goal_handle or not self.route_goal_handle.accepted:
956957
msg = 'Compute and track route was rejected!'
957-
self.setTaskError(ComputeAndTrackRoute.UNKNOWN, msg)
958+
self.setTaskError(ComputeAndTrackRoute.Result.UNKNOWN, msg)
958959
self.error(msg)
959960
return None
960961

@@ -988,7 +989,7 @@ def _smoothPathImpl(
988989
if not self.goal_handle or not self.goal_handle.accepted:
989990
self.error('Smooth path was rejected!')
990991
result = SmoothPath.Result()
991-
result.error_code = SmoothPath.UNKNOWN
992+
result.error_code = SmoothPath.Result.UNKNOWN
992993
result.error_msg = 'Smooth path was rejected'
993994
return result
994995

@@ -1030,14 +1031,14 @@ def changeMap(self, map_filepath: str) -> bool:
10301031
return False
10311032

10321033
result = future_result.result
1033-
if result != LoadMap.Response().RESULT_SUCCESS:
1034-
if result == LoadMap.RESULT_MAP_DOES_NOT_EXIST:
1034+
if result != LoadMap.Response.RESULT_SUCCESS:
1035+
if result == LoadMap.Response.RESULT_MAP_DOES_NOT_EXIST:
10351036
reason = 'Map does not exist'
1036-
elif result == LoadMap.INVALID_MAP_DATA:
1037+
elif result == LoadMap.Response.RESULT_INVALID_MAP_DATA:
10371038
reason = 'Invalid map data'
1038-
elif result == LoadMap.INVALID_MAP_METADATA:
1039+
elif result == LoadMap.Response.RESULT_INVALID_MAP_METADATA:
10391040
reason = 'Invalid map metadata'
1040-
elif result == LoadMap.UNDEFINED_FAILURE:
1041+
elif result == LoadMap.Response.RESULT_UNDEFINED_FAILURE:
10411042
reason = 'Undefined failure'
10421043
else:
10431044
reason = 'Unknown'
@@ -1144,7 +1145,7 @@ def clearGlobalCostmapAroundPose(self, pose: PoseStamped, reset_distance: float)
11441145

11451146
return
11461147

1147-
def getGlobalCostmap(self) -> Optional[OccupancyGrid]:
1148+
def getGlobalCostmap(self) -> Optional[Costmap]:
11481149
"""Get the global costmap."""
11491150
while not self.get_costmap_global_srv.wait_for_service(timeout_sec=1.0):
11501151
self.info('Get global costmaps service not available, waiting...')
@@ -1159,7 +1160,7 @@ def getGlobalCostmap(self) -> Optional[OccupancyGrid]:
11591160

11601161
return result.map
11611162

1162-
def getLocalCostmap(self) -> Optional[OccupancyGrid]:
1163+
def getLocalCostmap(self) -> Optional[Costmap]:
11631164
"""Get the local costmap."""
11641165
while not self.get_costmap_local_srv.wait_for_service(timeout_sec=1.0):
11651166
self.info('Get local costmaps service not available, waiting...')
@@ -1201,7 +1202,7 @@ def lifecycleStartup(self) -> None:
12011202
while not mgr_client.wait_for_service(timeout_sec=1.0):
12021203
self.info(f'{srv_name} service not available, waiting...')
12031204
req = ManageLifecycleNodes.Request()
1204-
req.command = ManageLifecycleNodes.Request().STARTUP
1205+
req.command = ManageLifecycleNodes.Request.STARTUP
12051206
future = mgr_client.call_async(req)
12061207

12071208
# starting up requires a full map->odom->base_link TF tree
@@ -1226,7 +1227,7 @@ def lifecycleShutdown(self) -> None:
12261227
while not mgr_client.wait_for_service(timeout_sec=1.0):
12271228
self.info(f'{srv_name} service not available, waiting...')
12281229
req = ManageLifecycleNodes.Request()
1229-
req.command = ManageLifecycleNodes.Request().SHUTDOWN
1230+
req.command = ManageLifecycleNodes.Request.SHUTDOWN
12301231
future = mgr_client.call_async(req)
12311232
rclpy.spin_until_future_complete(self, future)
12321233
future.result()
@@ -1268,12 +1269,13 @@ def _amclPoseCallback(self, msg: PoseWithCovarianceStamped) -> None:
12681269
self.initial_pose_received = True
12691270
return
12701271

1271-
def _feedbackCallback(self, msg: NavigateToPose.Feedback) -> None:
1272+
def _feedbackCallback(self, msg: Any) -> None:
12721273
self.debug('Received action feedback message')
12731274
self.feedback = msg.feedback
12741275
return
12751276

1276-
def _routeFeedbackCallback(self, msg: ComputeAndTrackRoute.Feedback) -> None:
1277+
def _routeFeedbackCallback(
1278+
self, msg: ComputeAndTrackRoute.Impl.FeedbackMessage) -> None:
12771279
self.debug('Received route action feedback message')
12781280
self.route_feedback.append(msg.feedback)
12791281
return

‎nav2_system_tests/src/behaviors/backup/backup_tester.py‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -299,7 +299,7 @@ def shutdown(self) -> None:
299299
self.info_msg(f'{transition_service} service not available, waiting...')
300300

301301
req = ManageLifecycleNodes.Request()
302-
req.command = ManageLifecycleNodes.Request().SHUTDOWN
302+
req.command = ManageLifecycleNodes.Request.SHUTDOWN
303303
future = mgr_client.call_async(req)
304304
try:
305305
rclpy.spin_until_future_complete(self, future)

‎nav2_system_tests/src/route/tester_node.py‎

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -316,7 +316,8 @@ def runTrackRouteTest(self) -> bool:
316316
self.info_msg('Goal succeeded!')
317317
return True
318318

319-
def feedback_callback(self, feedback_msg: ComputeAndTrackRoute.Feedback) -> None:
319+
def feedback_callback(
320+
self, feedback_msg: ComputeAndTrackRoute.Impl.FeedbackMessage) -> None:
320321
self.feedback_msgs.append(feedback_msg.feedback)
321322

322323
def distanceFromGoal(self) -> float:
@@ -386,7 +387,7 @@ def shutdown(self) -> None:
386387
self.info_msg(f'{transition_service} service not available, waiting...')
387388

388389
req = ManageLifecycleNodes.Request()
389-
req.command = ManageLifecycleNodes.Request().SHUTDOWN
390+
req.command = ManageLifecycleNodes.Request.SHUTDOWN
390391
future = mgr_client.call_async(req)
391392
try:
392393
self.info_msg('Shutting down navigation lifecycle manager...')
@@ -401,7 +402,7 @@ def shutdown(self) -> None:
401402
self.info_msg(f'{transition_service} service not available, waiting...')
402403

403404
req = ManageLifecycleNodes.Request()
404-
req.command = ManageLifecycleNodes.Request().SHUTDOWN
405+
req.command = ManageLifecycleNodes.Request.SHUTDOWN
405406
future = mgr_client.call_async(req)
406407
try:
407408
self.info_msg('Shutting down localization lifecycle manager...')

0 commit comments

Comments
 (0)