Skip to content

[WARN] [dynamixel_hardware_interface]: No position interface found in command interfaces for joint 'FL_wheel'. Skipping sync! #89

@BCaran

Description

@BCaran

Hello everyone,

I am using dynamixel_hardware_interface for my 4WIS4WID mobile robot, where I have 4 steering motors which are position controlled as well as 4 driving motors which are velocity controlled.

When I run everything works — I can send commands and motors are running — but I always get these warnings:

[WARN] [1760039933.972482687] [dynamixel_hardware_interface]: No position interface found in command interfaces for joint 'FL_wheel'. Skipping sync!
[WARN] [1760039933.972522102] [dynamixel_hardware_interface]: No position interface found in command interfaces for joint 'BL_wheel'. Skipping sync!
[WARN] [1760039933.972529999] [dynamixel_hardware_interface]: No position interface found in command interfaces for joint 'BR_wheel'. Skipping sync!
[WARN] [1760039933.972537054] [dynamixel_hardware_interface]: No position interface found in command interfaces for joint 'FR_wheel'. Skipping sync!

I am not sure if I should be worried about those or not.

I am sending you my .ros2_control.xacro and controllers.yaml files:


.ros2_control.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
    <ros2_control name="WCRHardwareInterface" type="system">
        <hardware>
            <plugin>dynamixel_hardware_interface/DynamixelHardware</plugin>
            <param name="port_name">/dev/ttyUSB0</param>
            <param name="baud_rate">4500000</param>
            <param name="disable_torque_at_init">true</param>
            <param name="error_timeout_ms">500</param>
            <param name="dynamixel_model_folder">/param/dxl_model</param>
            <param name="number_of_joints">8</param>
            <param name="number_of_transmissions">8</param>
            <param name="transmission_to_joint_matrix">1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1</param>
            <param name="joint_to_transmission_matrix">1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1</param>
            <param name="dynamixel_state_pub_msg_name">dynamixel_hardware_interface/dxl_state</param>
            <param name="get_dynamixel_data_srv_name">dynamixel_hardware_interface/get_dxl_data</param>
            <param name="set_dynamixel_data_srv_name">dynamixel_hardware_interface/set_dxl_data</param>
            <param name="reboot_dxl_srv_name">dynamixel_hardware_interface/reboot_dxl</param>
            <param name="set_dxl_torque_srv_name">dynamixel_hardware_interface/set_dxl_torque</param>

            <!-- This parameter is used for a prismatic joint that operates through a revolute mechanism.
            If the joint does not require this configuration, this parameter can be removed. -->
            <!--<param name="use_revolute_to_prismatic_gripper">1</param>-->
            <!--<param name="revolute_to_prismatic_dxl">dxl</param>-->
            <!--<param name="revolute_max">1.51</param>-->
            <!--<param name="revolute_min">0.56</param>-->
            <!--<param name="revolute_to_prismatic_joint">left_finger_joint</param>-->
            <!--<param name="prismatic_max">0.019</param>-->
            <!--<param name="prismatic_min">-0.01</param>-->
        </hardware>

        <!--JOINTS-->
        <joint name="FL_wheel">
            <command_interface name="velocity"/>
            <state_interface name="position"/>
            <state_interface name="velocity"/>
            <state_interface name="effort"/>
        </joint>
        <joint name="BL_wheel">
            <command_interface name="velocity"/>
            <state_interface name="position"/>
            <state_interface name="velocity"/>
            <state_interface name="effort"/>
        </joint>
        <joint name="BR_wheel">
            <command_interface name="velocity"/>
            <state_interface name="position"/>
            <state_interface name="velocity"/>
            <state_interface name="effort"/>
        </joint>
            <joint name="FR_wheel">
            <command_interface name="velocity"/>
            <state_interface name="position"/>
            <state_interface name="velocity"/>
            <state_interface name="effort"/>
        </joint>
        <joint name="FL_steering">
            <command_interface name="position"/>
            <state_interface name="position"/>
            <state_interface name="velocity"/>
            <state_interface name="effort"/>
        </joint>
        <joint name="BL_steering">
            <command_interface name="position"/>
            <state_interface name="position"/>
            <state_interface name="velocity"/>
            <state_interface name="effort"/>
        </joint>
        <joint name="BR_steering">
            <command_interface name="position"/>
            <state_interface name="position"/>
            <state_interface name="velocity"/>
            <state_interface name="effort"/>
        </joint>
        <joint name="FR_steering">
            <command_interface name="position"/>
            <state_interface name="position"/>
            <state_interface name="velocity"/>
            <state_interface name="effort"/>
        </joint>

        <gpio name="dxl1">
            <param name="type">dxl</param>
            <param name="ID">1</param>
            <command_interface name="Goal Velocity"/>
            <state_interface name="Present Position"/>
            <state_interface name="Present Velocity"/>
            <state_interface name="Present Current"/>
            <param name="Operating Mode">1</param>
            <param name="Velocity P Gain">100</param>
            <param name="Velocity I Gain">1920</param>
            <param name="Drive Mode">0</param>
            <param name="Return Delay Time">0</param>
        </gpio>
        <gpio name="dxl2">
            <param name="type">dxl</param>
            <param name="ID">2</param>
            <command_interface name="Goal Velocity"/>
            <state_interface name="Present Position"/>
            <state_interface name="Present Velocity"/>
            <state_interface name="Present Current"/>
            <param name="Operating Mode">1</param>
            <param name="Velocity P Gain">100</param>
            <param name="Velocity I Gain">1920</param>
            <param name="Drive Mode">0</param>
            <param name="Return Delay Time">0</param>
        </gpio>
        <gpio name="dxl3">
            <param name="type">dxl</param>
            <param name="ID">3</param>
            <command_interface name="Goal Velocity"/>
            <state_interface name="Present Position"/>
            <state_interface name="Present Velocity"/>
            <state_interface name="Present Current"/>
            <param name="Operating Mode">1</param>
            <param name="Velocity P Gain">100</param>
            <param name="Velocity I Gain">1920</param>
            <param name="Drive Mode">1</param>
            <param name="Return Delay Time">0</param>
        </gpio>
        <gpio name="dxl4">
            <param name="type">dxl</param>
            <param name="ID">4</param>
            <command_interface name="Goal Velocity"/>
            <state_interface name="Present Position"/>
            <state_interface name="Present Velocity"/>
            <state_interface name="Present Current"/>
            <param name="Operating Mode">1</param>
            <param name="Velocity P Gain">100</param>
            <param name="Velocity I Gain">1920</param>
            <param name="Drive Mode">1</param>
            <param name="Return Delay Time">0</param>
        </gpio>
        <gpio name="dxl5">
            <param name="type">dxl</param>
            <param name="ID">5</param>
            <command_interface name="Goal Position"/>
            <state_interface name="Present Position"/>
            <state_interface name="Present Velocity"/>
            <state_interface name="Present Current"/>
            <param name="Operating Mode">3</param>
            <param name="Position P Gain">900</param>
            <param name="Position I Gain">0</param>
            <param name="Position D Gain">0</param>
            <param name="Drive Mode">3</param>
            <param name="Return Delay Time">0</param>
        </gpio>
        <gpio name="dxl6">
            <param name="type">dxl</param>
            <param name="ID">6</param>
            <command_interface name="Goal Position"/>
            <state_interface name="Present Position"/>
            <state_interface name="Present Velocity"/>
            <state_interface name="Present Current"/>
            <param name="Operating Mode">3</param>
            <param name="Position P Gain">900</param>
            <param name="Position I Gain">0</param>
            <param name="Position D Gain">0</param>
            <param name="Drive Mode">3</param>
            <param name="Return Delay Time">0</param>
        </gpio>
        <gpio name="dxl7">
            <param name="type">dxl</param>
            <param name="ID">7</param>
            <command_interface name="Goal Position"/>
            <state_interface name="Present Position"/>
            <state_interface name="Present Velocity"/>
            <state_interface name="Present Current"/>
            <param name="Operating Mode">3</param>
            <param name="Position P Gain">900</param>
            <param name="Position I Gain">0</param>
            <param name="Position D Gain">0</param>
            <param name="Drive Mode">3</param>
            <param name="Return Delay Time">0</param>
        </gpio>
        <gpio name="dxl8">
            <param name="type">dxl</param>
            <param name="ID">8</param>
            <command_interface name="Goal Position"/>
            <state_interface name="Present Position"/>
            <state_interface name="Present Velocity"/>
            <state_interface name="Present Current"/>
            <param name="Operating Mode">3</param>
            <param name="Position P Gain">900</param>
            <param name="Position I Gain">0</param>
            <param name="Position D Gain">0</param>
            <param name="Drive Mode">3</param>
            <param name="Return Delay Time">0</param>
        </gpio>

    </ros2_control>
</robot>

controllers.yaml

controller_manager:
  ros__parameters:
    update_rate: 200  # Hz

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    forward_velocity_controller:
      type: forward_command_controller/ForwardCommandController

    forward_position_controller:
      type: forward_command_controller/ForwardCommandController

joint_state_broadcaster:
  ros__parameters:
    joints:
      - FL_wheel
      - BL_wheel
      - BR_wheel
      - FR_wheel
      - FL_steering
      - BL_steering
      - BR_steering
      - FR_steering

forward_velocity_controller:
  ros__parameters:
    joints:
      - FL_wheel
      - BL_wheel
      - BR_wheel
      - FR_wheel
    interface_name: velocity

forward_position_controller:
  ros__parameters:
    joints:
      - FL_steering
      - BL_steering
      - BR_steering
      - FR_steering
    interface_name: position

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions