From 8bf4bcd52780101e16e12e4c64eac559ddfe0c44 Mon Sep 17 00:00:00 2001 From: Pierre-Alexandre Leziart <paleziart@laas.fr> Date: Fri, 8 Dec 2023 16:46:20 +0100 Subject: [PATCH] Fix wrong position of the center of mass for Solo-8 and Solo-12 lower legs --- robots/solo_description/robots/solo.urdf | 4 ++-- robots/solo_description/robots/solo12.urdf | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/robots/solo_description/robots/solo.urdf b/robots/solo_description/robots/solo.urdf index a32d660..6c335fb 100644 --- a/robots/solo_description/robots/solo.urdf +++ b/robots/solo_description/robots/solo.urdf @@ -234,7 +234,7 @@ <link name="FR_LOWER_LEG"> <!-- Right lower leg inertia --> <inertial> - <origin rpy="0 0 0" xyz="0.0 0.00787644 -0.08928215"/> + <origin rpy="0 0 0" xyz="0.0 -0.00787644 -0.08928215"/> <mass value="0.03070001"/> <inertia ixx="0.00012024" ixy="0.0" ixz="0.0" iyy="0.00012029" iyz="-0.00000305" izz="0.00000216"/> </inertial> @@ -504,7 +504,7 @@ <link name="HR_LOWER_LEG"> <!-- Right lower leg inertia --> <inertial> - <origin rpy="0 0 0" xyz="0.0 0.00787644 -0.08928215"/> + <origin rpy="0 0 0" xyz="0.0 -0.00787644 -0.08928215"/> <mass value="0.03070001"/> <inertia ixx="0.00012024" ixy="0.0" ixz="0.0" iyy="0.00012029" iyz="-0.00000305" izz="0.00000216"/> </inertial> diff --git a/robots/solo_description/robots/solo12.urdf b/robots/solo_description/robots/solo12.urdf index 80d0e76..ecd62e9 100644 --- a/robots/solo_description/robots/solo12.urdf +++ b/robots/solo_description/robots/solo12.urdf @@ -312,7 +312,7 @@ <link name="FR_LOWER_LEG"> <!-- Right lower leg inertia --> <inertial> - <origin rpy="0 0 0" xyz="0.0 0.00787644 -0.08928215"/> + <origin rpy="0 0 0" xyz="0.0 -0.00787644 -0.08928215"/> <mass value="0.03070001"/> <inertia ixx="0.00012024" ixy="0.0" ixz="0.0" iyy="0.00012029" iyz="-0.00000305" izz="0.00000216"/> </inertial> @@ -660,7 +660,7 @@ <link name="HR_LOWER_LEG"> <!-- Right lower leg inertia --> <inertial> - <origin rpy="0 0 0" xyz="0.0 0.00787644 -0.08928215"/> + <origin rpy="0 0 0" xyz="0.0 -0.00787644 -0.08928215"/> <mass value="0.03070001"/> <inertia ixx="0.00012024" ixy="0.0" ixz="0.0" iyy="0.00012029" iyz="-0.00000305" izz="0.00000216"/> </inertial> -- GitLab