Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
58 changes: 24 additions & 34 deletions .github/workflows/lint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -3,42 +3,32 @@ on:
pull_request:

jobs:
ament_lint_general:
name: ament_${{ matrix.linter }}
runs-on: ubuntu-latest
container:
image: rostooling/setup-ros-docker:ubuntu-noble-ros-rolling-ros-base-latest
strategy:
fail-fast: false
matrix:
linter: [xmllint, cpplint, uncrustify, pep257, flake8, mypy]
steps:
- uses: actions/checkout@v6

- name: Install typeshed for mypy
if: matrix.linter == 'mypy'
run: sudo apt update && sudo apt install -y python3-typeshed

- uses: ros-tooling/action-ros-lint@0.1.4
with:
linter: ${{ matrix.linter }}
distribution: rolling
package-name: "*"
arguments: ${{ matrix.linter == 'mypy' && '--config tools/pyproject.toml' || '' }}

pre-commit:
name: pre-commit
runs-on: ubuntu-latest
container:
image: ghcr.io/ros-navigation/navigation2:main
env:
path: src/${{ github.repository }}
steps:
- uses: actions/checkout@v6
- uses: actions/setup-python@v6
- uses: pre-commit/action@v3.0.1
env:
SKIP: >-
ament_lint_cmake,
ament_cpplint,
ament_uncrustify,
ament_xmllint,
ament_flake8,
ament_pep257,
ament_mypy
with:
path: ${{ env.path }}
- name: Install pre-commit
shell: bash
run: |
sudo apt-get update
sudo apt-get install -y python3-venv
python3 -m venv .venv
source .venv/bin/activate
python3 -m pip install pre-commit
- uses: actions/cache@v4
with:
path: ~/.cache/pre-commit
key: pre-commit-3|${{ env.path }}|${{ hashFiles('.pre-commit-config.yaml') }}
- run: |
source .venv/bin/activate
source /opt/ros/rolling/setup.bash
cd ${{ env.path }}
pre-commit run --show-diff-on-failure --color=always --all-files
shell: bash
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
exclude: ".pgm$|.svg$"
repos:
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v5.0.0
rev: v6.0.0
hooks:
- id: check-added-large-files
- id: check-ast
Expand All @@ -33,7 +33,7 @@ repos:
exclude_types: [rst]
- id: fix-byte-order-marker
- repo: https://github.com/pycqa/isort
rev: 6.0.1
rev: 7.0.0
hooks:
- id: isort
args: ["tools/pyproject.toml"]
Expand All @@ -48,7 +48,7 @@ repos:
args:
[--toml=./tools/pyproject.toml]
- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.31.1
rev: 0.36.0
hooks:
- id: check-github-workflows
args: ["--verbose"]
Expand Down
31 changes: 16 additions & 15 deletions nav2_docking/opennav_docking/test/test_docking_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -285,6 +285,7 @@ def test_docking_server(self) -> None:

# Test docking action
self.action_result = []
self.undock_action_result = []
assert self.dock_action_client.wait_for_server(timeout_sec=5.0), \
'dock_robot service not available'

Expand Down Expand Up @@ -361,21 +362,21 @@ def test_docking_server(self) -> None:
# Test undocking action
self.is_charging = False
self.undock_action_client.wait_for_server(timeout_sec=5.0)
goal = UndockRobot.Goal()
goal.dock_type = 'test_dock_plugin'
future = self.undock_action_client.send_goal_async(goal)
rclpy.spin_until_future_complete(self.node, future)
self.goal_handle = future.result()
assert self.goal_handle is not None, 'goal_handle should not be None'
assert self.goal_handle.accepted, 'goal_handle not accepted'
result_future = self.goal_handle.get_result_async()
rclpy.spin_until_future_complete(self.node, result_future)
self.action_result.append(result_future.result())

self.assertIsNotNone(self.action_result[3])
if self.action_result[3] is not None:
self.assertEqual(self.action_result[3].status, GoalStatus.STATUS_SUCCEEDED)
self.assertTrue(self.action_result[3].result.success)
undock_goal = UndockRobot.Goal()
undock_goal.dock_type = 'test_dock_plugin'
undock_future = self.undock_action_client.send_goal_async(undock_goal)
rclpy.spin_until_future_complete(self.node, undock_future)
self.undock_goal_handle = undock_future.result()
assert self.undock_goal_handle is not None, 'goal_handle should not be None'
assert self.undock_goal_handle.accepted, 'goal_handle not accepted'
undock_result_future = self.undock_goal_handle.get_result_async()
rclpy.spin_until_future_complete(self.node, undock_result_future)
self.undock_action_result.append(undock_result_future.result())

self.assertIsNotNone(self.undock_action_result[3])
if self.undock_action_result[3] is not None:
self.assertEqual(self.undock_action_result[3].status, GoalStatus.STATUS_SUCCEEDED)
self.assertTrue(self.undock_action_result[3].result.success)


@launch_testing.post_shutdown_test() # type: ignore[no-untyped-call]
Expand Down
10 changes: 5 additions & 5 deletions nav2_following/opennav_following/test/test_following_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -219,8 +219,8 @@ def at_distance_getter() -> bool:

def wait_for_node_to_be_active(self, node_name: str, timeout_sec: float = 10.0) -> None:
"""Wait for a managed node to become active."""
client: Client[GetState.Request, GetState.Response] = ( # type: ignore[name-defined]
self.node.create_client(GetState, f'{node_name}/get_state') # type: ignore[arg-type]
client: Client[GetState.Request, GetState.Response] = (
self.node.create_client(GetState, f'{node_name}/get_state')
)
if not client.wait_for_service(timeout_sec=2.0):
self.fail(f'Service get_state for {node_name} not available.')
Expand Down Expand Up @@ -281,7 +281,7 @@ def publish(self) -> None:

def action_feedback_callback(
self,
msg: FollowObject.Feedback # type: ignore[name-defined]
msg: FollowObject.Feedback
) -> None:
# Force the following action to run a full recovery loop when
# the robot is at distance
Expand All @@ -300,9 +300,9 @@ def test_following_server(self) -> None:
self.timer = self.node.create_timer(0.05, self.timer_callback)

# Create action client
self.follow_action_client: ActionClient[ # type: ignore[name-defined]
self.follow_action_client: ActionClient[
FollowObject.Goal, FollowObject.Result, FollowObject.Feedback
] = ActionClient(self.node, FollowObject, 'follow_object') # type: ignore[arg-type]
] = ActionClient(self.node, FollowObject, 'follow_object')

# Subscribe to command velocity
self.node.create_subscription(
Expand Down
2 changes: 1 addition & 1 deletion nav2_loopback_sim/test/test_copyright.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,5 +19,5 @@
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright() -> None:
rc = main(argv=['.', 'test'])
rc = main(argv=['.', 'test']) # type: ignore[no-untyped-call]
assert rc == 0, 'Found errors'
2 changes: 1 addition & 1 deletion nav2_loopback_sim/test/test_flake8.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,6 @@
@pytest.mark.flake8
@pytest.mark.linter
def test_flake8() -> None:
rc, errors = main_with_errors(argv=[])
rc, errors = main_with_errors(argv=[]) # type: ignore[no-untyped-call]
assert rc == 0, f'Found {len(errors)} code style errors / warnings:\n' + \
'\n'.join(errors)
2 changes: 1 addition & 1 deletion nav2_loopback_sim/test/test_pep257.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,5 +19,5 @@
@pytest.mark.linter
@pytest.mark.pep257
def test_pep257() -> None:
rc = main(argv=['.', 'test'])
rc = main(argv=['.', 'test']) # type: ignore[no-untyped-call]
assert rc == 0, 'Found code style errors / warnings'
2 changes: 2 additions & 0 deletions nav2_msgs/action/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
from nav2_msgs.action._drive_on_heading import DriveOnHeading
from nav2_msgs.action._dummy_behavior import DummyBehavior
from nav2_msgs.action._follow_gps_waypoints import FollowGPSWaypoints
from nav2_msgs.action._follow_object import FollowObject
from nav2_msgs.action._follow_path import FollowPath
from nav2_msgs.action._follow_waypoints import FollowWaypoints
from nav2_msgs.action._navigate_through_poses import NavigateThroughPoses
Expand All @@ -29,6 +30,7 @@
'DummyBehavior',
'FollowGPSWaypoints',
'FollowPath',
'FollowObject',
'FollowWaypoints',
'NavigateThroughPoses',
'NavigateToPose',
Expand Down
10 changes: 5 additions & 5 deletions nav2_simple_commander/nav2_simple_commander/robot_navigator.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,11 @@
from geographic_msgs.msg import GeoPose
from geometry_msgs.msg import Point, PoseStamped, PoseWithCovarianceStamped
from lifecycle_msgs.srv import GetState
from nav2_msgs.action import (AssistedTeleop, BackUp, # type: ignore[attr-defined]
ComputeAndTrackRoute, ComputePathThroughPoses, ComputePathToPose,
ComputeRoute, DockRobot, DriveOnHeading, FollowGPSWaypoints,
FollowObject, FollowPath, FollowWaypoints, NavigateThroughPoses,
NavigateToPose, SmoothPath, Spin, UndockRobot)
from nav2_msgs.action import (AssistedTeleop, BackUp, ComputeAndTrackRoute,
ComputePathThroughPoses, ComputePathToPose, ComputeRoute, DockRobot,
DriveOnHeading, FollowGPSWaypoints, FollowObject, FollowPath,
FollowWaypoints, NavigateThroughPoses, NavigateToPose, SmoothPath,
Spin, UndockRobot)
from nav2_msgs.msg import Costmap, Route
from nav2_msgs.srv import (ClearCostmapAroundPose, ClearCostmapAroundRobot,
ClearCostmapExceptRegion, ClearEntireCostmap, GetCostmap, LoadMap,
Expand Down
2 changes: 1 addition & 1 deletion nav2_simple_commander/test/test_copyright.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,5 +19,5 @@
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright() -> None:
rc = main(argv=['.', 'test'])
rc = main(argv=['.', 'test']) # type: ignore[no-untyped-call]
assert rc == 0, 'Found errors'
2 changes: 1 addition & 1 deletion nav2_simple_commander/test/test_flake8.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,6 @@
@pytest.mark.flake8
@pytest.mark.linter
def test_flake8() -> None:
rc, errors = main_with_errors(argv=[])
rc, errors = main_with_errors(argv=[]) # type: ignore[no-untyped-call]
assert rc == 0, f'Found {len(errors)} code style errors / warnings:\n' \
+ '\n'.join(errors)
2 changes: 1 addition & 1 deletion nav2_simple_commander/test/test_pep257.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,5 +19,5 @@
@pytest.mark.linter
@pytest.mark.pep257
def test_pep257() -> None:
rc = main(argv=['.', 'test'])
rc = main(argv=['.', 'test']) # type: ignore[no-untyped-call]
assert rc == 0, 'Found code style errors / warnings'
Original file line number Diff line number Diff line change
Expand Up @@ -308,7 +308,7 @@ def shutdown(self) -> None:
self.info_msg(f'{transition_service} service not available, waiting...')

req = ManageLifecycleNodes.Request()
req.command = ManageLifecycleNodes.Request().SHUTDOWN
req.command = ManageLifecycleNodes.Request.SHUTDOWN
future = mgr_client.call_async(req)
try:
rclpy.spin_until_future_complete(self, future)
Expand Down
2 changes: 1 addition & 1 deletion nav2_system_tests/src/behaviors/spin/spin_tester.py
Original file line number Diff line number Diff line change
Expand Up @@ -289,7 +289,7 @@ def shutdown(self) -> None:
self.info_msg(f'{transition_service} service not available, waiting...')

req = ManageLifecycleNodes.Request()
req.command = ManageLifecycleNodes.Request().SHUTDOWN
req.command = ManageLifecycleNodes.Request.SHUTDOWN
future = mgr_client.call_async(req)
try:
rclpy.spin_until_future_complete(self, future)
Expand Down
6 changes: 3 additions & 3 deletions nav2_system_tests/src/costmap_filters/tester_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ def __init__(
self.limits = [50.0, 0.0]
# Permissive array: all received speed limits must match to 'limits' from above
self.limit_passed = [False, False]
self.plan_sub = self.create_subscription(
self.speed_limit_sub = self.create_subscription(
SpeedLimit, 'speed_limit', self.speedLimitCallback, volatile_qos
)

Expand Down Expand Up @@ -390,7 +390,7 @@ def shutdown(self) -> None:
self.info_msg(f'{transition_service} service not available, waiting...')

req = ManageLifecycleNodes.Request()
req.command = ManageLifecycleNodes.Request().SHUTDOWN
req.command = ManageLifecycleNodes.Request.SHUTDOWN
future = mgr_client.call_async(req)
try:
self.info_msg('Shutting down navigation lifecycle manager...')
Expand All @@ -405,7 +405,7 @@ def shutdown(self) -> None:
self.info_msg(f'{transition_service} service not available, waiting...')

req = ManageLifecycleNodes.Request()
req.command = ManageLifecycleNodes.Request().SHUTDOWN
req.command = ManageLifecycleNodes.Request.SHUTDOWN
future = mgr_client.call_async(req)
try:
self.info_msg('Shutting down localization lifecycle manager...')
Expand Down
64 changes: 32 additions & 32 deletions nav2_system_tests/src/error_codes/test_error_codes.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,13 +56,13 @@ def main(argv: list[str] = sys.argv[1:]): # type: ignore[no-untyped-def]

navigator._waitForNodeToActivate('controller_server')
follow_path = {
'unknown': FollowPath.Result().UNKNOWN,
'invalid_controller': FollowPath.Result().INVALID_CONTROLLER,
'tf_error': FollowPath.Result().TF_ERROR,
'invalid_path': FollowPath.Result().INVALID_PATH,
'patience_exceeded': FollowPath.Result().PATIENCE_EXCEEDED,
'failed_to_make_progress': FollowPath.Result().FAILED_TO_MAKE_PROGRESS,
'no_valid_control': FollowPath.Result().NO_VALID_CONTROL,
'unknown': FollowPath.Result.UNKNOWN,
'invalid_controller': FollowPath.Result.INVALID_CONTROLLER,
'tf_error': FollowPath.Result.TF_ERROR,
'invalid_path': FollowPath.Result.INVALID_PATH,
'patience_exceeded': FollowPath.Result.PATIENCE_EXCEEDED,
'failed_to_make_progress': FollowPath.Result.FAILED_TO_MAKE_PROGRESS,
'no_valid_control': FollowPath.Result.NO_VALID_CONTROL,
}

for controller, error_code in follow_path.items():
Expand Down Expand Up @@ -94,15 +94,15 @@ def main(argv: list[str] = sys.argv[1:]): # type: ignore[no-untyped-def]

navigator._waitForNodeToActivate('planner_server')
compute_path_to_pose = {
'unknown': ComputePathToPose.Result().UNKNOWN,
'invalid_planner': ComputePathToPose.Result().INVALID_PLANNER,
'tf_error': ComputePathToPose.Result().TF_ERROR,
'start_outside_map': ComputePathToPose.Result().START_OUTSIDE_MAP,
'goal_outside_map': ComputePathToPose.Result().GOAL_OUTSIDE_MAP,
'start_occupied': ComputePathToPose.Result().START_OCCUPIED,
'goal_occupied': ComputePathToPose.Result().GOAL_OCCUPIED,
'timeout': ComputePathToPose.Result().TIMEOUT,
'no_valid_path': ComputePathToPose.Result().NO_VALID_PATH,
'unknown': ComputePathToPose.Result.UNKNOWN,
'invalid_planner': ComputePathToPose.Result.INVALID_PLANNER,
'tf_error': ComputePathToPose.Result.TF_ERROR,
'start_outside_map': ComputePathToPose.Result.START_OUTSIDE_MAP,
'goal_outside_map': ComputePathToPose.Result.GOAL_OUTSIDE_MAP,
'start_occupied': ComputePathToPose.Result.START_OCCUPIED,
'goal_occupied': ComputePathToPose.Result.GOAL_OCCUPIED,
'timeout': ComputePathToPose.Result.TIMEOUT,
'no_valid_path': ComputePathToPose.Result.NO_VALID_PATH,
}

for planner, error_code in compute_path_to_pose.items():
Expand Down Expand Up @@ -130,16 +130,16 @@ def cancel_task() -> None:
goal_poses = [goal_pose, goal_pose1]

compute_path_through_poses = {
'unknown': ComputePathThroughPoses.Result().UNKNOWN,
'invalid_planner': ComputePathThroughPoses.Result().INVALID_PLANNER,
'tf_error': ComputePathThroughPoses.Result().TF_ERROR,
'start_outside_map': ComputePathThroughPoses.Result().START_OUTSIDE_MAP,
'goal_outside_map': ComputePathThroughPoses.Result().GOAL_OUTSIDE_MAP,
'start_occupied': ComputePathThroughPoses.Result().START_OCCUPIED,
'goal_occupied': ComputePathThroughPoses.Result().GOAL_OCCUPIED,
'timeout': ComputePathThroughPoses.Result().TIMEOUT,
'no_valid_path': ComputePathThroughPoses.Result().NO_VALID_PATH,
'no_viapoints_given': ComputePathThroughPoses.Result().NO_VIAPOINTS_GIVEN,
'unknown': ComputePathThroughPoses.Result.UNKNOWN,
'invalid_planner': ComputePathThroughPoses.Result.INVALID_PLANNER,
'tf_error': ComputePathThroughPoses.Result.TF_ERROR,
'start_outside_map': ComputePathThroughPoses.Result.START_OUTSIDE_MAP,
'goal_outside_map': ComputePathThroughPoses.Result.GOAL_OUTSIDE_MAP,
'start_occupied': ComputePathThroughPoses.Result.START_OCCUPIED,
'goal_occupied': ComputePathThroughPoses.Result.GOAL_OCCUPIED,
'timeout': ComputePathThroughPoses.Result.TIMEOUT,
'no_valid_path': ComputePathThroughPoses.Result.NO_VALID_PATH,
'no_viapoints_given': ComputePathThroughPoses.Result.NO_VIAPOINTS_GIVEN,
}

for planner, error_code in compute_path_through_poses.items():
Expand Down Expand Up @@ -176,12 +176,12 @@ def cancel_task() -> None:

navigator._waitForNodeToActivate('smoother_server')
smoother_errors = {
'invalid_smoother': SmoothPath.Result().INVALID_SMOOTHER,
'unknown': SmoothPath.Result().UNKNOWN,
'timeout': SmoothPath.Result().TIMEOUT,
'smoothed_path_in_collision': SmoothPath.Result().SMOOTHED_PATH_IN_COLLISION,
'failed_to_smooth_path': SmoothPath.Result().FAILED_TO_SMOOTH_PATH,
'invalid_path': SmoothPath.Result().INVALID_PATH,
'invalid_smoother': SmoothPath.Result.INVALID_SMOOTHER,
'unknown': SmoothPath.Result.UNKNOWN,
'timeout': SmoothPath.Result.TIMEOUT,
'smoothed_path_in_collision': SmoothPath.Result.SMOOTHED_PATH_IN_COLLISION,
'failed_to_smooth_path': SmoothPath.Result.FAILED_TO_SMOOTH_PATH,
'invalid_path': SmoothPath.Result.INVALID_PATH,
}

for smoother, error_code in smoother_errors.items():
Expand Down
Loading
Loading