From 705f9cccd56344b37d097b7cebfffa4db1101ab0 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Tue, 2 Jan 2024 10:44:59 +0100 Subject: [PATCH] Use TwistStamped (#424) (#426) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit (cherry picked from commit efe3aa2446ebc1aa43cccd586d568cb25c3b0f49) Co-authored-by: Christoph Fröhlich --- .../bringup/config/diffbot_controllers.yaml | 1 - example_2/doc/userdoc.rst | 18 ++++++++++-------- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/example_2/bringup/config/diffbot_controllers.yaml b/example_2/bringup/config/diffbot_controllers.yaml index d45de1b44..4f1ad7037 100644 --- a/example_2/bringup/config/diffbot_controllers.yaml +++ b/example_2/bringup/config/diffbot_controllers.yaml @@ -32,7 +32,6 @@ diffbot_base_controller: cmd_vel_timeout: 0.5 #publish_limited_velocity: true - use_stamped_vel: false #velocity_rolling_window_size: 10 # Velocity and acceleration limits diff --git a/example_2/doc/userdoc.rst b/example_2/doc/userdoc.rst index 116da462a..504172a9b 100644 --- a/example_2/doc/userdoc.rst +++ b/example_2/doc/userdoc.rst @@ -88,14 +88,16 @@ Tutorial steps .. code-block:: shell - ros2 topic pub --rate 30 /diffbot_base_controller/cmd_vel_unstamped geometry_msgs/msg/Twist "linear: - x: 0.7 - y: 0.0 - z: 0.0 - angular: - x: 0.0 - y: 0.0 - z: 1.0" + ros2 topic pub --rate 30 /diffbot_base_controller/cmd_vel geometry_msgs/msg/TwistStamped " + twist: + linear: + x: 0.7 + y: 0.0 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: 1.0" You should now see an orange box circling in *RViz*. Also, you should see changing states in the terminal where launch file is started.