Gazebo | Ignition | Community
Ask Your Question
1

Collision links appear at absolute positions

asked 2012-11-26 10:36:34 -0500

updated 2012-11-27 03:25:18 -0500

Hi all,

When I spawn a custom table model somewhere in Gazebo, the table legs still appear around the absolute 0 position in a simulated laser scan (/base_laser). Why?

Running ROS Fuerte.

Gazebo gui, showing the relative position of the table:

Gazebo GUI screenshot

RViz Screenshot (notice the two table legs visible in laser scan; the other two are behind the robot) RViz screenshot

launch file:

<launch>
  <include file="$(find pr2_bringup_gazebo_demo)/launch/pr2_uncalibrated_empty_world.launch" />

  <param name="table_description"
     textfile="$(find race_gazebo_worlds)/models/race_table2.model" />
  <node name="spawn_table0" pkg="gazebo" type="spawn_model" args="-gazebo
     -param table_description -x -5.15 -y 3.56 -z 0.001 -Y 0.00
     -model race_table0" respawn="false" output="screen" />
</launch>

model file (race_gazebo_worlds/models/race_table2.model):

<gazebo version="1.0">
<model name="race_table2" static="true">
  <link name="surface">
    <inertial mass="15.0">
      <inertia ixx="0.2134666666666667" ixy="0" ixz="0"
               iyy="0.2666666666666667" iyz="0"
               izz="0.053466666666666676"/>
    </inertial>

    <collision name="collision">
      <origin pose="0 0 0.69 0 0 0"/>
      <geometry>
        <box size="1.6 0.8 0.04"/>
      </geometry>
    </collision>
    <visual name="visual">
      <origin pose="0 0 0.69 0 0 0"/>
      <geometry>
        <box size="1.6 0.8 0.04"/>
      </geometry>
      <material script="Gazebo/Wood"/>
    </visual>
  </link>

  <link name="front_left_leg">
    <collision name="collision">
      <origin pose="0.78 0.38 0.34 0 0 0"/>
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
    </collision>
    <visual name="visual">
      <origin pose="0.78 0.38 0.34 0 0 0"/>
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
      <material script="Gazebo/Grey"/>
    </visual>
  </link>

  <link name="front_right_leg">
    <collision name="collision">
      <origin pose="0.78 -0.38 0.34 0 0 0"/>
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
    </collision>
    <visual name="visual">
      <origin pose="0.78 -0.38 0.34 0 0 0"/>
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
      <material script="Gazebo/Grey"/>
    </visual>
  </link>

  <link name="back_right_leg">
    <collision name="collision">
      <origin pose="-0.78 -0.38 0.34 0 0 0"/>
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
    </collision>
    <visual name="visual">
      <origin pose="-0.78 -0.38 0.34 0 0 0"/>
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
      <material script="Gazebo/Grey"/>
    </visual>
  </link>

  <link name="back_left_leg">
    <collision name="collision">
      <origin pose="-0.78 0.38 0.34 0 0 0"/>
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
    </collision>
    <visual name="visual">
      <origin pose="-0.78 0.38 0.34 0 0 0"/>
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
      <material script="Gazebo/Grey"/>
    </visual>
  </link>
</model>
</gazebo>
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2012-11-27 05:22:22 -0500

I solved the problem myself. The problem was that the links were missing <origin> tags (only the collision and visual tags had origin tags, but not the links themselves). Here's the fixed model file (I also added joints and inertials for all links, but the problem addressed in my question was solved by adding the origin tags):

<gazebo version="1.0">
  <model name="race_table2" static="true">
  <link name="surface">
    <inertial mass="15.0">
      <inertia ixx="0.2134666666666667" ixy="0" ixz="0" iyy="0.2666666666666667" iyz="0" izz="0.053466666666666676"/>
    </inertial>
    <origin pose="0 0 0.69 0 0 0"/>

    <collision name="collision">
      <geometry>
        <box size="1.6 0.8 0.04"/>
      </geometry>
    </collision>
    <visual name="visual">
      <geometry>
        <box size="1.6 0.8 0.04"/>
      </geometry>
      <material script="Gazebo/Wood"/>
    </visual>
  </link>

  <joint name="front_left_leg_joint" type="revolute">
    <parent link="surface"/>
    <child link="front_left_leg"/>
    <axis xyz="0 0 1">
      <limit lower="0.0000" upper="0.0000"/>
    </axis>
  </joint>

  <link name="front_left_leg">
    <inertial mass="1.0">
      <inertia ixx="0.038633333" ixy="0" ixz="0" iyy="0.038633333" iyz="0" izz="0.0002"/>
    </inertial>
    <origin pose="0.78 0.38 0.34 0 0 0"/>
    <collision name="collision">
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
    </collision>
    <visual name="visual">
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
      <material script="Gazebo/Grey"/>
    </visual>
  </link>

  <joint name="front_right_leg_joint" type="revolute">
    <parent link="surface"/>
    <child link="front_right_leg"/>
    <axis xyz="0 0 1">
      <limit lower="0.0000" upper="0.0000"/>
    </axis>
  </joint>

  <link name="front_right_leg">
    <inertial mass="1.0">
      <inertia ixx="0.038633333" ixy="0" ixz="0" iyy="0.038633333" iyz="0" izz="0.0002"/>
    </inertial>
    <origin pose="0.78 -0.38 0.34 0 0 0"/>
    <collision name="collision">
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
    </collision>
    <visual name="visual">
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
      <material script="Gazebo/Grey"/>
    </visual>
  </link>

  <joint name="back_right_leg_joint" type="revolute">
    <parent link="surface"/>
    <child link="back_right_leg"/>
    <axis xyz="0 0 1">
      <limit lower="0.0000" upper="0.0000"/>
    </axis>
  </joint>

  <link name="back_right_leg">
    <inertial mass="1.0">
      <inertia ixx="0.038633333" ixy="0" ixz="0" iyy="0.038633333" iyz="0" izz="0.0002"/>
    </inertial>
    <origin pose="-0.78 -0.38 0.34 0 0 0"/>
    <collision name="collision">
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
    </collision>
    <visual name="visual">
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
      <material script="Gazebo/Grey"/>
    </visual>
  </link>

  <joint name="back_left_leg_joint" type="revolute">
    <parent link="surface"/>
    <child link="back_left_leg"/>
    <axis xyz="0 0 1">
      <limit lower="0.0000" upper="0.0000"/>
    </axis>
  </joint>

  <link name="back_left_leg">
    <inertial mass="1.0">
      <inertia ixx="0.038633333" ixy="0" ixz="0" iyy="0.038633333" iyz="0" izz="0.0002"/>
    </inertial>
    <origin pose="-0.78 0.38 0.34 0 0 0"/>
    <collision name="collision">
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
    </collision>
    <visual name="visual">
      <geometry>
        <cylinder radius="0.02" length="0.68"/>
      </geometry>
      <material script="Gazebo/Grey"/>
    </visual>
  </link>
</model>
</gazebo>
edit flag offensive delete link more

Comments

1

You should mark this answer as correct if this answer has proven itself. (only moderator or original questioner can mark correct)

dcconner gravatar imagedcconner ( 2012-12-01 21:13:03 -0500 )edit

I can't accept my own question as correct, because it requires a minimum of 50 points. So we will have to wait for a moderator to do that.

Martin Günther gravatar imageMartin Günther ( 2012-12-09 04:11:15 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-11-26 10:36:34 -0500

Seen: 730 times

Last updated: Nov 27 '12