Skip to content

rviz RobotModel broken in melodic: <visual><origin> not used  #1249

Closed
@andreasBihlmaier

Description

@andreasBihlmaier

The following two pictures will likely tell the whole story:
Kinetic on 16.04

Melodic on 18.04

It appears that the <origin> tag within <visual> and <collision> is not taken into account anymore. This breaks most of our existing URDF models.

URDF:

<?xml version="1.0" ?>
<robot name="abc">
  <link name="a_link">
    <visual name="a_visual">
      <origin xyz="-0.5 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://rviz_melodic_urdf_issue/a.dae" scale="1.0 1.0 1.0" />
      </geometry>
    </visual>
  </link>
  <joint name="a_b_joint" type="fixed">
    <parent link="a_link"/>
    <child link="b_link"/>
    <origin xyz="0 0 0" rpy="0 0 0" />
  </joint>
  <link name="b_link">
    <visual name="b_visual">
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://rviz_melodic_urdf_issue/b.dae" scale="1.0 1.0 1.0" />
      </geometry>
    </visual>
  </link>
  <joint name="b_c_joint" type="fixed">
    <parent link="b_link"/>
    <child link="c_link"/>
    <origin xyz="0 0 0" rpy="0 0 0" />
  </joint>
  <link name="c_link">
    <visual name="c_visual">
      <origin xyz="0.5 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://rviz_melodic_urdf_issue/c.dae" scale="1.0 1.0 1.0" />
      </geometry>
    </visual>
  </link>
</robot>

Clone https://github.com/andreasBihlmaier/rviz_melodic_urdf_issue into catkin workspace, build and run

roslaunch urdf_tutorial display.launch model:=`rospack find rviz_melodic_urdf_issue`/abc.urdf

Update:
Geometric primitives, e.g. <box> are not shown at all:
Kinetic on 16.04

Melodic on 18.04

URDF:


<?xml version="1.0" ?>
<robot name="boxes">
  <link name="a_link">
    <visual name="a_visual">
      <origin xyz="-0.5 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.1 1 0.1" />
      </geometry>
    </visual>
  </link>
  <joint name="a_b_joint" type="fixed">
    <parent link="a_link"/>
    <child link="b_link"/>
    <origin xyz="0 0 0" rpy="0 0 0" />
  </joint>
  <link name="b_link">
    <visual name="b_visual">
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.1 1 0.1" />
      </geometry>
    </visual>
  </link>
  <joint name="b_c_joint" type="fixed">
    <parent link="b_link"/>
    <child link="c_link"/>
    <origin xyz="0 0 0" rpy="0 0 0" />
  </joint>
  <link name="c_link">
    <visual name="c_visual">
      <origin xyz="0.5 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.1 1 0.1" />
      </geometry>
    </visual>
  </link>
</robot>

Metadata

Metadata

Assignees

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions