This repository provides templates for the development of ros2_control
-enabled robots and a simple simulations to demonstrate and prove ros2_control
concepts.
The repository has three goals:
- Implements the example configuration described in the
ros-controls/roadmap
repository file components_architecture_and_urdf_examples. - It provides templates for faster implementation of custom hardware and controllers;
- The repository is a validation environment for
ros2_control
concepts, which can only be tested during run-time (e.g., execution of controllers by the controller manager, communication between robot hardware and controllers).
The repository is inspired by the ros_control_boilerplate repository from Dave Coleman. The examples have three parts/packages according to usual structure of ROS packages for robots:
- The bringup package
ros2_control_demo_bringup
, holds launch files and runtime configurations for demo robots. - Description packages
rrbot_description
anddiffbot_description
(insideros2_control_demo_description
), store URDF-description files, rviz configurations and meshes for the demo robots. - Hardware interface package
ros2_control_demo_hardware
, implements the hardware interfaces described in the roadmap.
The examples of RRBot and DiffBot are trivial simulations to demonstrate and test ros2_control
concepts.
This package does not have any dependencies except ros2
core packages and can, therefore, be used on SoC-hardware or headless systems.
This repository demonstrates the following ros2_control
concepts:
- Creating a
*HardwareInterface
for a System, Sensor, and Actuator. - Creating a robot description in the form of URDF files.
- Loading the configuration and starting a robot using launch files.
- Control of a differential mobile base DiffBot.
- Control of two joints of RRBot.
- Using simulated robots and starting
ros2_control
with Gazebo simulator. - Implementing a controller switching strategy for a robot.
- Using joint limits and transmission concepts in
ros2_control
.
These are some quick hints, especially for those coming from a ROS1 control background:
- There are now three categories of hardware components: Sensor, Actuator, and System.
Sensor is for individual sensors; Actuator is for individual actuators; System is for any combination of multiple sensors/actuators.
You could think of a Sensor as read-only.
All components are used as plugins and therefore exported using
PLUGINLIB_EXPORT_CLASS
macro. - ros(1)_control only allowed three hardware interface types: position, velocity, and effort.
ros2_control allows you to create any interface type by defining a custom string. For example, you might define a
position_in_degrees
or atemperature
interface. The most common (position, velocity, acceleration, effort) are already defined as constants in hardware_interface/types/hardware_interface_type_values.hpp. - Joint names in <ros2_control> tags in the URDF must be compatible with the controller's configuration.
- In ros2_control, all parameters for the driver are specified in the URDF. The ros2_control framework uses the <ros2_control> tag in the URDF.
- Joint names in <ros2_control> tags in the URDF must be compatible with the controller's configuration.
git clone https://github.com/ros-controls/ros2_control
git clone https://github.com/ros-controls/ros2_controllers
git clone https://github.com/ros-controls/ros2_control_demos
NOTE: ros2_control
and ros2_controllers
packages are released for foxy and can be installed using a package manager.
We provide officially released and maintained debian packages, which can easily be installed via aptitude.
However, there might be cases in which not-yet released demos or features are only available through a source build in your own workspace.
-
Install dependencies:
rosdep install --from-paths src --ignore-src -r -y
-
Build everything, e.g. with:
colcon build --symlink-install
-
Do not forget to source
setup.bash
from theinstall
folder!
This repository provides the following simple example robots: a 2 degrees of freedom manipulator - RRBot - and a mobile differential drive base - DiffBot.
The first two examples demonstrate the minimal setup for those two robots to run.
Later examples show more details about ros2_control
-concepts and some more advanced use-cases.
RRBot, or ''Revolute-Revolute Manipulator Robot'', is a simple 3-linkage, 2-joint arm that we will use to demonstrate various features.
It is essentially a double inverted pendulum and demonstrates some fun control concepts within a simulator and was originally introduced for Gazebo tutorials.
The RRBot URDF files can be found in the urdf
folder of rrbot_description
package.
-
To check that RRBot descriptions are working properly use following launch commands:
RRBot
ros2 launch rrbot_description view_robot.launch.py
NOTE: 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 becausejoint_state_publisher_gui
node need some time to start. Thejoint_state_publisher_gui
provides a GUI to generate a random configuration for rrbot. It is immediately displayed inRviz
. -
To start RRBot example open open a terminal, source your ROS2-workspace and execute its launch file with:
ros2 launch ros2_control_demo_bringup rrbot.launch.py
The launch file loads and starts the robot hardware, controllers and opens
RViz
. In starting terminal you will see a lot of output from the hardware implementation showing its internal states. This is only of exemplary purpuses and should be avoided as much as possible in a hardware interface implementation.If you can see two orange and one yellow rectangle in in
RViz
everything has started properly. Still, to be sure, let's introspect the control system before moving RRBot. -
Check if the hardware interface loaded properly, by opening another terminal and executing:
ros2 control list_hardware_interfaces
You should get:
command interfaces joint1/position [claimed] joint2/position [claimed] state interfaces joint1/position joint2/position
Marker
[claimed]
by command interfaces means that a controller has access to command RRBot. -
Check is controllers are running:
ros2 control list_controllers
You should get:
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active forward_position_controller[forward_command_controller/ForwardCommandController] active
-
If you get output from above you can send commands to Forward Command Controller, either:
a. Manually using ros2 cli interface:
ros2 topic pub /forward_position_controller/commands std_msgs/msg/Float64MultiArray "data: - 0.5 - 0.5"
B. Or you can start a demo node which sends two goals every 5 seconds in a loop:
ros2 launch ros2_control_demo_bringup test_forward_position_controller.launch.py
You should now see orange and yellow blocks moving in
RViz
. Also, you should see changing states in the terminal where launch file is started.
Files used for this demos:
-
Launch file: rrbot.launch.py
-
Controllers yaml: rrbot_controllers.yaml
-
URDF file: rrbot.urdf.xacro
- Description: rrbot_description.urdf.xacro
ros2_control
tag: rrbot.ros2_control.xacro
-
RViz configuration: rrbot.rviz
-
Hardware interface plugin: rrbot_system_position_only.cpp
Controllers from this demo:
Joint State Broadcaster
(ros2_controllers
repository): docForward Command Controller
(ros2_controllers
repository): doc
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.
The DiffBot URDF files can be found in urdf
folder of diffbot_description
package.
-
To check that DiffBot description is working properly use following launch commands:
ros2 launch diffbot_description view_robot.launch.py
NOTE: 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 becausejoint_state_publisher_gui
node need some time to start. -
To start DiffBot example open a terminal, source your ROS2-workspace and execute its launch file with:
ros2 launch ros2_control_demo_bringup diffbot.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. -
Check if the hardware interface loaded properly, by opening another terminal and executing:
ros2 control list_hardware_interfaces
You should get:
command interfaces left_wheel_joint/velocity [claimed] right_wheel_joint/velocity [claimed] state interfaces left_wheel_joint/position left_wheel_joint/velocity right_wheel_joint/position right_wheel_joint/velocity
The
[claimed]
marker on command interfaces means that a controller has access to command DiffBot. -
Check if controllers are running:
ros2 control list_controllers
You should get:
diffbot_base_controller[diff_drive_controller/DiffDriveController] active joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active
-
If everything is fine, now you can send a command to Diff Drive Controller using ros2 cli interface:
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"
You should now see an orange box circling in
RViz
. Also, you should see changing states in the terminal where launch file is started.
Files used for this demos:
-
Launch file: diffbot.launch.py
-
Controllers yaml: diffbot_controllers.yaml
-
URDF file: diffbot.urdf.xacro
- Description: diffbot_description.urdf.xacro
ros2_control
tag: diffbot.ros2_control.xacro
-
RViz configuration: diffbot.rviz
-
Hardware interface plugin: diffbot_system.cpp
Controllers from this demo:
Joint State Broadcaster
(ros2_controllers
repository): docDiff Drive Controller
(ros2_controllers
repository): doc
Each of the described example cases from the roadmap has its own launch and URDF file.
-
Each example is started with a single launch file which starts up the robot hardware, loads controller configurations and it also opens
RViz
.The
RViz
setup can be recreated following these steps:- The robot models can be visualized using
RobotModel
display using/robot_description
topic. - Or you can simply open the configuration from
rviz
folder inrrbot_description
ordiffbot_description
package manually or directly by executing:
rviz2 --display-config `ros2 pkg prefix rrbot_description`/share/rrbot_description/config/rrbot.rviz
- The robot models can be visualized using
-
To check that robot descriptions are working properly use following launch commands:
ros2 launch rrbot_description view_robot.launch.py
Optional arguments for specific example (the robot visualization will be the same for all examples):
description_file:=rrbot_system_multi_interface.urdf.xacro
NOTE: 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 need some time to start.
-
To start an example open a terminal, source your ROS2-workspace and execute a launch file with:
ros2 launch ros2_control_demo_bringup <example_launch_file>
-
To stop RViz2 from auto-start use
start_rviz:=false
launch file argument. -
To check if the hardware interface loaded properly, open another terminal and execute:
ros2 control list_hardware_interfaces
You should get something like:
command interfaces joint1/position [unclaimed] joint2/position [unclaimed] state interfaces joint1/position joint2/position
-
Check which controllers are running using:
ros2 control list_controllers
You should get something like:
forward_position_controller[forward_command_controller/ForwardCommandController] unconfigured joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active
-
Check Controllers and moving hardware section to move RRBot.
- Launch file: rrbot_system_position_only.launch.py
- Command interfaces:
- joint1/position
- joint2/position
- State interfaces:
- joint1/position
- joint2/position
Available controllers:
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster]
forward_position_controller[forward_command_controller/ForwardCommandController]
(position)
Available launch-file options:
use_fake_hardware:=true
- startFakeSystem
instead of hardware. This is a simple simulation that mimics joint command to their states. This is useful to test ros2_control integration and controllers without physical hardware.
- TBA
- Launch file: rrbot_system_multi_interface.launch.py
- Command interfaces:
- joint1/position
- joint2/position
- joint1/velocity
- joint2/velocity
- joint1/acceleration
- joint2/acceleration
- State interfaces:
- joint1/position
- joint2/position
- joint1/velocity
- joint2/velocity
- joint1/acceleration
- joint2/acceleration
Available controllers:
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster]
forward_position_controller[position_controllers/JointGroupPositionController]
forward_velocity_controller[velocity_controllers/JointGroupVelocityController]
forward_acceleration_controller[forward_command_controller/ForwardCommandController]
forward_illegal1_controller[forward_command_controller/ForwardCommandController]
forward_illegal2_controller[forward_command_controller/ForwardCommandController]
Notes:
- The example shows how to implement multi-interface robot hardware taking care about interfaces used. The two illegal controllers demonstrate how hardware interface declines faulty claims to access joint command interfaces.
- Launch file: diffbot_system.launch.py
- Command interfaces:
- left_wheel_joint/velocity
- right_wheel_joint/velocity
- State interfaces:
- left_wheel_joint/position
- left_wheel_joint/velocity
- right_wheel_joint/position
- right_wheel_joint/velocity
Available controllers:
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster]
diffbot_base_controller[diff_drive_controller/DiffDriveController] active
Sending commands to diff drive controller:
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"
You should now see an orange box circling in RViz
.
-
Launch file: rrbot_system_with_sensor.launch.py
-
ros2_control URDF: rrbot_system_with_sensor.ros2_control.xacro
-
Command interfaces:
- joint1/position
- joint2/position
-
State interfaces:
- joint1/position
- joint2/position
- tcp_fts_sensor/force.x
- tcp_fts_sensor/torque.z
Available controllers:
forward_position_controller[forward_command_controller/ForwardCommandController]
fts_broadcaster[force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster]
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster]
Notes:
- Wrench messages are not displayed properly in Rviz as NaN values are not handled in Rviz and FTS Broadcaster may send NaN values.
Commanding the robot: see the commands below.
Accessing Wrench data from 2D FTS:
ros2 topic echo /fts_broadcaster/wrench
To move the robot you should load and start controllers.
The JointStateController
is used to publish the joint states to ROS topics.
Direct joint commands are sent to this robot via the ForwardCommandController
and JointTrajectoryController
.
The sections below describe their usage.
Check the Results section on how to ensure that things went well.
NOTE: Before doing any action with controllers check their state using command:
ros2 control list_controllers
Open another terminal and load, configure and start joint_state_controller
:
ros2 control set_controller_state joint_state_controller start
Check if controller is loaded properly:
ros2 control list_controllers
You should get the response:
joint_state_controller[joint_state_controller/JointStateController] active
Now you should also see the RRbot represented correctly in RViz
.
-
If you want to test hardware with
ForwardCommandController
first load a controller (not always needed):ros2 control load_controller forward_position_controller
Check if the controller is loaded properly:
ros2 control list_controllers
-
Then configure it:
ros2 control set_controller_state forward_position_controller configure
Check if the controller is loaded properly:
ros2 control list_controllers
You should get the response:
forward_position_controller[forward_command_controller/ForwardCommandController] inactive
-
Now start the controller:
ros2 control switch_controllers --start forward_position_controller
Check if controllers are activated:
ros2 control list_controllers
You should get
active
in the response:joint_state_controller[joint_state_controller/JointStateController] active forward_position_controller[forward_command_controller/ForwardCommandController] active
-
Send a command to the controller, either:
a. Manually using ros2 cli interface:
ros2 topic pub /forward_position_controller/commands std_msgs/msg/Float64MultiArray "data: - 0.5 - 0.5"
B. Or you can start a demo node which sends two goals every 5 seconds in a loop:
ros2 launch ros2_control_demo_bringup test_forward_position_controller.launch.py
You can adjust the goals in rrbot_forward_position_publisher.yaml.
-
If you want to test hardware with
JointTrajectoryController
first load and configure a controller (not always needed):ros2 control load_controller position_trajectory_controller --set-state configure
Check if the controller is loaded and configured properly:
ros2 control list_controllers
You should get the response:
position_trajectory_controller[joint_trajectory_controller/JointTrajectoryController] inactive
-
Now start the controller (and stop other running contorller):
ros2 control switch_controllers --stop forward_position_controller --start position_trajectory_controller
Check if controllers are activated:
ros2 control list_controllers
You should get
active
in the response:joint_state_controller[joint_state_controller/JointStateController] active position_trajectory_controller[joint_trajectory_controller/JointTrajectoryController] active
-
Send a command to the controller using demo node which sends two goals every 5 seconds in a loop:
ros2 launch ros2_control_demo_bringup test_forward_position_controller.launch.py
You can adjust the goals in rrbot_joint_trajectory_publisher.yaml.
-
Independently from the controller you should see how the example's output changes. Look for the following lines
[RRBotSystemPositionOnlyHardware]: Got state 0.0 for joint 0! [RRBotSystemPositionOnlyHardware]: Got state 0.0 for joint 1!
-
If you echo the
/joint_states
or/dynamic_joint_states
topics you should also get similar values.ros2 topic echo /joint_states ros2 topic echo /dynamic_joint_states
-
You should also see the RRbot moving in
RViz
.