Standardized, Integrated Management of Motion Controller Status and Commands
This guide details the step-by-step process for configuring a CiA 402 compliant servo motor using the simple node-based operation of the ros2_canopen stack.
Later on, the same configuration files and packages can be used for ros2_control integration using lifecycle nodes.
This guide assumes you have ROS 2 Jazzy and the ros2_canopen packages installed, and you have a your physical CAN bus present.
Follow these steps to ensure that your CAN bus is working.
Activate the CAN interface (replace can0 with your CAN device, and update the bitrate if required)
$ sudo ip link set up can0 type can bitrate 1000000
Verify the interface is up and listening
$ candump can0
Depending on your device, you should now see some CAN data bring printed to the terminal
If you don't already have a dedicated package, create one in your ROS 2 workspace and directories for files:
$ mkdir -p ~/ros2_ws/src
$ cd ~/ros2_ws/src
$ ros2 pkg create --build-type ament_cmake my_canopen_setup
$ mkdir -p my_canopen_setup/config/bus_1
$ mkdir -p my_canopen_setup/launch
This file tells the ros2_canopen device container which devices are on the bus, their IDs, and which driver to use.
Download the EDS file from your device manufacturer or distributor (e.g., my_servo_drive.eds) and place it inside the newly created config directory.
Create and populate the bus.yaml file in my_canopen_setup/config/bus_1/bus.yaml:
options:
# This is a placeholder that will be expanded by CMake into the final DCF path
dcf_path: "@BUS_CONFIG_PATH@"
master:
node_id: 1
driver: "ros2_canopen::MasterDriver"
package: "canopen_master_driver"
baudrate: 1000 # CAN bus baudrate in kHz
sync_period: 10000 # SYNC period in microseconds
nodes:
servo_motor: # This becomes the ROS 2 namespace (/servo_motor)
node_id: 2 # The slave device's unique Node ID
dcf: "my_servo_drive.eds" # Reference your EDS file (must be in the same directory for CMake processing)
dcf_path: "@BUS_CONFIG_PATH@"
driver: "ros2_canopen::Canopen402Driver" # Use the CiA 402 driver for motion control functionality
package: "canopen_402_driver"
# RPDOs (Receive PDOs) are messages *sent by the master* (ROS) to the slave (motor)
rpdo:
1:
enabled: true
cob_id: "auto"
mapping:
- {index: 0x6040, sub_index: 0} # controlword
- {index: 0x60FF, sub_index: 0} # Target Velocity
# TPDOs (Transmit PDOs) are messages *sent by the slave* (motor) to the master (ROS)
tpdo:
3:
enabled: true
cob_id: "auto"
transmission: 0x01
mapping:
- {index: 0x6041, sub_index: 0} # status word
- {index: 0x7009, sub_index: 0} # Actual Velocity
The rpdo and tpdo section will need to be customised according to your device. Check the documentation supplied with your device for the correct settings.
You must use CMake functions to process the YAML configuration and EDS file into a binary DCF file that ros2_canopen reads at runtime.
Edit my_canopen_setup/CMakeLists.txt and add the following block before the ament_package() call:
# Find the required component
find_package(canopen_core REQUIRED)
Generate the binary DCF from the bus.yaml and EDS file(s)
canopen_core_generate_dcf_bin(
FILE "config/bus.yaml"
DCFS "config/my_servo_drive.eds" # List all EDS files used in bus.yaml
OUTPUT_NAME "bus.bin"
)
Install the generated DCF file so it can be found at runtime
install(
FILES ${canopen_core_OUTPUT_FILE}
DESTINATION share/${PROJECT_NAME}/config
)
Install the original configuration files (optional)
install(
DIRECTORY config/
DESTINATION share/${PROJECT_NAME}/config
PATTERN "*.yaml"
PATTERN "*.eds"
)
This Python launch file is responsible for starting the core device_container_node and passing the necessary configuration parameters.
Create the file at my_canopen_setup/launch/servo_setup.launch.py:
The following launch file runs the canopen_core node using our configuration files (agan, replace can0 with your device if required):
import os
import sys
import launch
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python import get_package_share_directory
from launch import LaunchDescription
def generate_launch_description():
ld = LaunchDescription()
bus_config_path = os.path.join(
get_package_share_directory("my_canopen_setup"),
"config",
"bus_1",
)
master_bin_path = os.path.join(os.path.join(bus_config_path, "master.bin"))
if not os.path.exists(master_bin_path):
master_bin_path = ""
device_container = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[
os.path.join(get_package_share_directory("canopen_core"), "launch"),
"/canopen.launch.py",
]
),
launch_arguments={
"master_config": os.path.join(bus_config_path, "master.dcf"),
"master_bin": master_bin_path,
"bus_config": os.path.join(bus_config_path, "bus.yaml"),
"can_interface_name": "can0",
}.items(),
)
ld.add_action(device_container)
return ld
$ cd ~/ros2_ws
$ colcon build --packages-select my_canopen_setup
First, launch the package
$ source install/setup.bash
$ ros2 launch my_canopen_setup servo_setup.launch.py
Since we used the canopen_402_driver, the motor is now exposed via standard ROS 2 services under its namespace defined in the bus.yaml file (/servo_motor).
ros2 service call /servo_motor/init std_srvs/srv/Trigger
ros2 service call /servo_motor/velocity_mode std_srvs/srv/Trigger
This command will set the target velocity to 5.0 (check your drive documentation for units, but often revolutions per second):
ros2 service call /servo_motor/target canopen_interfaces/srv/COTargetDouble '{target: 5.0}'
Now that your servo drive can be controlled from ROS 2 using CANopen, the next step is to integrate it with ros2_control, which comes with many controllers that can be used to create diff drive vehicles, robot arms and more.
If you're ready to dive deeper into these practical steps or need personalized guidance on your specific servo drive integration, I invite you to schedule a call with me to learn more!
Ready to revolutionize your ROS 2 projects with seamless cross-platform communication?