Kashu7100 commited on
Commit
4e56776
·
1 Parent(s): 517866f

add origami hand

Browse files
hands/origami_hand/assets/500000000001_8_1.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:5906b21f66b20c1e6379a4d94a13e20279fb3ef3c8c3bc7cf80b803774ebb3ad
3
+ size 2115184
hands/origami_hand/assets/540000000007_4_1.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:e6f5ba82fe64d4b7ff0bc4caf683b15aeba52c96efc258f69b0383b5ef593a63
3
+ size 3396684
hands/origami_hand/assets/i1.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:20b6b4a4cf57fe00a1059bf9bceaaa0008d9e0e336f643f4626ddf4e8ddb23d3
3
+ size 124384
hands/origami_hand/assets/i2.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:07bb13a417da5e1a760fda84a34ca089fb1e81aaab011528b6e707e38d70baed
3
+ size 546484
hands/origami_hand/assets/i3.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:f5baa3acc9660a524444f32eb9697321b93be85e2caa34aadcab58f932105bd8
3
+ size 414184
hands/origami_hand/assets/m1.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:6a68ee996f2584120cf8338eea68da24f8416007adab89c098325590588cecd0
3
+ size 169384
hands/origami_hand/assets/m2.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:68f17be07008e57f53a1570e16e8c6771bdeefc2a00225ebac03ac18de805bf2
3
+ size 517684
hands/origami_hand/assets/m3.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:0abeb8d82a4016cf51064e7f793544d59a46db6a2bbdceb9d7a60a88da974c6a
3
+ size 440184
hands/origami_hand/assets/p1.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:2b531f0f66bae84321059093988cd29470d6fb34966e3965a18314025ef390d2
3
+ size 135684
hands/origami_hand/assets/p2.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:796b23e820df1f5843b38b97a6d761ce98aaba63a659be51f0bf511220dada65
3
+ size 566184
hands/origami_hand/assets/p3.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:ff1500fb6448b20b575f250ad8d85f0a2e901f3d94f59468725b7c1455aeaaab
3
+ size 348684
hands/origami_hand/assets/part_1.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:cc01a9556103636375a69e179afaf6e0790ca3ee861484b052ca7a688f06f87b
3
+ size 137484
hands/origami_hand/assets/part_2.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:2af2b85c2a98976baee3386f963169691003e24ef810994ae429c6f1108db386
3
+ size 847984
hands/origami_hand/assets/r1.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:9d72ee34ce218c71b08747f9e75deb616bdd5f7196754b0a7dcc8b4494f1e66f
3
+ size 169484
hands/origami_hand/assets/r2.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:1d5160a6967007ec1f68ca4871cdc8851a6c76639c9c5208497f56e971816c58
3
+ size 586884
hands/origami_hand/assets/r3.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:c3e9f0e5db159c74b8dbc8163a5b3e313ec405a4d2f5619224a8fd3ec0544e53
3
+ size 409984
hands/origami_hand/assets/t1.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:b76dd331913cf4328c4935587e5699c9c4af9c30852548177202e19ec411883f
3
+ size 570484
hands/origami_hand/assets/t2.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:10b35be703ef4d5b10b3f1b811f0be52802573048d8fd68e426ee092a161776d
3
+ size 536084
hands/origami_hand/assets/t3.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:16f0f730b65c8efe143fb1c0f3dea2520dcd0487c5389b92a2765e5bddb7a785
3
+ size 167184
hands/origami_hand/assets/t4.stl ADDED
@@ -0,0 +1,3 @@
 
 
 
 
1
+ version https://git-lfs.github.com/spec/v1
2
+ oid sha256:861633d5efb0ebdfcabe51254b7c61b3f2dd67119426683ce4ecac4e07846947
3
+ size 431384
hands/origami_hand/origami_hand_right.urdf ADDED
@@ -0,0 +1,625 @@
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
+ <?xml version="1.0" ?>
2
+ <robot name="onshape">
3
+ <link name="palm_right">
4
+ <inertial>
5
+ <origin xyz="-0.00769703740926917096 0.00032818036971677175652 0.066267448217897303997" rpy="0 0 0"/>
6
+ <mass value="0.20213551823676464969"/>
7
+ <inertia ixx="0.00024545437741353525038" ixy="-1.2900597732128486026e-06" ixz="4.5184378569874368646e-05" iyy="0.00017584860565140726868" iyz="-1.0764512287008028407e-05" izz="0.000131511652678016432"/>
8
+ </inertial>
9
+ <visual>
10
+ <origin xyz="-0.031761297057535761712 0.038609080041375205827 0.10644827452508121013" rpy="-0.468547792716846212 -1.3931484186187172991 0.41878539987152263446"/>
11
+ <geometry>
12
+ <mesh filename="assets/part_2.stl"/>
13
+ </geometry>
14
+ <material name="part_2_material">
15
+ <color rgba="0.97254901960784312376 0.97254901960784312376 0.97254901960784312376 1.0"/>
16
+ </material>
17
+ </visual>
18
+ <collision>
19
+ <origin xyz="-0.031761297057535761712 0.038609080041375205827 0.10644827452508121013" rpy="-0.468547792716846212 -1.3931484186187172991 0.41878539987152263446"/>
20
+ <geometry>
21
+ <mesh filename="assets/part_2.stl"/>
22
+ </geometry>
23
+ </collision>
24
+ </link>
25
+ <link name="mcp">
26
+ <inertial>
27
+ <origin xyz="-0.0060023163519498179755 0.00025177495731567846272 -0.0085371117029702375811" rpy="0 0 0"/>
28
+ <mass value="0.011997794815819877792"/>
29
+ <inertia ixx="1.067583663726661394e-06" ixy="2.798592854540713704e-09" ixz="7.1007160798907797468e-08" iyy="1.4119442702440308874e-06" iyz="1.3028227692870918133e-08" izz="1.3060419035433753762e-06"/>
30
+ </inertial>
31
+ <visual>
32
+ <origin xyz="-0.0030000000000002663425 -0.0089999999999993973709 -0.012550000000758999158" rpy="1.570796326794896558 -3.0287066927506901767e-17 -4.5504094187732721737e-18"/>
33
+ <geometry>
34
+ <mesh filename="assets/part_1.stl"/>
35
+ </geometry>
36
+ <material name="part_1_material">
37
+ <color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0"/>
38
+ </material>
39
+ </visual>
40
+ <collision>
41
+ <origin xyz="-0.0030000000000002663425 -0.0089999999999993973709 -0.012550000000758999158" rpy="1.570796326794896558 -3.0287066927506901767e-17 -4.5504094187732721737e-18"/>
42
+ <geometry>
43
+ <mesh filename="assets/part_1.stl"/>
44
+ </geometry>
45
+ </collision>
46
+ </link>
47
+ <link name="index_pp">
48
+ <inertial>
49
+ <origin xyz="8.3106665109204609686e-05 -0.027654180876390044297 -0.010340858876139974454" rpy="0 0 0"/>
50
+ <mass value="0.023401901302167425756"/>
51
+ <inertia ixx="8.382534162069301526e-06" ixy="-9.1470251563533886914e-09" ixz="3.2375318204396778535e-09" iyy="1.9077917284914978893e-06" iyz="-7.7160756059404120133e-07" izz="7.7653220506009268355e-06"/>
52
+ </inertial>
53
+ <visual>
54
+ <origin xyz="-4.8841269585469387904e-05 -0.052483993814880655626 -0.0014869131821292416729" rpy="0.00027697750879545875516 5.2315624655356272584e-05 -1.570796326794896558"/>
55
+ <geometry>
56
+ <mesh filename="assets/i1.stl"/>
57
+ </geometry>
58
+ <material name="i1_material">
59
+ <color rgba="0.99215686274509806708 0.97254901960784312376 0.97254901960784312376 1.0"/>
60
+ </material>
61
+ </visual>
62
+ <collision>
63
+ <origin xyz="-4.8841269585469387904e-05 -0.052483993814880655626 -0.0014869131821292416729" rpy="0.00027697750879545875516 5.2315624655356272584e-05 -1.570796326794896558"/>
64
+ <geometry>
65
+ <mesh filename="assets/i1.stl"/>
66
+ </geometry>
67
+ </collision>
68
+ </link>
69
+ <link name="index_dp">
70
+ <inertial>
71
+ <origin xyz="0.015046022550638207815 -0.0075158430384271246796 -0.010553740388166196057" rpy="0 0 0"/>
72
+ <mass value="0.026930993065676697013"/>
73
+ <inertia ixx="2.8842808160681450037e-06" ixy="-4.2965790038794834547e-07" ixz="4.6271841079938576202e-07" iyy="5.8599467920196493805e-06" iyz="-1.6878547210875548732e-07" izz="6.0963878731600326197e-06"/>
74
+ </inertial>
75
+ <visual>
76
+ <origin xyz="0.029633360463355296055 -5.056765038223554054e-05 -0.0014481443236484536907" rpy="-1.7157020104995065816e-06 -6.6781129667690847002e-05 1.5640016312940503429"/>
77
+ <geometry>
78
+ <mesh filename="assets/i2.stl"/>
79
+ </geometry>
80
+ <material name="i2_material">
81
+ <color rgba="0.99215686274509806708 0.97254901960784312376 0.97254901960784312376 1.0"/>
82
+ </material>
83
+ </visual>
84
+ <collision>
85
+ <origin xyz="0.029633360463355296055 -5.056765038223554054e-05 -0.0014481443236484536907" rpy="-1.7157020104995065816e-06 -6.6781129667690847002e-05 1.5640016312940503429"/>
86
+ <geometry>
87
+ <mesh filename="assets/i2.stl"/>
88
+ </geometry>
89
+ </collision>
90
+ </link>
91
+ <link name="index_tip">
92
+ <inertial>
93
+ <origin xyz="-0.00013983496158648009542 -0.011536207751147532774 -0.0084271870789682443159" rpy="0 0 0"/>
94
+ <mass value="0.010363860292333678878"/>
95
+ <inertia ixx="1.0771188335871507996e-06" ixy="-1.783646637977598805e-08" ixz="-3.7607226551736960944e-09" iyy="5.9342750579617967268e-07" iyz="-2.8281287691672616255e-07" izz="7.5075279992269147672e-07"/>
96
+ </inertial>
97
+ <visual>
98
+ <origin xyz="0.0060714187805481732718 -0.019494980509104919975 -0.021127158677588651903" rpy="-1.5707963267948357178 2.1319222321874657456e-14 -3.141592653589793116"/>
99
+ <geometry>
100
+ <mesh filename="assets/i3.stl"/>
101
+ </geometry>
102
+ <material name="i3_material">
103
+ <color rgba="0.64705882352941179736 0.64705882352941179736 0.64705882352941179736 1.0"/>
104
+ </material>
105
+ </visual>
106
+ <collision>
107
+ <origin xyz="0.0060714187805481732718 -0.019494980509104919975 -0.021127158677588651903" rpy="-1.5707963267948357178 2.1319222321874657456e-14 -3.141592653589793116"/>
108
+ <geometry>
109
+ <mesh filename="assets/i3.stl"/>
110
+ </geometry>
111
+ </collision>
112
+ </link>
113
+ <joint name="dip_i" type="revolute">
114
+ <origin xyz="0.029633357426173206894 -5.0661125486111541205e-05 -4.8144326770666046045e-05" rpy="-2.169416262323568544e-06 -6.6767930615214534447e-05 1.5707963267948286123"/>
115
+ <parent link="index_dp"/>
116
+ <child link="index_tip"/>
117
+ <axis xyz="0 0 1"/>
118
+ <limit effort="1" velocity="20" lower="-0.1745329251994329478" upper="1.9198621771937625091"/>
119
+ <joint_properties friction="0.0"/>
120
+ </joint>
121
+ <joint name="pip_i" type="revolute">
122
+ <origin xyz="-4.2636570638618365159e-05 -0.052482821944934796021 8.6912292140174651767e-05" rpy="-0.00027697751031813142237 -5.2315616628456015371e-05 -1.5707962978143950039"/>
123
+ <parent link="index_pp"/>
124
+ <child link="index_dp"/>
125
+ <axis xyz="0 0 1"/>
126
+ <limit effort="1" velocity="20" lower="-0.1745329251994329478" upper="1.9198621771937625091"/>
127
+ <joint_properties friction="0.0"/>
128
+ </joint>
129
+ <joint name="mcp_i2" type="revolute">
130
+ <origin xyz="0.0004500000000000059508 0.011900000000000823114 -0.012850000000951617568" rpy="-1.5707963267948978903 1.5707963267948950037 0"/>
131
+ <parent link="mcp"/>
132
+ <child link="index_pp"/>
133
+ <axis xyz="0 0 1"/>
134
+ <limit effort="1" velocity="20" lower="-0.26179938779914940783" upper="2.2689280275926284602"/>
135
+ <joint_properties friction="0.0"/>
136
+ </joint>
137
+ <joint name="mcp_i" type="revolute">
138
+ <origin xyz="-0.0087493330982606268287 0.03264613025807983071 0.11671614018381347433" rpy="-0.33002752767306170467 -1.4033511418516371183 0.27818585255123273736"/>
139
+ <parent link="palm_right"/>
140
+ <child link="mcp"/>
141
+ <axis xyz="0 0 1"/>
142
+ <limit effort="1" velocity="20" lower="-0.52359877559829881566" upper="0.52359877559829881566"/>
143
+ <joint_properties friction="0.0"/>
144
+ </joint>
145
+ <link name="mcp_2">
146
+ <inertial>
147
+ <origin xyz="-0.0060023163519498864971 0.00025177495731563916039 -0.0085371117029702393159" rpy="0 0 0"/>
148
+ <mass value="0.011997794815819877792"/>
149
+ <inertia ixx="1.0675836637266457239e-06" ixy="2.7985928545432059992e-09" ixz="7.1007160798902940264e-08" iyy="1.4119442702440109822e-06" iyz="1.3028227692868598719e-08" izz="1.306041903543358012e-06"/>
150
+ </inertial>
151
+ <visual>
152
+ <origin xyz="-0.0030000000000002663425 -0.0089999999999993939015 -0.012550000000759002627" rpy="1.570796326794896558 -1.2821626540935736283e-17 -3.369347396693575551e-18"/>
153
+ <geometry>
154
+ <mesh filename="assets/part_1.stl"/>
155
+ </geometry>
156
+ <material name="part_1_material">
157
+ <color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0"/>
158
+ </material>
159
+ </visual>
160
+ <collision>
161
+ <origin xyz="-0.0030000000000002663425 -0.0089999999999993939015 -0.012550000000759002627" rpy="1.570796326794896558 -1.2821626540935736283e-17 -3.369347396693575551e-18"/>
162
+ <geometry>
163
+ <mesh filename="assets/part_1.stl"/>
164
+ </geometry>
165
+ </collision>
166
+ </link>
167
+ <link name="mid_pp">
168
+ <inertial>
169
+ <origin xyz="0.00020642381520217934605 -0.030948508641522307072 -0.010297599179503931846" rpy="0 0 0"/>
170
+ <mass value="0.0259285629131962847"/>
171
+ <inertia ixx="1.1251938207984032907e-05" ixy="-1.5001819921474718543e-08" ixz="1.8970737388782971584e-08" iyy="2.2564106704208488113e-06" iyz="-9.4495831915399096309e-07" izz="1.0451763676512779752e-05"/>
172
+ </inertial>
173
+ <visual>
174
+ <origin xyz="8.6692831862942437704e-05 -0.059458936830413283703 -0.0014765243235707325997" rpy="-0.0064104741917886442007 0.038570602308532389579 -1.570796326794896558"/>
175
+ <geometry>
176
+ <mesh filename="assets/m1.stl"/>
177
+ </geometry>
178
+ <material name="m1_material">
179
+ <color rgba="0.98431372549019602314 0.97647058823529409022 0.97647058823529409022 1.0"/>
180
+ </material>
181
+ </visual>
182
+ <collision>
183
+ <origin xyz="8.6692831862942437704e-05 -0.059458936830413283703 -0.0014765243235707325997" rpy="-0.0064104741917886442007 0.038570602308532389579 -1.570796326794896558"/>
184
+ <geometry>
185
+ <mesh filename="assets/m1.stl"/>
186
+ </geometry>
187
+ </collision>
188
+ </link>
189
+ <link name="mid_dp">
190
+ <inertial>
191
+ <origin xyz="0.017709850750268707475 -0.0072607810702285070434 -0.010694744861636372446" rpy="0 0 0"/>
192
+ <mass value="0.03076754148749898457"/>
193
+ <inertia ixx="3.2753774808777764933e-06" ixy="-5.0066958380293198363e-07" ixz="5.5526837231369128579e-07" iyy="7.7718642235663393556e-06" iyz="-1.6017670889125388231e-07" izz="8.0763474992073897778e-06"/>
194
+ </inertial>
195
+ <visual>
196
+ <origin xyz="0.034825229980873395608 -4.7256357965714222702e-05 -0.0014508000204274985878" rpy="0.0068334652552994330083 -6.6766034189123270575e-05 1.5931182112839588072"/>
197
+ <geometry>
198
+ <mesh filename="assets/m2.stl"/>
199
+ </geometry>
200
+ <material name="m2_material">
201
+ <color rgba="1 0.99215686274509806708 0.99215686274509806708 1.0"/>
202
+ </material>
203
+ </visual>
204
+ <collision>
205
+ <origin xyz="0.034825229980873395608 -4.7256357965714222702e-05 -0.0014508000204274985878" rpy="0.0068334652552994330083 -6.6766034189123270575e-05 1.5931182112839588072"/>
206
+ <geometry>
207
+ <mesh filename="assets/m2.stl"/>
208
+ </geometry>
209
+ </collision>
210
+ </link>
211
+ <link name="mid_tip">
212
+ <inertial>
213
+ <origin xyz="-0.0001374443180512010111 -0.011771744731359039954 -0.0084069111573039645435" rpy="0 0 0"/>
214
+ <mass value="0.010557985408193627103"/>
215
+ <inertia ixx="1.1157458017043927943e-06" ixy="-1.843818312602291334e-08" ixz="-3.49207427269780171e-09" iyy="6.0032240422606891493e-07" iyz="-2.8375846998417933349e-07" izz="7.8710719692190812342e-07"/>
216
+ </inertial>
217
+ <visual>
218
+ <origin xyz="0.006071418780548188017 -0.019494980509104808952 -0.020927158677777921852" rpy="-1.5707963267948392705 2.1341007071201703946e-14 -3.141592653589793116"/>
219
+ <geometry>
220
+ <mesh filename="assets/m3.stl"/>
221
+ </geometry>
222
+ <material name="m3_material">
223
+ <color rgba="0.64705882352941179736 0.64705882352941179736 0.64705882352941179736 1.0"/>
224
+ </material>
225
+ </visual>
226
+ <collision>
227
+ <origin xyz="0.006071418780548188017 -0.019494980509104808952 -0.020927158677777921852" rpy="-1.5707963267948392705 2.1341007071201703946e-14 -3.141592653589793116"/>
228
+ <geometry>
229
+ <mesh filename="assets/m3.stl"/>
230
+ </geometry>
231
+ </collision>
232
+ </link>
233
+ <joint name="dip_m" type="revolute">
234
+ <origin xyz="0.03483479646073059377 -4.7136274190512014726e-05 -5.0832710793868862709e-05" rpy="0.0068334311544149687126 -7.0169534612881509961e-05 1.5936162683823218433"/>
235
+ <parent link="mid_dp"/>
236
+ <child link="mid_tip"/>
237
+ <axis xyz="0 0 1"/>
238
+ <limit effort="1" velocity="20" lower="-0.1745329251994329478" upper="1.9198621771937625091"/>
239
+ <joint_properties friction="0.0"/>
240
+ </joint>
241
+ <joint name="pip_m" type="revolute">
242
+ <origin xyz="-6.3787996818521867926e-05 -0.058595187291039130262 5.93601512490528338e-05" rpy="0.0064295938991052615369 -0.038567421257756348552 -1.5712921768872887274"/>
243
+ <parent link="mid_pp"/>
244
+ <child link="mid_dp"/>
245
+ <axis xyz="0 0 1"/>
246
+ <limit effort="1" velocity="20" lower="-0.1745329251994329478" upper="1.9198621771937625091"/>
247
+ <joint_properties friction="0.0"/>
248
+ </joint>
249
+ <joint name="mcp_m2" type="revolute">
250
+ <origin xyz="0.00044999999999986717292 0.011900000000000625355 -0.012850000000951612364" rpy="-1.5707963267948903408 1.5707963267948903408 0"/>
251
+ <parent link="mcp_2"/>
252
+ <child link="mid_pp"/>
253
+ <axis xyz="0 0 1"/>
254
+ <limit effort="1" velocity="20" lower="-0.26179938779914940783" upper="2.2689280275926284602"/>
255
+ <joint_properties friction="0.0"/>
256
+ </joint>
257
+ <joint name="mcp_m" type="revolute">
258
+ <origin xyz="-0.013585782285931357824 0.0031923793527567278713 0.1115647841111791494" rpy="1.0107988252284711983 -1.4663430875941414477 -0.94690564513796204871"/>
259
+ <parent link="palm_right"/>
260
+ <child link="mcp_2"/>
261
+ <axis xyz="0 0 1"/>
262
+ <limit effort="1" velocity="20" lower="-0.52359877559829881566" upper="0.52359877559829881566"/>
263
+ <joint_properties friction="0.0"/>
264
+ </joint>
265
+ <link name="mcp_3">
266
+ <inertial>
267
+ <origin xyz="-0.0060023163519500556326 0.00025177495731549214258 -0.0085371117029702358464" rpy="0 0 0"/>
268
+ <mass value="0.011997794815819877792"/>
269
+ <inertia ixx="1.0675836637266137484e-06" ixy="2.7985928545449736842e-09" ixz="7.100716079888238648e-08" iyy="1.411944270243962913e-06" iyz="1.3028227692877552122e-08" izz="1.3060419035433237072e-06"/>
270
+ </inertial>
271
+ <visual>
272
+ <origin xyz="-0.0030000000000002663425 -0.008999999999999390432 -0.012550000000758999158" rpy="1.570796326794896558 -1.5497950495990618087e-18 5.7760625291484165321e-17"/>
273
+ <geometry>
274
+ <mesh filename="assets/part_1.stl"/>
275
+ </geometry>
276
+ <material name="part_1_material">
277
+ <color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0"/>
278
+ </material>
279
+ </visual>
280
+ <collision>
281
+ <origin xyz="-0.0030000000000002663425 -0.008999999999999390432 -0.012550000000758999158" rpy="1.570796326794896558 -1.5497950495990618087e-18 5.7760625291484165321e-17"/>
282
+ <geometry>
283
+ <mesh filename="assets/part_1.stl"/>
284
+ </geometry>
285
+ </collision>
286
+ </link>
287
+ <link name="ring_pp">
288
+ <inertial>
289
+ <origin xyz="0.00030264967647336267313 -0.02638798743915453035 -0.010263942299543898223" rpy="0 0 0"/>
290
+ <mass value="0.022161510072681630396"/>
291
+ <inertia ixx="7.357670315073239423e-06" ixy="3.301168407885867136e-08" ixz="9.6351728790383255478e-09" iyy="1.7718168447636220457e-06" iyz="-7.409251447229338509e-07" izz="6.8079323432279007571e-06"/>
292
+ </inertial>
293
+ <visual>
294
+ <origin xyz="0.00024379594914731767311 -0.049611197653331814972 -0.0014179780360628491814" rpy="0.003918591041116451304 -0.016942922424153159661 -1.570796326794896558"/>
295
+ <geometry>
296
+ <mesh filename="assets/r1.stl"/>
297
+ </geometry>
298
+ <material name="r1_material">
299
+ <color rgba="0.96470588235294119084 0.96470588235294119084 0.96470588235294119084 1.0"/>
300
+ </material>
301
+ </visual>
302
+ <collision>
303
+ <origin xyz="0.00024379594914731767311 -0.049611197653331814972 -0.0014179780360628491814" rpy="0.003918591041116451304 -0.016942922424153159661 -1.570796326794896558"/>
304
+ <geometry>
305
+ <mesh filename="assets/r1.stl"/>
306
+ </geometry>
307
+ </collision>
308
+ </link>
309
+ <link name="ring_dp">
310
+ <inertial>
311
+ <origin xyz="0.016398866487979911477 -0.0074240994970753955776 -0.010636281158039643038" rpy="0 0 0"/>
312
+ <mass value="0.028880445733497361188"/>
313
+ <inertia ixx="3.0804492348058500528e-06" ixy="-4.4783318807127398874e-07" ixz="5.0081930692520125481e-07" iyy="6.8025304524099440597e-06" iyz="-1.6569713481598340715e-07" izz="7.0614319639936931711e-06"/>
314
+ </inertial>
315
+ <visual>
316
+ <origin xyz="0.031820608826912177847 -1.5561223506076882336e-05 -0.0014250581053474754151" rpy="-0.0010460530973805857134 -6.6693665106133423839e-05 1.6224309945620556395"/>
317
+ <geometry>
318
+ <mesh filename="assets/r2.stl"/>
319
+ </geometry>
320
+ <material name="r2_material">
321
+ <color rgba="0.98431372549019602314 0.98431372549019602314 0.98431372549019602314 1.0"/>
322
+ </material>
323
+ </visual>
324
+ <collision>
325
+ <origin xyz="0.031820608826912177847 -1.5561223506076882336e-05 -0.0014250581053474754151" rpy="-0.0010460530973805857134 -6.6693665106133423839e-05 1.6224309945620556395"/>
326
+ <geometry>
327
+ <mesh filename="assets/r2.stl"/>
328
+ </geometry>
329
+ </collision>
330
+ </link>
331
+ <link name="ring_tip">
332
+ <inertial>
333
+ <origin xyz="-0.00014059199462245432666 -0.011476739564431390206 -0.0083495564280027800841" rpy="0 0 0"/>
334
+ <mass value="0.010316504954417608092"/>
335
+ <inertia ixx="1.0633531111374943171e-06" ixy="-1.7615077617786101218e-08" ixz="-3.5636622147964772965e-09" iyy="5.8751989174125021629e-07" iyz="-2.7614918590464416061e-07" izz="7.4186876744895746471e-07"/>
336
+ </inertial>
337
+ <visual>
338
+ <origin xyz="0.0060714187805481299037 -0.019494980509104808952 -0.020927158677777932261" rpy="-1.5707963267948394925 1.7833054019154067181e-14 -3.141592653589793116"/>
339
+ <geometry>
340
+ <mesh filename="assets/r3.stl"/>
341
+ </geometry>
342
+ <material name="r3_material">
343
+ <color rgba="0.64705882352941179736 0.64705882352941179736 0.64705882352941179736 1.0"/>
344
+ </material>
345
+ </visual>
346
+ <collision>
347
+ <origin xyz="0.0060714187805481299037 -0.019494980509104808952 -0.020927158677777932261" rpy="-1.5707963267948394925 1.7833054019154067181e-14 -3.141592653589793116"/>
348
+ <geometry>
349
+ <mesh filename="assets/r3.stl"/>
350
+ </geometry>
351
+ </collision>
352
+ </link>
353
+ <joint name="dip_r" type="revolute">
354
+ <origin xyz="0.031819151123697347883 -1.5730054178829757684e-05 -2.5058874419984014659e-05" rpy="-0.0010460618720948594747 -6.6555895603804784066e-05 1.622562698081550181"/>
355
+ <parent link="ring_dp"/>
356
+ <child link="ring_tip"/>
357
+ <axis xyz="0 0 1"/>
358
+ <limit effort="1" velocity="20" lower="-0.1745329251994329478" upper="1.9198621771937625091"/>
359
+ <joint_properties friction="0.0"/>
360
+ </joint>
361
+ <joint name="pip_r" type="revolute">
362
+ <origin xyz="0.00032972576770142663152 -0.049990698044420203705 1.4598292893552508587e-05" rpy="-0.0039208418223830952126 0.016942401748866707523 -1.5709291801160660818"/>
363
+ <parent link="ring_pp"/>
364
+ <child link="ring_dp"/>
365
+ <axis xyz="0 0 1"/>
366
+ <limit effort="1" velocity="20" lower="-0.1745329251994329478" upper="1.9198621771937625091"/>
367
+ <joint_properties friction="0.0"/>
368
+ </joint>
369
+ <joint name="mcp_r2" type="revolute">
370
+ <origin xyz="0.00044999999999945083928 0.011900000000000006059 -0.012850000000951612364" rpy="-1.5707963267948856778 1.5707963267948852337 0"/>
371
+ <parent link="mcp_3"/>
372
+ <child link="ring_pp"/>
373
+ <axis xyz="0 0 1"/>
374
+ <limit effort="1" velocity="20" lower="-0.26179938779914940783" upper="2.2689280275926284602"/>
375
+ <joint_properties friction="0.0"/>
376
+ </joint>
377
+ <joint name="mcp_r" type="revolute">
378
+ <origin xyz="-0.013595572898163005987 -0.01992824891857686298 0.10870409632225215557" rpy="1.5570456636767608938 -1.3820811560982539934 -1.6052607701396544027"/>
379
+ <parent link="palm_right"/>
380
+ <child link="mcp_3"/>
381
+ <axis xyz="0 0 1"/>
382
+ <limit effort="1" velocity="20" lower="-0.52359877559829881566" upper="0.52359877559829881566"/>
383
+ <joint_properties friction="0.0"/>
384
+ </joint>
385
+ <link name="mcp_4">
386
+ <inertial>
387
+ <origin xyz="-0.0060023163519500408875 0.00025177495731553420962 -0.008537111702970232377" rpy="0 0 0"/>
388
+ <mass value="0.011997794815819877792"/>
389
+ <inertia ixx="1.0675836637266143836e-06" ixy="2.7985928545460333025e-09" ixz="7.1007160798886145189e-08" iyy="1.4119442702439654541e-06" iyz="1.302822769288258138e-08" izz="1.30604190354332646e-06"/>
390
+ </inertial>
391
+ <visual>
392
+ <origin xyz="-0.0030000000000002524647 -0.0089999999999993956362 -0.012550000000758999158" rpy="1.570796326794896558 2.3993509894768450468e-17 4.3197524071597988484e-17"/>
393
+ <geometry>
394
+ <mesh filename="assets/part_1.stl"/>
395
+ </geometry>
396
+ <material name="part_1_material">
397
+ <color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0"/>
398
+ </material>
399
+ </visual>
400
+ <collision>
401
+ <origin xyz="-0.0030000000000002524647 -0.0089999999999993956362 -0.012550000000758999158" rpy="1.570796326794896558 2.3993509894768450468e-17 4.3197524071597988484e-17"/>
402
+ <geometry>
403
+ <mesh filename="assets/part_1.stl"/>
404
+ </geometry>
405
+ </collision>
406
+ </link>
407
+ <link name="pinky_pp">
408
+ <inertial>
409
+ <origin xyz="0.00018204358572647264588 -0.02210357782830142323 -0.010071732372793682983" rpy="0 0 0"/>
410
+ <mass value="0.019375248300184902406"/>
411
+ <inertia ixx="4.8905470529686601234e-06" ixy="2.2038677790626081134e-09" ixz="6.4369969992078090002e-09" iyy="1.58513058522294263e-06" iyz="-6.2440512419780724514e-07" izz="4.3609195742727675842e-06"/>
412
+ </inertial>
413
+ <visual>
414
+ <origin xyz="5.2851093160093814971e-05 -0.041040624904057354527 -0.0013321729401315021181" rpy="0.00057911570467857954089 -0.00037050405234141225302 -1.570796326794896558"/>
415
+ <geometry>
416
+ <mesh filename="assets/p1.stl"/>
417
+ </geometry>
418
+ <material name="p1_material">
419
+ <color rgba="0.99215686274509806708 0.98431372549019602314 0.98431372549019602314 1.0"/>
420
+ </material>
421
+ </visual>
422
+ <collision>
423
+ <origin xyz="5.2851093160093814971e-05 -0.041040624904057354527 -0.0013321729401315021181" rpy="0.00057911570467857954089 -0.00037050405234141225302 -1.570796326794896558"/>
424
+ <geometry>
425
+ <mesh filename="assets/p1.stl"/>
426
+ </geometry>
427
+ </collision>
428
+ </link>
429
+ <link name="pinky_dp">
430
+ <inertial>
431
+ <origin xyz="0.011959233119249713939 -0.0079277114363721281481 -0.010248751790605116485" rpy="0 0 0"/>
432
+ <mass value="0.022352398517031715069"/>
433
+ <inertia ixx="2.3993203955692214109e-06" ixy="-3.1843699926407766625e-07" ixz="3.5924595444439152598e-07" iyy="4.059530465798097023e-06" iyz="-1.8477062876321859491e-07" izz="4.2367167822319156314e-06"/>
434
+ </inertial>
435
+ <visual>
436
+ <origin xyz="0.023452097442602098942 1.2908372472395651664e-05 -0.0013779261167804332175" rpy="-0.00013927521758416854815 -6.6557195506202379803e-05 1.6529932011010619597"/>
437
+ <geometry>
438
+ <mesh filename="assets/p2.stl"/>
439
+ </geometry>
440
+ <material name="p2_material">
441
+ <color rgba="1 0.98431372549019602314 0.98431372549019602314 1.0"/>
442
+ </material>
443
+ </visual>
444
+ <collision>
445
+ <origin xyz="0.023452097442602098942 1.2908372472395651664e-05 -0.0013779261167804332175" rpy="-0.00013927521758416854815 -6.6557195506202379803e-05 1.6529932011010619597"/>
446
+ <geometry>
447
+ <mesh filename="assets/p2.stl"/>
448
+ </geometry>
449
+ </collision>
450
+ </link>
451
+ <link name="pinky_tip">
452
+ <inertial>
453
+ <origin xyz="-0.00014571628233765379764 -0.010168228043897699353 -0.0080340199694863678043" rpy="0 0 0"/>
454
+ <mass value="0.009158799797994348138"/>
455
+ <inertia ixx="8.5348810155979951696e-07" ixy="-1.324120808560548346e-08" ixz="-3.7234087738084207781e-09" iyy="5.210037764234841864e-07" iyz="-2.4240797219952365341e-07" izz="5.7151870109769394578e-07"/>
456
+ </inertial>
457
+ <visual>
458
+ <origin xyz="0.0060714187805479121959 -0.019494980509104725686 -0.020927158677777942669" rpy="-1.5707963267948426012 9.6626025860878951936e-15 3.141592653589793116"/>
459
+ <geometry>
460
+ <mesh filename="assets/p3.stl"/>
461
+ </geometry>
462
+ <material name="p3_material">
463
+ <color rgba="0.64705882352941179736 0.64705882352941179736 0.64705882352941179736 1.0"/>
464
+ </material>
465
+ </visual>
466
+ <collision>
467
+ <origin xyz="0.0060714187805479121959 -0.019494980509104725686 -0.020927158677777942669" rpy="-1.5707963267948426012 9.6626025860878951936e-15 3.141592653589793116"/>
468
+ <geometry>
469
+ <mesh filename="assets/p3.stl"/>
470
+ </geometry>
471
+ </collision>
472
+ </link>
473
+ <joint name="dip_p" type="revolute">
474
+ <origin xyz="0.023451910766108363671 1.2799497859344866058e-05 2.2073866540435384959e-05" rpy="-0.00013927524449198501791 -6.6557139184647781953e-05 1.6529936054872862439"/>
475
+ <parent link="pinky_dp"/>
476
+ <child link="pinky_tip"/>
477
+ <axis xyz="0 0 1"/>
478
+ <limit effort="1" velocity="20" lower="-0.1745329251994329478" upper="1.9198621771937625091"/>
479
+ <joint_properties friction="0.0"/>
480
+ </joint>
481
+ <joint name="pip_p" type="revolute">
482
+ <origin xyz="6.5817319321070585914e-05 -0.04104892419324798758 -6.7832350073549884523e-05" rpy="-0.00057911586366674895881 0.00037050380380514630384 -1.5707967559243394273"/>
483
+ <parent link="pinky_pp"/>
484
+ <child link="pinky_dp"/>
485
+ <axis xyz="0 0 1"/>
486
+ <limit effort="1" velocity="20" lower="-0.1745329251994329478" upper="1.9198621771937625091"/>
487
+ <joint_properties friction="0.0"/>
488
+ </joint>
489
+ <joint name="mcp_p2" type="revolute">
490
+ <origin xyz="0.00044999999999942308371 0.011900000000000136163 -0.01285000000095160716" rpy="-1.5707963267948901187 1.5707963267948679142 0"/>
491
+ <parent link="mcp_4"/>
492
+ <child link="pinky_pp"/>
493
+ <axis xyz="0 0 1"/>
494
+ <limit effort="1" velocity="20" lower="-0.26179938779914940783" upper="2.2689280275926284602"/>
495
+ <joint_properties friction="0.0"/>
496
+ </joint>
497
+ <joint name="mcp_p" type="revolute">
498
+ <origin xyz="-0.011690517476412733144 -0.04305841731162472763 0.094882338690386619495" rpy="1.9230910059425032621 -1.2151655686968523273 -1.9156054830100193165"/>
499
+ <parent link="palm_right"/>
500
+ <child link="mcp_4"/>
501
+ <axis xyz="0 0 1"/>
502
+ <limit effort="1" velocity="20" lower="-0.52359877559829881566" upper="0.52359877559829881566"/>
503
+ <joint_properties friction="0.0"/>
504
+ </joint>
505
+ <link name="thumb_mc_right">
506
+ <inertial>
507
+ <origin xyz="-0.0016935865029098326646 -0.020210248526407383063 -0.0060325559286673741122" rpy="0 0 0"/>
508
+ <mass value="0.01809108122181146"/>
509
+ <inertia ixx="3.890841183493018996e-06" ixy="-2.9964901780270823671e-07" ixz="6.7533347392471751343e-08" iyy="1.5942962900839490293e-06" iyz="1.3079697467387851645e-07" izz="3.3398534638052647479e-06"/>
510
+ </inertial>
511
+ <visual>
512
+ <origin xyz="-0.014738084263467867568 -0.021212686249319788467 -0.015091575712131134746" rpy="0.97337928639691750909 -0.99971690513084077168 0.83594055961233915131"/>
513
+ <geometry>
514
+ <mesh filename="assets/t1.stl"/>
515
+ </geometry>
516
+ <material name="t1_material">
517
+ <color rgba="0.91764705882352937127 0.91764705882352937127 0.91764705882352937127 1.0"/>
518
+ </material>
519
+ </visual>
520
+ <collision>
521
+ <origin xyz="-0.014738084263467867568 -0.021212686249319788467 -0.015091575712131134746" rpy="0.97337928639691750909 -0.99971690513084077168 0.83594055961233915131"/>
522
+ <geometry>
523
+ <mesh filename="assets/t1.stl"/>
524
+ </geometry>
525
+ </collision>
526
+ </link>
527
+ <link name="thumb_pp">
528
+ <inertial>
529
+ <origin xyz="0.00093845134115162168621 -0.030099080632036544908 -0.016325980243802523662" rpy="0 0 0"/>
530
+ <mass value="0.035005649325678553363"/>
531
+ <inertia ixx="1.3314476232042362161e-05" ixy="1.7590627951876447482e-07" ixz="7.2316833363281050409e-08" iyy="4.136544184910209209e-06" iyz="-3.2222278950606029932e-06" izz="1.1508733598987962008e-05"/>
532
+ </inertial>
533
+ <visual>
534
+ <origin xyz="-0.0090000000000007244344 -0.05999980000000110919 -0.023599999999900405506" rpy="1.5707963267948974462 -1.1828120143115827988e-14 -1.57079632679489678"/>
535
+ <geometry>
536
+ <mesh filename="assets/t2.stl"/>
537
+ </geometry>
538
+ <material name="t2_material">
539
+ <color rgba="0.99215686274509806708 0.99215686274509806708 0.99215686274509806708 1.0"/>
540
+ </material>
541
+ </visual>
542
+ <collision>
543
+ <origin xyz="-0.0090000000000007244344 -0.05999980000000110919 -0.023599999999900405506" rpy="1.5707963267948974462 -1.1828120143115827988e-14 -1.57079632679489678"/>
544
+ <geometry>
545
+ <mesh filename="assets/t2.stl"/>
546
+ </geometry>
547
+ </collision>
548
+ </link>
549
+ <link name="thumb_dp">
550
+ <inertial>
551
+ <origin xyz="-0.00013798474378660697008 -0.020872207455279234711 -0.0099770687395277363185" rpy="0 0 0"/>
552
+ <mass value="0.018480607007365298933"/>
553
+ <inertia ixx="4.2765872397224850488e-06" ixy="-7.9647283171848492117e-10" ixz="-4.8063536693520802461e-09" iyy="1.4970764426906150985e-06" iyz="-5.8744596198565671398e-07" izz="3.7891805046058543726e-06"/>
554
+ </inertial>
555
+ <visual>
556
+ <origin xyz="-3.8782293714987453592e-05 -0.038500828035054390774 -0.0014680254372141899547" rpy="-0.00015526927360580455081 -0.00019703944324336170046 -1.570796326794896336"/>
557
+ <geometry>
558
+ <mesh filename="assets/t3.stl"/>
559
+ </geometry>
560
+ <material name="t3_material">
561
+ <color rgba="0.97647058823529409022 0.97254901960784312376 0.97254901960784312376 1.0"/>
562
+ </material>
563
+ </visual>
564
+ <collision>
565
+ <origin xyz="-3.8782293714987453592e-05 -0.038500828035054390774 -0.0014680254372141899547" rpy="-0.00015526927360580455081 -0.00019703944324336170046 -1.570796326794896336"/>
566
+ <geometry>
567
+ <mesh filename="assets/t3.stl"/>
568
+ </geometry>
569
+ </collision>
570
+ </link>
571
+ <link name="thumb_tip">
572
+ <inertial>
573
+ <origin xyz="9.1377377873939322249e-05 -0.01497202671172666831 -0.0088811551911988379643" rpy="0 0 0"/>
574
+ <mass value="0.013097436717419946861"/>
575
+ <inertia ixx="1.8380971610695962503e-06" ixy="2.4816390739331679573e-08" ixz="2.4323882192464227917e-09" iyy="7.3720348821426234131e-07" iyz="-3.662883498400851325e-07" izz="1.4343570236482938597e-06"/>
576
+ </inertial>
577
+ <visual>
578
+ <origin xyz="0.0060714187805480553106 -0.019494980509104808952 -0.020927158677777907975" rpy="-1.5707963267948430452 2.1295587997715661316e-14 -3.141592653589793116"/>
579
+ <geometry>
580
+ <mesh filename="assets/t4.stl"/>
581
+ </geometry>
582
+ <material name="t4_material">
583
+ <color rgba="0.64705882352941179736 0.64705882352941179736 0.64705882352941179736 1.0"/>
584
+ </material>
585
+ </visual>
586
+ <collision>
587
+ <origin xyz="0.0060714187805480553106 -0.019494980509104808952 -0.020927158677777907975" rpy="-1.5707963267948430452 2.1295587997715661316e-14 -3.141592653589793116"/>
588
+ <geometry>
589
+ <mesh filename="assets/t4.stl"/>
590
+ </geometry>
591
+ </collision>
592
+ </link>
593
+ <joint name="dip_t" type="revolute">
594
+ <origin xyz="-3.8564916732621717932e-05 -0.038500552179839192535 -6.8025481267263224194e-05" rpy="-0.00019703774938394422568 0.00015527142312957397914 1.0893822014221158837e-05"/>
595
+ <parent link="thumb_dp"/>
596
+ <child link="thumb_tip"/>
597
+ <axis xyz="0 0 1"/>
598
+ <limit effort="1" velocity="20" lower="-1.7453292519943295336" upper="0.785398163397448279"/>
599
+ <joint_properties friction="0.0"/>
600
+ </joint>
601
+ <joint name="mcp_t" type="revolute">
602
+ <origin xyz="-0.010400000000000750658 -0.059999800000001261846 -0.023599999999900252851" rpy="-1.1999537453667003845e-16 -1.5707963140946192837 0"/>
603
+ <parent link="thumb_pp"/>
604
+ <child link="thumb_dp"/>
605
+ <axis xyz="0 0 1"/>
606
+ <limit effort="1" velocity="20" lower="-1.8325957145940461324" upper="0.785398163397448279"/>
607
+ <joint_properties friction="0.0"/>
608
+ </joint>
609
+ <joint name="cmc_t2" type="revolute">
610
+ <origin xyz="-0.0031479612979940724618 -0.040374910195936822288 0.0052750329215571489794" rpy="-1.2680493445054867863 -0.059693201235992220111 3.1414884687288249232"/>
611
+ <parent link="thumb_mc_right"/>
612
+ <child link="thumb_pp"/>
613
+ <axis xyz="0 0 1"/>
614
+ <limit effort="1" velocity="20" lower="-1.2217304763960306069" upper="1.570796326794896558"/>
615
+ <joint_properties friction="0.0"/>
616
+ </joint>
617
+ <joint name="cmc_t" type="revolute">
618
+ <origin xyz="0.01466339118003531436 0.026642338251219234435 0.033611244645212742799" rpy="0.7310493186081153949 -0.23348225521831431073 2.9391115213016831831"/>
619
+ <parent link="palm_right"/>
620
+ <child link="thumb_mc_right"/>
621
+ <axis xyz="0 0 1"/>
622
+ <limit effort="1" velocity="20" lower="-2.356194490192344837" upper="0.1745329251994329478"/>
623
+ <joint_properties friction="0.0"/>
624
+ </joint>
625
+ </robot>