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

This robot has a joint named "joint_1" which is not in the gazebo model.

asked 2016-07-06 10:38:26 -0500

Oguz gravatar image

updated 2016-07-06 10:49:22 -0500

Hello. There is also a topic "This robot has a joint named "foo" which is not in the gazebo model."link But it didn't help. I get the following error;

[ERROR] [1467817563.508002714, 0.339000000]: This robot has a joint named "joint_1" which is not in the gazebo model.
[FATAL] [1467817563.508348807, 0.339000000]: Could not initialize robot simulation interface

My corresponding URDF file part is;

<robot name="itecharm">

  <link name="world"/>

  <joint name="fixed" type="fixed">
    <parent link="world"/>
    <child link="link_base"/>
  </joint>


  <link name="link_base">
    <inertial>
      <origin xyz="-0.0325856 5.11013e-06 0" rpy="0 0 0"/>
      <mass value="1.26763"/>
      <inertia ixx="0.00165595" ixy="-8.29854e-06" ixz="-3.99028e-11" iyy="0.00129758" iyz="1.56383e-07" izz="0.00130449"/>
    </inertial>
    <visual>
      <origin xyz="-0.0742893 -0.0873818 0.0157596" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://itecharm_description/meshes/link_base.STL"/>
      </geometry>
      <material name="link_base_color">
        <color rgba="0.792157 0.819608 0.933333 1.0"/>
      </material>
    </visual>
    <collision>
      <origin xyz="-0.0742893 -0.0873818 0.0157596" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://itecharm_description/meshes/link_base.STL"/>
      </geometry>
    </collision>
  </link>
  <link name="link_1">
    <inertial>
      <origin xyz="0.137802209307 0.090396 0.0227196811405" rpy="0 0 0"/>
      <mass value="0.0"/>
      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
    </inertial>
    <visual>
      <origin xyz="0.137802209307 0.090396 0.0227196811405" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://itecharm_description/meshes/link_1.STL" />
      </geometry>
      <material name="link_1_color">
        <color rgba="0.792157 0.819608 0.933333 1.0"/>
      </material>
    </visual>
    <collision>
      <origin xyz="0.137802209307 0.090396 0.0227196811405" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://itecharm_description/meshes/link_1.STL" />
      </geometry>
    </collision>
  </link>
  <joint name="joint_1" type="revolute">
    <origin xyz="-0.0688 0 0" rpy="0 0.261799319827 1.57079632679"/>
    <axis xyz="-2.22044604925e-16 1.0 0.0"/>
    <parent link="link_base"/>
    <child link="link_1"/>
    <limit effort="50000" lower="-3.14159265359" upper="3.14159265359" velocity="50000"/>
    <dynamics damping="0.1"/>
  </joint>

Also, the transmission part of the URDF;

<gazebo>
    <plugin name="ros_control" filename="libgazebo_ros_control.so">
      <robotNamespace>/itecharm</robotNamespace>
      <!--<robotSimType>ros_control/DefaultRobotHWSim</robotSimType>-->
    </plugin>
  </gazebo>

 <transmission name="trans_1">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="joint_1">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="joint_servo_1">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>100</mechanicalReduction>
    </actuator>
  </transmission>

I have another URDF file for a simple two R robot that works. I couldn't figure out why this doesn't. I spawned the robot in Rviz and checked the joints without any problem. I am using ROS-Indigo

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
5

answered 2016-07-06 17:21:11 -0500

Oguz gravatar image

After changing the

   <inertial>
      <origin xyz="0.137802209307 0.090396 0.0227196811405" rpy="0 0 0"/>
      <mass value="0.0"/>
      <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
    </inertial>

part, giving random values to mass and inertia, the problem is gone.

edit flag offensive delete link more

Comments

Also, Gazebo will round sufficiently small numbers to 0, so you may encounter this problem even with a nonzero mass/inertia.

Andrew Price gravatar image Andrew Price  ( 2018-03-17 18:23:38 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-07-06 10:38:26 -0500

Seen: 4,473 times

Last updated: Jul 06 '16