gazebosim / gazebo-classic

Gazebo classic. For the latest version, see https://github.com/gazebosim/gz-sim
http://classic.gazebosim.org/
Other
1.17k stars 477 forks source link

URDF to SDF conversions ignores links with no visual #2591

Open osrf-migration opened 5 years ago

osrf-migration commented 5 years ago

Original report (archived issue) by Christian Rauch (Bitbucket: christian-rauch).

The original report had attachments: robotiq-3f-gripper_articulated.sdf, robotiq-3f-gripper_articulated.urdf


When converting a URDF via gz sdf -p robot.urdf > robot.sdf to SDF, links with no visual element get removed / are ignored.

Converting the attached URDF (source: robotiq 3finger xacro) via gz sdf -p robotiq-3f-gripper_articulated.urdf > robotiq-3f-gripper_articulated.sdf results in the attached SDF.

While the URDF contains the link tool0 (<link name="tool0"/>), the exported SDF is missing this link. This also effects the spawning of URDF models via the ROS plugin. I guess this also breaks the kinematic tree in general. E.g. Gazebo cannot spawn models that have an "invisible" link in their kinematic chain.

Since this link is not part of the kinematic chain, it cannot be used as reference for spawning other models. This is however important if models are to be spawn relative to "invisible" links, like grasp links that are commonly used for grippers.

osrf-migration commented 5 years ago

Original comment by Ринат Назаров (Bitbucket: Rinat Nazarov).


Your tool0 link should have inertial element in it, and you should use revolute joint with zero limits instead of fixed one.