Building a ros2_control System: ROS2 Control with the JetBot Part 2
See how to build a ros2_control System with the Motor and I2CDevice classes from the previous post, and how to integrate this System with a Differential Drive Controller from ROS2.


As the motor configuration is the same, the mathematics for controlling them is also the same, which means we can write one controller to control either robot - assuming we can abstract away the code to move the motors.
write
call, instead of having two separate Actuators.jetbot-motors-pt2
to get the same code version as in this article!1
2
3
4
5
6
7
8
9
10
add_library(${PROJECT_NAME}
SHARED
hardware/src/jetbot_system.cpp
hardware/src/i2c_device.cpp
hardware/src/motor.cpp
)
...
pluginlib_export_plugin_description_file(hardware_interface jetbot_control.xml)
jetbot_control.xml
, tells ros2_control more information about this library to allow it to be loaded - in this case, the library name and ros2_control plugin type (SystemInterface - we'll discuss this more in the Describing the JetBot section).JetBotSystemHardware
class extends the SystemInterface class:1
class JetBotSystemHardware : public hardware_interface::SystemInterface {
I2CDevice
and two Motor
classes from the previous post, along with two vectors for the hardware commands and hardware velocities:1
2
3
4
5
6
private:
std::vector<MotorPins> motor_pin_sets_;
std::vector<Motor> motors_;
std::shared_ptr<I2CDevice> i2c_device_;
std::vector<double> hw_commands_;
std::vector<double> hw_velocities_;
export_state_interfaces
/export_command_interfaces
: report the state and command interfaces supported by this system class. These interfaces can then be checked by the controller for compatibility.on_init
/on_activate
/on_deactivate
: lifecycle methods automatically called by the controller. Different setup stages for the System occur in these methods, including enabling the motors in theon_activate
method and stopping them inon_deactivate
.read
/write
: methods called every controller update.read
is for reading the velocities from the motors, andwrite
is for writing requested speeds into the motors.
on_init
method to:- Initialize the base SystemInterface class
- Read the pin configuration used for connecting to the motors from the parameters
- Check that the provided hardware information matches the expected information - for example, that there are two velocity command interfaces
- Initialize the
I2CDevice
andMotor
s
on_activate
is called, the motors are enabled and ready to receive commands. The read
and write
methods are then repeatedly called for reading from and writing to the motors respectively. When it's time to shutdown, on_deactivate
will stop the motors, and the destructors of the classes perform any required cleanup. There are more lifecycle states that could potentially be used for a more complex system - these are documented in the ros2 demos repository.I2CDevice
and Motor
classes, are compiled into the plugin library, ready to be loaded by the controller.description
folder from the example contains the files that define the robot, including its ros2_control configuration, simulation configuration, and materials used to represent it during simulation. As this implementation has been pared down to basics, only the ros2_control configuration with mock hardware flag have been kept in.jetbot.ros2_control.xacro
file defines the ros2_control configuration needed to control the robot. It uses xacro
files to define this configuration, where xacro
is a tool that extends XML files by allowing us to define macros that can be referenced in other files:1
<xacro:macro name="jetbot_ros2_control" params="name prefix use_mock_hardware">
system
:1
<ros2_control name="${name}" type="system">
1
2
3
4
5
6
7
8
9
<hardware>
<plugin>jetbot_control/JetBotSystemHardware</plugin>
<param name="pin_enable_0">8</param>
<param name="pin_pos_0">9</param>
<param name="pin_neg_0">10</param>
<param name="pin_enable_1">13</param>
<param name="pin_pos_1">12</param>
<param name="pin_neg_1">11</param>
</hardware>
1
2
3
4
<joint name="${prefix}left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="velocity"/>
</joint>
1
2
3
<xacro:include filename="$(find jetbot_control)/ros2_control/jetbot.ros2_control.xacro" />
<xacro:jetbot_ros2_control
name="JetBot" prefix="$(arg prefix)" use_mock_hardware="$(arg use_mock_hardware)"/>
- A plugin library capable of writing commands to the JetBot motors
- A ros2_control xacro file, describing the plugin to load and the parameters to give it
- One joint per motor, each with a velocity command and state interface
- An overall description file that imports the ros2_control file and calls the macro
xacro
to build the overall description file, it will import the ros2_control file macro and expand it, giving a complete robot description that we can add to later. It's now time to look at creating a controller manager and a differential drive controller.jetbot_controllers.yaml
file.1
2
3
4
5
6
controller_manager:
ros__parameters:
update_rate: 10 # Hz
jetbot_base_controller:
type: diff_drive_controller/DiffDriveController
diff_drive_controller/DiffDriveController
controller. This is the standard differential drive controller discussed earlier. If we take a look at the information page, we can see a lot of configuration for it - we provide this configuration in the same file.1
2
3
4
linear.x.max_velocity: 0.016
linear.x.min_velocity: -0.016
angular.z.max_velocity: 0.25
angular.z.min_velocity: -0.25
1
2
wheel_separation: 0.104
wheel_radius: 0.032
xacro
tool to generate the full XML for us:1
2
3
4
5
6
7
8
9
10
11
12
13
14
# Get URDF via xacro
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[FindPackageShare("jetbot_control"), "urdf", "jetbot.urdf.xacro"]
),
" ",
"use_mock_hardware:=",
use_mock_hardware,
]
)
robot_description = {"robot_description": robot_description_content}
1
2
3
4
5
6
7
robot_controllers = PathJoinSubstitution(
[
FindPackageShare("jetbot_control"),
"config",
"jetbot_controllers.yaml",
]
)
1
2
3
4
5
6
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
output="both",
)
jetbot_base_controller
:1
2
3
4
5
6
7
8
9
robot_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=[
"jetbot_base_controller",
"--controller-manager",
"/controller_manager",
],
)
- We launch the JetBot launch file defined in the package
- The launch file spawns the controller manager, which is used to load controllers and manage resources
- The launch file requests that the controller manager launches the differential drive controller
- The differential drive controller loads the JetBot System as a plugin library
- The System connects to the I2C bus, and hence, the motors
- The controller can then command the System to move the motors as requested by ROS2 messaging
1
2
3
4
mkdir ~/dev_ws
cd ~/dev_ws
git clone https://github.com/mikelikesrobots/jetbot-ros-control -b jetbot-motors-pt2
cp -r ./jetbot-ros-control/.devcontainer .
1
2
3
4
source /opt/ros/humble/setup.bash
colcon build --symlink-install
source install/setup.bash
ros2 launch jetbot_control jetbot.launch.py
teleop_twist_keyboard
to test it - but with a couple of changes./jetbot_base_controller/cmd_vel
topic instead of the previous /cmd_vel
topic. We can fix that by asking teleop_twist_keyboard
to remap the topic it normally publishes to./cmd_vel
to accept Twist messages, but the controller expects TwistStamped messages. There is a parameter for teleop_twist_keyboard
that turns its messages into TwistStamped messages, but while trying it out I found that the node ignored that parameter. Checking it out from source fixed it for me, so in order to run the keyboard test, I recommend building and running from source:1
2
3
4
5
6
7
git clone https://github.com/ros2/teleop_twist_keyboard
colcon build --symlink-install
source install/setup.bash
ros2 run teleop_twist_keyboard teleop_twist_keyboard \
--ros-args \
-p stamped:=true \
-r /cmd_vel:=/jetbot_base_controller/cmd_vel
jetbot_controllers.yaml
file and play with the maximum velocity and acceleration fields, to see how the robot reacts. Relaunch after every configuration change to see the result. You can also tune these parameters to match what you expect more closely.