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 1061aea7..a5c426d2 100644 --- a/gz_ros2_control_demos/config/diff_drive_controller_velocity.yaml +++ b/gz_ros2_control_demos/config/diff_drive_controller_velocity.yaml @@ -32,7 +32,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 b0951649..c8e0c5b7 100644 --- a/gz_ros2_control_demos/config/tricycle_drive_controller.yaml +++ b/gz_ros2_control_demos/config/tricycle_drive_controller.yaml @@ -50,7 +50,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.