Gazebo | Ignition | Community
Ask Your Question
0

"The minimum corner of the box must be less than or equal to maximum corner"' failed. SDF model

asked 2018-10-02 03:30:21 -0600

tristochief117 gravatar image

updated 2018-10-03 08:37:40 -0600

chapulina gravatar image

I am trying to import a simple pillow into Gazebo. I have 2 files: a pillow.world file which contains my pillow and the ground plane, and a pillow.sdf file which contains only my pillow collada mesh.

The model inside my world file is the exact same as the model inside my sdf file.

When I run in the terminal:

gazebo pillow.world

the pillow loads up successfully:

image description

yet when I run my sdf file by first running:

gazebo

then in a separate/new terminal, running:

gz model -f pillow.sdf -m my_mesh

The following error occurs:

enter code hereNode::Advertise(): Error advertising a topic. Did you forget to start the discovery service? 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. escalating to SIGKILL on server

here is my pillow.world file:

<?xml version="1.0"?>
<sdf version="1.4">
  <world name="default">
    <include>
      <uri>model://ground_plane</uri>
    </include>
    <include>
      <uri>model://sun</uri>
    </include>
    <model name="my_mesh">
      <pose>0 0 0.0  0 0 0</pose>
      <static>true</static>
      <link name="body">
        <inertial>
          <mass>1.0</mass>
          <inertia> <!-- inertias are tricky to compute -->
            <!-- http://gazebosim.org/tutorials?tut=inertia&cat=build_robot -->
            <ixx>0.00000</ixx>       <!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
            <ixy>000000</ixy>         <!-- for a box: ixy = 0 -->
            <ixz>0.000000</ixz>         <!-- for a box: ixz = 0 -->
            <iyy>0.000000</iyy>       <!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
            <iyz>0.000000</iyz>         <!-- for a box: iyz = 0 -->
            <izz>0.000000</izz>       <!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
          </inertia>
        </inertial>
        <collision name="collision">
          <geometry>
            <box>
              <size>1 1 1</size>
            </box>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <mesh><uri>file://my_mesh.dae</uri></mesh>
          </geometry>
        </visual>
      </link>
    </model>
  </world>
</sdf>

and here is my pillow.sdf file:

<?xml version='1.0'?>
<sdf version="1.4">
  <model name="my_mesh">
    <pose>0 0 0.5  0 0 0</pose>
    <static>true</static>
    <link name="body">
      <inertial>
        <mass>1.0</mass>
        <inertia> <!-- inertias are tricky to compute -->
          <!-- http://gazebosim.org/tutorials?tut=inertia&cat=build_robot -->
          <ixx>0.00000</ixx>       <!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
          <ixy>000000</ixy>         <!-- for a box: ixy = 0 -->
          <ixz>0.000000</ixz>         <!-- for a box: ixz = 0 -->
          <iyy>0.000000</iyy>       <!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
          <iyz>0.000000</iyz>         <!-- for a box: iyz = 0 -->
          <izz>0.000000</izz>       <!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
        </inertia>
      </inertial>
      <collision name="collision">
        <geometry>
          <box>
            <size>1 1 1</size>
          </box>
        </geometry>
      </collision>
      <visual name="visual">
        <geometry>
          <mesh><uri>file://my_mesh.dae</uri></mesh>
        </geometry>
      </visual>
    </link>
  </model>
</sdf>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-10-04 07:18:24 -0600

Duckfrost gravatar image

Hi,

I created a git with a spawining of your sdf through roslaunch and had no problems. I coulnt reproduce your issue. I leave here the code just in case its enough for what you need.

I firstly created a dae from a bledner file that I found in BLENDSWAP just because you didnt give any here at the time of writting this. Here I leave the original link , the dae file is in the repo:

Pillow Blender File

Here you have a modified version of your model.sdf, just made it non static and added some pose tags. I also made the collisions also the mesh.

model.sdf

simple_world.world

And I used for the spawning ROS to make it easier. I created a spawn_sdf launch file that basicaly spawns the model into the gazebo world, and a generic sdf spawner.

spawn_pillow.launch

spawn_sdf.launch

I also creted a ROSJECT, Repository and a VIDEO that explains the process. Hope its usefull

pillow spawned

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-10-02 03:30:21 -0600

Seen: 7,630 times

Last updated: Oct 04 '18