Home | Tutorials | Wiki | Issues
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Your robot model consists of 3 parts.

  • visual (used by rendering library to visualize the robot)
  • collision (used by physics engine to check contacts between objects in the world)
  • inertial (used by physics engine to compute all the physics of the simulation)

If I remember correctly, for SDF file is collision part the base (but rather try it yourself). And you can position the visual and inertial parts with respect to the center of the collision geometry.

So lets say you have a wheeled robot. For the collision geometry you use simple primitive cylinder, because that makes the computation faster. For the visuals you have generated nice mesh geometry of the wheels, but you have centered it poorly. The center of the mesh is 1 cm away from the wheel center in the x axis. And now if you put the visual mesh without any pose adjustment into the model, it is shifted away from the place you want it to have. It sticks out of the robot. It doesn't have any effect on the simulation, because the collision geometry is positioned correctly (if you switch on the visualization of collisions on, you will see the collision cylinder and the wheel mesh 1cm shifted from each other). So you can just specify the pose of the visual geometry as <pose frame=''>-0.01 0 0 0 -0 0</pose> and the visuals will align.

Your robot model consists of 3 parts.

  • visual (used by rendering library to visualize the robot)
  • collision (used by physics engine to check contacts between objects in the world)
  • inertial (used by physics engine to compute all the physics of the simulation)

If I remember correctly, for SDF file is collision part the base (but rather try it yourself). And you can position the visual and inertial parts with respect to the center of the collision geometry.

So lets say you have a wheeled robot. For the collision geometry of a wheel you use simple primitive cylinder, because that makes the computation faster. For the visuals you have generated nice mesh geometry of the wheels, but you have centered it poorly. The center of the mesh is 1 cm away from the wheel center in the x axis. And now if you put the visual mesh without any pose adjustment into the model, it is shifted away from the place you want it to have. It sticks out of the robot. It doesn't have any effect on the simulation, because the collision geometry is positioned correctly (if you switch on the visualization of collisions on, you will see the collision cylinder and the wheel mesh 1cm shifted from each other). So you can just specify the pose of the visual geometry as <pose frame=''>-0.01 0 0 0 -0 0</pose> and the visuals will align.

Your robot model consists of 3 parts.

  • visual (used by rendering library to visualize the robot)
  • collision (used by physics engine to check contacts between objects in the world)
  • inertial (used by physics engine to compute all the physics of the simulation)

If I remember correctly, for SDF file is collision part the base (but rather try it yourself). And you can position the visual and inertial parts with respect to the center of the collision geometry.

So lets say you have a wheeled robot. For the collision geometry of a wheel you use simple primitive cylinder, because that makes the computation faster. For the visuals you have generated nice mesh geometry of the wheels, but you have centered it poorly. The center of the mesh is 1 cm away from the wheel center in the x axis. And now if you put the visual mesh without any pose adjustment into the model, it is shifted away from the place you want it to have. be. It sticks out of the robot. It doesn't have any effect on the simulation, because the collision geometry is positioned correctly (if you switch on the visualization of collisions on, you will see the collision cylinder and the wheel mesh 1cm shifted from each other). So you can just specify the pose of the visual geometry as <pose frame=''>-0.01 0 0 0 -0 0</pose> and the visuals will align.

Your robot model consists of 3 parts.

  • visual (used by rendering library to visualize the robot)
  • collision (used by physics engine to check contacts between objects in the world)
  • inertial (used by physics engine to compute all the physics of the simulation)

If I remember correctly, for SDF file is collision part the base (but rather try it yourself). And you can position the visual and inertial parts with respect to the center of the collision geometry.

So lets say you have a wheeled robot. For the collision geometry of a wheel you use simple primitive cylinder, because that makes the computation faster. For the visuals you have generated nice mesh geometry of the wheels, but you have centered it poorly. The center of the mesh is 1 cm away from the wheel center in the x axis. And now if you put the visual mesh without any pose adjustment into the model, it is shifted away from the place you want it to be. It sticks out of the robot. It doesn't have any effect on the simulation, because the collision geometry is positioned correctly (if you switch on the visualization of collisions on, you will see the collision cylinder and the wheel mesh 1cm shifted from each other). So you can just specify the pose of the visual geometry as <pose frame=''>-0.01 0 0 0 -0 0</pose> and the visuals will align.

Your robot model consists of 3 parts.

  • visual (used by rendering library to visualize the robot)
  • collision (used by physics engine to check contacts between objects in the world)
  • inertial (used by physics engine to compute all the physics of the simulation)

If I remember correctly, for SDF file is collision part the base (but rather try it yourself). And you can position the visual and inertial parts with respect to the center of the collision geometry.

So lets say you have a wheeled robot. For the collision geometry of a wheel you use simple primitive cylinder, because that makes the computation faster. For the visuals you have generated nice mesh geometry of the wheels, but you have centered it poorly. The center of the mesh is 1 cm away from the wheel center in the x axis. And now if you put the visual mesh without any pose adjustment into the model, it is shifted away from the place you want it to be. It sticks out of the robot. It doesn't have any effect on the simulation, because the collision geometry is positioned correctly (if you switch the visualization of collisions on, you will see the collision cylinder and the wheel mesh 1cm shifted from each other). So you can just specify the pose of the visual geometry as <pose frame=''>-0.01 0 0 0 -0 0</pose> and the visuals will align.


EDIT

I will show you on an example how SDF works.

Here is an SDF file:

<?xml version='1.0'?>
<sdf version='1.6'>
  <model name='test'>
    <link name='link1'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <mass>0.10669</mass>
        <inertia>
          <ixx>0.00676935</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.00676935</iyy>
          <iyz>0</iyz>
          <izz>0.0133363</izz>
        </inertia>
        <pose frame=''>0 0 0 0 -0 0</pose>
      </inertial>

      <visual name='visual'>
        <geometry>
          <cylinder>
            <radius>0.5</radius>
            <length>0.10669</length>
          </cylinder>
        </geometry>
        <pose frame=''>0 0 0 0 -0 0</pose>
      </visual>

      <collision name='collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <radius>0.5</radius>
            <length>0.10669</length>
          </cylinder>
        </geometry>
      </collision>
    </link>


    <link name='link2'>
      <pose frame=''>0.0 0.0 0.40 0 0 0</pose>
      <inertial>
        <mass>0.10669</mass>
        <inertia>
          <ixx>0.00676935</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.00676935</iyy>
          <iyz>0</iyz>
          <izz>0.0133363</izz>
        </inertia>
        <pose frame=''>0 0 0 0 -0 0</pose>
      </inertial>

      <visual name='visual'>
        <geometry>
          <cylinder>
            <radius>0.5</radius>
            <length>0.10669</length>
          </cylinder>
        </geometry>
        <pose frame=''>0 0 0 0 -0 0</pose>
      </visual>

      <collision name='collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <radius>0.5</radius>
            <length>0.10669</length>
          </cylinder>
        </geometry>
      </collision>
    </link>

    <joint name='joint0' type='fixed'>
      <parent>link1</parent>
      <child>link2</child>
      <pose frame=''>0 0 0 0 -0 0</pose>
    </joint>

  </model>
</sdf>

It has two links and a fixed joint between them. Notice, that the individual parts of both links have pose of 0. This means, they are not shifted from the center. The center is given by the global pose of the link (the pose specified between <link> tags). You can see the link1 has the global pose 0, that means it is positioned exactly at the center of map. The link2 has its global pose 40 cm above ground. This is what it looks like with both collision geometry and inertial visible:

image description

Now say we put an offset to the visual part of the link1model, shift it 20 cm in x axis.

<link name='link1'>
  <pose frame=''>0 0 0 0 -0 0</pose>
  <inertial>
    <mass>0.10669</mass>
    <inertia>
      <ixx>0.00676935</ixx>
      <ixy>0</ixy>
      <ixz>0</ixz>
      <iyy>0.00676935</iyy>
      <iyz>0</iyz>
      <izz>0.0133363</izz>
    </inertia>
    <pose frame=''>0 0 0 0 -0 0</pose>
  </inertial>

  <visual name='visual'>
    <geometry>
      <cylinder>
        <radius>0.5</radius>
        <length>0.10669</length>
      </cylinder>
    </geometry>
    <pose frame=''>0.20 0 0 0 -0 0</pose>
  </visual>

  <collision name='collision'>
    <pose frame=''>0 0 0 0 -0 0</pose>
    <geometry>
      <cylinder>
        <radius>0.5</radius>
        <length>0.10669</length>
      </cylinder>
    </geometry>
  </collision>
</link>

image description

At this point nothing has change for the simulation. Gazebo only renders the visuals of the link1 20 cm away from the center of the map. If there was a robot running throught the visual geometry of the link1, it would not collide with it. It would go right through. Now let's shift the collision part of link1 30 cm in x axis.

<link name='link1'>
  <pose frame=''>0 0 0 0 -0 0</pose>
  <inertial>
    <mass>0.10669</mass>
    <inertia>
      <ixx>0.00676935</ixx>
      <ixy>0</ixy>
      <ixz>0</ixz>
      <iyy>0.00676935</iyy>
      <iyz>0</iyz>
      <izz>0.0133363</izz>
    </inertia>
    <pose frame=''>0 0 0 0 -0 0</pose>
  </inertial>

  <visual name='visual'>
    <geometry>
      <cylinder>
        <radius>0.5</radius>
        <length>0.10669</length>
      </cylinder>
    </geometry>
    <pose frame=''>0.2 0 0 0 -0 0</pose>
  </visual>

  <collision name='collision'>
    <pose frame=''>0.3 0 0 0 -0 0</pose>
    <geometry>
      <cylinder>
        <radius>0.5</radius>
        <length>0.10669</length>
      </cylinder>
    </geometry>
  </collision>
</link>

image description

So it's apparent, that the individual parts of the model's link are not positioned with respect to collision geometry, but with respect to the global pose of the link, which is defined between <link> tags.

Now the joint is automatically positioned at the center of the child link. Imagine this is a revolute joint. In this case the link2 would rotate around its own center. If we now also shift the joint 30 cm in x axis, the link2 would rotate (if it was a revolute joint) around this axis, so it would make those circles with the radius of 30 cm.

<joint name='joint0' type='revolute'>
  <parent>link1</parent>
  <child>link2</child>
  <pose frame=''>0.3 0 0 0 -0 0</pose>
</joint>

image description

I encourage you to try try it yourself. The personal experience beats any explanations.