Skip to content

Commit d01728e

Browse files
leander-dsouzaSakshayMahna
authored andcommitted
Mypy opennav_docking (ros-navigation#5047)
* Define attributes for nav2_msgs. Signed-off-by: Leander Stephen D'Souza <[email protected]> * Configured opennav_docking to use strict mypy. Signed-off-by: Leander Stephen D'Souza <[email protected]> * Added opennav_docking to the mypy linting workflow. Signed-off-by: Leander Stephen D'Souza <[email protected]> --------- Signed-off-by: Leander Stephen D'Souza <[email protected]> Signed-off-by: Sakshay Mahna <[email protected]>
1 parent a4bba54 commit d01728e

File tree

6 files changed

+131
-24
lines changed

6 files changed

+131
-24
lines changed

.github/workflows/lint.yml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ jobs:
3333
- "nav2_bringup"
3434
- "nav2_collision_monitor"
3535
- "nav2_costmap_2d"
36+
- "opennav_docking"
3637
steps:
3738
- uses: actions/checkout@v4
3839

nav2_docking/opennav_docking/test/test_docking_server.py

Lines changed: 36 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
import pytest
3131
import rclpy
3232
from rclpy.action.client import ActionClient
33-
from rclpy.action.server import ActionServer
33+
from rclpy.action.server import ActionServer, ServerGoalHandle
3434
from sensor_msgs.msg import BatteryState
3535
from tf2_ros import TransformBroadcaster
3636

@@ -45,7 +45,7 @@
4545
@pytest.mark.rostest
4646
# @pytest.mark.flaky
4747
# @pytest.mark.flaky(max_runs=5, min_passes=3)
48-
def generate_test_description():
48+
def generate_test_description() -> LaunchDescription:
4949

5050
return LaunchDescription([
5151
# SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),
@@ -86,14 +86,14 @@ def generate_test_description():
8686
class TestDockingServer(unittest.TestCase):
8787

8888
@classmethod
89-
def setUpClass(cls):
89+
def setUpClass(cls) -> None:
9090
rclpy.init()
9191

9292
@classmethod
93-
def tearDownClass(cls):
93+
def tearDownClass(cls) -> None:
9494
rclpy.shutdown()
9595

96-
def setUp(self):
96+
def setUp(self) -> None:
9797
# Create a ROS node for tests
9898
# Latest odom -> base_link
9999
self.x = 0.0
@@ -105,14 +105,14 @@ def setUp(self):
105105
self.command = Twist()
106106
self.node = rclpy.create_node('test_docking_server')
107107

108-
def tearDown(self):
108+
def tearDown(self) -> None:
109109
self.node.destroy_node()
110110

111-
def command_velocity_callback(self, msg):
112-
self.node.get_logger().info('Command: %f %f' % (msg.twist.linear.x, msg.twist.angular.z))
111+
def command_velocity_callback(self, msg: TwistStamped) -> None:
112+
self.node.get_logger().info(f'Command: {msg.twist.linear.x:f} {msg.twist.angular.z:f}')
113113
self.command = msg.twist
114114

115-
def timer_callback(self):
115+
def timer_callback(self) -> None:
116116
# Propagate command
117117
period = 0.05
118118
self.x += cos(self.theta) * self.command.linear.x * period
@@ -121,7 +121,7 @@ def timer_callback(self):
121121
# Need to publish updated TF
122122
self.publish()
123123

124-
def publish(self):
124+
def publish(self) -> None:
125125
# Publish base->odom transform
126126
t = TransformStamped()
127127
t.header.stamp = self.node.get_clock().now().to_msg()
@@ -140,20 +140,24 @@ def publish(self):
140140
b.current = -1.0
141141
self.battery_state_pub.publish(b)
142142

143-
def action_feedback_callback(self, msg):
143+
def action_feedback_callback(self, msg: DockRobot.Feedback) -> None:
144144
# Force the docking action to run a full recovery loop and then
145145
# make contact with the dock (based on pose of robot) before
146146
# we report that the robot is charging
147147
if msg.feedback.num_retries > 0 and \
148148
msg.feedback.state == msg.feedback.WAIT_FOR_CHARGE:
149149
self.is_charging = True
150150

151-
def nav_execute_callback(self, goal_handle):
151+
def nav_execute_callback(
152+
self,
153+
goal_handle: ServerGoalHandle[NavigateToPose.Goal,
154+
NavigateToPose.Result, NavigateToPose.Feedback]
155+
) -> NavigateToPose.Result:
152156
goal = goal_handle.request
153157
self.x = goal.pose.pose.position.x - 0.05
154158
self.y = goal.pose.pose.position.y + 0.05
155159
self.theta = 2.0 * acos(goal.pose.pose.orientation.w)
156-
self.node.get_logger().info('Navigating to %f %f %f' % (self.x, self.y, self.theta))
160+
self.node.get_logger().info(f'Navigating to {self.x:f} {self.y:f} {self.theta:f}')
157161
goal_handle.succeed()
158162
self.publish()
159163

@@ -162,7 +166,7 @@ def nav_execute_callback(self, goal_handle):
162166
result.error_msg = ''
163167
return result
164168

165-
def test_docking_server(self):
169+
def test_docking_server(self) -> None:
166170
# Publish TF for odometry
167171
self.tf_broadcaster = TransformBroadcaster(self.node)
168172

@@ -239,8 +243,10 @@ def test_docking_server(self):
239243
self.action_result.append(result_future_original.result())
240244

241245
# First is aborted due to preemption
242-
self.assertEqual(self.action_result[0].status, GoalStatus.STATUS_ABORTED)
243-
self.assertFalse(self.action_result[0].result.success)
246+
self.assertIsNotNone(self.action_result[0])
247+
if self.action_result[0] is not None:
248+
self.assertEqual(self.action_result[0].status, GoalStatus.STATUS_ABORTED)
249+
self.assertFalse(self.action_result[0].result.success)
244250

245251
self.node.get_logger().info('Goal preempted')
246252

@@ -250,8 +256,10 @@ def test_docking_server(self):
250256
time.sleep(0.1)
251257

252258
# Second is aborted due to preemption during main loop (takes down all actions)
253-
self.assertEqual(self.action_result[1].status, GoalStatus.STATUS_ABORTED)
254-
self.assertFalse(self.action_result[1].result.success)
259+
self.assertIsNotNone(self.action_result[1])
260+
if self.action_result[1] is not None:
261+
self.assertEqual(self.action_result[1].status, GoalStatus.STATUS_ABORTED)
262+
self.assertFalse(self.action_result[1].result.success)
255263

256264
# Resend the goal
257265
self.node.get_logger().info('Sending goal again')
@@ -265,9 +273,11 @@ def test_docking_server(self):
265273
rclpy.spin_until_future_complete(self.node, result_future)
266274
self.action_result.append(result_future.result())
267275

268-
self.assertEqual(self.action_result[2].status, GoalStatus.STATUS_SUCCEEDED)
269-
self.assertTrue(self.action_result[2].result.success)
270-
self.assertEqual(self.action_result[2].result.num_retries, 1)
276+
self.assertIsNotNone(self.action_result[2])
277+
if self.action_result[2] is not None:
278+
self.assertEqual(self.action_result[2].status, GoalStatus.STATUS_SUCCEEDED)
279+
self.assertTrue(self.action_result[2].result.success)
280+
self.assertEqual(self.action_result[2].result.num_retries, 1)
271281

272282
# Test undocking action
273283
self.is_charging = False
@@ -283,13 +293,15 @@ def test_docking_server(self):
283293
rclpy.spin_until_future_complete(self.node, result_future)
284294
self.action_result.append(result_future.result())
285295

286-
self.assertEqual(self.action_result[3].status, GoalStatus.STATUS_SUCCEEDED)
287-
self.assertTrue(self.action_result[3].result.success)
296+
self.assertIsNotNone(self.action_result[3])
297+
if self.action_result[3] is not None:
298+
self.assertEqual(self.action_result[3].status, GoalStatus.STATUS_SUCCEEDED)
299+
self.assertTrue(self.action_result[3].result.success)
288300

289301

290302
@launch_testing.post_shutdown_test()
291303
class TestProcessOutput(unittest.TestCase):
292304

293-
def test_exit_code(self, proc_info):
305+
def test_exit_code(self, proc_info: launch_testing.ProcInfoHandler) -> None:
294306
# Check that all processes in the launch exit with code 0
295307
launch_testing.asserts.assertExitCodes(proc_info)

nav2_msgs/action/__init__.py

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
from nav2_msgs.action._assisted_teleop import AssistedTeleop
2+
from nav2_msgs.action._back_up import BackUp
3+
from nav2_msgs.action._compute_path_through_poses import ComputePathThroughPoses
4+
from nav2_msgs.action._compute_path_to_pose import ComputePathToPose
5+
from nav2_msgs.action._dock_robot import DockRobot
6+
from nav2_msgs.action._drive_on_heading import DriveOnHeading
7+
from nav2_msgs.action._dummy_behavior import DummyBehavior
8+
from nav2_msgs.action._follow_gps_waypoints import FollowGPSWaypoints
9+
from nav2_msgs.action._follow_path import FollowPath
10+
from nav2_msgs.action._follow_waypoints import FollowWaypoints
11+
from nav2_msgs.action._navigate_through_poses import NavigateThroughPoses
12+
from nav2_msgs.action._navigate_to_pose import NavigateToPose
13+
from nav2_msgs.action._smooth_path import SmoothPath
14+
from nav2_msgs.action._spin import Spin
15+
from nav2_msgs.action._undock_robot import UndockRobot
16+
from nav2_msgs.action._wait import Wait
17+
18+
__all__ = [
19+
'AssistedTeleop',
20+
'BackUp',
21+
'ComputePathThroughPoses',
22+
'ComputePathToPose',
23+
'DockRobot',
24+
'DriveOnHeading',
25+
'DummyBehavior',
26+
'FollowGPSWaypoints',
27+
'FollowPath',
28+
'FollowWaypoints',
29+
'NavigateThroughPoses',
30+
'NavigateToPose',
31+
'SmoothPath',
32+
'Spin',
33+
'UndockRobot',
34+
'Wait',
35+
]

nav2_msgs/msg/__init__.py

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
from nav2_msgs.msg._behavior_tree_log import BehaviorTreeLog
2+
from nav2_msgs.msg._behavior_tree_status_change import BehaviorTreeStatusChange
3+
from nav2_msgs.msg._collision_detector_state import CollisionDetectorState
4+
from nav2_msgs.msg._collision_monitor_state import CollisionMonitorState
5+
from nav2_msgs.msg._costmap import Costmap
6+
from nav2_msgs.msg._costmap_filter_info import CostmapFilterInfo
7+
from nav2_msgs.msg._costmap_meta_data import CostmapMetaData
8+
from nav2_msgs.msg._costmap_update import CostmapUpdate
9+
from nav2_msgs.msg._missed_waypoint import MissedWaypoint
10+
from nav2_msgs.msg._particle import Particle
11+
from nav2_msgs.msg._particle_cloud import ParticleCloud
12+
from nav2_msgs.msg._speed_limit import SpeedLimit
13+
from nav2_msgs.msg._voxel_grid import VoxelGrid
14+
15+
__all__ = [
16+
'BehaviorTreeLog',
17+
'BehaviorTreeStatusChange',
18+
'CollisionDetectorState',
19+
'CollisionMonitorState',
20+
'Costmap',
21+
'CostmapFilterInfo',
22+
'CostmapMetaData',
23+
'CostmapUpdate',
24+
'MissedWaypoint',
25+
'Particle',
26+
'ParticleCloud',
27+
'SpeedLimit',
28+
'VoxelGrid',
29+
]

nav2_msgs/srv/__init__.py

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
from nav2_msgs.srv._clear_costmap_around_robot import ClearCostmapAroundRobot
2+
from nav2_msgs.srv._clear_costmap_except_region import ClearCostmapExceptRegion
3+
from nav2_msgs.srv._clear_entire_costmap import ClearEntireCostmap
4+
from nav2_msgs.srv._get_costmap import GetCostmap
5+
from nav2_msgs.srv._get_costs import GetCosts
6+
from nav2_msgs.srv._is_path_valid import IsPathValid
7+
from nav2_msgs.srv._load_map import LoadMap
8+
from nav2_msgs.srv._manage_lifecycle_nodes import ManageLifecycleNodes
9+
from nav2_msgs.srv._reload_dock_database import ReloadDockDatabase
10+
from nav2_msgs.srv._save_map import SaveMap
11+
from nav2_msgs.srv._set_initial_pose import SetInitialPose
12+
13+
__all__ = [
14+
'ClearCostmapAroundRobot',
15+
'ClearCostmapExceptRegion',
16+
'ClearEntireCostmap',
17+
'GetCostmap',
18+
'GetCosts',
19+
'IsPathValid',
20+
'LoadMap',
21+
'ManageLifecycleNodes',
22+
'ReloadDockDatabase',
23+
'SaveMap',
24+
'SetInitialPose',
25+
]

tools/pyproject.toml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,12 @@ module = [
2424
"launch.*",
2525
"ament_index_python.*",
2626
"nav2_common.*",
27+
"nav2_msgs.*",
2728
"launch_testing.*",
29+
"action_msgs.*",
30+
"geometry_msgs.*",
31+
"sensor_msgs.*",
32+
"tf2_ros.*",
2833
]
2934

3035
ignore_missing_imports = true

0 commit comments

Comments
 (0)