diff --git a/cmake b/cmake index 52d25e05c3b5dfd70c79b3e75787fdc78c6f695e..b47ff3fd66e5f4cbca8eb5a7c078c735689f3ba8 160000 --- a/cmake +++ b/cmake @@ -1 +1 @@ -Subproject commit 52d25e05c3b5dfd70c79b3e75787fdc78c6f695e +Subproject commit b47ff3fd66e5f4cbca8eb5a7c078c735689f3ba8 diff --git a/urdf/talos_reduced_v2.urdf b/urdf/talos_reduced_v2.urdf index 79e6453e671ea9fb470f67a81217b0d84ced33c9..1a77db552ed43549aa81e2f7abbdafdc925661a6 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"/>