diff --git a/talos-data/distinfo b/talos-data/distinfo index 342447a8c6346f66c076a9e530bae3cee50b4b61..d702ebe22926ac7d27c6033655180b39b850772a 100644 --- a/talos-data/distinfo +++ b/talos-data/distinfo @@ -1,3 +1,4 @@ SHA1 (talos_data-0.0.19.tar.gz) = 17439b6a1730f1dd5b6efc4773539b897da434ec RMD160 (talos_data-0.0.19.tar.gz) = da0fedb3336ea1c3e68d7ae90964e52503610e93 Size (talos_data-0.0.19.tar.gz) = 8773911 bytes +SHA1 (patch-aa) = deeeeb585f8ed87d0bce8486ac8a69dfa2e570b6 diff --git a/talos-data/patches/patch-aa b/talos-data/patches/patch-aa new file mode 100644 index 0000000000000000000000000000000000000000..f2e3d92226f249416d4c206d60d8689ffb441ec7 --- /dev/null +++ b/talos-data/patches/patch-aa @@ -0,0 +1,56 @@ +--- urdf/talos_reduced_v2.urdf ++++ 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"/>