ros-controls / gazebo_ros2_control

Wrappers, tools and additional API's for using ros2_control with Gazebo Classic
Apache License 2.0
186 stars 118 forks source link

Do mimic joints on gazebo_ros2_control work for grippers with one part interacting with the rest? (1 to 5 Gripper) #303

Closed MarioCavero closed 2 months ago

MarioCavero commented 2 months ago

I posted a question in RSE gazebo-ros2-control-mimic-joints-not-working-as-expected . I am using Ubuntu 22 and ros2 Humble. Plugins and everything installed using sudo apt install gazeb-ros2 ... etc. My research shows me that it is possible to mimic these joints and this kind of gripper. There are repos with very similar robotic arms to mine (the Hiwonder LeArm) that manage to get it working. I am currently working on extending this repo to allow simulations. In this other repo mimicking also works, the robotic arm is very similar (check first picture I post) but it's on ros, not ros2 and not gazebo_ros2_control. I have also read this recent PR but I do not know if it's helpful for me.

image

scaled_gripper

My main concern when the gripper closes (I used position, also effort in ros_controllers.yaml) is that it seems that there is either some connection not being properly made or that the collisions/meshes (.STL files) in the urdf are not complete in the gripper part. All the gripper joints can be moved individually and simultaenously to "mimic the mimicking" but I guess it's not what I want for simulation interaction with objects.

The edited urdf to allow gazebo_ros2_control, meshes available in the first repo. : (This is the .xacro transformed into an urdf).

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from learm-gazebo.urdf.xacro        | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="LeArm">
  <ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>
    <joint name="shoulder_pan">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="shoulder_lift">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="elbow">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="wrist_flex">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="wrist_roll">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="grip_left">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">0</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="grip_right">
      <command_interface name="position">
        <param name="min">0</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="tendon_left">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">0</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="tendon_right">
      <command_interface name="position">
        <param name="min">0</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="finger_left">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">0</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="finger_right">
      <command_interface name="position">
        <param name="min">0</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
  </ros2_control>
  <gazebo>
    <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
      <!-- <robot_param>robot_description</robot_param> -->
      <!-- <robot_param_node>robot_state_publisher</robot_param_node> -->
      <parameters>/home/mk/ros2_ws/install/learm_ros2_description/share/learm_ros2_description/config/combined_controllers.yaml</parameters>
      <!-- <parameters>/home/mk/ros2_ws/src/learm_ros2_description/config/combined_controllers.yaml</parameters> -->
      <!-- <controller_manager_name>simulation_controller_manager</controller_manager_name> -->
    </plugin>
  </gazebo>
  <link name="world"/>
  <link name="base_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/base.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/base.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="shoulder_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/shoulder.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/shoulder.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="humerus_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/humerus.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/humerus.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="forearm_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/forearm.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/forearm.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="wrist_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/wrist.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/wrist.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="hand_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/hand.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/hand.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="grip_left_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/carpal-left.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/carpal-left.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="grip_right_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/carpal-right.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/carpal-right.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="tendon_left_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/tendon.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/tendon.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="tendon_right_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/tendon.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/tendon.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="finger_left_link">
    <visual>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/finger.stl"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/finger.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <link name="finger_right_link">
    <visual>
      <origin rpy="0 0 3.14159"/>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/finger.stl"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 3.14159"/>
      <geometry>
        <mesh filename="file:///home/mk/ros2_ws/src/learm_ros2/meshes/finger.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <inertia ixx="0.03" ixy="0.0" ixz="0.0" iyy="0.03" iyz="0.0" izz="0.03"/>
    </inertial>
  </link>
  <joint name="base_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 1.04"/>
    <parent link="world"/>
    <child link="base_link"/>
  </joint>
  <joint name="shoulder_pan" type="revolute">
    <parent link="base_link"/>
    <child link="shoulder_link"/>
    <origin xyz="0 0 0.059"/>
    <axis xyz="0 0 1"/>
    <limit effort="1000" lower="-1.57" upper="1.57" velocity="0.5"/>
  </joint>
  <joint name="shoulder_lift" type="revolute">
    <parent link="shoulder_link"/>
    <child link="humerus_link"/>
    <origin xyz="-0.010 0 0.028"/>
    <axis xyz="0 1 0"/>
    <limit effort="1000" lower="-1.57" upper="1.57" velocity="0.5"/>
  </joint>
  <joint name="elbow" type="revolute">
    <parent link="humerus_link"/>
    <child link="forearm_link"/>
    <origin xyz="0 0 0.105"/>
    <axis xyz="0 -1 0"/>
    <limit effort="1000" lower="-1.57" upper="1.57" velocity="0.5"/>
  </joint>
  <joint name="wrist_flex" type="revolute">
    <parent link="forearm_link"/>
    <child link="wrist_link"/>
    <origin xyz="0 0 0.090"/>
    <axis xyz="0 -1 0"/>
    <limit effort="1000" lower="-1.57" upper="1.57" velocity="0.5"/>
  </joint>
  <joint name="wrist_roll" type="revolute">
    <parent link="wrist_link"/>
    <child link="hand_link"/>
    <origin xyz="0 0 0.060"/>
    <axis xyz="0 0 1"/>
    <limit effort="1000" lower="-1.57" upper="1.57" velocity="0.5"/>
  </joint>
  <joint name="grip_left" type="revolute">
    <parent link="hand_link"/>
    <child link="grip_left_link"/>
    <origin rpy="-1.57 0 0" xyz="0 +0.015 0.030"/>
    <axis xyz="-1 0 0"/>
    <limit effort="1000" lower="-1.57" upper="0" velocity="0.5"/>
     <dynamics damping="50" friction="1"/>
  </joint>

  <joint name="grip_right" type="revolute">
    <parent link="hand_link"/>
    <child link="grip_right_link"/>
    <origin rpy="1.57 0 0" xyz="0 -0.015 0.030"/>
    <axis xyz="-1 0 0"/>
    <limit effort="1000" lower="0" upper="1.57" velocity="0.5"/>
    <mimic joint="grip_left" multiplier="-1.0"/>
  </joint>
  <joint name="tendon_left" type="revolute">
    <parent link="hand_link"/>
    <child link="tendon_left_link"/>
    <origin rpy="-1.57 0 0" xyz="0 +0.005 0.050"/>
    <axis xyz="-1 0 0"/>
    <limit effort="1000" lower="-1.57" upper="0" velocity="0.5"/>
    <mimic joint="grip_left"/>
  </joint>
  <joint name="tendon_right" type="revolute">
    <parent link="hand_link"/>
    <child link="tendon_right_link"/>
    <origin rpy="1.57 0 0" xyz="0 -0.005 0.050"/>
    <axis xyz="-1 0 0"/>
    <limit effort="1000" lower="0" upper="1.57" velocity="0.5"/>
    <mimic joint="grip_left" multiplier="-1"/>
  </joint>
  <joint name="finger_left" type="revolute">
    <parent link="grip_left_link"/>
    <child link="finger_left_link"/>
    <origin rpy="1.57 0 0" xyz="0 0 0.030"/>
    <axis xyz="-1 0 0"/>
    <limit effort="1000" lower="-1.57" upper="1.57" velocity="0.5"/>
    <!-- <limit effort="1000" lower="-1.57" upper="0" velocity="0.5"/> -->
    <mimic joint="grip_left" multiplier="-1"/>
  </joint>
  <joint name="finger_right" type="revolute">
    <parent link="grip_right_link"/>
    <child link="finger_right_link"/>
    <origin rpy="-1.57 0 0" xyz="0 0 0.030"/>
    <axis xyz="-1 0 0"/>
    <!-- <limit effort="1000" lower="0" upper="1.57" velocity="0.5"/> -->
    <limit effort="1000" lower="-1.57" upper="1.57" velocity="0.5"/>
    <mimic joint="grip_left"/>
  </joint>
  <transmission name="trans_shoulder_pan">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_pan">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="shoulder_pan_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_shoulder_lift">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_lift">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="shoulder_lift_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_elbow">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="elbow">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="elbow_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_wrist_flex">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_flex">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="wrist_flex_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_wrist_roll">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="wrist_roll">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="wrist_roll_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_grip_left">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="grip_left">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="grip_left_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_grip_right">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="grip_right">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="grip_right_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_tendon_left">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="tendon_left">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="tendon_left_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_tendon_right">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="tendon_right">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="tendon_right_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_finger_left">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="finger_left">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="finger_left_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <transmission name="trans_finger_right">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="finger_right">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="finger_right_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>
    <joint name="shoulder_pan">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="shoulder_lift">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="elbow">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="wrist_flex">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="wrist_roll">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="grip_left">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">0</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="grip_right">
      <command_interface name="position">
        <param name="min">0</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="tendon_left">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">0</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="tendon_right">
      <command_interface name="position">
        <param name="min">0</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="finger_left">
      <command_interface name="position">
        <param name="min">-1.57</param>
        <param name="max">0</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
    <joint name="finger_right">
      <command_interface name="position">
        <param name="min">0</param>
        <param name="max">1.57</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-0.5</param>
        <param name="max">0.5</param>
      </command_interface>
      <command_interface name="effort">
        <param name="min">-1000</param>
        <param name="max">1000</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
    </joint>
  </ros2_control>
  <!-- <gazebo>

    <plugin  name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
      <parameters>$(find learm_ros2_description)/config/combined_controllers.yaml</parameters>
    </plugin>
</gazebo> -->
</robot>

combined_controllers.yaml:

controller_manager:
  ros__parameters:
    update_rate: 100
    use_sim_time: true

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster
    arm_controller:
      type: joint_trajectory_controller/JointTrajectoryController
    gripper_controller:
      # type: joint_trajectory_controller/JointTrajectoryController
      type: effort_controllers/JointGroupEffortController

arm_controller:
  ros__parameters:
    publish_rate: 50.0
    base_frame_id: base_link

    command_interfaces:
      - position
    state_interfaces:
      - position
      - velocity
    joints:
      - shoulder_pan
      - shoulder_lift
      - elbow
      - wrist_flex
      - wrist_roll

gripper_controller:
  ros__parameters:
    publish_rate: 50.0

    command_interfaces: 
      - position
    state_interfaces: 
      - position
      - velocity
    joints:
      - grip_left
      # - grip_right
      # - tendon_left
      # - tendon_right
      # - finger_left
      # - finger_right
    gains:
      grip_left: {p: 100.0, i: 0.01, d: 10.0, i_clamp: 1}
      # grip_right: {p: 100.0, i: 0.01, d: 10.0, i_clamp: 1}
      # tendon_left: {p: 100.0, i: 0.01, d: 10.0, i_clamp: 1}
      # tendon_right: {p: 100.0, i: 0.01, d: 10.0, i_clamp: 1}
      # finger_left: {p: 100.0, i: 0.01, d: 10.0, i_clamp: 1}
      # finger_right: {p: 100.0, i: 0.01, d: 10.0, i_clamp: 1}
    # pid: {p: 100.0, i: 0.01, d: 10.0}

My new_run.launch.py:

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch_ros.actions import Node

import xacro

def generate_launch_description():
    gazebo = IncludeLaunchDescription(
                PythonLaunchDescriptionSource([os.path.join(
                    get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
             )

    gazebo_ros2_control_demos_path = os.path.join(
        get_package_share_directory('learm_ros2'))

    xacro_file = os.path.join(gazebo_ros2_control_demos_path,
                              'urdf',
                              'learm-gazebo-xacroTurdf.urdf')

    doc = xacro.parse(open(xacro_file))
    xacro.process_doc(doc)
    params = {'robot_description': doc.toxml()}

    node_robot_state_publisher = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        output='screen',
        parameters=[params]
    )

    spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
                        arguments=['-topic', 'robot_description',
                                   '-entity', 'cart'],
                        output='screen')

    load_joint_state_broadcaster = ExecuteProcess(
        cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
             'joint_state_broadcaster'],
        output='screen'
    )

    load_joint_trajectory_controller = ExecuteProcess(
        cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
             'arm_controller'],
        output='screen'
    )

    load_gripper = ExecuteProcess(
        cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
             'gripper_controller'],
        output='screen'
    )

    return LaunchDescription([
        RegisterEventHandler(
            event_handler=OnProcessExit(
                target_action=spawn_entity,
                on_exit=[load_joint_state_broadcaster],
            )
        ),
        RegisterEventHandler(
            event_handler=OnProcessExit(
                target_action=load_joint_state_broadcaster,
                on_exit=[load_joint_trajectory_controller],
            )
        ),
                RegisterEventHandler(
            event_handler=OnProcessExit(
                target_action=load_joint_trajectory_controller,
                on_exit=[load_gripper],
            )
        ),
        gazebo,
        node_robot_state_publisher,
        spawn_entity,
    ])

Why does the mimicking of grip_left not work in gazebo_ros2_control? Am I missing something? Or might it be due to a bad design in the .STL files?

As an addition to why I am be missing something, in Rviz and with the joint sliders, it works fine and the joints seem to move as connected. So there may be some physical parameters in the urdf or the pid values that may make it not work for me?

The original intertial values made the top part of the arm fall down if moved forwards/backwards in pybullet, in gazebo so it seems as well. so I used a tool to get inertial values for urdfs, by sending an .stl file and an approximate mass and it worked in pybullet but in gazebo the arm goes flying into pieces.

When I send an effort to the gripper (or position, depending on the type).

name:
- shoulder_lift
- wrist_flex
- grip_left
- elbow
- tendon_left
- wrist_roll
- tendon_right
- shoulder_pan
- finger_left
- grip_right
- finger_right
position:
- 3.3154011980229825e-08
- 9.883790674791726e-09
- -0.10458005539275295
- 1.1437988334250804e-08
- -2.9790358624381952e-08
- 9.28907262220946e-09
- 3.897504008421038e-08
- -3.205951415452546e-08
- 9.504799614035164e-09
- -5.224012866733574e-08
- 8.60402042945907e-08
velocity:
- 3.768342829450743e-10
- 6.775513665214036e-11
- -0.010215260824597354
- 3.2041162817638713e-10
- 2.4650073283037877e-11
- 1.0443308298690066e-11
- 2.4650092550034157e-11
- -1.234524015638026e-11
- 1.2715338293590355e-11
- -1.218327947861214e-12
- 2.5868410864353314e-11
effort:
- 0.0
- 0.0
- -1.54
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
---

I only get an effort from grip_left, so I do not think the problem right now are the intertial values, but no clue.