Skip to main content
⚙️ ros2_control

ROS 2 ros2_control Hardware Interface Guide 2026

ros2_control decouples robot hardware from controllers. This guide covers every layer — SystemInterface, CommandInterface/StateInterface, the on_init/read/write lifecycle, controller manager YAML, and wiring a real actuator.

Architecture Overview

ros2_control has three layers:

LayerClassPurpose
ControllerControllerInterfaceReads state, computes command (JTC, DiffDrive…)
Resource ManagerResourceManagerOwns all interfaces, mediates controller↔HW
HardwareSystemInterface / ActuatorInterface / SensorInterfaceReads sensors, writes actuators on real HW or sim

Rule: Use SystemInterface when joints share the same bus (most robots). Use ActuatorInterface for single standalone actuators. Use SensorInterface for read-only devices (encoders, IMUs).

Package Dependencies

Add these to package.xml and CMakeLists.txt:

<!-- package.xml -->
<depend>hardware_interface</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
# CMakeLists.txt
find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)

add_library(my_robot_hardware SHARED src/my_robot_hardware.cpp)
ament_target_dependencies(my_robot_hardware hardware_interface pluginlib rclcpp)

pluginlib_export_plugin_description_file(hardware_interface my_robot_hardware.xml)

Plugin Description File

my_robot_hardware.xml — tells pluginlib where to find your class:

<library path="my_robot_hardware">
  <class
    name="my_robot_hardware/MyRobotHardware"
    type="my_robot_hardware::MyRobotHardware"
    base_class_type="hardware_interface::SystemInterface">
    <description>My robot hardware interface</description>
  </class>
</library>

SystemInterface: Header

// include/my_robot_hardware/my_robot_hardware.hpp
#pragma once
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/rclcpp.hpp"

namespace my_robot_hardware {

class MyRobotHardware : public hardware_interface::SystemInterface {
public:
  RCLCPP_SHARED_PTR_DEFINITIONS(MyRobotHardware)

  // Lifecycle hooks — called by controller manager
  hardware_interface::CallbackReturn on_init(
    const hardware_interface::HardwareInfo & info) override;

  hardware_interface::CallbackReturn on_configure(
    const rclcpp_lifecycle::State & previous_state) override;

  hardware_interface::CallbackReturn on_activate(
    const rclcpp_lifecycle::State & previous_state) override;

  hardware_interface::CallbackReturn on_deactivate(
    const rclcpp_lifecycle::State & previous_state) override;

  // Called every control cycle
  std::vector<hardware_interface::StateInterface>
    export_state_interfaces() override;

  std::vector<hardware_interface::CommandInterface>
    export_command_interfaces() override;

  hardware_interface::return_type read(
    const rclcpp::Time & time,
    const rclcpp::Duration & period) override;

  hardware_interface::return_type write(
    const rclcpp::Time & time,
    const rclcpp::Duration & period) override;

private:
  // One entry per joint
  std::vector<double> hw_positions_;
  std::vector<double> hw_velocities_;
  std::vector<double> hw_commands_;  // position or velocity targets
};

}  // namespace my_robot_hardware

on_init: Parse URDF Info

on_init receives the parsed URDF <ros2_control> block. Validate joint count and interface types here.

hardware_interface::CallbackReturn MyRobotHardware::on_init(
  const hardware_interface::HardwareInfo & info)
{
  // Always call parent first
  if (hardware_interface::SystemInterface::on_init(info) !=
      hardware_interface::CallbackReturn::SUCCESS) {
    return hardware_interface::CallbackReturn::ERROR;
  }

  // Validate: expect exactly 1 position command + 2 state interfaces per joint
  for (const auto & joint : info_.joints) {
    if (joint.command_interfaces.size() != 1) {
      RCLCPP_ERROR(rclcpp::get_logger("MyRobotHardware"),
        "Joint '%s' has %zu command interfaces, expected 1",
        joint.name.c_str(), joint.command_interfaces.size());
      return hardware_interface::CallbackReturn::ERROR;
    }
    if (joint.command_interfaces[0].name !=
        hardware_interface::HW_IF_POSITION) {
      RCLCPP_ERROR(rclcpp::get_logger("MyRobotHardware"),
        "Expected position command interface, got '%s'",
        joint.command_interfaces[0].name.c_str());
      return hardware_interface::CallbackReturn::ERROR;
    }
  }

  hw_positions_.resize(info_.joints.size(), 0.0);
  hw_velocities_.resize(info_.joints.size(), 0.0);
  hw_commands_.resize(info_.joints.size(), 0.0);

  return hardware_interface::CallbackReturn::SUCCESS;
}

Export Interfaces

Return references to your internal storage. The controller manager reads/writes via these handles every cycle.

std::vector<hardware_interface::StateInterface>
MyRobotHardware::export_state_interfaces()
{
  std::vector<hardware_interface::StateInterface> state_interfaces;
  for (size_t i = 0; i < info_.joints.size(); i++) {
    state_interfaces.emplace_back(
      info_.joints[i].name,
      hardware_interface::HW_IF_POSITION,
      &hw_positions_[i]);  // <-- reference to storage
    state_interfaces.emplace_back(
      info_.joints[i].name,
      hardware_interface::HW_IF_VELOCITY,
      &hw_velocities_[i]);
  }
  return state_interfaces;
}

std::vector<hardware_interface::CommandInterface>
MyRobotHardware::export_command_interfaces()
{
  std::vector<hardware_interface::CommandInterface> command_interfaces;
  for (size_t i = 0; i < info_.joints.size(); i++) {
    command_interfaces.emplace_back(
      info_.joints[i].name,
      hardware_interface::HW_IF_POSITION,
      &hw_commands_[i]);
  }
  return command_interfaces;
}

read() and write()

read() pulls sensor data from hardware into your state vectors. write() sends command vectors to hardware.

hardware_interface::return_type MyRobotHardware::read(
  const rclcpp::Time & /*time*/,
  const rclcpp::Duration & /*period*/)
{
  // Example: read from serial/CAN/EtherCAT
  for (size_t i = 0; i < hw_positions_.size(); i++) {
    hw_positions_[i] = read_encoder_position(i);   // your HW call
    hw_velocities_[i] = read_encoder_velocity(i);
  }
  return hardware_interface::return_type::OK;
}

hardware_interface::return_type MyRobotHardware::write(
  const rclcpp::Time & /*time*/,
  const rclcpp::Duration & /*period*/)
{
  for (size_t i = 0; i < hw_commands_.size(); i++) {
    send_position_command(i, hw_commands_[i]);  // your HW call
  }
  return hardware_interface::return_type::OK;
}

Timing: read() is called before controllers update; write() is called after. Cycle rate is set by update_rate in controller_manager.yaml (default 100 Hz).

URDF: <ros2_control> Tag

Add the <ros2_control> block to your robot's URDF/xacro to declare joints and interfaces:

<ros2_control name="MyRobot" type="system">
  <hardware>
    <plugin>my_robot_hardware/MyRobotHardware</plugin>
    <!-- Optional parameters read in on_init via info_.hardware_parameters -->
    <param name="serial_port">/dev/ttyUSB0</param>
    <param name="baud_rate">115200</param>
  </hardware>

  <joint name="left_wheel_joint">
    <command_interface name="velocity"/>
    <state_interface name="position"/>
    <state_interface name="velocity"/>
  </joint>

  <joint name="right_wheel_joint">
    <command_interface name="velocity"/>
    <state_interface name="position"/>
    <state_interface name="velocity"/>
  </joint>
</ros2_control>

Controller Manager YAML

Configure the controller manager and load controllers in config/controller_manager.yaml:

controller_manager:
  ros__parameters:
    update_rate: 100  # Hz

    # Controllers to load at startup
    diff_drive_controller:
      type: diff_drive_controller/DiffDriveController

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

diff_drive_controller:
  ros__parameters:
    left_wheel_names: ["left_wheel_joint"]
    right_wheel_names: ["right_wheel_joint"]
    wheel_separation: 0.34   # meters between wheels
    wheel_radius: 0.075      # meters
    odom_frame_id: odom
    base_frame_id: base_link
    publish_rate: 50.0       # Hz

Launch File

from launch import LaunchDescription
from launch.actions import RegisterEventHandler
from launch.event_handlers import OnProcessStart
from launch_ros.actions import Node
import os
from ament_index_python.packages import get_package_share_directory

def generate_launch_description():
    pkg = get_package_share_directory("my_robot")
    robot_description = open(os.path.join(pkg, "urdf", "robot.urdf")).read()
    controller_params = os.path.join(pkg, "config", "controller_manager.yaml")

    robot_state_publisher = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        parameters=[{"robot_description": robot_description}],
    )

    controller_manager = Node(
        package="controller_manager",
        executable="ros2_control_node",
        parameters=[{"robot_description": robot_description}, controller_params],
        output="screen",
    )

    # Spawners run after controller_manager is up
    jsb_spawner = Node(
        package="controller_manager",
        executable="spawner",
        arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
    )

    drive_spawner = Node(
        package="controller_manager",
        executable="spawner",
        arguments=["diff_drive_controller", "--controller-manager", "/controller_manager"],
    )

    delayed_drive = RegisterEventHandler(
        OnProcessStart(
            target_action=jsb_spawner,
            on_start=[drive_spawner],
        )
    )

    return LaunchDescription([
        robot_state_publisher,
        controller_manager,
        jsb_spawner,
        delayed_drive,
    ])

Essential CLI Commands

ros2 control list_hardware_interfaces

Show all state + command interfaces and their claim status

ros2 control list_controllers

Show loaded controllers and their state (active/inactive)

ros2 run controller_manager spawner <name>

Load and activate a controller at runtime

ros2 run controller_manager unspawner <name>

Deactivate and unload a controller

ros2 control set_controller_state <name> active

Activate a loaded (but inactive) controller

ros2 control reload_controller_libraries --force-kill

Hot-reload plugin libs without restarting CM

Common Issues

"Could not activate controller" — interface not available

Run ros2 control list_hardware_interfaces. If position/velocity shows [unclaimed] the HW plugin loaded. If missing entirely, check plugin.xml name matches the type in CMakeLists.txt pluginlib_export_plugin_description_file.

Controller deactivates immediately after activation

Your read() is probably returning ERROR. Add RCLCPP_ERROR logging inside read() to find the failing hardware call. Check serial port permissions: sudo chmod 666 /dev/ttyUSB0.

Joints moving but state not updating in /joint_states

Ensure joint_state_broadcaster is active. Check that export_state_interfaces() returns references to hw_positions_ (not local copies).

Next Steps