From 8b63910c11148eebe876eee277fa3051fe77dd76 Mon Sep 17 00:00:00 2001 From: fherrero <fherrero@iri.upc.edu> Date: Fri, 5 Feb 2021 12:40:58 +0100 Subject: [PATCH] urdf: move intertia to _body frame --- urdf/world.xacro | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 deletions(-) diff --git a/urdf/world.xacro b/urdf/world.xacro index 6a419db..f178ae1 100644 --- a/urdf/world.xacro +++ b/urdf/world.xacro @@ -5,11 +5,6 @@ <link name="$(arg parent)"/> <link name="$(arg frame)"> - <inertial> - <mass value="10000"/> - <origin xyz="0 0 0" rpy="0 0 0"/> - <inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" /> - </inertial> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> @@ -31,4 +26,18 @@ <axis xyz="0 0 1"/> </joint> + <link name="$(arg frame)_body"> + <inertial> + <mass value="10000"/> + <origin xyz="0 0 0" rpy="0 0 0"/> + <inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" /> + </inertial> + </link> + + <joint name="$(arg frame)2$(arg frame)_body" type="fixed"> + <parent link="$(arg frame)"/> + <child link="$(arg frame)_body"/> + <origin xyz="0 0 0" rpy="0 0 0"/> + </joint> + </robot> -- GitLab