Trying to connect nested models with a revolute joint
Hello, everyone!
I've been using Gazebo Fortress to simulate an steered omnidirectional robot and for that I created two files. One, let's call robot.sdf, has the chassis of the robot and the other, let's call wheel.sdf, has the wheel and a steer mechanism.
Since the robot has four steered wheels I included the wheel.sdf file in the robot.sdf file and tried to create a joint between them, but it doesn't work for some reason. It loads the chassis and the wheels and it is in the correct position, but the joint frame isn't there.
Here is the robot.sdf file:
<model name='robot' canonical_link='chassis'>
<self_colide>true</self_colide>
<link name='chassis'>
<visual name='visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.4 0.3 0.04</size>
</box>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
<frame name='FR_mount'>
<pose relative_to="chassis">0.14 -0.166 -0.043 0 0 3.1415</pose>
</frame>
<include>
<name>front_right_motor</name>
<placement_frame>motor_mount</placement_frame>
<pose relative_to='FR_mount'/>
<uri>include://models/steer_wheel</uri>
</include>
<joint name='FR_motor_joint' type='revolute'>
<parent>FR_mount</parent>
<child>front_right_motor::motor_mount</child>
<axis>
<xyz expressed_in='__model__'>0 0 1</xyz>
</axis>
<limit>
<lower>-1.5708</lower>
<upper>1.5708</upper>
</limit>
</joint>
</model>
</sdf>
And here is the wheel.sdf file:
<model name="steer_wheel" canonical_link="motor">
<frame name='motor_mount'/>
<link name='motor'>
<visual name='visual'>
<geometry>
<box>
<size>0.04 0.04 0.1</size>
</box>
</geometry>
<material>
<ambient>0.1 0.1 0.1 1</ambient>
<diffuse>0.1 0.1 0.1 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
</material>
</visual>
</link>
<link name="wheel">
<pose relative_to="motor">0 -0.03 -0.03 1.5808 0 0</pose>
<visual name='visual'>
<geometry>
<cylinder>
<radius>0.04</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<ambient>0.9 0.8 0.2 1</ambient>
<diffuse>0.9 0.8 0.2 1</diffuse>
<specular>0.9 0.8 0.2 1</specular>
</material>
</visual>
</link>
<joint name='wheel_joint' type='revolute'>
<pose relative_to='wheel'/>
<parent>motor</parent>
<child>wheel</child>
<axis>
<xyz expressed_in='__model__'>0 1 0</xyz>
</axis>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</joint>
</model>
Do you get any errors running
ign sdf -k path/to/robot.sdf
?I was getting an weird error, it wasn't locating the file URI, but in the world.sdf file that included robot.sdf was returning valid. I debugged the problem, for that I used
export SDF_PATH=path/to/project/folder
now both are valid but still no joint frame. I even checked usingign sdf -p path/to/robot.sdf
and the wheel block is correct, yet it isn't working.PS.: Also tried GAZEBO_RESOURSE_PATH and IGN_GAZEBO_RESOURSE_PATH but only SDF_PATH worked.