From ca2f97deff28921a3207a9f280045f1c0549f307 Mon Sep 17 00:00:00 2001 From: Luca <luca.marchionni@pal-robotics.com> Date: Fri, 4 Nov 2016 18:24:26 +0100 Subject: [PATCH] Invert torso joints order. Check base_link --- talos_description/urdf/torso/torso.urdf.xacro | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/talos_description/urdf/torso/torso.urdf.xacro b/talos_description/urdf/torso/torso.urdf.xacro index b2eeacc..5ceb621 100644 --- a/talos_description/urdf/torso/torso.urdf.xacro +++ b/talos_description/urdf/torso/torso.urdf.xacro @@ -77,13 +77,13 @@ </link> <joint name="${name}_1_joint" type="revolute"> - <parent link="${name}_2_link"/> + <parent link="base_link"/> <child link="${name}_1_link"/> - <origin xyz="0.0 0.0 0.0" + <origin xyz="0.0 0.0 0.0722" rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="0 1 0" /> - <limit lower="${-45.0 * deg_to_rad}" upper="${15.0 * deg_to_rad}" - effort="${torso_max_effort}" velocity="${torso_max_vel}"/> + <axis xyz="0 0 1" /> + <limit lower="${-75.00000 * deg_to_rad}" upper="${75.00000 * deg_to_rad}" + effort="${torso_max_effort}" velocity="${torso_max_vel}" /> <dynamics damping="1.0" friction="1.0"/> <!-- <safety_controller k_position="20" @@ -122,12 +122,12 @@ <joint name="${name}_2_joint" type="revolute"> <parent link="${name}_1_link"/> - <child link="base_link"/> - <origin xyz="0.0 0.0 -0.0722" + <child link="${name}_2_link"/> + <origin xyz="0.0 0.0 0.0" rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> - <axis xyz="0 0 1" /> - <limit lower="${-75.00000 * deg_to_rad}" upper="${75.00000 * deg_to_rad}" - effort="${torso_max_effort}" velocity="${torso_max_vel}" /> + <axis xyz="0 1 0" /> + <limit lower="${-15.0 * deg_to_rad}" upper="${45.0 * deg_to_rad}" + effort="${torso_max_effort}" velocity="${torso_max_vel}"/> <dynamics friction="1.0" damping="1.0"/> <!-- <safety_controller k_position="20" -- GitLab