Skip to content

Commit

Permalink
Use TwistStamped (#424) (#426)
Browse files Browse the repository at this point in the history
(cherry picked from commit efe3aa2)

Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>
  • Loading branch information
mergify[bot] and christophfroehlich committed Jan 2, 2024
1 parent dbdd26f commit 705f9cc
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 9 deletions.
1 change: 0 additions & 1 deletion example_2/bringup/config/diffbot_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
18 changes: 10 additions & 8 deletions example_2/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down

0 comments on commit 705f9cc

Please sign in to comment.