Skip to content

Dynamixel Hardware Interface#

ROS2 hardware interface for Dynamixel Motors. You can control Dynamixel motors like below.

How to use#

Write URDF/XACRO file for your robot#

Example is here. You can use dynamixel hardware interface by writing URDF like below.

<xacro:macro name="azimuth_thruster_control" params="left_joint right_joint enable_dummy">
    <ros2_control name="azimuth_thruster_control" type="system">
        <hardware>
            <plugin>dynamixel_hardware_interface/DynamixelHardwareInterface</plugin>
            <param name="port_name">/dev/ttyUSB0</param>
            <param name="baudrate">9600</param>
            <param name="enable_dummy">${enable_dummy}</param>
        </hardware>
        <joint name="${left_joint}">
            <param name="id">1</param>
            <param name="motor_type">XW540-T260</param>
            <command_interface name="position"/>
            <state_interface name="position"/>
        </joint>
        <joint name="${right_joint}">
            <param name="id">2</param>
            <param name="motor_type">XW540-T260</param>
            <command_interface name="position"/>
            <state_interface name="position"/>
        </joint>
    </ros2_control>
</xacro:macro>

Hardware parameters in URDF/XACRO#

Name Type Description
port_name string USB port name of the U2D2
baudrate int baudrate of the RS485 communication
enable_dummy bool If true, this hardware interface runs without real dynamixel hardwre.

Joint parameters in URDF/XACRO#

Name Type Description
id int id of the dynamixel motor attached to the joint
motor_type string type of the dynamixel motor

Connect motors to the U2D2#

Connect motors to the U2D2. Power cable is also required.

Setup motors#

Use dynamixel wizard and configure motor ID and baudrate

Support Status#

State Interface#

Motor Position Interface Velocity Interface Effort Interface Temperature Interface
XW540-T260

Command Interface#

Motor Position Interface Velocity Interface Effort Interface
XW540-T260