ros2_control_hardware_interface
Scaffold a ros2_control hardware component (SystemInterface / ActuatorInterface / SensorInterface) and its bringup — the plugin (on_init/on_configure/on_activate, RT-safe read()/write()), URDF <ros2_control> wiring, controllers.yaml + launch, pluginlib export. Trigger when the user asks to integrate hardware or bring up a robot under ros2_control.
git clone --depth 1 https://github.com/harunkurtdev/ros2-claude-code-template /tmp/ros2_control_hardware_interface && cp -r /tmp/ros2_control_hardware_interface/.claude/skills/ros2_control_hardware_interface ~/.claude/skills/ros2_control_hardware_interfaceSKILL.md
# Writing a ros2_control Hardware Component + Bringup
How to bring up a real (or simulated) robot under ros2_control: write a
`hardware_interface` plugin, wire it in the URDF, and launch it. Mirrors
the patterns in `~/nav2_ws/src/ros2_control_demos/`.
- Framework + interfaces + lifecycle: `rules/ros2_control_architecture.md`.
- Example catalog (copy the closest one): `rules/ros2_control_demos.md`.
- Controller side (the plugin that *commands* this hardware):
`skills/ros2_controller_creation/SKILL.md`.
- Reference implementations to mirror:
- whole robot → `example_1` (RRBot `SystemInterface`)
- mobile base → `example_2` (DiffBot)
- standalone sensor → `example_5` (`SensorInterface`)
- per-actuator modular → `example_6` (`ActuatorInterface`)
- GPIO → `example_10`, diagnostics → `example_17`
## First decision: which hardware base class?
| You are integrating… | Base class | Exports |
|----------------------|-----------|---------|
| A whole robot (joints + maybe sensors) | `hardware_interface::SystemInterface` | command + state interfaces |
| A single actuator | `hardware_interface::ActuatorInterface` | command + state for one actuator |
| A read-only sensor | `hardware_interface::SensorInterface` | **state interfaces only** |
A hardware component is a **pluginlib plugin** loaded by the
`controller_manager` (via the URDF), not a node. It runs in the RT loop:
`read() → controllers' update() → write()` every cycle.
## 1. The hardware plugin
`hardware/include/<pkg>/<robot>.hpp`:
```cpp
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "rclcpp_lifecycle/state.hpp"
namespace my_robot
{
class MyRobotHardware : public hardware_interface::SystemInterface
{
public:
RCLCPP_SHARED_PTR_DEFINITIONS(MyRobotHardware)
hardware_interface::CallbackReturn on_init(
const hardware_interface::HardwareComponentInterfaceParams & params) override;
hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State &) override;
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &) override;
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) 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:
double cfg_param_; // read from URDF <param> in on_init
};
} // namespace my_robot
```
`hardware/<robot>.cpp` essentials:
```cpp
CallbackReturn MyRobotHardware::on_init(const HardwareComponentInterfaceParams & params)
{
if (SystemInterface::on_init(params) != CallbackReturn::SUCCESS)
return CallbackReturn::ERROR;
// joints + their interfaces come from the URDF (get_hardware_info());
// read custom params: info_.hardware_parameters["my_param"]
return CallbackReturn::SUCCESS;
}
CallbackReturn MyRobotHardware::on_activate(const rclcpp_lifecycle::State &)
{
for (const auto & [name, descr] : joint_state_interfaces_) set_state(name, 0.0);
for (const auto & [name, descr] : joint_command_interfaces_) set_command(name, get_state(name));
return CallbackReturn::SUCCESS; // open device handles HERE
}
hardware_interface::return_type MyRobotHardware::read(const rclcpp::Time &, const rclcpp::Duration &)
{
// RT-safe: poll the device, push values into state interfaces
set_state("joint1/position", read_encoder());
return hardware_interface::return_type::OK;
}
hardware_interface::return_type MyRobotHardware::write(const rclcpp::Time &, const rclcpp::Duration &)
{
// RT-safe: take command-interface values, send them to the device
send_to_motor(get_command("joint1/position"));
return hardware_interface::return_type::OK;
}
```
Modern hardware_interface auto-creates the interface handles from the
URDF, so you use `get_state/set_state/get_command/set_command(name)`
helpers rather than hand-managing `std::vector<double>`. (Older demos
override `export_state_interfaces()` / `export_command_interfaces()` —
both patterns exist; prefer the URDF-driven one.)
`read()` / `write()` are the **RT hot path** — same rules as a
controller's `update()`: no allocation, no locks, no throw, no blocking
I/O, no unthrottled logging. Do device setup in `on_configure`/`on_activate`.
## 2. Plugin export
`<pkg>.xml`:
```xml
<library path="my_robot">
<class name="my_robot/MyRobotHardware" type="my_robot::MyRobotHardware"
base_class_type="hardware_interface::SystemInterface">
<description>My robot hardware interface.</description>
</class>
</library>
```
```cpp
#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(my_robot::MyRobotHardware, hardware_interface::SystemInterface)
```
```cmake
pluginlib_export_plugin_description_file(hardware_interface my_robot.xml)
```
`package.xml` depends: `hardware_interface`, `pluginlib`,
`rclcpp_lifecycle` (+ device libs).
## 3. URDF `<ros2_control>` tag (wires joints → your plugin)
`description/ros2_control/<robot>.ros2_control.xacro`:
```xml
<ros2_control name="${name}" type="system">
<hardware>
<plugin>my_robot/MyRobotHardware</plugin>
<param name="my_param">0.5</param> <!-- read in on_init -->
</hardware>
<joint name="${prefix}joint1">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
</ros2_control>
```
The `<plugin>` string must equal the pluginlib `name` alias above. The
`<command_interface>` / `<state_interface>` names here are exactly what
controllers claim (`joint1/position`).
## 4. Bringup
`bringup/config/<robot>_controllers.yaml`:
```yaml
controller_manager:
ros__parameters:
update_rate: 100 # Hz — the read/update/write loop frequency
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
forwarUse proactively before opening a PR that adds or changes BehaviorTree.CPP nodes or BehaviorTree.ROS2 wrappers (RosActionNode/RosServiceNode/RosTopicPub/SubNode, TreeExecutionServer). Reviews a diff against BT.CPP v4 conventions — node base-class choice, non-blocking ticks, ports/blackboard typing, factory/plugin registration, XML v4, and the ROS 2 wrapper contract. Returns a punch list with file:line anchors, not a rewrite.
Use when a design decision touches Clean Architecture boundaries in a ROS 2 project — which layer a new behaviour belongs to, whether a port belongs in domain or application, whether a new node should be lifecycle-managed, whether to compose nodes or split packages. Returns an architectural recommendation with trade-offs, not implementation.
Use when a design decision touches the gz-sim ECS — where new state should live, which system phase should write it, how to avoid coupling, whether to add a component vs. a member variable, whether a new system should be split or merged with an existing one. Returns an architectural recommendation with trade-offs, not implementation.
Use proactively before opening any gz-sim PR. Reviews a diff against the project's C++17 style, ECS conventions, plugin registration patterns, CMake structure, test placement, Migration.md / Changelog.md expectations, and pre-commit configuration. Returns a punch list, not a rewrite.
Use proactively before opening a PR that adds or changes a ros2_control controller, broadcaster, or hardware component (incl. URDF <ros2_control> bringup). Reviews a diff against ros2_controllers / ros2_control_demos conventions — controller & hardware lifecycle, command/state interface configuration, real-time safety of update()/read()/write(), generate_parameter_library usage, pluginlib registration, chainable-controller correctness, URDF wiring, and tests. Returns a punch list with file:line anchors, not a rewrite.
Use proactively before opening any ROS 2 / Nav 2 PR. Reviews a diff against this template's Clean Architecture, ROS 2 communication, lifecycle, testing, and Nav 2 plugin conventions. Returns a punch list with file:line anchors, not a rewrite.
Use proactively before opening a PR that touches a VDA 5050 connector / fleet bridge. Reviews a diff against VDA 5050 v3.0.0 protocol compliance (topics, QoS, header rules, base/horizon, action state machine, schema validation) and the template's Clean Architecture for the MQTT↔Nav 2 bridge. Returns a punch list with file:line anchors, not a rewrite.
Build the colcon workspace (optionally a single package) and report the outcome.