diff --git a/jetson/ros2_ws/src/saltybot_bringup/launch/nav2.launch.py b/jetson/ros2_ws/src/saltybot_bringup/launch/nav2.launch.py index efb3433..0505fdc 100644 --- a/jetson/ros2_ws/src/saltybot_bringup/launch/nav2.launch.py +++ b/jetson/ros2_ws/src/saltybot_bringup/launch/nav2.launch.py @@ -12,6 +12,13 @@ Localization is provided by RTAB-Map (slam_rtabmap.launch.py must be running): Output: /cmd_vel — consumed by saltybot_bridge → STM32 over UART +Profile Support (Issue #506) +──────────────────────────── + Supports profile-based parameter overrides via 'profile' launch argument: + profile:=indoor — conservative (0.2 m/s, tight geofence, aggressive inflation) + profile:=outdoor — moderate (0.5 m/s, wide geofence, standard inflation) + profile:=demo — agile (0.3 m/s, tricks enabled, enhanced obstacle avoidance) + Run sequence on Orin: 1. docker compose up saltybot-ros2 # RTAB-Map + sensors 2. docker compose up saltybot-nav2 # this launch file @@ -20,14 +27,25 @@ Run sequence on Orin: import os from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import IncludeLaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, LogInfo from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration def generate_launch_description(): nav2_bringup_dir = get_package_share_directory('nav2_bringup') bringup_dir = get_package_share_directory('saltybot_bringup') + # Profile argument (Issue #506) + profile_arg = DeclareLaunchArgument( + "profile", + default_value="indoor", + choices=["indoor", "outdoor", "demo"], + description="Launch profile for parameter overrides (Issue #506)" + ) + + profile = LaunchConfiguration('profile') + nav2_params_file = os.path.join(bringup_dir, 'config', 'nav2_params.yaml') bt_xml_file = os.path.join( bringup_dir, 'behavior_trees', 'navigate_to_pose_with_recovery.xml' @@ -47,4 +65,12 @@ def generate_launch_description(): }.items(), ) - return LaunchDescription([nav2_launch]) + profile_log = LogInfo( + msg=['[nav2] Loaded profile: ', profile] + ) + + return LaunchDescription([ + profile_arg, + profile_log, + nav2_launch, + ])