Newer
Older
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by
Stephen Brawner (brawner@gmail.com)
Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="go2_description">
<link
name="base">
<inertial>
<origin
xyz="0.021112 0 -0.005366"
rpy="0 0 0" />
<mass
value="6.921" />
<inertia
ixx="0.02448"
ixy="0.00012166"
ixz="0.0014849"
iyy="0.098077"
iyz="-3.12E-05"
izz="0.107" />
</inertial>
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/go2_description/visuals/base.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/base_convex.stl" />
</geometry>
</collision>
</link>
<link
name="FL_hip">
<inertial>
<origin
xyz="-0.0054 0.00194 -0.000105"
rpy="0 0 0" />
<mass
value="0.678" />
<inertia
ixx="0.00048"
ixy="-3.01E-06"
ixz="1.11E-06"
iyy="0.000884"
iyz="-1.42E-06"
izz="0.000596" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/hip.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/hip_convex.stl" />
</geometry></collision>
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
</link>
<joint
name="FL_hip_joint"
type="revolute">
<origin
xyz="0.1934 0.0465 0"
rpy="0 0 0" />
<parent
link="base" />
<child
link="FL_hip" />
<axis
xyz="1 0 0" />
<limit
lower="-1.0472"
upper="1.0472"
effort="23.7"
velocity="30.1" />
</joint>
<link name="FL_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000111842" ixy="0.0" ixz="0.0" iyy="0.000059647" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="FL_hip_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.11215 0.04675 0"/>
<parent link="base"/>
<child link="FL_hip_rotor"/>
</joint>
<link
name="FL_thigh">
<inertial>
<origin
xyz="-0.00374 -0.0223 -0.0327"
rpy="0 0 0" />
<mass
value="1.152" />
<inertia
ixx="0.00584"
ixy="8.72E-05"
ixz="-0.000289"
iyy="0.0058"
iyz="0.000808"
izz="0.00103" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/thigh.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/thigh_convex.stl" />
</geometry></collision>
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
</link>
<joint
name="FL_thigh_joint"
type="revolute">
<origin
xyz="0 0.0955 0"
rpy="0 0 0" />
<parent
link="FL_hip" />
<child
link="FL_thigh" />
<axis
xyz="0 1 0" />
<limit
lower="-1.5708"
upper="3.4907"
effort="23.7"
velocity="30.1" />
</joint>
<link name="FL_thigh_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="FL_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.00015 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh_rotor"/>
</joint>
<link
name="FL_calf">
<inertial>
<origin
xyz="0.00548 -0.000975 -0.115"
rpy="0 0 0" />
<mass
value="0.154" />
<inertia
ixx="0.00108"
ixy="3.4E-07"
ixz="1.72E-05"
iyy="0.0011"
iyz="8.28E-06"
izz="3.29E-05" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/calf.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
Etienne ARLAUD
committed
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_upper_convex.stl" />
</geometry></collision>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_lower_convex.stl" />
</geometry></collision>
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
</link>
<joint
name="FL_calf_joint"
type="revolute">
<origin
xyz="0 0 -0.213"
rpy="0 0 0" />
<parent
link="FL_thigh" />
<child
link="FL_calf" />
<axis
xyz="0 1 0" />
<limit
lower="-2.7227"
upper="-0.83776"
effort="45.43"
velocity="15.70" />
</joint>
<link name="FL_calf_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="FL_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.03235 0"/>
<parent link="FL_thigh"/>
<child link="FL_calf_rotor"/>
</joint>
<link
name="FL_foot">
<inertial>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<mass
value="0.04" />
<inertia
ixx="9.6e-06"
ixy="0"
ixz="0"
iyy="9.6e-06"
iyz="0"
izz="9.6e-06" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/foot.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/foot_convex.stl" />
</geometry></collision>
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
</link>
<joint
name="FL_foot_joint"
type="fixed" dont_collapse="true">
<origin
xyz="0 0 -0.213"
rpy="0 0 0" />
<parent
link="FL_calf" />
<child
link="FL_foot" />
<axis
xyz="0 0 0" />
</joint>
<link
name="FR_hip">
<inertial>
<origin
xyz="-0.0054 -0.00194 -0.000105"
rpy="0 0 0" />
<mass
value="0.678" />
<inertia
ixx="0.00048"
ixy="3.01E-06"
ixz="1.11E-06"
iyy="0.000884"
iyz="1.42E-06"
izz="0.000596" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="3.1415 0 0" />
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/hip.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="3.1415 0 0" />
<mesh filename="package://example-robot-data/robots/go2_description/collisions/hip_convex.stl" />
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
</geometry>
</collision>
</link>
<joint
name="FR_hip_joint"
type="revolute">
<origin
xyz="0.1934 -0.0465 0"
rpy="0 0 0" />
<parent
link="base" />
<child
link="FR_hip" />
<axis
xyz="1 0 0" />
<limit
lower="-1.0472"
upper="1.0472"
effort="23.7"
velocity="30.1" />
</joint>
<link name="FR_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000111842" ixy="0.0" ixz="0.0" iyy="0.000059647" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="FR_hip_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.11215 -0.04675 0"/>
<parent link="base"/>
<child link="FR_hip_rotor"/>
</joint>
<link
name="FR_thigh">
<inertial>
<origin
xyz="-0.00374 0.0223 -0.0327"
rpy="0 0 0" />
<mass
value="1.152" />
<inertia
ixx="0.00584"
ixy="-8.72E-05"
ixz="-0.000289"
iyy="0.0058"
iyz="-0.000808"
izz="0.00103" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/thigh_mirror.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/thigh_mirror_convex.stl" />
</geometry></collision>
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
</link>
<joint
name="FR_thigh_joint"
type="revolute">
<origin
xyz="0 -0.0955 0"
rpy="0 0 0" />
<parent
link="FR_hip" />
<child
link="FR_thigh" />
<axis
xyz="0 1 0" />
<limit
lower="-1.5708"
upper="3.4907"
effort="23.7"
velocity="30.1" />
</joint>
<link name="FR_thigh_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="FR_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.00015 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh_rotor"/>
</joint>
<link
name="FR_calf">
<inertial>
<origin
xyz="0.00548 0.000975 -0.115"
rpy="0 0 0" />
<mass
value="0.154" />
<inertia
ixx="0.00108"
ixy="-3.4E-07"
ixz="1.72E-05"
iyy="0.0011"
iyz="-8.28E-06"
izz="3.29E-05" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/calf_mirror.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
Etienne ARLAUD
committed
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_upper_mirror_convex.stl" />
</geometry></collision>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_lower_mirror_convex.stl" />
</geometry></collision>
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
</link>
<joint
name="FR_calf_joint"
type="revolute">
<origin
xyz="0 0 -0.213"
rpy="0 0 0" />
<parent
link="FR_thigh" />
<child
link="FR_calf" />
<axis
xyz="0 1 0" />
<limit
lower="-2.7227"
upper="-0.83776"
effort="45.43"
velocity="15.70" />
</joint>
<link name="FR_calf_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="FR_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.03235 0"/>
<parent link="FR_thigh"/>
<child link="FR_calf_rotor"/>
</joint>
<link
name="FR_foot">
<inertial>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<mass
value="0.04" />
<inertia
ixx="9.6e-06"
ixy="0"
ixz="0"
iyy="9.6e-06"
iyz="0"
izz="9.6e-06" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/foot.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/foot_convex.stl" />
</geometry></collision>
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
</link>
<joint
name="FR_foot_joint"
type="fixed" dont_collapse="true">
<origin
xyz="0 0 -0.213"
rpy="0 0 0" />
<parent
link="FR_calf" />
<child
link="FR_foot" />
<axis
xyz="0 0 0" />
</joint>
<link
name="RL_hip">
<inertial>
<origin
xyz="0.0054 0.00194 -0.000105"
rpy="0 0 0" />
<mass
value="0.678" />
<inertia
ixx="0.00048"
ixy="3.01E-06"
ixz="-1.11E-06"
iyy="0.000884"
iyz="-1.42E-06"
izz="0.000596" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 3.1415 0" />
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/hip.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 3.1415 0" />
<mesh filename="package://example-robot-data/robots/go2_description/collisions/hip_convex.stl" />
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
</geometry>
</collision>
</link>
<joint
name="RL_hip_joint"
type="revolute">
<origin
xyz="-0.1934 0.0465 0"
rpy="0 0 0" />
<parent
link="base" />
<child
link="RL_hip" />
<axis
xyz="1 0 0" />
<limit
lower="-1.0472"
upper="1.0472"
effort="23.7"
velocity="30.1" />
</joint>
<link name="RL_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000111842" ixy="0.0" ixz="0.0" iyy="0.000059647" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="RL_hip_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.11215 0.04675 0"/>
<parent link="base"/>
<child link="RL_hip_rotor"/>
</joint>
<link
name="RL_thigh">
<inertial>
<origin
xyz="-0.00374 -0.0223 -0.0327"
rpy="0 0 0" />
<mass
value="1.152" />
<inertia
ixx="0.00584"
ixy="8.72E-05"
ixz="-0.000289"
iyy="0.0058"
iyz="0.000808"
izz="0.00103" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/thigh.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/thigh_convex.stl" />
</geometry></collision>
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
</link>
<joint
name="RL_thigh_joint"
type="revolute">
<origin
xyz="0 0.0955 0"
rpy="0 0 0" />
<parent
link="RL_hip" />
<child
link="RL_thigh" />
<axis
xyz="0 1 0" />
<limit
lower="-0.5236"
upper="4.5379"
effort="23.7"
velocity="30.1" />
</joint>
<link name="RL_thigh_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="RL_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.00015 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh_rotor"/>
</joint>
<link
name="RL_calf">
<inertial>
<origin
xyz="0.00548 -0.000975 -0.115"
rpy="0 0 0" />
<mass
value="0.154" />
<inertia
ixx="0.00108"
ixy="3.4E-07"
ixz="1.72E-05"
iyy="0.0011"
iyz="8.28E-06"
izz="3.29E-05" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/calf.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
Etienne ARLAUD
committed
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_upper_convex.stl" />
</geometry></collision>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_lower_convex.stl" />
</geometry></collision>
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
</link>
<joint
name="RL_calf_joint"
type="revolute">
<origin
xyz="0 0 -0.213"
rpy="0 0 0" />
<parent
link="RL_thigh" />
<child
link="RL_calf" />
<axis
xyz="0 1 0" />
<limit
lower="-2.7227"
upper="-0.83776"
effort="45.43"
velocity="15.70" />
</joint>
<link name="RL_calf_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="RL_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.03235 0"/>
<parent link="RL_thigh"/>
<child link="RL_calf_rotor"/>
</joint>
<link
name="RL_foot">
<inertial>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<mass
value="0.04" />
<inertia
ixx="9.6e-06"
ixy="0"
ixz="0"
iyy="9.6e-06"
iyz="0"
izz="9.6e-06" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/foot.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/foot_convex.stl" />
</geometry></collision>
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
</link>
<joint
name="RL_foot_joint"
type="fixed" dont_collapse="true">
<origin
xyz="0 0 -0.213"
rpy="0 0 0" />
<parent
link="RL_calf" />
<child
link="RL_foot" />
<axis
xyz="0 0 0" />
</joint>
<link
name="RR_hip">
<inertial>
<origin
xyz="0.0054 -0.00194 -0.000105"
rpy="0 0 0" />
<mass
value="0.678" />
<inertia
ixx="0.00048"
ixy="-3.01E-06"
ixz="-1.11E-06"
iyy="0.000884"
iyz="1.42E-06"
izz="0.000596" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="3.1415 3.1415 0" />
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/hip.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="3.1415 3.1415 0" />
<mesh filename="package://example-robot-data/robots/go2_description/collisions/hip_convex.stl" />
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
</geometry>
</collision>
</link>
<joint
name="RR_hip_joint"
type="revolute">
<origin
xyz="-0.1934 -0.0465 0"
rpy="0 0 0" />
<parent
link="base" />
<child
link="RR_hip" />
<axis
xyz="1 0 0" />
<limit
lower="-1.0472"
upper="1.0472"
effort="23.7"
velocity="30.1" />
</joint>
<link name="RR_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000111842" ixy="0.0" ixz="0.0" iyy="0.000059647" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="RR_hip_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.11215 -0.04675 0"/>
<parent link="base"/>
<child link="RR_hip_rotor"/>
</joint>
<link
name="RR_thigh">
<inertial>
<origin
xyz="-0.00374 0.0223 -0.0327"
rpy="0 0 0" />
<mass
value="1.152" />
<inertia
ixx="0.00584"
ixy="-8.72E-05"
ixz="-0.000289"
iyy="0.0058"
iyz="-0.000808"
izz="0.00103" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/thigh_mirror.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/thigh_mirror_convex.stl" />
</geometry></collision>
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
</link>
<joint
name="RR_thigh_joint"
type="revolute">
<origin
xyz="0 -0.0955 0"
rpy="0 0 0" />
<parent
link="RR_hip" />
<child
link="RR_thigh" />
<axis
xyz="0 1 0" />
<limit
lower="-0.5236"
upper="4.5379"
effort="23.7"
velocity="30.1" />
</joint>
<link name="RR_thigh_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="RR_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.00015 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh_rotor"/>
</joint>
<link
name="RR_calf">
<inertial>
<origin
xyz="0.00548 0.000975 -0.115"
rpy="0 0 0" />
<mass
value="0.154" />
<inertia
ixx="0.00108"
ixy="-3.4E-07"
ixz="1.72E-05"
iyy="0.0011"
iyz="-8.28E-06"
izz="3.29E-05" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/calf_mirror.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
Etienne ARLAUD
committed
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_upper_mirror_convex.stl" />
</geometry></collision>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/calf_lower_mirror_convex.stl" />
</geometry></collision>
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
</link>
<joint
name="RR_calf_joint"
type="revolute">
<origin
xyz="0 0 -0.213"
rpy="0 0 0" />
<parent
link="RR_thigh" />
<child
link="RR_calf" />
<axis
xyz="0 1 0" />
<limit
lower="-2.7227"
upper="-0.83776"
effort="45.43"
velocity="15.70" />
</joint>
<link name="RR_calf_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.089"/>
<inertia ixx="0.000059647" ixy="0.0" ixz="0.0" iyy="0.000111842" iyz="0.0" izz="0.000059647"/>
</inertial>
</link>
<joint name="RR_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0.03235 0"/>
<parent link="RR_thigh"/>
<child link="RR_calf_rotor"/>
</joint>
<link
name="RR_foot">
<inertial>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<mass
value="0.04" />
<inertia
ixx="9.6e-06"
ixy="0"
ixz="0"
iyy="9.6e-06"
iyz="0"
izz="9.6e-06" />
</inertial>
<visual>
<geometry>
<mesh
filename="package://example-robot-data/robots/go2_description/visuals/foot.dae" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision><geometry>
<mesh filename="package://example-robot-data/robots/go2_description/collisions/foot_convex.stl" />
</geometry></collision>
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
</link>
<joint
name="RR_foot_joint"
type="fixed" dont_collapse="true">
<origin
xyz="0 0 -0.213"
rpy="0 0 0" />
<parent
link="RR_calf" />
<child
link="RR_foot" />
<axis
xyz="0 0 0" />
</joint>
<link
name="imu">
<inertial>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<mass
value="0" />
<inertia
ixx="0"
ixy="0"
ixz="0"
iyy="0"
iyz="0"
izz="0" />
</inertial>
</link>