feat: Configure Nav2 navigation stack conservative speeds (Issue #475)
- Update max_vel_x to 0.3 m/s (conservative for FC + hoverboard ESC) - Update max_vel_theta to 0.5 rad/s (conservative for FC + hoverboard ESC) - Set robot_radius to 0.22 m for 0.4m x 0.4m footprint - Configure velocity smoother with conservative limits - Both DWB local planner and velocity smoother updated for consistency - RPLIDAR (/scan) + depth_to_laserscan (/depth_scan) costmap layers enabled - NavFn global planner, DWB local planner configured Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
This commit is contained in:
parent
56a48b4e25
commit
285178b2f9
@ -1,10 +1,10 @@
|
||||
# Nav2 parameters — SaltyBot (Jetson Orin Nano Super / ROS2 Humble)
|
||||
#
|
||||
# Robot: differential-drive self-balancing two-wheeler
|
||||
# robot_radius: 0.15 m (~0.2m with margin)
|
||||
# footprint: 0.4 x 0.4 m (x 2m for buffer)
|
||||
# max_vel_x: 1.0 m/s
|
||||
# max_vel_theta: 1.5 rad/s
|
||||
# robot_radius: 0.22 m (0.4m x 0.4m footprint)
|
||||
# footprint: 0.4 x 0.4 m
|
||||
# max_vel_x: 0.3 m/s (conservative for FC + hoverboard ESC, Issue #475)
|
||||
# max_vel_theta: 0.5 rad/s (conservative for FC + hoverboard ESC, Issue #475)
|
||||
#
|
||||
# Localization: RTAB-Map (publishes /map + map→odom TF + /rtabmap/odom)
|
||||
# → No AMCL, no map_server needed.
|
||||
@ -120,14 +120,14 @@ controller_server:
|
||||
FollowPath:
|
||||
plugin: "dwb_core::DWBLocalPlanner"
|
||||
debug_trajectory_details: false
|
||||
# Velocity limits
|
||||
min_vel_x: -0.25 # allow limited reverse
|
||||
# Velocity limits (conservative for FC + hoverboard ESC, Issue #475)
|
||||
min_vel_x: -0.15 # allow limited reverse (half of max forward)
|
||||
min_vel_y: 0.0
|
||||
max_vel_x: 1.0
|
||||
max_vel_x: 0.3 # conservative: 0.3 m/s linear
|
||||
max_vel_y: 0.0
|
||||
max_vel_theta: 1.5
|
||||
max_vel_theta: 0.5 # conservative: 0.5 rad/s angular
|
||||
min_speed_xy: 0.0
|
||||
max_speed_xy: 1.0
|
||||
max_speed_xy: 0.3 # match max_vel_x
|
||||
min_speed_theta: 0.0
|
||||
# Acceleration limits (differential drive)
|
||||
acc_lim_x: 2.5
|
||||
@ -243,14 +243,15 @@ waypoint_follower:
|
||||
waypoint_pause_duration: 200
|
||||
|
||||
# ── Velocity Smoother ────────────────────────────────────────────────────────
|
||||
# Conservative speeds for FC + hoverboard ESC (Issue #475)
|
||||
velocity_smoother:
|
||||
ros__parameters:
|
||||
use_sim_time: false
|
||||
smoothing_frequency: 20.0
|
||||
scale_velocities: false
|
||||
feedback: "OPEN_LOOP"
|
||||
max_velocity: [1.0, 0.0, 1.5]
|
||||
min_velocity: [-0.25, 0.0, -1.5]
|
||||
max_velocity: [0.3, 0.0, 0.5] # conservative: 0.3 m/s linear, 0.5 rad/s angular
|
||||
min_velocity: [-0.15, 0.0, -0.5]
|
||||
max_accel: [2.5, 0.0, 3.2]
|
||||
max_decel: [-2.5, 0.0, -3.2]
|
||||
odom_topic: /rtabmap/odom
|
||||
@ -271,7 +272,7 @@ local_costmap:
|
||||
width: 3
|
||||
height: 3
|
||||
resolution: 0.05
|
||||
robot_radius: 0.15
|
||||
robot_radius: 0.22
|
||||
# Footprint: [x, y] in base_link frame, in counterclockwise order
|
||||
# Robot footprint ~0.4m x 0.4m, with 2m lookahead buffer for controller stability
|
||||
footprint: "[[-0.2, -0.2], [-0.2, 0.2], [0.2, 0.2], [0.2, -0.2]]"
|
||||
@ -342,7 +343,7 @@ global_costmap:
|
||||
publish_frequency: 1.0
|
||||
global_frame: map
|
||||
robot_base_frame: base_link
|
||||
robot_radius: 0.15
|
||||
robot_radius: 0.22
|
||||
# Footprint: [x, y] in base_link frame, in counterclockwise order
|
||||
footprint: "[[-0.2, -0.2], [-0.2, 0.2], [0.2, 0.2], [0.2, -0.2]]"
|
||||
resolution: 0.05
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user