From e496178e853213ba09361b78418a9ae751ad1a92 Mon Sep 17 00:00:00 2001 From: Thomas Chou Date: Mon, 4 Mar 2024 13:08:03 -0800 Subject: [PATCH] navigation: add velocity_smoother parameters with default values This for 2wd/4wd, Y=0. max_velocity: [0.5, 0.0, 2.5] min_velocity: [-0.5, 0.0, -2.5] max_accel: [2.5, 0.0, 3.2] max_decel: [-2.5, 0.0, -3.2] Set Y=X for mecanum max_velocity: [0.5, 0.5, 2.5] min_velocity: [-0.5, -0.5, -2.5] max_accel: [2.5, 2.5, 3.2] max_decel: [-2.5, -2.5, -3.2] Signed-off-by: Thomas Chou --- linorobot2_navigation/config/navigation.yaml | 14 ++++++++++++++ linorobot2_navigation/config/navigation_sim.yaml | 14 ++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/linorobot2_navigation/config/navigation.yaml b/linorobot2_navigation/config/navigation.yaml index a56cbd49..c9ef6dba 100644 --- a/linorobot2_navigation/config/navigation.yaml +++ b/linorobot2_navigation/config/navigation.yaml @@ -396,3 +396,17 @@ waypoint_follower: plugin: "nav2_waypoint_follower::WaitAtWaypoint" enabled: true waypoint_pause_duration: 200 + +velocity_smoother: + ros__parameters: + smoothing_frequency: 20.0 + scale_velocities: False + feedback: "OPEN_LOOP" + max_velocity: [0.5, 0.0, 2.5] + min_velocity: [-0.5, 0.0, -2.5] + max_accel: [2.5, 0.0, 3.2] + max_decel: [-2.5, 0.0, -3.2] + odom_topic: "odom" + odom_duration: 0.1 + deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0 diff --git a/linorobot2_navigation/config/navigation_sim.yaml b/linorobot2_navigation/config/navigation_sim.yaml index 41333d2b..22e74d45 100644 --- a/linorobot2_navigation/config/navigation_sim.yaml +++ b/linorobot2_navigation/config/navigation_sim.yaml @@ -396,3 +396,17 @@ waypoint_follower: plugin: "nav2_waypoint_follower::WaitAtWaypoint" enabled: true waypoint_pause_duration: 200 + +velocity_smoother: + ros__parameters: + smoothing_frequency: 20.0 + scale_velocities: False + feedback: "OPEN_LOOP" + max_velocity: [0.5, 0.0, 2.5] + min_velocity: [-0.5, 0.0, -2.5] + max_accel: [2.5, 0.0, 3.2] + max_decel: [-2.5, 0.0, -3.2] + odom_topic: "odom" + odom_duration: 0.1 + deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0