This workspace provides a ROS 2 action server node that opens/closes a custom gripper driven by a Dynamixel motor using DynamixelSDK Protocol 2.0.
The main entrypoint is:
- Node:
gripper_dynamixel_action_node(package:gripper_dynamixel)
This node follows the common action interface described in Action Interface.
There are two parameter YAML layers:
-
Main runtime config (in
gripper_ros)- File:
gripper_ros/config/dynamixel.yaml - Contains the “site specific” choices: which motor model preset, which serial port, which ID, and your
open_position/close_position.
- File:
-
Motor model preset (in
gripper_dynamixel)- Files:
gripper_dynamixel/config/<MODEL>.yaml(examples:XL330.yaml,XM430.yaml,W350.yaml) - Contains the “motor specific” details: control table addresses, operating mode values, and position scaling constants.
- Files:
At startup the node:
- Declares parameters with safe defaults.
- Loads the model preset if
motor_modelormotor_config_pathis provided. - Initializes the Dynamixel SDK driver using the final parameter values.
The node supports two command styles:
- Position mode: writes
Goal Position. - Torque mode (implemented as current/torque control): writes
Goal Current.
When torque mode is enabled and a target position is also provided (open/close), the node uses Current-based Position Control (operating mode 5 by default on many X-series), i.e. it writes both goal current and goal position.
Important: the goal field named torque is treated as a raw Goal Current value (units are motor/model specific). This is intentional so the model preset can stay generic.
By default, open_position and close_position are interpreted as radians and then converted to Dynamixel ticks using:
If you prefer to specify raw ticks directly, set:
position_is_radians: false
- Connect the motor via a U2D2 (or equivalent USB2Serial adapter).
- Ensure your user can access the serial port (often requires
dialoutgroup):
sudo usermod -a -G dialout $USERLog out/in after changing groups.
Edit gripper_ros/config/dynamixel.yaml:
motor_model:XL330/XM430/W350(or your custom preset name)device_name: e.g./dev/ttyUSB0baudrate: e.g.57600or whatever you configured on the motordxl_id: the motor IDopen_position/close_position: your gripper’s open/close targets
Launch via gripper_ros:
source install/setup.bash
ros2 launch gripper_ros dyanmixel.launch.pyOverride the params file if needed:
source install/setup.bash
ros2 launch gripper_ros dyanmixel.launch.py params_file:=/abs/path/to/dynamixel.yamlSee docs/action_interface.md for action goal examples.
motor_model(string): loads${share}/config/<motor_model>.yamlfrom thegripper_dynamixelpackage.motor_config_path(string): explicit YAML file path (overridesmotor_modellookup).
device_name(string): serial port, e.g./dev/ttyUSB0baudrate(int): serial baud ratedxl_id(int): motor ID
open_position(float): target open position (radians by default)close_position(float): target close position (radians by default)
goal_tolerance_ticks(int): success whenabs(target - present) <= tolerancemotion_timeout_sec(float): abort if not reached in timepoll_rate_hz(float): present position polling frequency
use_torque_mode(bool): default torque-mode behavior if the action goal does not explicitly enable itdefault_torque(float): used when goaltorqueis0.0close_default(bool): used when close goal’s boolean flag is default-constructed / false
These must match your motor model’s control table:
addr_operating_modeaddr_torque_enableaddr_goal_currentaddr_goal_positionaddr_present_currentaddr_present_position
operating_mode_current(commonly0)operating_mode_position(commonly3)operating_mode_current_based_position(commonly5)
position_is_radians(bool)ticks_per_rev(int)gear_ratio(float)direction(int, usually+1or-1)zero_offset_ticks(int)
- YAML parsing errors: YAML indentation must use spaces (tabs are invalid YAML). Keep
ros__parametersblocks consistently indented. - Port open failures: verify
device_nameand permissions (dialoutgroup). - No response / timeouts: likely wrong
dxl_id, baudrate, or a control-table address mismatch. - Motor moves the wrong way: set
direction: -1or adjust your sign convention. - Open/close not matching physical endpoints:
- Use
zero_offset_ticksto shift the reference - Adjust
open_position/close_position - Consider switching to
position_is_radians: falsetemporarily and tune in ticks
- Use
This is the smallest useful main config file. Keep indentation as spaces (tabs will break YAML parsing).
gripper_dynamixel_action_node:
ros__parameters:
motor_model: XL330
device_name: /dev/ttyUSB0
baudrate: 57600
dxl_id: 1
open_position: 0.0
close_position: 1.0To add a new model preset, create a new file in gripper_dynamixel/config/, for example:
gripper_dynamixel/config/MY_GRIPPER.yaml
gripper_dynamixel_action_node:
ros__parameters:
# Control table addresses (MUST match your motor's e-manual)
addr_operating_mode: 11
addr_torque_enable: 64
addr_goal_current: 102
addr_goal_position: 116
addr_present_current: 126
addr_present_position: 132
# Operating modes (Protocol 2.0)
operating_mode_current: 0
operating_mode_position: 3
operating_mode_current_based_position: 5
# Position scaling
position_is_radians: true
ticks_per_rev: 4096
gear_ratio: 1.0
direction: 1
zero_offset_ticks: 0Then set in your main gripper_ros/config/dynamixel.yaml:
gripper_dynamixel_action_node:
ros__parameters:
motor_model: MY_GRIPPER
device_name: /dev/ttyUSB0
baudrate: 57600
dxl_id: 1