From 90c681f8f4aec183b0ef30faae5cd2e7b8412918 Mon Sep 17 00:00:00 2001 From: Stephen Phillips Date: Mon, 18 Mar 2024 15:04:53 -0400 Subject: [PATCH] Mod: Set 'publish_cmd' param to true in warthog_control/config - With this change the diff drive controller will output the final cmd_vel to /warthog_velocity_controller/cmd_vel_out after any filters are applied (e.g., speed/acceleration limits) Signed-off-by: Stephen Phillips --- warthog_control/config/control.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/warthog_control/config/control.yaml b/warthog_control/config/control.yaml index 109103b..acb3b96 100644 --- a/warthog_control/config/control.yaml +++ b/warthog_control/config/control.yaml @@ -12,6 +12,9 @@ warthog_velocity_controller: cmd_vel_timeout: 0.25 velocity_rolling_window_size: 2 + # Publish final output cmd_vel to /warthog_velocity_controller/cmd_vel_out + publish_cmd: true + # Odometry fused with IMU is published by robot_localization, so # no need to publish a TF based on encoders alone. enable_odom_tf: false