Skip to content

Commit

Permalink
docs and clean up
Browse files Browse the repository at this point in the history
  • Loading branch information
ARK3r committed Sep 21, 2023
1 parent 5b8f573 commit cdaafef
Show file tree
Hide file tree
Showing 7 changed files with 52 additions and 36 deletions.
1 change: 1 addition & 0 deletions .github/workflows/ci-coverage-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ jobs:
ros2_control_demo_example_7
ros2_control_demo_example_8
ros2_control_demo_example_9
ros2_control_demo_example_11
ros2_control_demo_example_12

vcs-repo-file-url: |
Expand Down
1 change: 1 addition & 0 deletions .github/workflows/ci-ros-lint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ jobs:
ros2_control_demo_example_7
ros2_control_demo_example_8
ros2_control_demo_example_9
ros2_control_demo_example_11
ros2_control_demo_example_12

ament_lint_100:
Expand Down
4 changes: 4 additions & 0 deletions doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,9 @@ Example 8: "Using transmissions"
Example 9: "Gazebo Classic"
Demonstrates how to switch between simulation and hardware.

Example 11: "CarlikeBot"
*CarlikeBot* with an Ackermann steering controller would be similiar to how a car would be controlled.

Example 12: "Controller chaining"
The example shows a simple chainable controller and its integration to form a controller chain to control the joints of *RRBot*.

Expand Down Expand Up @@ -259,4 +262,5 @@ Examples
Example 7: Full tutorial with a 6DOF robot <../example_7/doc/userdoc.rst>
Example 8: Using transmissions <../example_8/doc/userdoc.rst>
Example 9: Gazebo classic <../example_9/doc/userdoc.rst>
Example 11: CarlikeBot <../example_11/doc/userdoc.rst>
Example 12: Controller chaining <../example_12/doc/userdoc.rst>
2 changes: 1 addition & 1 deletion example_11/bringup/launch/carlikebot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, RegisterEventHandler
from launch.conditions import IfCondition, UnlessCondition
from launch.conditions import IfCondition
from launch.event_handlers import OnProcessExit
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration

Expand Down
77 changes: 43 additions & 34 deletions example_11/doc/userdoc.rst
Original file line number Diff line number Diff line change
@@ -1,50 +1,51 @@
:github_url: https://github.com/ros-controls/ros2_control_demos/blob/{REPOS_FILE_BRANCH}/example_11/doc/userdoc.rst

.. _ros2_control_demos_example_2_userdoc:
.. _ros2_control_demos_example_11_userdoc:

*********
DiffBot
CarlikeBot
*********

*DiffBot*, or ''Differential Mobile Robot'', is a simple mobile base with differential drive.
The robot is basically a box moving according to differential drive kinematics.
*CarlikeBot* is a simple mobile base with ackermann drive.

For *example_2*, the hardware interface plugin is implemented having only one interface.
This example shows how to use the ackermann steering controller, which is a sub-design of the steering controller library.

* The communication is done using proprietary API to communicate with the robot control box.
* Data for all joints is exchanged at once.

The *DiffBot* URDF files can be found in ``description/urdf`` folder.
The *CarlikeBot* URDF files can be found in ``description/urdf`` folder.

.. include:: ../../doc/run_from_docker.rst

Tutorial steps
--------------------------

1. To check that *DiffBot* description is working properly use following launch commands
1. To check that *CarlikeBot* description is working properly use following launch commands

.. code-block:: shell
ros2 launch ros2_control_demo_example_2 view_robot.launch.py
ros2 launch ros2_control_demo_example_11 view_robot.launch.py
.. warning::
Getting the following output in terminal is OK: ``Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist``.
This happens because ``joint_state_publisher_gui`` node needs some time to start.

.. image:: carlikebot.png
:width: 400
:alt: Carlike Mobile Robot
:alt: Ackermann Mobile Robot

2. To start *DiffBot* example open a terminal, source your ROS2-workspace and execute its launch file with
2. To start *CarlikeBot* example open a terminal, source your ROS2-workspace and execute its launch file with

.. code-block:: shell
ros2 launch ros2_control_demo_example_2 diffbot.launch.py
ros2 launch ros2_control_demo_example_11 carlikebot.launch.py
The launch file loads and starts the robot hardware, controllers and opens *RViz*.
In the starting terminal you will see a lot of output from the hardware implementation showing its internal states.
This excessive printing is only added for demonstration. In general, printing to the terminal should be avoided as much as possible in a hardware interface implementation.

If you can see an orange box in *RViz* everything has started properly.
Still, to be sure, let's introspect the control system before moving *DiffBot*.
Still, to be sure, let's introspect the control system before moving *CarlikeBot*.

3. Check if the hardware interface loaded properly, by opening another terminal and executing

Expand All @@ -57,15 +58,21 @@ Tutorial steps
.. code-block:: shell
command interfaces
left_wheel_joint/velocity [available] [claimed]
right_wheel_joint/velocity [available] [claimed]
ackermann_steering_controller/angular/position [unavailable] [unclaimed]
ackermann_steering_controller/linear/velocity [unavailable] [unclaimed]
left_steering_joint/position [available] [claimed]
rear_left_wheel_joint/velocity [available] [claimed]
rear_right_wheel_joint/velocity [available] [claimed]
right_steering_joint/position [available] [claimed]
state interfaces
left_wheel_joint/position
left_wheel_joint/velocity
right_wheel_joint/position
right_wheel_joint/velocity
left_steering_joint/position
rear_left_wheel_joint/position
rear_left_wheel_joint/velocity
rear_right_wheel_joint/position
rear_right_wheel_joint/velocity
right_steering_joint/position
The ``[claimed]`` marker on command interfaces means that a controller has access to command *DiffBot*.
The ``[claimed]`` marker on command interfaces means that a controller has access to command *CarlikeBot*.

4. Check if controllers are running

Expand All @@ -77,47 +84,49 @@ Tutorial steps

.. code-block:: shell
diffbot_base_controller[diff_drive_controller/DiffDriveController] active
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active
ackermann_steering_controller[ackermann_steering_controller/AckermannSteeringController] active
5. If everything is fine, now you can send a command to *Diff Drive Controller* using ROS 2 CLI interface:

.. code-block:: shell
ros2 topic pub --rate 30 /diffbot_base_controller/cmd_vel_unstamped geometry_msgs/msg/Twist "linear:
ros2 topic pub --rate 30 /ackermann_steering_controller/reference_unstamped geometry_msgs/msg/Twist "linear:
x: 0.7
y: 0.0
z: 0.0
angular:
angular:
x: 0.0
y: 0.0
z: 1.0"
z: 0.01"
You should now see an orange box circling in *RViz*.
Also, you should see changing states in the terminal where launch file is started.

.. code-block:: shell
[DiffBotSystemHardware]: Got command 43.33333 for 'left_wheel_joint'!
[DiffBotSystemHardware]: Got command 50.00000 for 'right_wheel_joint'!
[CarlikeBotSystemHardware]: Got command 0.00464 for 'left_steering_joint'
[CarlikeBotSystemHardware]: Got command 0.00465 for 'right_steering_joint'
[CarlikeBotSystemHardware]: Got command 13.97230 for 'rear_left_wheel_joint'
[CarlikeBotSystemHardware]: Got command 14.02830 for 'rear_right_wheel_joint'
Files used for this demos
--------------------------

* Launch file: `diffbot.launch.py <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_2/bringup/launch/diffbot.launch.py>`__
* Controllers yaml: `diffbot_controllers.yaml <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_2/bringup/config/diffbot_controllers.yaml>`__
* URDF file: `diffbot.urdf.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_2/description/urdf/diffbot.urdf.xacro>`__
* Launch file: `carlikebot.launch.py <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_11/bringup/launch/carlikebot.launch.py>`__
* Controllers yaml: `carlikebot_controllers.yaml <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_11/bringup/config/carlikebot_controllers.yaml>`__
* URDF file: `carlikebot.urdf.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_11/description/urdf/carlikebot.urdf.xacro>`__

* Description: `diffbot_description.urdf.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_2/description/urdf/diffbot_description.urdf.xacro>`__
* ``ros2_control`` tag: `diffbot.ros2_control.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_2/description/ros2_control/diffbot.ros2_control.xacro>`__
* Description: `carlikebot_description.urdf.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_11/description/urdf/carlikebot_description.urdf.xacro>`__
* ``ros2_control`` tag: `carlikebot.ros2_control.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_11/description/ros2_control/carlikebot.ros2_control.xacro>`__

* RViz configuration: `diffbot.rviz <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_2/description/rviz/diffbot.rviz>`__
* RViz configuration: `carlikebot.rviz <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_11/description/rviz/carlikebot.rviz>`__

* Hardware interface plugin: `diffbot_system.cpp <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_2/hardware/diffbot_system.cpp>`__
* Hardware interface plugin: `carlikebot_system.cpp <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_11/hardware/carlikebot_system.cpp>`__


Controllers from this demo
--------------------------

* ``Joint State Broadcaster`` (`ros2_controllers repository <https://github.com/ros-controls/ros2_controllers/tree/{REPOS_FILE_BRANCH}/joint_state_broadcaster>`__): `doc <https://control.ros.org/{REPOS_FILE_BRANCH}/doc/ros2_controllers/joint_state_broadcaster/doc/userdoc.html>`__
* ``Diff Drive Controller`` (`ros2_controllers repository <https://github.com/ros-controls/ros2_controllers/tree/{REPOS_FILE_BRANCH}/diff_drive_controller>`__): `doc <https://control.ros.org/{REPOS_FILE_BRANCH}/doc/ros2_controllers/diff_drive_controller/doc/userdoc.html>`__
* ``Ackermann Steering Controller`` (`ros2_controllers repository <https://github.com/ros-controls/ros2_controllers/tree/{REPOS_FILE_BRANCH}/ackermann_steering_controller>`__): `doc <https://control.ros.org/{REPOS_FILE_BRANCH}/doc/ros2_controllers/ackermann_steering_controller/doc/userdoc.html>`__
2 changes: 1 addition & 1 deletion example_11/hardware/carlikebot_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ hardware_interface::return_type ros2_control_demo_example_11 ::CarlikeBotSystemH
hw_velocities_[i] = hw_commands_[i];

RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "Got command %.5f for '%s'", hw_commands_[0],
rclcpp::get_logger("CarlikeBotSystemHardware"), "Got command %.5f for '%s'", hw_commands_[i],
info_.joints[i].name.c_str());
}

Expand Down
1 change: 1 addition & 0 deletions ros2_control_demos/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
<exec_depend>ros2_control_demo_example_8</exec_depend>
<exec_depend>ros2_control_demo_example_9</exec_depend>
<exec_depend>ros2_control_demo_example_11</exec_depend>
<exec_depend>ros2_control_demo_example_12</exec_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down

0 comments on commit cdaafef

Please sign in to comment.