Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Using roslaunch to start Gazebo, I got core dump error.

Using roslaunch to start Gazebo, I got below error and no showing model..

gzclient: /build/ogre-1.9-B6QkmW/ogre-1.9-1.9.0+dfsg1/OgreMain/include/OgreAxisAlignedBox.h:252: void Ogre::AxisAlignedBox::setExtents(const Ogre::Vector3&, const Ogre::Vector3&): Assertion `(min.x <= max.x && min.y <= max.y && min.z <= max.z) && "The minimum corner of the box must be less than or equal to maximum corner"' failed.Aborted (core dumped)

How to solve it? and what is the problem? If anyone knows how to solve the problem, please reply...

My xacro file.

<?xml version="1.0" encoding="utf-8" ?>
<robot name="robot">
<material name="grey">
        <color rgba="0.2 0.2 0.2 1.0" />
</material>
<!--======================= Links =========================-->
<!-- Body Base -->
<link name="Body_Base">
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 0" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_1_base.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 0" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_1_base.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>

    <inertial>
        <mass value="1" />
        <inertia ixx="0.1" iyy="0.1" izz="0.1" ixy="0.0" ixz="0.0" iyz="0.0" />
    </inertial>

</link>
<!-- Body Module 1 -->
<link name="Body_Module_1">
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 0" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_2_module_1.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 0" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_2_module_1.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>

    <inertial>
        <mass value="1" />
        <inertia ixx="0.1" iyy="0.1" izz="0.1" ixy="0.0" ixz="0.0" iyz="0.0" />
    </inertial>

</link>
<!-- Body Module 2 -->
<link name="Body_Module_2">
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 -0.1" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_3_module_2.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 -0.1" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_4_pipe_1.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 -0.1" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_5_module_3.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 -0.1" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_3_module_2.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 -0.1" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_4_pipe_1.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 -0.1" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_5_module_3.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>

    <inertial>
        <mass value="1" />
        <inertia ixx="0.1" iyy="0.1" izz="0.1" ixy="0.0" ixz="0.0" iyz="0.0" />
    </inertial>

</link>
<!-- Body Module 3 -->
<link name="Body_Module_3">
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 -0.5" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_6_module_dummy.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 -0.5" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_7_pipe_2.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 -0.5" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_8_module_4.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 -0.5" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_6_module_dummy.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 -0.5" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_7_pipe_2.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 -0.5" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_8_module_4.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>

    <inertial>
        <mass value="1" />
        <inertia ixx="0.1" iyy="0.1" izz="0.1" ixy="0.0" ixz="0.0" iyz="0.0" />
    </inertial>

</link>
<!-- Body Module 4 -->
<link name="Body_Module_4">
    <visual>
        <origin rpy="0 0 -1" xyz="0 0 -0.9" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_9_module_5.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0 -0.9" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_9_module_5.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>

    <inertial>
        <mass value="1" />
        <inertia ixx="0.1" iyy="0.1" izz="0.1" ixy="0.0" ixz="0.0" iyz="0.0" />
    </inertial>

</link>
<!-- Body Module 5 -->
<link name="Body_Module_5">
    <visual>
        <origin rpy="0 0 -1" xyz="0 0.1 -0.9" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_10_module_6.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0.1 -0.9" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_10_module_6.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>

    <inertial>
        <mass value="1" />
        <inertia ixx="0.1" iyy="0.1" izz="0.1" ixy="0.0" ixz="0.0" iyz="0.0" />
    </inertial>

</link>
<!-- Body Tool Flange -->
<link name="Body_Tool_Flange">
    <visual>
        <origin rpy="0 0 -1" xyz="0 0.1 -1" />
        <geometry>
            <mesh filename="package://rb_description/meshes/visual/_11_tool_flange.dae" />
        </geometry>
        <material name="grey" />
    </visual>
    <collision>
        <origin rpy="0 0 -1" xyz="0 0.1 -1" />
        <geometry>
            <mesh filename="package://rb_description/meshes/collision/_11_tool_flange.stl" scale="0.001 0.001 0.001" />
        </geometry>
    </collision>

    <inertial>
        <mass value="1" />
        <inertia ixx="0.1" iyy="0.1" izz="0.1" ixy="0.0" ixz="0.0" iyz="0.0" />
    </inertial>

</link>
<link name="Tool_Center_Point">
    <visual>
        <origin rpy="0 0 0" xyz="0.1 0 -1" />
        <geometry>
            <box size="0.001 0.001 0.001" />
        </geometry>
        <material name="grey" />
    </visual>
</link>
<!--======================= Joints =========================-->
<link name="world" />
<joint name="world_fixed" type="fixed">
    <parent link="world" />
    <child link="Body_Base" />
    <origin rpy="0 0 0" xyz="0 0 0" />
</joint>
<joint name="base" type="revolute">
    <parent link="Body_Base" />
    <child link="Body_Module_1" />
    <origin rpy="0 0 0" xyz="0 0 0" />
    <axis xyz="0 0 1" />
    <limit effort="10.0" lower="-6" upper="6" velocity="2.5" />
</joint>
<joint name="shoulder" type="revolute">
    <parent link="Body_Module_1" />
    <child link="Body_Module_2" />
    <origin rpy="0 0 0" xyz="0 0 0.1" />
    <axis xyz="0 1 0" />
    <limit effort="10.0" lower="-6" upper="6" velocity="2.5" />
</joint>
<joint name="elbow" type="revolute">
    <parent link="Body_Module_2" />
    <child link="Body_Module_3" />
    <origin rpy="0 0 0" xyz="0 0 0.4" />
    <axis xyz="0 1 0" />
    <limit effort="10.0" lower="-2" upper="2" velocity="2.5" />
</joint>
<joint name="wrist1" type="revolute">
    <parent link="Body_Module_3" />
    <child link="Body_Module_4" />
    <origin rpy="0 0 0" xyz="0 0 0.392" />
    <axis xyz="0 1 0" />
    <limit effort="10.0" lower="-6" upper="6" velocity="2.5" />
</joint>
<joint name="wrist2" type="revolute">
    <parent link="Body_Module_4" />
    <child link="Body_Module_5" />
    <origin rpy="0 0 0" xyz="0 -0.1 0" />
    <axis xyz="0 0 1" />
    <limit effort="10.0" lower="-6" upper="6" velocity="2.5" />
</joint>
<joint name="wrist3" type="revolute">
    <parent link="Body_Module_5" />
    <child link="Body_Tool_Flange" />
    <origin rpy="0 0 0" xyz="0 0 0.1" />
    <axis xyz="0 1 0" />
    <limit effort="10.0" lower="-6" upper="6" velocity="2.5" />
</joint>
<joint name="Tool_Flange" type="fixed">
    <parent link="Body_Tool_Flange" />
    <child link="Tool_Center_Point" />
    <origin rpy="0 0 0" xyz="0 -0.09 0" />
    <axis xyz="0 0 0" />
</joint>

</robot> image description