Problem: Your CAN Bus Motor Won't Talk to ROS 2
You've got a brushless motor with a CAN Bus interface — BLDC, servo, or ODrive — and ROS 2 doesn't see it. No /cmd_vel, no feedback, just silence.
You'll learn:
- How to bring up a SocketCAN interface on Linux
- How to send and receive raw CAN frames from your motor controller
- How to wrap that in a ROS 2 node using
ros2_control
Time: 30 min | Level: Advanced
Why This Happens
ROS 2 has no built-in CAN driver. CAN Bus is a low-level serial protocol — Linux exposes it via the SocketCAN kernel module as a network interface (like eth0, but for CAN). You must bring up that interface manually, then read/write frames from userspace.
Most motor controllers (ODrive, VESC, CANopen devices) speak their own application-layer protocol on top of raw CAN frames. Your ROS 2 node needs to encode/decode those frames correctly.
Common symptoms:
ip link showdoesn't list acan0interfacecandump can0shows nothing after sending a command- Motor responds to
cansendbut ignores ROS 2 messages
Solution
Step 1: Install SocketCAN and CAN Utilities
# Install kernel tools and userspace utilities
sudo apt update
sudo apt install can-utils iproute2 -y
# Verify the kernel module is available
modinfo can
Expected: modinfo prints module metadata with filename: path ending in .ko.
If it fails:
- "Module not found": Your kernel was built without CAN support. On embedded boards (Jetson, Pi), install
linux-modules-extra-$(uname -r).
Step 2: Bring Up the CAN Interface
For a USB-to-CAN adapter (e.g., CANable, PEAK PCAN-USB):
# Load the driver — use gs_usb for CANable, peak_usb for PEAK
sudo modprobe gs_usb
# Set bitrate to match your motor controller (typically 1M or 500K)
sudo ip link set can0 type can bitrate 1000000
# Bring the interface up
sudo ip link set can0 up
# Confirm it's live
ip link show can0
Expected: Output shows can0: <NOARP,UP,LOWER_UP> with your bitrate.
For a native CAN interface (Xavier, i.MX, STM32 via slcan):
# slcan bridges a serial port to SocketCAN
sudo slcand -o -s8 -t hw -S 3000000 /dev/ttyUSB0 can0
sudo ip link set can0 up
If it fails:
- "RTNETLINK answers: Operation not permitted": Prepend
sudoor run as root. - Interface goes down immediately: Bitrate mismatch — check your motor controller's CAN settings and match exactly.
Step 3: Verify Raw CAN Communication
Open two terminals. In the first, listen:
candump can0
In the second, send a test frame:
# Send frame: ID 0x001, 8 bytes of zeros
cansend can0 001#0000000000000000
Expected in Terminal 1:
can0 001 [8] 00 00 00 00 00 00 00 00
Now send a real command. For an ODrive at node ID 0, request encoder position (0x009):
cansend can0 009#0000000000000000
Expected: ODrive echoes back a frame with position data. If you see a response, your hardware path is working.
Step 4: Install ROS 2 CAN Dependencies
# ros2_control hardware interface framework
sudo apt install ros-humble-ros2-control ros-humble-ros2-controllers -y
# ros-humble-canopen for CANopen devices (skip if using ODrive/VESC)
sudo apt install ros-humble-canopen -y
Verify:
ros2 pkg list | grep -E "ros2_control|canopen"
Expected: At least ros2_control, controller_manager, hardware_interface appear.
Step 5: Write a Minimal CAN Hardware Interface
Create the package:
cd ~/ros2_ws/src
ros2 pkg create can_motor_hw --build-type ament_cmake --dependencies rclcpp hardware_interface
Add can_motor_interface.cpp:
#include "hardware_interface/system_interface.hpp"
#include <linux/can.h>
#include <linux/can/raw.h>
#include <net/if.h>
#include <sys/socket.h>
#include <sys/ioctl.h>
#include <unistd.h>
class CanMotorInterface : public hardware_interface::SystemInterface {
public:
hardware_interface::CallbackReturn on_init(
const hardware_interface::HardwareInfo & info) override
{
// Open SocketCAN socket — fails fast if interface is down
sock_ = socket(PF_CAN, SOCK_RAW, CAN_RAW);
struct ifreq ifr;
strcpy(ifr.ifr_name, "can0");
ioctl(sock_, SIOCGIFINDEX, &ifr);
struct sockaddr_can addr{};
addr.can_family = AF_CAN;
addr.can_ifindex = ifr.ifr_ifindex;
bind(sock_, (struct sockaddr *)&addr, sizeof(addr));
return hardware_interface::CallbackReturn::SUCCESS;
}
hardware_interface::return_type write(
const rclcpp::Time &, const rclcpp::Duration &) override
{
struct can_frame frame{};
frame.can_id = 0x00D; // ODrive node 0, command 0x0D = velocity setpoint
frame.can_dlc = 8;
// Pack velocity (float32) into bytes 0-3
float vel = static_cast<float>(hw_commands_[0]);
memcpy(frame.data, &vel, 4);
::write(sock_, &frame, sizeof(frame)); // Send the frame
return hardware_interface::return_type::OK;
}
hardware_interface::return_type read(
const rclcpp::Time &, const rclcpp::Duration &) override
{
struct can_frame frame{};
// Non-blocking read — set O_NONBLOCK on sock_ in on_init for production
if (::read(sock_, &frame, sizeof(frame)) > 0) {
float pos;
memcpy(&pos, frame.data, 4); // Unpack position from bytes 0-3
hw_states_[0] = pos;
}
return hardware_interface::return_type::OK;
}
private:
int sock_;
std::vector<double> hw_commands_{0.0};
std::vector<double> hw_states_{0.0};
};
#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(CanMotorInterface, hardware_interface::SystemInterface)
Why this works: ros2_control calls read() and write() on every control loop tick. Your hardware interface translates those to raw SocketCAN frames — no extra middleware needed.
Step 6: Configure ros2_control URDF and Launch
Add can_motor.ros2_control.xacro:
<ros2_control name="CanMotorSystem" type="system">
<hardware>
<plugin>can_motor_hw/CanMotorInterface</plugin>
</hardware>
<joint name="wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
</joint>
</ros2_control>
Launch file can_motor.launch.py:
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[{"robot_description": open("can_motor.urdf").read()}],
),
Node(
package="controller_manager",
executable="spawner",
arguments=["velocity_controllers"],
),
])
Verification
Build and launch:
cd ~/ros2_ws
colcon build --packages-select can_motor_hw
source install/setup.bash
ros2 launch can_motor_hw can_motor.launch.py
In a second terminal, send a velocity command:
ros2 topic pub /velocity_controllers/commands std_msgs/msg/Float64MultiArray \
"data: [1.5]" --once
You should see: The motor spin at 1.5 rad/s and candump can0 showing outgoing frames with your velocity packed in bytes 0–3.
What You Learned
- SocketCAN exposes CAN Bus as a Linux network interface — always bring it up before launching ROS 2
ros2_controlseparates your control logic from hardware details viaSystemInterface- Raw
can_framestructs let you talk to any motor controller without library lock-in
Limitation: This uses blocking socket I/O in read(). For production robots, set O_NONBLOCK and handle EAGAIN — otherwise a missed frame stalls your entire control loop.
When NOT to use this: If your device speaks CANopen (CiA 301/402), use ros-humble-canopen instead — it handles NMT state machines and PDO mapping for you.
Tested on ROS 2 Humble, Ubuntu 22.04, Linux kernel 5.15, CANable 1.0 adapter at 1 Mbit/s