3535import rclpy
3636from rclpy .action import ActionClient # type: ignore[attr-defined]
3737from rclpy .action .client import ClientGoalHandle
38+ from rclpy .client import Client
3839from rclpy .duration import Duration as rclpyDuration
3940from rclpy .node import Node
4041from 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
0 commit comments