Joint pose ignored when loading URDF in Gazebo 1.9.5
Hi everybody!
As I am migrating custom models (as URDF) from Gazebo 1.9.2 to 1.9.5 (I realize I am behind the times a bit, but due to project restrictions - we had decided to stick to Version 1.9 between multiple partners), I have encountered issues where all the links are placed at the origin of the parent.
I tried creating a simple new model file to debug, with just two links and a joint between them, and I noticed that the joint offsets are not taken into account anymore.
Further, no matter where I spawn the model using gzclient, it appears at the origin of the world.
As you can see in the picture below (taken just before I spawn the model) both links are in the expected position in the model preview.
However, when the model is spawned the link position changes relative to its parent (moved to the origin of the parent), and the model is not spawned where I expected.
The URDF code is as follows:
<robot name="scout">
<!-- LINKS -->
<link name='chassis_front'>
<inertial>
<origin xyz="-0.18 0 0" rpy="0 0 0" />
<!-- inertia calculated as per moments of inertia for a cuboid, based on simple collision frame -->
<inertia
ixx="0.06" ixy="0.0" ixz="0"
iyy="0.242" iyz="0.0"
izz="0.286"
/>
<mass value="10.0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh
filename="model://scout/meshes/ChassisFront_Combined.dae"
scale="1 1 1"
/>
</geometry>
</visual>
<collision>
<origin xyz="-0.23 0 0.06" rpy="0 0 0" />
<geometry>
<box size="0.57 0.43 0.12" />
</geometry>
</collision>
</link>
<link name='chassis_back'>
<inertial>
<inertia
ixx="0.0" ixy="0" ixz="0"
iyy="0.0" iyz="0"
izz="0.0"
/>
<mass value="0.01" />
</inertial>
<visual>
<geometry>
<mesh
filename="model://scout/meshes/ChassisBack.dae"
scale="1 1 1"
/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.09 0.42 0.09" />
</geometry>
</collision>
</link>
<!-- JOINTS -->
<joint name="chassis_front_back_hinge" type="continuous">
<origin xyz="-0.581 0 0.01331" rpy="0 0 0" />
<parent link="chassis_front" />
<child link="chassis_back" />
<axis xyz="1 0 0" />
- <limit velocity="100" effort="1000"/> </joint>
<gazebo>
<static>false</static>
</gazebo>
</robot>
Any ideas how to fix this or get around it?
Thanks!
Yasho
Spawning the model on a computer with Gazebo 1.9.2 (built from source) works fine - I am not sure which version of sdformat is used here. I compared the outputs of gzsdf print on this machine with that of the machine with the Gazebo 1.9.5 (installed from binaries) and they are identical.
Also, I can move the links (not directly as urdf does not support a pose element) by adding an origin to the visual, inertial and collision blocks, but the joint remains at the origin of the parent - which is a problem for me!
Also, I can move the links (not directly as urdf does not support a pose element) by adding an origin to the visual, inertial and collision blocks, but the joint remains at the origin of the parent - which is a problem for me!
hey! I have exactly the same problem. Did you solve it?