diff --git a/tor_description/urdf/leg/leg_v2.urdf.xacro b/tor_description/urdf/leg/leg_v2.urdf.xacro index d7e7c575aed8f6ecfaa2d8785beded069fcb752b..a28438fae4b10f704428b94edb96622b7ebc76ed 100644 --- a/tor_description/urdf/leg/leg_v2.urdf.xacro +++ b/tor_description/urdf/leg/leg_v2.urdf.xacro @@ -95,7 +95,7 @@ <link name="leg_${prefix}_3_link"> <inertial> - <origin xyz="0.00658 0.06563 -0.17278" rpy="0.00000 0.00000 0.00000"/> + <origin xyz="0.00658 ${reflect*0.06563} -0.17278" rpy="0.00000 0.00000 0.00000"/> <mass value="6.82734"/> <inertia ixx="0.12390600000" ixy="${reflect*-0.00041200000}" ixz="-0.00205900000" iyy="0.10844700000" iyz="${reflect*0.01672500000}" @@ -132,10 +132,10 @@ <link name="leg_${prefix}_4_link"> <inertial> - <origin xyz="0.01520 0.02331 -0.12063" rpy="0.00000 0.00000 0.00000"/> + <origin xyz="0.01520 ${reflect*0.02331} -0.12063" rpy="0.00000 0.00000 0.00000"/> <mass value="3.63668"/> - <inertia ixx="0.03531500000" ixy="0.00002900000" ixz="-0.00016600000" - iyy="0.02933600000" iyz="-0.00130500000" + <inertia ixx="0.03531500000" ixy="${reflect*0.00002900000}" ixz="-0.00016600000" + iyy="0.02933600000" iyz="${reflect*-0.00130500000}" izz="0.01174000000"/> </inertial> @@ -172,8 +172,8 @@ <inertial> <origin xyz="-0.01106 ${reflect*0.04708} 0.05271" rpy="0.00000 0.00000 0.00000"/> <mass value="1.24433"/> - <inertia ixx="0.01148700000" ixy="-0.00068600000" ixz="-0.00052600000" - iyy="0.00952600000" iyz="0.00263300000" + <inertia ixx="0.01148700000" ixy="${reflect*-0.00068600000}" ixz="-0.00052600000" + iyy="0.00952600000" iyz="${reflect*0.00263300000}" izz="0.00390800000"/> </inertial>