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

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

asked 2013-11-18 01:48:07 -0500

lucasw gravatar image

updated 2020-11-21 11:19:40 -0500

I'm following http://gazebosim.org/wiki/Tutorials/1.9/ROS_Control_with_Gazebo to create my own project and getting this error:

[ERROR] [1384781890.186377319, 0.001000000]: This robot has a joint named "joint_seg_1" which is not in the gazebo model.
[FATAL] [1384781890.186620755, 0.001000000]: Could not initialize robot simulation interface

From the project I've created at https://github.com/lucasw/testbot ( current commit is 0f96ef7fcc8e31ff1bf1883dc10bc32ec440d8f1 )

I think there is something wrong with my joint or transmission, but I'm not seeing it:

<joint name="joint_seg_1" type="revolute">
    <parent link="base_link"/>
    <child link="link_1"/>
    <origin rpy="0 0 0" xyz="0.2 0 0"/>
    <axis xyz="0 0 1"/>
    <limit effort="1000.0" lower="-0.5" upper="0.5" velocity="0.5"/>
    <dynamics damping="0.5"/>
  </joint>
  <transmission name="tran_joint_seg_1">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="joint_seg_1"/>
    <actuator name="motor_seg_1">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

The only google hit was the code that outputs the error The code producing the error is https://github.com/pal-robotics/ros_control_gazebo/blob/master/ros_control_gazebo_tests/src/robot_sim_rr.cpp

edit retag flag offensive close merge delete

5 Answers

Sort by ยป oldest newest most voted
8

answered 2013-11-19 02:58:33 -0500

lucasw gravatar image

I think the problem was that the joint_seg_1 was attached to a link with no physical properties, once I created an extra link below base_link (which as the root is not allowed to have physical properties) the error went away:

<link name="head">
    <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <mesh filename="package://testbot_description/meshes/cylinder.dae" scale="${seg_length/3} ${seg_length/6} ${seg_length/3}" />
        </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <cylinder length="${seg_length/6}" radius="${seg_length/3}" />
      </geometry>
    </collision>

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

</link>

  <joint name="joint_base_head" type="fixed">
        <parent link="base_link" />
        <child link="head" />
        <origin xyz="0 0 0" rpy="0 0 0" />
        <axis xyz="0 0 1" />
  </joint>

<xacro:segment parent="head" postfix="1" length="${seg_length}" width="${seg_width}" height="${seg_height}" />

https://github.com/lucasw/testbot/commit/a883039bcd4d56917bb3e5da89797e48373e1685

edit flag offensive delete link more

Comments

4

I had the same problem, but it's unclear from your terminology, and it took me a while to understand what you discovered, but incase anyone else was wondering, it's because you were missing the <inertial> tag. And just using an <inertia> tag, which is apparently very different, won't work either.

Cerin gravatar image Cerin  ( 2015-05-02 13:21:58 -0500 )edit

The problem occured to me because i used "planar" as a joint type. Gazebo does apparently not support that.

Panda1638 gravatar image Panda1638  ( 2017-08-24 08:09:04 -0500 )edit

I had the same issue when I generated urdf file for gazebo using MoveIt. It indeed skipped to automatically insert the <inertial> tag for one of the joints and was causing the error.

jaiswalharsh gravatar image jaiswalharsh  ( 2023-02-02 06:24:56 -0500 )edit
0

answered 2021-07-20 20:32:20 -0500

Yokai- gravatar image

I found this error because of changing a joint name. I have changed the name in all the files but still, the error persists.

edit flag offensive delete link more

Comments

Is this an answer, comment, or question?

jayess gravatar image jayess  ( 2021-07-22 17:52:19 -0500 )edit
0

answered 2020-08-19 22:10:59 -0500

omkar_a_k gravatar image

I too had run into this kind of problem. In my case, the error I made was that the joint was just at the edge of the parent link. If the joint is fixed it doesn't give any error but for any other type, it gives error as there is no physical material for the joint to pass-through as the joint is just at the edge of the links. Creating an intersection region for the joint between the links fixed the error for me.

edit flag offensive delete link more
0

answered 2013-11-27 10:52:14 -0500

JoeRomano gravatar image

same problem here, except the child had no physical properties and had to be filled in. too bad no related errror is thrown.

thanks for posting the hint

edit flag offensive delete link more
0

answered 2015-01-13 19:42:40 -0500

DevonW gravatar image

Just ran into this error myself. Will see if implementing <inertial> <origin xyz="0 0 0" rpy="0 0 0"/> <mass value="1"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/> </inertial>

into the block fixes the error.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2013-11-18 01:48:07 -0500

Seen: 10,350 times

Last updated: Jul 20 '21