From b9be2aa3411580975bfe581798a21bade3ba99c6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Tue, 27 Aug 2024 09:55:39 +0200 Subject: [PATCH] Remove stamped twist parameter (#308) --- gz_ros2_control_demos/config/diff_drive_controller_velocity.yaml | 1 - gz_ros2_control_demos/config/tricycle_drive_controller.yaml | 1 - 2 files changed, 2 deletions(-) diff --git a/gz_ros2_control_demos/config/diff_drive_controller_velocity.yaml b/gz_ros2_control_demos/config/diff_drive_controller_velocity.yaml index a8982e5b..6335341f 100644 --- a/gz_ros2_control_demos/config/diff_drive_controller_velocity.yaml +++ b/gz_ros2_control_demos/config/diff_drive_controller_velocity.yaml @@ -30,7 +30,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/gz_ros2_control_demos/config/tricycle_drive_controller.yaml b/gz_ros2_control_demos/config/tricycle_drive_controller.yaml index 17e482f7..ff90ad57 100644 --- a/gz_ros2_control_demos/config/tricycle_drive_controller.yaml +++ b/gz_ros2_control_demos/config/tricycle_drive_controller.yaml @@ -47,7 +47,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.