From 61683f1ae630b061be0eb08fcfe30bc240bfda2c Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Sun, 26 May 2024 17:52:11 +0000 Subject: [PATCH] Remove stamped twist parameter --- gazebo_ros2_control_demos/config/diff_drive_controller.yaml | 1 - gazebo_ros2_control_demos/config/tricycle_drive_controller.yaml | 1 - 2 files changed, 2 deletions(-) diff --git a/gazebo_ros2_control_demos/config/diff_drive_controller.yaml b/gazebo_ros2_control_demos/config/diff_drive_controller.yaml index fdc04e13..56f88f52 100644 --- a/gazebo_ros2_control_demos/config/diff_drive_controller.yaml +++ b/gazebo_ros2_control_demos/config/diff_drive_controller.yaml @@ -33,7 +33,6 @@ diff_drive_base_controller: cmd_vel_timeout: 0.5 #publish_limited_velocity: true - use_stamped_vel: true #velocity_rolling_window_size: 10 # Velocity and acceleration limits diff --git a/gazebo_ros2_control_demos/config/tricycle_drive_controller.yaml b/gazebo_ros2_control_demos/config/tricycle_drive_controller.yaml index c94b81d5..97d13100 100644 --- a/gazebo_ros2_control_demos/config/tricycle_drive_controller.yaml +++ b/gazebo_ros2_control_demos/config/tricycle_drive_controller.yaml @@ -51,7 +51,6 @@ tricycle_controller: # cmd_vel input cmd_vel_timeout: 500 # In milliseconds. Timeout to stop if no cmd_vel is received - use_stamped_vel: true # Set to True if using TwistStamped. # Debug publish_ackermann_command: true # Publishes AckermannDrive. The speed does not comply to the msg definition, it the wheel angular speed in rad/s.