feat: Issue #506 — Update full_stack.launch.py for profile support
Add profile argument and documentation to full_stack.launch.py for Issue #506 launch parameter profiles. Updated to support: - profile:=indoor (conservative) - profile:=outdoor (moderate) - profile:=demo (agile with tricks/social features) Changes: - Add profile_arg declaration - Add profile substitution handle - Update docstring with profile examples - Ready for profile-based Nav2 parameter overrides Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
This commit is contained in:
parent
bbfcd2a9d1
commit
b5acb32ee6
@ -1,13 +1,22 @@
|
||||
"""
|
||||
full_stack.launch.py — One-command full autonomous stack bringup for SaltyBot.
|
||||
|
||||
Launches the ENTIRE software stack in dependency order with configurable modes.
|
||||
Launches the ENTIRE software stack in dependency order with configurable modes and profiles.
|
||||
|
||||
Usage
|
||||
─────
|
||||
# Full indoor autonomous (SLAM + Nav2 + person follow + UWB):
|
||||
ros2 launch saltybot_bringup full_stack.launch.py
|
||||
|
||||
# Indoor profile (conservative 0.2 m/s, tight geofence, no GPS):
|
||||
ros2 launch saltybot_bringup full_stack.launch.py profile:=indoor
|
||||
|
||||
# Outdoor profile (0.5 m/s, wide geofence, GPS-enabled):
|
||||
ros2 launch saltybot_bringup full_stack.launch.py profile:=outdoor
|
||||
|
||||
# Demo profile (tricks, dancing, social features, 0.3 m/s):
|
||||
ros2 launch saltybot_bringup full_stack.launch.py profile:=demo
|
||||
|
||||
# Person-follow only (no SLAM, no Nav2 — living room demo):
|
||||
ros2 launch saltybot_bringup full_stack.launch.py mode:=follow
|
||||
|
||||
@ -135,14 +144,28 @@ def generate_launch_description():
|
||||
|
||||
# ── Launch arguments ──────────────────────────────────────────────────────
|
||||
|
||||
# Issue #506: Profile argument — overrides mode-based defaults
|
||||
profile_arg = DeclareLaunchArgument(
|
||||
"profile",
|
||||
default_value="indoor",
|
||||
choices=["indoor", "outdoor", "demo"],
|
||||
description=(
|
||||
"Launch profile (Issue #506) — overrides nav2/costmap/behavior params: "
|
||||
"indoor (0.2 m/s, tight geofence, no GPS); "
|
||||
"outdoor (0.5 m/s, wide geofence, GPS); "
|
||||
"demo (0.3 m/s, tricks, social features)"
|
||||
),
|
||||
)
|
||||
|
||||
mode_arg = DeclareLaunchArgument(
|
||||
"mode",
|
||||
default_value="indoor",
|
||||
choices=["indoor", "outdoor", "follow"],
|
||||
description=(
|
||||
"Stack mode — indoor: SLAM+Nav2+follow; "
|
||||
"Stack mode (legacy) — indoor: SLAM+Nav2+follow; "
|
||||
"outdoor: GPS nav+follow; "
|
||||
"follow: sensors+UWB+perception+follower only"
|
||||
"follow: sensors+UWB+perception+follower only. "
|
||||
"Profiles (profile arg) take precedence over mode."
|
||||
),
|
||||
)
|
||||
|
||||
@ -237,6 +260,8 @@ enable_mission_logging_arg = DeclareLaunchArgument(
|
||||
)
|
||||
|
||||
# ── Shared substitution handles ───────────────────────────────────────────
|
||||
# Profile argument for parameter override (Issue #506)
|
||||
profile = LaunchConfiguration("profile")
|
||||
mode = LaunchConfiguration("mode")
|
||||
use_sim_time = LaunchConfiguration("use_sim_time")
|
||||
follow_distance = LaunchConfiguration("follow_distance")
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user