ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
There are some errors in your xml,
box size is negative
<box size="-4.8 3 0.1" />
one of the origin tag missing one element
<origin xyz="2.45 0.75"/>
the links are not static, so once the simulation is unpaused, the links flies off. But you can fix this by adding a static tag. See working model below:
<robot name="my_robot">
<link name="base_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="100.0"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0"/>
</inertial>
<visual>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<geometry>
<box size="4.8 3 0.1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<geometry>
<box size="4.8 3 0.1"/>
</geometry>
</collision>
</link>
<link name="child_link">
<inertial>
<origin xyz="2.45 0 0.75"/>
<mass value="10.0"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0"/>
</inertial>
<visual>
<geometry>
<box size="0.1 3 1.5"/>
</geometry>
<origin xyz="2.45 0 0.75"/>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="2.45 0 0.75"/>
<geometry>
<box size="0.1 3 1.5"/>
</geometry>
</collision>
</link>
<joint name="base_link_to_child_link" type="continuous"> <parent link="base_link"/> <child link="child_link"/> <axis xyz="0 1 0"/> <calibration rising="0.0"/> </joint>
<gazebo> <static>true</static> </gazebo> <gazebo reference="child_link"> <turngravityoff>true</turngravityoff> </gazebo> <gazebo reference="base_link"> <turngravityoff>true</turngravityoff> </gazebo> </robot>
2 | No.2 Revision |
There are some errors in your xml,
box size is negative
<box size="-4.8 3 0.1" />
one of the origin tag missing one element
<origin xyz="2.45 0.75"/>
the links are not static, so once the simulation is unpaused, the links flies off. But you can fix this by adding a static tag. See working model below:
<?xml version="1.0"?>
<robot name="my_robot"> name="my_robot">
<link name="base_link">
<inertial>
name="base_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
0" />
<mass value="100.0"/>
value="100.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0"/>
</inertial> izz="1.0" />
</inertial>
<visual>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
0" />
<geometry>
<box size="4.8 3 0.1"/>
0.1" />
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual> <collision>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
0" />
<geometry>
<box size="4.8 3 0.1"/>
0.1" />
</geometry>
</collision>
</link> <link name="child_link"> name="child_link">
<inertial>
<origin xyz="2.45 0 0.75"/> 0.75" />
<mass value="10.0"/>
value="10.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0"/> izz="1.0" />
</inertial> <visual>
<geometry>
<box size="0.1 3 1.5"/>
</geometry>
<origin xyz="2.45 0 0.75"/>
0.75" />
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual> <collision>
<origin xyz="2.45 0 0.75"/>
0.75" />
<geometry>
<box size="0.1 3 1.5"/>
1.5" />
</geometry>
</collision>
</link> <joint name="base_link_to_child_link" type="continuous">
<parent link="base_link"/> link="base_link" />
<child link="child_link"/> link="child_link" />
<axis xyz="0 1 0"/>
0" />
<calibration rising="0.0"/> rising="0.0" />
</joint> <gazebo>
<static>true</static>
</gazebo>
<gazebo reference="child_link">
<turngravityoff>true</turngravityoff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<gazebo reference="base_link">
<turngravityoff>true</turngravityoff>
<turnGravityOff>true</turnGravityOff>
</gazebo>
</robot> </robot>