ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Robot model falls down in Gazebo when setting <transmission> as EffortJointInterface

asked 2021-12-23 08:06:14 -0500

mug gravatar image

updated 2021-12-26 08:52:54 -0500

Robot model collapses in Gazebo when setting <transmission> as EffortJointInterface. How to fix this? Any advice will be appreciated.

image description

And below's the content of the urdf file

<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) 
     Commit Version: 1.6.0-1-g15f4949  Build Version: 1.6.7594.29634
     For more information, please see http://wiki.ros.org/sw_urdf_exporter -->

<robot name="arm">

  <link name="world" />

  <link name="base_link">
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://arm_description/meshes/base_link.STL" />
      </geometry>
      <material name="3143">
        <color rgba="0.79216 0.81961 0.93333 1" />
      </material>
    </visual>
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://arm_description/meshes/base_link.STL" />
      </geometry>
    </collision>
    <inertial>
      <origin xyz="-0.52E-03 -0.01E-03 20.01E-03" rpy="0 0 0" />
      <mass value="1.25" />
      <inertia ixx="3000.53E-06"    ixy="-2.36E-06"    ixz="-15.68E-06"
                                    iyy="3039.39E-06"  iyz="0.05E-06"
                                                       izz="5609.85E-06" />
    </inertial>
  </link>

  <joint name="joint_0" type="fixed">
    <origin xyz="0 0 0" rpy="0 0 0" />
    <parent link="world" />
    <child link="base_link" />
  </joint>

  <link name="J1_link">
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://arm_description/meshes/J1_link.STL" />
      </geometry>
      <material name="">
        <color rgba="1 1 1 1" />
      </material>
    </visual>
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://arm_description/meshes/J1_link.STL" />
      </geometry>
    </collision>
    <inertial>
      <origin xyz="-2.92E-03 0.04E-03 -68.53E-03" rpy="0 0 0" />
      <mass value="8.62" />
      <inertia ixx="31417.22E-06"    ixy="-7.17E-06"    ixz="1741.59E-06"
                                     iyy="31776.39E-06" iyz="-13.11E-06"
                                                        izz="13349.46E-06" />
    </inertial>
  </link>

  <joint name="J1_joint" type="revolute">
    <origin xyz="0 0 0.141" rpy="0 0 0" />
    <parent link="base_link" />
    <child link="J1_link" />
    <axis xyz="0 0 1" />
    <limit lower="-3.1416" upper="3.1416" effort="200" velocity="6.1416" />
    <dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
    <safety_controller k_position="200.0" k_velocity="200.0" soft_lower_limit="-3.6" soft_upper_limit="3.6"/>
  </joint>

  <link name="J2_Link">
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://arm_description/meshes/J2_Link.STL" />
      </geometry>
      <material name="">
        <color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
      </material>
    </visual>
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://arm_description/meshes/J2_Link.STL" />
      </geometry>
    </collision>
    <inertial>
      <origin xyz="-200.85E-03 0 132.08E-03" rpy="0 0 0" />
      <mass value="14.09" />
      <inertia ixx="43424.6E-06"   ixy="-17.37E-06"       ixz="-52659.14E-06"
                                   iyy="1117037.51E-06"   iyz="-9.59E-06"
                                                          izz="1093506 ...
(more)
edit retag flag offensive close merge delete

Comments

Hi @mug, can you post the complete urdf file please

osilva gravatar image osilva  ( 2021-12-26 08:46:55 -0500 )edit

@osilva I just update the question and paste the urdf.

mug gravatar image mug  ( 2021-12-26 08:51:16 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-12-26 08:57:32 -0500

osilva gravatar image

updated 2021-12-26 09:25:44 -0500

Mike Scheutzow gravatar image

Thank you for adding urdf file.

For transmission tags replace <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> with <hardwareInterface>EffortJointInterface</hardwareInterface>

In the Transmission wiki: http://wiki.ros.org/urdf/XML/Transmis...

<hardwareInterface> (one or more occurrences)

Specifies a supported joint-space hardware interface. Note that the value of this tag should be EffortJointInterface when this transmission is loaded in Gazebo and hardware_interface/EffortJointInterface when this transmission is loaded in RobotHW.:

Also you check this tutorial: http://gazebosim.org/tutorials/?tut=r...

edit flag offensive delete link more

Comments

@osilva Thank you for the detailed answer. I replace <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> with <hardwareInterface>EffortJointInterface</hardwareInterface> but the same issue occurs. Because although hardware_interface/EffortJointInterface is an old usage, it can still be used, so the two description methods seem to be the same by now.

mug gravatar image mug  ( 2021-12-26 09:29:33 -0500 )edit

I think the problem is that you have not started a ros node to send commands to the joint (and without any input, a joint controlled by an EffortInterface probably just lets gravity do whatever it wants.) The modern way to run this ros node is to use a controller_manager from ros_control. Here is an example from the universal_robot repo file ur5.launch:

  <rosparam file="$(find ur_gazebo)/controller/arm_controller_ur5.yaml" command="load"/>
  <node name="arm_controller_spawner" pkg="controller_manager" type="controller_manager" args="spawn arm_controller" respawn="false" output="screen"/>

It may be easier for you to get things working with a Position Interface instead of an Effort Interface.

Mike Scheutzow gravatar image Mike Scheutzow  ( 2021-12-26 09:54:19 -0500 )edit

@Mike Scheutzow I just tried to start a controller_manager from ros_control (effort_controllers/JointTrajectoryController), but some of the joints start shaking once I launch the controller node.

mug gravatar image mug  ( 2021-12-26 10:03:32 -0500 )edit

That symptom is caused by many different config problems: remember that gazebo is doing a physics simulation. Just two possibilities: Your joints might not be strong enough to lift the weight of the arm, or one part of the arm might be colliding with something (possibly the ground or some other part of the arm.)

I will repeat: you are making it more difficult to debug by starting off with an Effort Interface.

Mike Scheutzow gravatar image Mike Scheutzow  ( 2021-12-26 10:18:53 -0500 )edit

@Mike Scheutzow Thanks for your suggestion. The reason I use EffortJointInterface is because I want to simulate the force of the joints. I don't know if PositionJointInterface can do this.

mug gravatar image mug  ( 2021-12-26 10:27:21 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-12-23 08:06:14 -0500

Seen: 553 times

Last updated: Dec 26 '21