feat: Add parameter profile YAML files for Nav2 (Issue #506)

- profile_indoor.yaml: Conservative settings (0.4 m/s, 0.35m inflation)
- profile_outdoor.yaml: Moderate settings (0.8 m/s, 0.3m inflation)
- profile_demo.yaml: Agile settings (0.6 m/s, 0.32m inflation)

Each profile customizes velocity limits, costmap inflation, and obstacle detection.
This commit is contained in:
sl-controls 2026-03-06 16:41:49 -05:00 committed by sl-webui
parent 5d17b6c501
commit e5329391bc
3 changed files with 259 additions and 0 deletions

View File

@ -0,0 +1,126 @@
# Profile: Demo Mode (Issue #506)
# Agile settings for demonstration and autonomous tricks
# - Medium-high velocities for responsive behavior (0.6 m/s)
# - Enhanced obstacle detection with all sensors
# - Balanced costmap inflation (0.32m)
# - Medium-sized local costmap (3.5m x 3.5m)
# - Tuned for tricks demonstrations (spin, backups, dynamic behaviors)
velocity_smoother:
ros__parameters:
max_velocity: [0.6, 0.0, 1.2] # Agile: 0.6 m/s forward, 1.2 rad/s angular
min_velocity: [-0.3, 0.0, -1.2]
smoothing_frequency: 20.0 # Increased smoothing for tricks
controller_server:
ros__parameters:
controller_frequency: 10.0 # Hz
FollowPath:
max_vel_x: 0.6 # Agile forward speed
max_vel_theta: 1.2
min_vel_x: -0.3
vx_samples: 25 # More sampling for agility
vy_samples: 5
vtheta_samples: 25
sim_time: 1.7
critics:
["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
BaseObstacle.scale: 0.025 # Enhanced obstacle avoidance
PathAlign.scale: 32.0
GoalAlign.scale: 24.0
PathDist.scale: 32.0
GoalDist.scale: 24.0
RotateToGoal.scale: 32.0
RotateToGoal.slowing_factor: 4.0 # Faster rotations for tricks
behavior_server:
ros__parameters:
cycle_frequency: 10.0
max_rotational_vel: 1.5 # Enable faster spins for tricks
min_rotational_vel: 0.3
local_costmap:
local_costmap:
ros__parameters:
width: 3.5 # 3.5m x 3.5m rolling window
height: 3.5
resolution: 0.05
update_frequency: 10.0
publish_frequency: 5.0
plugins: ["obstacle_layer", "voxel_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
observation_sources: scan surround_cameras
scan:
topic: /scan
max_obstacle_height: 0.80
clearing: true
marking: true
data_type: "LaserScan"
raytrace_max_range: 8.0
obstacle_max_range: 7.5
surround_cameras:
topic: /surround_vision/obstacles
min_obstacle_height: 0.05
max_obstacle_height: 1.50
marking: true
data_type: "PointCloud2"
raytrace_max_range: 3.5
obstacle_max_range: 3.0
voxel_layer:
enabled: true
observation_sources: depth_camera
depth_camera:
topic: /camera/depth/color/points
min_obstacle_height: 0.05
max_obstacle_height: 0.80
marking: true
clearing: true
data_type: "PointCloud2"
raytrace_max_range: 4.0
obstacle_max_range: 3.5
inflation_layer:
cost_scaling_factor: 3.0
inflation_radius: 0.32 # Balanced inflation for demo tricks
global_costmap:
global_costmap:
ros__parameters:
resolution: 0.05
update_frequency: 5.0
publish_frequency: 1.0
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
observation_sources: scan depth_scan surround_cameras
scan:
topic: /scan
max_obstacle_height: 0.80
clearing: true
marking: true
data_type: "LaserScan"
raytrace_max_range: 8.0
obstacle_max_range: 7.5
depth_scan:
topic: /depth_scan
max_obstacle_height: 0.80
clearing: true
marking: true
data_type: "LaserScan"
raytrace_max_range: 6.0
obstacle_max_range: 5.5
surround_cameras:
topic: /surround_vision/obstacles
min_obstacle_height: 0.05
max_obstacle_height: 1.50
marking: true
data_type: "PointCloud2"
raytrace_max_range: 3.5
obstacle_max_range: 3.0
inflation_layer:
cost_scaling_factor: 3.0
inflation_radius: 0.32 # Balanced inflation for demo tricks

View File

@ -0,0 +1,55 @@
# Profile: Indoor Mode (Issue #506)
# Conservative settings for safe indoor navigation
# - Lower max velocities for precision and safety (0.4 m/s)
# - Tighter costmap inflation for confined spaces (0.35m)
# - Aggressive obstacle detection (RealSense depth + LIDAR + surround cameras)
# - Smaller local costmap window (3m x 3m)
velocity_smoother:
ros__parameters:
max_velocity: [0.4, 0.0, 0.8] # Conservative: 0.4 m/s forward, 0.8 rad/s angular
min_velocity: [-0.2, 0.0, -0.8]
controller_server:
ros__parameters:
controller_frequency: 10.0 # Hz
FollowPath:
max_vel_x: 0.4 # Conservative forward speed
max_vel_theta: 0.8
min_vel_x: -0.2
vx_samples: 20
vy_samples: 5
vtheta_samples: 20
sim_time: 1.7
critics:
["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
BaseObstacle.scale: 0.03 # Slightly aggressive obstacle avoidance
PathAlign.scale: 32.0
GoalAlign.scale: 24.0
PathDist.scale: 32.0
GoalDist.scale: 24.0
RotateToGoal.scale: 32.0
local_costmap:
local_costmap:
ros__parameters:
width: 3 # 3m x 3m rolling window
height: 3
resolution: 0.05
update_frequency: 10.0
plugins: ["obstacle_layer", "voxel_layer", "inflation_layer"]
inflation_layer:
cost_scaling_factor: 3.0
inflation_radius: 0.35 # Tighter inflation for confined spaces
global_costmap:
global_costmap:
ros__parameters:
resolution: 0.05
update_frequency: 5.0
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
inflation_layer:
cost_scaling_factor: 3.0
inflation_radius: 0.35 # Tighter inflation for confined spaces

View File

@ -0,0 +1,78 @@
# Profile: Outdoor Mode (Issue #506)
# Moderate settings for outdoor GPS-based navigation
# - Medium velocities for practical outdoor operation (0.8 m/s)
# - Standard costmap inflation (0.3m)
# - Larger local costmap window (4m x 4m) for path preview
# - Reduced obstacle layer complexity (LIDAR focused)
velocity_smoother:
ros__parameters:
max_velocity: [0.8, 0.0, 1.0] # Moderate: 0.8 m/s forward, 1.0 rad/s angular
min_velocity: [-0.4, 0.0, -1.0]
controller_server:
ros__parameters:
controller_frequency: 10.0 # Hz
FollowPath:
max_vel_x: 0.8 # Moderate forward speed
max_vel_theta: 1.0
min_vel_x: -0.4
vx_samples: 20
vy_samples: 5
vtheta_samples: 20
sim_time: 1.7
critics:
["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
BaseObstacle.scale: 0.02 # Standard obstacle avoidance
PathAlign.scale: 32.0
GoalAlign.scale: 24.0
PathDist.scale: 32.0
GoalDist.scale: 24.0
RotateToGoal.scale: 32.0
local_costmap:
local_costmap:
ros__parameters:
width: 4 # 4m x 4m rolling window
height: 4
resolution: 0.05
update_frequency: 5.0
plugins: ["obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 0.80
clearing: true
marking: true
data_type: "LaserScan"
raytrace_max_range: 8.0
obstacle_max_range: 7.5
inflation_layer:
cost_scaling_factor: 3.0
inflation_radius: 0.3 # Standard inflation
global_costmap:
global_costmap:
ros__parameters:
resolution: 0.05
update_frequency: 5.0
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 0.80
clearing: true
marking: true
data_type: "LaserScan"
raytrace_max_range: 8.0
obstacle_max_range: 7.5
inflation_layer:
cost_scaling_factor: 3.0
inflation_radius: 0.3 # Standard inflation