From 1f2c5df28165ae38293fd6c18295b06e4c389b8e Mon Sep 17 00:00:00 2001 From: Guilhem Saurel <guilhem.saurel@laas.fr> Date: Fri, 1 Apr 2022 18:45:50 +0200 Subject: [PATCH] laikago: set 0 mass / inertia to thigh shoulders --- robots/laikago_description/urdf/laikago.urdf | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/robots/laikago_description/urdf/laikago.urdf b/robots/laikago_description/urdf/laikago.urdf index abff999..7bc2bb0 100644 --- a/robots/laikago_description/urdf/laikago.urdf +++ b/robots/laikago_description/urdf/laikago.urdf @@ -93,6 +93,11 @@ <cylinder length="0.08" radius="0.044"/> </geometry> </collision> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> </link> <joint name="FR_thigh_joint" type="revolute"> <origin rpy="0 0 0" xyz="0 -0.037 0"/> @@ -215,6 +220,11 @@ <cylinder length="0.08" radius="0.044"/> </geometry> </collision> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> </link> <joint name="FL_thigh_joint" type="revolute"> <origin rpy="0 0 0" xyz="0 0.037 0"/> @@ -337,6 +347,11 @@ <cylinder length="0.08" radius="0.044"/> </geometry> </collision> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> </link> <joint name="RR_thigh_joint" type="revolute"> <origin rpy="0 0 0" xyz="0 -0.037 0"/> @@ -459,6 +474,11 @@ <cylinder length="0.08" radius="0.044"/> </geometry> </collision> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> </link> <joint name="RL_thigh_joint" type="revolute"> <origin rpy="0 0 0" xyz="0 0.037 0"/> -- GitLab