Skip to content
Snippets Groups Projects
Commit 61eebe78 authored by Olivier Stasse's avatar Olivier Stasse
Browse files

[wip/talos-data] Release 0.0.20

Grippers have fixed frames now.
parent 0bfbe121
No related branches found
No related tags found
No related merge requests found
# robotpkg Makefile for: wip/talos-data
# Created: Olivier Stasse, on Tue. 9th May, 2017
#
VERSION= 0.0.19
VERSION= 0.0.20
PKGNAME= talos-data-${VERSION}
DISTNAME= $(subst -,_,${PKGBASE})-${VERSION}
PKGREVISION= 1
MASTER_SITES= ${MASTER_SITE_OPENROBOTS:=talos/talos_data/}
MASTER_REPOSITORY= https://redmine.laas.fr/laas/users/
......
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
SHA1 (talos_data-0.0.20.tar.gz) = 9ab692837c02c2d5978c2118c3a6e89b601c0d13
RMD160 (talos_data-0.0.20.tar.gz) = c71e021aadac9aad0ca7eaf8ac3490299ce8a3fb
Size (talos_data-0.0.20.tar.gz) = 8780610 bytes
--- 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"/>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment