ros-controls / ros2_control

Generic and simple controls framework for ROS 2
https://control.ros.org
Apache License 2.0
517 stars 308 forks source link

not able to activate 2 controllers #1480

Closed FrGe2016 closed 7 months ago

FrGe2016 commented 7 months ago

Not realy a bug probably just missunderstanding.

I have a homemade robotic arm. IT is controlled by 2 ESP32 one for the arm the other for the gripper. Based on dr denis.stogl roscon22 demonstration, i have made 2 hardware interface named FBotHardwareInterface and FGripHardwareInterface to read states and send commands with the good ESP32.

When i launch my file , every thing looks good: Loaded joint_state_broadcaster Configured and activated joint_state_broadcaster Loaded arm_controller Loaded gripper_controller

Then :

[spawner-5] [INFO] [1713139921.790703759] [spawner_arm_controller]: Loaded arm_controller
[ros2_control_node-1] [INFO] [1713139921.815671804] [controller_manager]: Configuring controller 'arm_controller'
[ros2_control_node-1] [INFO] [1713139921.816031492] [arm_controller]: No specific joint names are used for command interfaces. Using 'joints' parameter.
[ros2_control_node-1] [INFO] [1713139921.816094901] [arm_controller]: Command interfaces are [position] and state interfaces are [position velocity].
[ros2_control_node-1] [INFO] [1713139921.816122192] [arm_controller]: Using 'splines' interpolation method.
[ros2_control_node-1] [INFO] [1713139921.816573321] [arm_controller]: Controller state will be published at 50.00 Hz.
[ros2_control_node-1] [INFO] [1713139921.818986078] [arm_controller]: Goals with partial set of joints are allowed
[ros2_control_node-1] [INFO] [1713139921.819019753] [arm_controller]: Action status changes will be monitored at 20.00 Hz.
[ros2_control_node-1] [ERROR] [1713139921.865749934] [resource_manager]: Not acceptable command interfaces combination: 
[ros2_control_node-1] Start interfaces: 
[ros2_control_node-1] [
[ros2_control_node-1]   gripper/position
[ros2_control_node-1]   gripper_top/position
[ros2_control_node-1] ]
[ros2_control_node-1] Stop interfaces: 
[ros2_control_node-1] [
[ros2_control_node-1] ]
[ros2_control_node-1] Not existing: 
[ros2_control_node-1] [
[ros2_control_node-1]  gripper/position
[ros2_control_node-1]  gripper_top/position
[ros2_control_node-1] ]
[ros2_control_node-1] 
[ros2_control_node-1] [ERROR] [1713139921.865782549] [controller_manager]: Could not switch controllers since prepare command mode switch was rejected.
[spawner-4] [ERROR] [1713139921.866887511] [spawner_gripper_controller]: Failed to activate controller
[spawner-5] [INFO] [1713139921.967324003] [spawner_arm_controller]: Configured and activated arm_controller

When i look closely B4 in the log i see that only the fbot_hardware_interface was activated. If i swithch controller lines, i have the opposite result .

Here are the associated files:

g_controllers.yaml

# This config file is used by ros2_control
controller_manager:
  ros__parameters:                            # 'est ce fichier qui est utilisé dans d2.real
    update_rate: 20  # Hz

    arm_controller:
      type: joint_trajectory_controller/JointTrajectoryController

    gripper_controller:
      type: joint_trajectory_controller/JointTrajectoryController  

    joint_state_broadcaster:                                   
      type: joint_state_broadcaster/JointStateBroadcaster      

arm_controller:
  ros__parameters:
    command_interfaces:
      - position
    state_interfaces:
      - position
      - velocity
    allow_partial_joints_goal: true
    joints:
      - elbow
      - wrist
      - rotator
      - lateral

gripper_controller:
  ros__parameters:
    command_interfaces:
      - position
    state_interfaces:
      - position
      - velocity
    allow_partial_joints_goal: true
    joints:
      - gripper
      - gripper_top

g.ros2_control_arm.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:macro name="g_ros2_control" params="
               name
               use_mock_hardware:=^|false
               mock_sensor_commands:=^|false
               sim_gazebo_classic:=^|false
               sim_gazebo:=^|false"
               >
    <ros2_control name="${name}" type="system">
      <hardware>
        <xacro:if value="${use_mock_hardware}">
          <plugin>mock_components/GenericSystem</plugin>
          <param name="mock_sensor_commands">${mock_sensor_commands}</param>
        </xacro:if>
        <xacro:if value="${sim_gazebo_classic}">
          <plugin>gazebo_ros2_control/GazeboSystem</plugin>
        </xacro:if>
        <xacro:if value="${sim_gazebo}">
          <plugin>ign_ros2_control/IgnitionSystem</plugin>
        </xacro:if>
        <xacro:unless value="${use_mock_hardware or sim_gazebo_classic or sim_gazebo}">
          <plugin>f_hardware_interface/FBotHardwareInterface</plugin>

        </xacro:unless>
      </hardware>
      <joint name="elbow">
         <command_interface name="position"/>
         <command_interface name="velocity"/>
         <state_interface name="position">
             <param name="initial_value">0.0</param>
          </state_interface>
          <state_interface name="velocity">
             <param name="initial_value">0.0</param>
          </state_interface>    
      </joint>
      <joint name="wrist">
         <command_interface name="position"/>
         <command_interface name="velocity"/>
         <state_interface name="position">
             <param name="initial_value">0.0</param>
          </state_interface>
          <state_interface name="velocity">
             <param name="initial_value">0.0</param>
          </state_interface> 
      </joint>
      <joint name="rotator">
         <command_interface name="position"/>
         <command_interface name="velocity"/>
         <state_interface name="position">
             <param name="initial_value">0.0</param>
          </state_interface>
          <state_interface name="velocity">
             <param name="initial_value">0.0</param>
          </state_interface> 
      </joint>
      <joint name="lateral">
         <command_interface name="position"/>
         <state_interface name="position">
             <param name="initial_value">0.0</param>
          </state_interface>
          <state_interface name="velocity">
             <param name="initial_value">0.0</param>
          </state_interface> 
      </joint>
    </ros2_control>
  </xacro:macro>
</robot>

g.ros2_control_gripper.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:macro name="g_ros2_control" params="
               name
               use_mock_hardware:=^|false
               mock_sensor_commands:=^|false
               sim_gazebo_classic:=^|false
               sim_gazebo:=^|false"
               >
    <ros2_control name="${name}" type="system">
      <hardware>
        <xacro:if value="${use_mock_hardware}">
          <plugin>mock_components/GenericSystem</plugin>
          <param name="mock_sensor_commands">${mock_sensor_commands}</param>
        </xacro:if>
        <xacro:if value="${sim_gazebo_classic}">
          <plugin>gazebo_ros2_control/GazeboSystem</plugin>
        </xacro:if>
        <xacro:if value="${sim_gazebo}">
          <plugin>ign_ros2_control/IgnitionSystem</plugin>
        </xacro:if>
        <xacro:unless value="${use_mock_hardware or sim_gazebo_classic or sim_gazebo}">
          <plugin>f_grip_hardware_interface/FGripHardwareInterface</plugin>

        </xacro:unless>
      </hardware>
      <joint name="gripper">
         <command_interface name="position"/>
         <command_interface name="velocity"/>
         <state_interface name="position">
             <param name="initial_value">0.0</param>
          </state_interface>
          <state_interface name="velocity">
             <param name="initial_value">0.0</param>
          </state_interface> 
      </joint>
      <joint name="gripper_top">
         <command_interface name="position"/>
         <command_interface name="velocity"/>
         <state_interface name="position">
             <param name="initial_value">0.0</param>
          </state_interface>
          <state_interface name="velocity">
             <param name="initial_value">0.0</param>
          </state_interface> 
      </joint>

    </ros2_control>

  </xacro:macro>
</robot>
christophfroehlich commented 7 months ago

First of all, please take your time to properly format your questions (I did that now for you).

The error means that your hardware component did not load the requested interfaces. Remove the controller spawners from your launch file, launch your system and have a look with ros2 control list_hardware_components and ros2 control list_hardware_interfaces

From your code snippets it seems that you override your macro g_ros2_control for the gripper if you load that in the same URDF. Try to run xacro manually and introspect the resulting URDF in an editor, is there <plugin>f_grip_hardware_interface/FGripHardwareInterface</plugin> and <plugin>f_hardware_interface/FBotHardwareInterface</plugin> for both components?

FrGe2016 commented 7 months ago

Thank for the urdf clue. Since both macro had the same name, the macro was called only for one of the controller only.

FrGe2016 commented 7 months ago

Closed issue