Newer
Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
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"/>