From b31c885a563ca79e60063221d31473fc077a3c06 Mon Sep 17 00:00:00 2001 From: Joseph Mirabel <jmirabel@laas.fr> Date: Mon, 17 Sep 2018 19:17:14 +0200 Subject: [PATCH] Fix talos_reduced_v2.urdf * Make fixed the following joints: * gripper_left_inner_double_joint * gripper_left_inner_single_joint * gripper_left_motor_single_joint * gripper_right_inner_double_joint * gripper_right_inner_single_joint * gripper_right_motor_single_joint --- urdf/talos_reduced_v2.urdf | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/urdf/talos_reduced_v2.urdf b/urdf/talos_reduced_v2.urdf index 79e6453..1a77db5 100644 --- a/urdf/talos_reduced_v2.urdf +++ b/urdf/talos_reduced_v2.urdf @@ -1349,7 +1349,7 @@ </geometry> </collision> </link> - <joint name="gripper_left_inner_double_joint" type="revolute"> + <joint name="gripper_left_inner_double_joint" type="fixed"> <parent link="gripper_left_base_link"/> <child link="gripper_left_inner_double_link"/> <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00525 -0.05598"/> @@ -1433,7 +1433,7 @@ </geometry> </collision> </link> - <joint name="gripper_left_motor_single_joint" type="revolute"> + <joint name="gripper_left_motor_single_joint" type="fixed"> <parent link="gripper_left_base_link"/> <child link="gripper_left_motor_single_link"/> <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.02025 -0.03000"/> @@ -1461,7 +1461,7 @@ </geometry> </collision> </link> - <joint name="gripper_left_inner_single_joint" type="revolute"> + <joint name="gripper_left_inner_single_joint" type="fixed"> <parent link="gripper_left_base_link"/> <child link="gripper_left_inner_single_link"/> <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.00525 -0.05598"/> @@ -1702,7 +1702,7 @@ </geometry> </collision> </link> - <joint name="gripper_right_inner_double_joint" type="revolute"> + <joint name="gripper_right_inner_double_joint" type="fixed"> <parent link="gripper_right_base_link"/> <child link="gripper_right_inner_double_link"/> <origin rpy="0.0 0.0 0.0" xyz="0.00000 0.00525 -0.05598"/> @@ -1786,7 +1786,7 @@ </geometry> </collision> </link> - <joint name="gripper_right_motor_single_joint" type="revolute"> + <joint name="gripper_right_motor_single_joint" type="fixed"> <parent link="gripper_right_base_link"/> <child link="gripper_right_motor_single_link"/> <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.02025 -0.03000"/> @@ -1814,7 +1814,7 @@ </geometry> </collision> </link> - <joint name="gripper_right_inner_single_joint" type="revolute"> + <joint name="gripper_right_inner_single_joint" type="fixed"> <parent link="gripper_right_base_link"/> <child link="gripper_right_inner_single_link"/> <origin rpy="0.0 0.0 0.0" xyz="0.00000 -0.00525 -0.05598"/> -- GitLab