diff --git a/tor_description/urdf/leg/leg.urdf.xacro b/tor_description/urdf/leg/leg.urdf.xacro index 65f54bfdaf0560b7f71e73114f5954b3b50da94b..9dd9633a59a6e6c82aee7ab9305b621897f4bbb3 100644 --- a/tor_description/urdf/leg/leg.urdf.xacro +++ b/tor_description/urdf/leg/leg.urdf.xacro @@ -168,7 +168,12 @@ <!-- nominal --> <!-- <limit lower="-0.5236" upper="1.571" effort="49" velocity="3.87" /> --> <!-- peak --> - <limit lower="-0.5236" upper="1.571" effort="100" velocity="3.87" /> + <xacro:if value="${reflect == 1}"> + <limit lower="-0.5236" upper="1.571" effort="100" velocity="3.87" /> + </xacro:if> + <xacro:if value="${reflect == -1}"> + <limit lower="-1.571" upper="0.5236" effort="100" velocity="3.87" /> + </xacro:if> <dynamics friction="${leg_friction}" damping="${leg_damping}"/> </joint>