Skip to content
Merged
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
1 change: 1 addition & 0 deletions .github/workflows/lint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ jobs:
nav2_loopback_sim
nav2_map_server
nav2_simple_commander
nav2_system_tests
arguments: --config tools/pyproject.toml

pre-commit:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
from nav2_common.launch import RewrittenYaml


def generate_launch_description():
def generate_launch_description() -> LaunchDescription:
sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')
nav2_bringup_dir = get_package_share_directory('nav2_bringup')

Expand All @@ -43,7 +43,7 @@ def generate_launch_description():
bt_navigator_xml = os.path.join(
get_package_share_directory('nav2_bt_navigator'),
'behavior_trees',
os.getenv('BT_NAVIGATOR_XML'),
os.getenv('BT_NAVIGATOR_XML', ''),
)

params_file = os.path.join(nav2_bringup_dir, 'params/nav2_params.yaml')
Expand Down Expand Up @@ -109,10 +109,10 @@ def generate_launch_description():
)


def main(argv=sys.argv[1:]):
def main(argv: list[str] = sys.argv[1:]): # type: ignore[no-untyped-def]
ld = generate_launch_description()

testExecutable = os.getenv('TEST_EXECUTABLE')
testExecutable = os.getenv('TEST_EXECUTABLE', '')

test1_action = ExecuteProcess(
cmd=[testExecutable], name='test_assisted_teleop_behavior_node', output='screen'
Expand Down
51 changes: 27 additions & 24 deletions nav2_system_tests/src/behaviors/backup/backup_tester.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,22 +15,24 @@

import sys
import time
from typing import Optional

from action_msgs.msg import GoalStatus
from geometry_msgs.msg import Point32, PolygonStamped
from nav2_msgs.action import BackUp
from nav2_msgs.msg import Costmap
from nav2_msgs.srv import ManageLifecycleNodes
import rclpy
from rclpy.action import ActionClient
from rclpy.action import ActionClient # type: ignore[attr-defined]
from rclpy.action.client import ClientGoalHandle
from rclpy.duration import Duration
from rclpy.node import Node
from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy, QoSProfile, QoSReliabilityPolicy


class BackupTest(Node):

def __init__(self):
def __init__(self) -> None:
super().__init__(node_name='backup_tester', namespace='')
self.costmap_qos = QoSProfile(
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
Expand All @@ -43,10 +45,11 @@ def __init__(self):
Costmap, 'local_costmap/costmap_raw', self.costmap_qos)
self.footprint_pub = self.create_publisher(
PolygonStamped, 'local_costmap/published_footprint', 10)
self.goal_handle = None
self.action_result = None
self.goal_handle: Optional[ClientGoalHandle[
BackUp.Goal, BackUp.Result, BackUp.Feedback]] = None
self.action_result = BackUp.Result()

def sendCommand(self, command):
def sendCommand(self, command: BackUp.Goal) -> bool:
self.info_msg('Sending goal request...')
self.goal_future = self.action_client.send_goal_async(command)
try:
Expand All @@ -55,7 +58,7 @@ def sendCommand(self, command):
except Exception as e: # noqa: B902
self.error_msg(f'Service call failed {e!r}')

if not self.goal_handle.accepted:
if not self.goal_handle or not self.goal_handle.accepted:
self.error_msg('Goal rejected')
return False

Expand All @@ -65,8 +68,8 @@ def sendCommand(self, command):
self.info_msg("Waiting for 'Backup' action to complete")
try:
rclpy.spin_until_future_complete(self, self.result_future)
status = self.result_future.result().status
result = self.result_future.result().result
status = self.result_future.result().status # type: ignore[union-attr]
result = self.result_future.result().result # type: ignore[union-attr]
self.action_result = result
except Exception as e: # noqa: B902
self.error_msg(f'Service call failed {e!r}')
Expand All @@ -80,7 +83,7 @@ def sendCommand(self, command):
self.info_msg('Backup failed to meet target!')
return False

def sendAndPreemptWithFasterCommand(self, command):
def sendAndPreemptWithFasterCommand(self, command: BackUp.Goal) -> bool:
# Send initial goal
self.info_msg('Sending goal request...')
self.goal_future = self.action_client.send_goal_async(command)
Expand All @@ -90,7 +93,7 @@ def sendAndPreemptWithFasterCommand(self, command):
except Exception as e: # noqa: B902
self.error_msg(f'Service call failed {e!r}')

if not self.goal_handle.accepted:
if not self.goal_handle or not self.goal_handle.accepted:
self.error_msg('Goal rejected')
return False

Expand All @@ -108,7 +111,7 @@ def sendAndPreemptWithFasterCommand(self, command):
except Exception as e: # noqa: B902
self.error_msg(f'Service call failed {e!r}')

if not self.goal_handle.accepted:
if not self.goal_handle or not self.goal_handle.accepted:
self.error_msg('Preemption rejected')
return False

Expand All @@ -119,8 +122,8 @@ def sendAndPreemptWithFasterCommand(self, command):
self.info_msg("Waiting for 'backup' action Preemption to complete")
try:
rclpy.spin_until_future_complete(self, self.result_future)
status = self.result_future.result().status
result = self.result_future.result().result
status = self.result_future.result().status # type: ignore[union-attr]
result = self.result_future.result().result # type: ignore[union-attr]
self.action_result = result
except Exception as e: # noqa: B902
self.error_msg(f'Service call failed {e!r}')
Expand All @@ -134,7 +137,7 @@ def sendAndPreemptWithFasterCommand(self, command):
self.info_msg('Backup failed to meet target!')
return False

def sendAndCancelCommand(self, command):
def sendAndCancelCommand(self, command: BackUp.Goal) -> bool:
self.info_msg('Sending goal request...')
self.goal_future = self.action_client.send_goal_async(command)
try:
Expand All @@ -143,7 +146,7 @@ def sendAndCancelCommand(self, command):
except Exception as e: # noqa: B902
self.error_msg(f'Service call failed {e!r}')

if not self.goal_handle.accepted:
if not self.goal_handle or not self.goal_handle.accepted:
self.error_msg('Goal rejected')
return False

Expand All @@ -155,15 +158,15 @@ def sendAndCancelCommand(self, command):
cancel_future = self.goal_handle.cancel_goal_async()
rclpy.spin_until_future_complete(self, cancel_future)
rclpy.spin_until_future_complete(self, self.result_future)
status = self.result_future.result().status
status = self.result_future.result().status # type: ignore[union-attr]
if status != GoalStatus.STATUS_CANCELED:
self.info_msg(f'Goal failed with status code: {status}')
return False
else:
self.info_msg('Goal was canceled successfully')
return True

def sendFreeCostmap(self):
def sendFreeCostmap(self) -> None:
costmap_msg = Costmap()
costmap_msg.header.frame_id = 'odom'
costmap_msg.header.stamp = self.get_clock().now().to_msg()
Expand All @@ -186,7 +189,7 @@ def sendFreeCostmap(self):
]
self.footprint_pub.publish(footprint_msg)

def sendOccupiedCostmap(self):
def sendOccupiedCostmap(self) -> None:
costmap_msg = Costmap()
costmap_msg.header.frame_id = 'odom'
costmap_msg.header.stamp = self.get_clock().now().to_msg()
Expand All @@ -209,7 +212,7 @@ def sendOccupiedCostmap(self):
]
self.footprint_pub.publish(footprint_msg)

def run(self):
def run(self) -> bool:
while not self.action_client.wait_for_server(timeout_sec=1.0):
self.info_msg("'Backup' action server not available, waiting...")

Expand Down Expand Up @@ -278,7 +281,7 @@ def run(self):
self.info_msg('Test D passed')
return True

def shutdown(self):
def shutdown(self) -> None:
self.info_msg('Shutting down')

self.action_client.destroy()
Expand All @@ -300,17 +303,17 @@ def shutdown(self):

self.info_msg(f'{transition_service} finished')

def info_msg(self, msg: str):
def info_msg(self, msg: str) -> None:
self.get_logger().info(msg)

def warn_msg(self, msg: str):
def warn_msg(self, msg: str) -> None:
self.get_logger().warn(msg)

def error_msg(self, msg: str):
def error_msg(self, msg: str) -> None:
self.get_logger().error(msg)


def main(argv=sys.argv[1:]):
def main(argv: list[str] = sys.argv[1:]): # type: ignore[no-untyped-def]
rclpy.init()
time.sleep(10)
test = BackupTest()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
from nav2_common.launch import RewrittenYaml


def generate_launch_description():
def generate_launch_description() -> LaunchDescription:
bringup_dir = get_package_share_directory('nav2_bringup')
sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')
params_file = LaunchConfiguration('params_file')
Expand Down Expand Up @@ -133,12 +133,13 @@ def generate_launch_description():
)


def main(argv=sys.argv[1:]):
def main(argv: list[str] = sys.argv[1:]): # type: ignore[no-untyped-def]
ld = generate_launch_description()

test1_action = ExecuteProcess(
cmd=[os.path.join(
os.getenv('TEST_DIR'), 'backup_tester.py'), '--ros-args', '-p', 'use_sim_time:=True'],
os.getenv('TEST_DIR', ''),
'backup_tester.py'), '--ros-args', '-p', 'use_sim_time:=True'],
name='tester_node',
output='screen',
)
Expand Down
Loading
Loading