Skip to content

Commit d43d8e8

Browse files
leander-dsouzaSakshayMahna
authored andcommitted
Fix ament mypy (ros-navigation#5280)
* Configured nav2_loopback_sim to be compliant with mypy. Signed-off-by: Leander Stephen D'Souza <[email protected]> * Configured nav2_simple_commander to be compliant with mypy. Signed-off-by: Leander Stephen D'Souza <[email protected]> * Configured nav2_system_tests to be compliant with mypy. Signed-off-by: Leander Stephen D'Souza <[email protected]> --------- Signed-off-by: Leander Stephen D'Souza <[email protected]>
1 parent 18a2fed commit d43d8e8

File tree

15 files changed

+228
-73
lines changed

15 files changed

+228
-73
lines changed

nav2_loopback_sim/nav2_loopback_sim/loopback_simulator.py

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -18,11 +18,14 @@
1818

1919
from geometry_msgs.msg import (PoseWithCovarianceStamped, Quaternion, TransformStamped, Twist,
2020
TwistStamped, Vector3)
21+
from nav2_loopback_sim.utils import (addYawToQuat, getMapOccupancy, matrixToTransform,
22+
transformStampedToMatrix, worldToMap)
2123
from nav2_simple_commander.line_iterator import LineIterator
2224
from nav_msgs.msg import Odometry
2325
from nav_msgs.srv import GetMap
2426
import numpy as np
2527
import rclpy
28+
from rclpy.client import Client
2629
from rclpy.duration import Duration
2730
from rclpy.node import Node
2831
from rclpy.qos import DurabilityPolicy, QoSProfile, ReliabilityPolicy
@@ -32,9 +35,6 @@
3235
from tf2_ros import Buffer, TransformBroadcaster, TransformListener
3336
import tf_transformations
3437

35-
from .utils import (addYawToQuat, getMapOccupancy, matrixToTransform, transformStampedToMatrix,
36-
worldToMap)
37-
3838
"""
3939
This is a loopback simulator that replaces a physics simulator to create a
4040
frictionless, inertialess, and collisionless simulation environment. It
@@ -144,7 +144,8 @@ def __init__(self) -> None:
144144

145145
self.setupTimer = self.create_timer(0.1, self.setupTimerCallback)
146146

147-
self.map_client = self.create_client(GetMap, '/map_server/map')
147+
self.map_client: Client[GetMap.Request, GetMap.Response] = \
148+
self.create_client(GetMap, '/map_server/map')
148149

149150
self.tf_buffer = Buffer()
150151
self.tf_listener = TransformListener(self.tf_buffer, self)

nav2_simple_commander/nav2_simple_commander/demo_security.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ def main() -> None:
5656
navigator.waitUntilNav2Active()
5757

5858
# Do security route until dead
59-
while rclpy.ok(): # type: ignore[attr-defined]
59+
while rclpy.ok():
6060
# Send our route
6161
route_poses = []
6262
pose = PoseStamped()

nav2_simple_commander/nav2_simple_commander/robot_navigator.py

Lines changed: 110 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@
3535
import rclpy
3636
from rclpy.action import ActionClient # type: ignore[attr-defined]
3737
from rclpy.action.client import ClientGoalHandle
38+
from rclpy.client import Client
3839
from rclpy.duration import Duration as rclpyDuration
3940
from rclpy.node import Node
4041
from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy
@@ -103,37 +104,101 @@ def __init__(self, node_name: str = 'basic_navigator', namespace: str = '') -> N
103104
)
104105

105106
self.initial_pose_received = False
106-
self.nav_through_poses_client = ActionClient(
107-
self, NavigateThroughPoses, 'navigate_through_poses'
108-
)
109-
self.nav_to_pose_client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
110-
self.follow_waypoints_client = ActionClient(
107+
self.nav_through_poses_client: ActionClient[
108+
NavigateThroughPoses.Goal,
109+
NavigateThroughPoses.Result,
110+
NavigateThroughPoses.Feedback
111+
] = ActionClient(
112+
self, NavigateThroughPoses, 'navigate_through_poses')
113+
self.nav_to_pose_client: ActionClient[
114+
NavigateToPose.Goal,
115+
NavigateToPose.Result,
116+
NavigateToPose.Feedback
117+
] = ActionClient(self, NavigateToPose, 'navigate_to_pose')
118+
self.follow_waypoints_client: ActionClient[
119+
FollowWaypoints.Goal,
120+
FollowWaypoints.Result,
121+
FollowWaypoints.Feedback
122+
] = ActionClient(
111123
self, FollowWaypoints, 'follow_waypoints'
112124
)
113-
self.follow_gps_waypoints_client = ActionClient(
125+
self.follow_gps_waypoints_client: ActionClient[
126+
FollowGPSWaypoints.Goal,
127+
FollowGPSWaypoints.Result,
128+
FollowGPSWaypoints.Feedback
129+
] = ActionClient(
114130
self, FollowGPSWaypoints, 'follow_gps_waypoints'
115131
)
116-
self.follow_path_client = ActionClient(self, FollowPath, 'follow_path')
117-
self.compute_path_to_pose_client = ActionClient(
132+
self.follow_path_client: ActionClient[
133+
FollowPath.Goal,
134+
FollowPath.Result,
135+
FollowPath.Feedback
136+
] = ActionClient(self, FollowPath, 'follow_path')
137+
self.compute_path_to_pose_client: ActionClient[
138+
ComputePathToPose.Goal,
139+
ComputePathToPose.Result,
140+
ComputePathToPose.Feedback
141+
] = ActionClient(
118142
self, ComputePathToPose, 'compute_path_to_pose'
119143
)
120-
self.compute_path_through_poses_client = ActionClient(
144+
self.compute_path_through_poses_client: ActionClient[
145+
ComputePathThroughPoses.Goal,
146+
ComputePathThroughPoses.Result,
147+
ComputePathThroughPoses.Feedback
148+
] = ActionClient(
121149
self, ComputePathThroughPoses, 'compute_path_through_poses'
122150
)
123-
self.smoother_client = ActionClient(self, SmoothPath, 'smooth_path')
124-
self.compute_route_client = ActionClient(self, ComputeRoute, 'compute_route')
125-
self.compute_and_track_route_client = ActionClient(self, ComputeAndTrackRoute,
126-
'compute_and_track_route')
127-
self.spin_client = ActionClient(self, Spin, 'spin')
128-
self.backup_client = ActionClient(self, BackUp, 'backup')
129-
self.drive_on_heading_client = ActionClient(
151+
self.smoother_client: ActionClient[
152+
SmoothPath.Goal,
153+
SmoothPath.Result,
154+
SmoothPath.Feedback
155+
] = ActionClient(self, SmoothPath, 'smooth_path')
156+
self.compute_route_client: ActionClient[
157+
ComputeRoute.Goal,
158+
ComputeRoute.Result,
159+
ComputeRoute.Feedback
160+
] = ActionClient(self, ComputeRoute, 'compute_route')
161+
self.compute_and_track_route_client: ActionClient[
162+
ComputeAndTrackRoute.Goal,
163+
ComputeAndTrackRoute.Result,
164+
ComputeAndTrackRoute.Feedback
165+
] = ActionClient(self, ComputeAndTrackRoute, 'compute_and_track_route')
166+
self.spin_client: ActionClient[
167+
Spin.Goal,
168+
Spin.Result,
169+
Spin.Feedback
170+
] = ActionClient(self, Spin, 'spin')
171+
172+
self.backup_client: ActionClient[
173+
BackUp.Goal,
174+
BackUp.Result,
175+
BackUp.Feedback
176+
] = ActionClient(self, BackUp, 'backup')
177+
self.drive_on_heading_client: ActionClient[
178+
DriveOnHeading.Goal,
179+
DriveOnHeading.Result,
180+
DriveOnHeading.Feedback
181+
] = ActionClient(
130182
self, DriveOnHeading, 'drive_on_heading'
131183
)
132-
self.assisted_teleop_client = ActionClient(
184+
self.assisted_teleop_client: ActionClient[
185+
AssistedTeleop.Goal,
186+
AssistedTeleop.Result,
187+
AssistedTeleop.Feedback
188+
] = ActionClient(
133189
self, AssistedTeleop, 'assisted_teleop'
134190
)
135-
self.docking_client = ActionClient(self, DockRobot, 'dock_robot')
136-
self.undocking_client = ActionClient(self, UndockRobot, 'undock_robot')
191+
self.docking_client: ActionClient[
192+
DockRobot.Goal,
193+
DockRobot.Result,
194+
DockRobot.Feedback
195+
] = ActionClient(self, DockRobot, 'dock_robot')
196+
self.undocking_client: ActionClient[
197+
UndockRobot.Goal,
198+
UndockRobot.Result,
199+
UndockRobot.Feedback
200+
] = ActionClient(self, UndockRobot, 'undock_robot')
201+
137202
self.localization_pose_sub = self.create_subscription(
138203
PoseWithCovarianceStamped,
139204
'amcl_pose',
@@ -143,23 +208,36 @@ def __init__(self, node_name: str = 'basic_navigator', namespace: str = '') -> N
143208
self.initial_pose_pub = self.create_publisher(
144209
PoseWithCovarianceStamped, 'initialpose', 10
145210
)
146-
self.change_maps_srv = self.create_client(LoadMap, 'map_server/load_map')
147-
self.clear_costmap_global_srv = self.create_client(
211+
self.change_maps_srv: Client[LoadMap.Request, LoadMap.Response] = \
212+
self.create_client(LoadMap, 'map_server/load_map')
213+
self.clear_costmap_global_srv: Client[
214+
ClearEntireCostmap.Request, ClearEntireCostmap.Response] = \
215+
self.create_client(
148216
ClearEntireCostmap, 'global_costmap/clear_entirely_global_costmap'
149217
)
150-
self.clear_costmap_local_srv = self.create_client(
218+
self.clear_costmap_local_srv: Client[
219+
ClearEntireCostmap.Request, ClearEntireCostmap.Response] = \
220+
self.create_client(
151221
ClearEntireCostmap, 'local_costmap/clear_entirely_local_costmap'
152222
)
153-
self.clear_costmap_except_region_srv = self.create_client(
223+
self.clear_costmap_except_region_srv: Client[
224+
ClearCostmapExceptRegion.Request, ClearCostmapExceptRegion.Response] = \
225+
self.create_client(
154226
ClearCostmapExceptRegion, 'local_costmap/clear_costmap_except_region'
155227
)
156-
self.clear_costmap_around_robot_srv = self.create_client(
228+
self.clear_costmap_around_robot_srv: Client[
229+
ClearCostmapAroundRobot.Request, ClearCostmapAroundRobot.Response] = \
230+
self.create_client(
157231
ClearCostmapAroundRobot, 'local_costmap/clear_costmap_around_robot'
158232
)
159-
self.get_costmap_global_srv = self.create_client(
233+
self.get_costmap_global_srv: Client[
234+
GetCostmap.Request, GetCostmap.Response] = \
235+
self.create_client(
160236
GetCostmap, 'global_costmap/get_costmap'
161237
)
162-
self.get_costmap_local_srv = self.create_client(
238+
self.get_costmap_local_srv: Client[
239+
GetCostmap.Request, GetCostmap.Response] = \
240+
self.create_client(
163241
GetCostmap, 'local_costmap/get_costmap'
164242
)
165243

@@ -1035,7 +1113,8 @@ def lifecycleStartup(self) -> None:
10351113
for srv_name, srv_type in self.get_service_names_and_types():
10361114
if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
10371115
self.info(f'Starting up {srv_name}')
1038-
mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
1116+
mgr_client: Client[ManageLifecycleNodes.Request, ManageLifecycleNodes.Response] = \
1117+
self.create_client(ManageLifecycleNodes, srv_name)
10391118
while not mgr_client.wait_for_service(timeout_sec=1.0):
10401119
self.info(f'{srv_name} service not available, waiting...')
10411120
req = ManageLifecycleNodes.Request()
@@ -1059,7 +1138,8 @@ def lifecycleShutdown(self) -> None:
10591138
for srv_name, srv_type in self.get_service_names_and_types():
10601139
if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
10611140
self.info(f'Shutting down {srv_name}')
1062-
mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
1141+
mgr_client: Client[ManageLifecycleNodes.Request, ManageLifecycleNodes.Response] = \
1142+
self.create_client(ManageLifecycleNodes, srv_name)
10631143
while not mgr_client.wait_for_service(timeout_sec=1.0):
10641144
self.info(f'{srv_name} service not available, waiting...')
10651145
req = ManageLifecycleNodes.Request()
@@ -1073,7 +1153,8 @@ def _waitForNodeToActivate(self, node_name: str) -> None:
10731153
# Waits for the node within the tester namespace to become active
10741154
self.debug(f'Waiting for {node_name} to become active..')
10751155
node_service = f'{node_name}/get_state'
1076-
state_client = self.create_client(GetState, node_service)
1156+
state_client: Client[GetState.Request, GetState.Response] = \
1157+
self.create_client(GetState, node_service)
10771158
while not state_client.wait_for_service(timeout_sec=1.0):
10781159
self.info(f'{node_service} service not available, waiting...')
10791160

nav2_system_tests/src/behaviors/backup/backup_tester.py

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
import rclpy
2626
from rclpy.action import ActionClient # type: ignore[attr-defined]
2727
from rclpy.action.client import ClientGoalHandle
28+
from rclpy.client import Client
2829
from rclpy.duration import Duration
2930
from rclpy.node import Node
3031
from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy
@@ -40,7 +41,11 @@ def __init__(self) -> None:
4041
history=QoSHistoryPolicy.KEEP_LAST,
4142
depth=1,
4243
)
43-
self.action_client = ActionClient(self, BackUp, 'backup')
44+
self.action_client: ActionClient[
45+
BackUp.Goal,
46+
BackUp.Result,
47+
BackUp.Feedback
48+
] = ActionClient(self, BackUp, 'backup')
4449
self.costmap_pub = self.create_publisher(
4550
Costmap, 'local_costmap/costmap_raw', self.costmap_qos)
4651
self.footprint_pub = self.create_publisher(
@@ -288,7 +293,8 @@ def shutdown(self) -> None:
288293
self.info_msg('Destroyed backup action client')
289294

290295
transition_service = 'lifecycle_manager_navigation/manage_nodes'
291-
mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
296+
mgr_client: Client[ManageLifecycleNodes.Request, ManageLifecycleNodes.Response] \
297+
= self.create_client(ManageLifecycleNodes, transition_service)
292298
while not mgr_client.wait_for_service(timeout_sec=1.0):
293299
self.info_msg(f'{transition_service} service not available, waiting...')
294300

nav2_system_tests/src/behaviors/drive_on_heading/drive_tester.py

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
import rclpy
2626
from rclpy.action import ActionClient # type: ignore[attr-defined]
2727
from rclpy.action.client import ClientGoalHandle
28+
from rclpy.client import Client
2829
from rclpy.duration import Duration
2930
from rclpy.node import Node
3031
from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy
@@ -40,7 +41,11 @@ def __init__(self) -> None:
4041
history=QoSHistoryPolicy.KEEP_LAST,
4142
depth=1,
4243
)
43-
self.action_client = ActionClient(self, DriveOnHeading, 'drive_on_heading')
44+
self.action_client: ActionClient[
45+
DriveOnHeading.Goal,
46+
DriveOnHeading.Result,
47+
DriveOnHeading.Feedback
48+
] = ActionClient(self, DriveOnHeading, 'drive_on_heading')
4449
self.costmap_pub = self.create_publisher(
4550
Costmap, 'local_costmap/costmap_raw', self.costmap_qos)
4651
self.footprint_pub = self.create_publisher(
@@ -297,7 +302,8 @@ def shutdown(self) -> None:
297302
self.info_msg('Destroyed DriveOnHeading action client')
298303

299304
transition_service = 'lifecycle_manager_navigation/manage_nodes'
300-
mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
305+
mgr_client: Client[ManageLifecycleNodes.Request, ManageLifecycleNodes.Response] \
306+
= self.create_client(ManageLifecycleNodes, transition_service)
301307
while not mgr_client.wait_for_service(timeout_sec=1.0):
302308
self.info_msg(f'{transition_service} service not available, waiting...')
303309

nav2_system_tests/src/behaviors/spin/spin_tester.py

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
import rclpy
2626
from rclpy.action import ActionClient # type: ignore[attr-defined]
2727
from rclpy.action.client import ClientGoalHandle
28+
from rclpy.client import Client
2829
from rclpy.duration import Duration
2930
from rclpy.node import Node
3031
from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy
@@ -40,7 +41,9 @@ def __init__(self) -> None:
4041
history=QoSHistoryPolicy.KEEP_LAST,
4142
depth=1,
4243
)
43-
self.action_client = ActionClient(self, Spin, 'spin')
44+
self.action_client: ActionClient[Spin.Goal, Spin.Result, Spin.Feedback] \
45+
= ActionClient(self, Spin, 'spin')
46+
4447
self.costmap_pub = self.create_publisher(
4548
Costmap, 'local_costmap/costmap_raw', self.costmap_qos)
4649
self.footprint_pub = self.create_publisher(
@@ -280,7 +283,8 @@ def shutdown(self) -> None:
280283
self.info_msg('Destroyed backup action client')
281284

282285
transition_service = 'lifecycle_manager_navigation/manage_nodes'
283-
mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
286+
mgr_client: Client[ManageLifecycleNodes.Request, ManageLifecycleNodes.Response] \
287+
= self.create_client(ManageLifecycleNodes, transition_service)
284288
while not mgr_client.wait_for_service(timeout_sec=1.0):
285289
self.info_msg(f'{transition_service} service not available, waiting...')
286290

nav2_system_tests/src/costmap_filters/tester_node.py

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
from nav_msgs.msg import OccupancyGrid, Path
3232
import rclpy
3333
from rclpy.action import ActionClient # type: ignore[attr-defined]
34+
from rclpy.client import Client
3435
from rclpy.node import Node
3536
from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy
3637
from sensor_msgs.msg import PointCloud2
@@ -151,7 +152,9 @@ def __init__(
151152
self.initial_pose_received = False
152153
self.initial_pose = initial_pose
153154
self.goal_pose = goal_pose
154-
self.action_client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
155+
self.action_client: ActionClient[
156+
NavigateToPose.Goal, NavigateToPose.Result, NavigateToPose.Feedback] = \
157+
ActionClient(self, NavigateToPose, 'navigate_to_pose')
155158

156159
def info_msg(self, msg: str) -> None:
157160
self.get_logger().info('\033[1;37;44m' + msg + '\033[0m')
@@ -357,7 +360,8 @@ def wait_for_node_active(self, node_name: str) -> None:
357360
# Waits for the node within the tester namespace to become active
358361
self.info_msg(f'Waiting for {node_name} to become active')
359362
node_service = f'{node_name}/get_state'
360-
state_client = self.create_client(GetState, node_service)
363+
state_client: Client[GetState.Request, GetState.Response] \
364+
= self.create_client(GetState, node_service)
361365
while not state_client.wait_for_service(timeout_sec=1.0):
362366
self.info_msg(f'{node_service} service not available, waiting...')
363367
req = GetState.Request() # empty request
@@ -380,7 +384,8 @@ def shutdown(self) -> None:
380384
self.action_client.destroy()
381385

382386
transition_service = 'lifecycle_manager_navigation/manage_nodes'
383-
mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
387+
mgr_client: Client[ManageLifecycleNodes.Request, ManageLifecycleNodes.Response] \
388+
= self.create_client(ManageLifecycleNodes, transition_service)
384389
while not mgr_client.wait_for_service(timeout_sec=1.0):
385390
self.info_msg(f'{transition_service} service not available, waiting...')
386391

0 commit comments

Comments
 (0)