-
Notifications
You must be signed in to change notification settings - Fork 43
/
JAXON_JVRCmain_hrpsys_bush.wrl
1879 lines (1868 loc) · 91.6 KB
/
JAXON_JVRCmain_hrpsys_bush.wrl
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
57
58
59
60
61
62
63
64
65
66
67
68
69
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
120
121
122
123
124
125
126
127
128
129
130
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
181
182
183
184
185
186
187
188
189
190
191
192
193
194
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
245
246
247
248
249
250
251
252
253
254
255
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
292
293
294
295
296
297
298
299
300
301
302
303
304
305
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
358
359
360
361
362
363
364
365
366
367
368
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
419
420
421
422
423
424
425
426
427
428
429
430
431
432
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
483
484
485
486
487
488
489
490
491
492
493
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
530
531
532
533
534
535
536
537
538
539
540
541
542
543
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
596
597
598
599
600
601
602
603
604
605
606
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
657
658
659
660
661
662
663
664
665
666
667
668
669
670
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
721
722
723
724
725
726
727
728
729
730
731
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
768
769
770
771
772
773
774
775
776
777
778
779
780
781
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
834
835
836
837
838
839
840
841
842
843
844
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
895
896
897
898
899
900
901
902
903
904
905
906
907
908
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
959
960
961
962
963
964
965
966
967
968
969
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
#VRML V2.0 utf8
PROTO Joint [
exposedField SFVec3f center 0 0 0
exposedField MFNode children []
exposedField MFFloat llimit []
exposedField MFFloat lvlimit []
exposedField SFRotation limitOrientation 0 0 1 0
exposedField SFString name ""
exposedField SFRotation rotation 0 0 1 0
exposedField SFVec3f scale 1 1 1
exposedField SFRotation scaleOrientation 0 0 1 0
exposedField MFFloat stiffness [ 0 0 0 ]
exposedField SFVec3f translation 0 0 0
exposedField MFFloat ulimit []
exposedField MFFloat uvlimit []
exposedField MFFloat climit []
exposedField SFString jointType ""
exposedField SFInt32 jointId -1
exposedField SFVec3f jointAxis 0 0 1
exposedField SFFloat gearRatio 1
exposedField SFFloat rotorInertia 0
exposedField SFFloat rotorResistor 0
exposedField SFFloat torqueConst 1
exposedField SFFloat encoderPulse 1
]
{
Transform {
center IS center
children IS children
rotation IS rotation
scale IS scale
scaleOrientation IS scaleOrientation
translation IS translation
}
}
PROTO Segment [
field SFVec3f bboxCenter 0 0 0
field SFVec3f bboxSize -1 -1 -1
exposedField SFVec3f centerOfMass 0 0 0
exposedField MFNode children [ ]
exposedField SFNode coord NULL
exposedField MFNode displacers [ ]
exposedField SFFloat mass 0
exposedField MFFloat momentsOfInertia [ 0 0 0 0 0 0 0 0 0 ]
exposedField SFString name ""
eventIn MFNode addChildren
eventIn MFNode removeChildren
]
{
Group {
addChildren IS addChildren
bboxCenter IS bboxCenter
bboxSize IS bboxSize
children IS children
removeChildren IS removeChildren
}
}
PROTO Humanoid [
field SFVec3f bboxCenter 0 0 0
field SFVec3f bboxSize -1 -1 -1
exposedField SFVec3f center 0 0 0
exposedField MFNode humanoidBody [ ]
exposedField MFString info [ ]
exposedField MFNode joints [ ]
exposedField SFString name ""
exposedField SFRotation rotation 0 0 1 0
exposedField SFVec3f scale 1 1 1
exposedField SFRotation scaleOrientation 0 0 1 0
exposedField MFNode segments [ ]
exposedField MFNode sites [ ]
exposedField SFVec3f translation 0 0 0
exposedField SFString version "1.1"
exposedField MFNode viewpoints [ ]
]
{
Transform {
bboxCenter IS bboxCenter
bboxSize IS bboxSize
center IS center
rotation IS rotation
scale IS scale
scaleOrientation IS scaleOrientation
translation IS translation
children [
Group {
children IS viewpoints
}
Group {
children IS humanoidBody
}
]
}
}
PROTO VisionSensor [
exposedField SFVec3f translation 0 0 0
exposedField SFRotation rotation 0 0 1 0
exposedField MFNode children [ ]
exposedField SFFloat fieldOfView 0.785398
exposedField SFString name ""
exposedField SFFloat frontClipDistance 0.01
exposedField SFFloat backClipDistance 10.0
exposedField SFString type "NONE"
exposedField SFInt32 sensorId -1
exposedField SFInt32 width 320
exposedField SFInt32 height 240
exposedField SFFloat frameRate 30
]
{
Transform {
rotation IS rotation
translation IS translation
children IS children
}
}
PROTO RangeSensor [
exposedField SFVec3f translation 0 0 0
exposedField SFRotation rotation 0 0 1 0
exposedField MFNode children [ ]
exposedField SFInt32 sensorId -1
exposedField SFFloat scanAngle 3.14159 #[rad]
exposedField SFFloat scanStep 0.1 #[rad]
exposedField SFFloat scanRate 10 #[Hz]
exposedField SFFloat minDistance 0.01
exposedField SFFloat maxDistance 10
]
{
Transform {
rotation IS rotation
translation IS translation
children IS children
}
}
PROTO ForceSensor [
exposedField SFVec3f maxForce -1 -1 -1
exposedField SFVec3f maxTorque -1 -1 -1
exposedField SFVec3f translation 0 0 0
exposedField SFRotation rotation 0 0 1 0
exposedField SFInt32 sensorId -1
]
{
Transform {
translation IS translation
rotation IS rotation
}
}
PROTO Gyro [
exposedField SFVec3f maxAngularVelocity -1 -1 -1
exposedField SFVec3f translation 0 0 0
exposedField SFRotation rotation 0 0 1 0
exposedField SFInt32 sensorId -1
]
{
Transform {
translation IS translation
rotation IS rotation
}
}
PROTO AccelerationSensor [
exposedField SFVec3f maxAcceleration -1 -1 -1
exposedField SFVec3f translation 0 0 0
exposedField SFRotation rotation 0 0 1 0
exposedField SFInt32 sensorId -1
]
{
Transform {
translation IS translation
rotation IS rotation
}
}
PROTO SpotLightDevice [
exposedField SFVec3f attenuation 1 0 0 # [0,)
exposedField SFFloat beamWidth 1.570796 # (0,/2]
exposedField SFColor color 1 1 1 # [0,1]
exposedField SFFloat cutOffAngle 0.785398 # (0,/2]
exposedField SFVec3f direction 0 0 -1 # (-,)
exposedField SFFloat intensity 1 # [0,1]
exposedField SFBool on TRUE
exposedField SFVec3f translation 0 0 0
exposedField SFRotation rotation 0 0 1 0
]
{
Transform {
translation IS translation
rotation IS rotation
}
}
PROTO Surface [
field SFVec3f bboxCenter 0 0 0
field SFVec3f bboxSize -1 -1 -1
field MFNode visual [ ]
field MFNode collision [ ]
eventIn MFNode addChildren
eventIn MFNode removeChildren
]
{
Group {
addChildren IS addChildren
bboxCenter IS bboxCenter
bboxSize IS bboxSize
children IS visual
removeChildren IS removeChildren
}
}
DEF JAXON_JVRC Humanoid {
humanoidBody [
DEF WAIST Joint {
jointType "free"
jointAxis 0 0 0
translation 0 0 1.0225
children [
DEF BODY Segment {
#mass 13.417
#centerOfMass -0.07476 -0.00162 0.01632
#momentsOfInertia [0.105595 -0.013907 -0.00090839 -0.013907 0.13452 0.00169817 -0.00090839 0.00169817 0.179963 ]
## mass refine 2015.4.25
#mass 18.7
#centerOfMass -0.1159 -0.00067 -0.023
## fix by hand 2015.4.26
mass 22.7
centerOfMass -0.1059 -0.00067 -0.023
momentsOfInertia [0.229835 0.00171 0.135708 0.00171 0.535336 0.000616 0.135708 0.000616 0.549159]
children [
Surface {
visual [ Inline { url "BODY.wrl" } ] # visual
collision [ Inline { url "collision_directory/BODY.wrl" } ] # collision
} # surface
DEF gsensor AccelerationSensor{
translation 0 0 0
rotation 0.707107 0 -0.707107 3.14159
sensorId 0
} #Sensor
DEF gyrometer Gyro{
translation 0 0 0
rotation 0.707107 0 -0.707107 3.14159
sensorId 0
} #Sensor
]
} #Segment BODY
DEF CHEST_JOINT0 Joint {
translation 0.006 0 0.128
jointId 12
jointType "rotate"
jointAxis 1 0 0
## with margin
ulimit 0.198551
llimit -0.198551
## actual measure
# ulimit 0.228551
# llimit -0.309578
## from CAD
# ulimit 0.436332
# llimit -0.436332
uvlimit 4
lvlimit -4
climit [100.0]
gearRatio 384
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF CHEST_LINK0 Segment {
mass 0.866
centerOfMass -0.0084 0.00137 0.01359
momentsOfInertia [0.00125384 0 0 0 0.00123407 0 0 0 0.000677392 ]
children [
Surface {
visual [ Inline { url "CHEST_LINK0.wrl" } ] # visual
collision [ Inline { url "collision_directory/CHEST_LINK0.wrl" } ] # collision
} # surface
]
} #Segment CHEST_LINK0
DEF CHEST_JOINT1 Joint {
translation 0 0 0.025
jointId 13
jointType "rotate"
jointAxis 0 1 0
## for min-max
ulimit +0.6108652381980153 # +35deg
# llimit -0.05235987755982989 # -3deg
llimit -0.034906585040 # -2deg
## with margin
# ulimit 1.37639
# llimit 0
## actual measure
# ulimit 0.6108652381980153 # +35.0[deg]
# llimit -0.04363323129985824 # -2.5[deg]
## from CAD
# ulimit 1.39626
# llimit 0
uvlimit 4
lvlimit -4
climit [100.0]
gearRatio 384
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF CHEST_LINK1 Segment {
#mass 18.768
#centerOfMass -0.07913 0.00529 0.04387
#momentsOfInertia [0.232458 -0.00962265 0.00541821 -0.00962265 0.271384 -0.0229267 0.00541821 -0.0229267 0.426617 ]
## mass refine 2015.4.25
#mass 15.23
#centerOfMass -0.11697 0.00390 0.03652
## fix by hand 2015.4.26
mass 18.23
centerOfMass -0.111697 0.00390 0.03652
momentsOfInertia [0.186526 0.003889 -0.039414 0.003889 0.418012 0.001281 -0.039414 0.001281 0.477668]
children [
Surface {
visual [ Inline { url "CHEST_LINK1.wrl" } ] # visual
collision [ Inline { url "collision_directory/CHEST_LINK1.wrl" } ] # collision
} # surface
]
} #Segment CHEST_LINK1
DEF CHEST_JOINT2 Joint {
translation 0 0 0.3085
jointId 14
jointType "rotate"
jointAxis 0 0 1
# with margin
ulimit 1.0566
llimit -1.0566
# actual measure
# ulimit 1.0866
# llimit -1.30716
# from CAD
# ulimit 1.5708
# llimit -1.5708
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 384
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF CHEST_LINK2 Segment {
#mass 33.649
#centerOfMass -0.12477 -0.02127 -0.0874
#momentsOfInertia [0.416269 -0.0305686 0.0316549 -0.0305686 0.365396 0.0727096 0.0316549 0.0727096 0.36815 ]
## mass refine 2015.4.25
#mass 25.33
#centerOfMass -0.13693 -0.00113 -0.03796
## fix by hand 2015.4.26
mass 31.33
centerOfMass -0.13693 -0.00113 -0.05796
momentsOfInertia [0.510746 0.005161 0.143334 0.005161 1.09582 0.004687 0.143334 0.004687 1.02505]
children [
Surface {
visual [ Inline { url "CHEST_LINK2.wrl" } ] # visual
collision [ Inline { url "collision_directory/CHEST_LINK2.wrl" } ] # collision
} # surface
### comment out ## this is jvrc's regulation
# Transform {
# translation 0.10 0.0 0.06
# children [
# DEF JVRC-Robot-Marker Shape {
# geometry Sphere { radius 0.025 }
# appearance Appearance {
# material Material {
# diffuseColor 1.0 0.0 0.0
# emissiveColor 1.0 0.0 0.0
# }
# }
# }
# ]
# }
]
} #Segment CHEST_LINK2
DEF CHEST_CAMERA VisionSensor {
name "fisheye"
translation 0.164 0 -0.007
rotation 0.3243587440432960 -0.3243587440432962 -0.8885847232117547 1.6886478500368325
type "COLOR"
frontClipDistance 0.1
width 640
height 640
frameRate 5
fieldOfView 2.61799 ## 150 deg / fisheye like
sensorId 2
}
DEF HEAD_JOINT0 Joint {
translation -0.015 0 0.0835
jointId 15
jointType "rotate"
jointAxis 0 0 1
# with margin
ulimit 0.5410520681182421 # +31[deg] for min-max table. please fix model shape
llimit -0.5759586531581288 # -33[deg] for min-max table. please fix model shape
# actual measure
# ulimit 0.739147
# llimit -0.846485
# from CAD
# ulimit 3.14159
# llimit -3.14159
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF HEAD_LINK0 Segment {
mass 1.086
centerOfMass -0.01227 3e-05 0.03231
momentsOfInertia [0.0031 0 0 0 0.0035 0 0 0 0.00119 ]
children [
Surface {
visual [ Inline { url "HEAD_LINK0.wrl" } ] # visual
collision [ Inline { url "collision_directory/HEAD_LINK0.wrl" } ] # collision
} # surface
]
} #Segment HEAD_LINK0
DEF HEAD_JOINT1 Joint {
translation 0 0 0.102
jointId 16
jointType "rotate"
jointAxis 0 1 0
# with margin
ulimit 0.698132
llimit -0.5759586531581288 # -33[deg] for min-max table. please fix model shape
# actual measure
# ulimit 0.855211
# llimit -0.783979
# from CAD
# ulimit 0.698132
# llimit -0.785398
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF HEAD_LINK1 Segment {
#mass 0.5
#centerOfMass 0 0 0.02
#momentsOfInertia [0.01 0 0 0 0.01 0 0 0 0.005 ]
### add camera mass
mass 4.274
centerOfMass 0.042 0.004 0.058
momentsOfInertia [0.035683 0.000877 -0.003172 0.000877 0.040037 0.000652 -0.003172 0.000652 0.035345]
children [
Surface {
visual [ Inline { url "HEAD_LINK1_JVRC.wrl" } ] # visual
collision [ Inline { url "collision_directory/HEAD_LINK1_JVRC.wrl" } ] # collision
} # surface
]
} #Segment HEAD_LINK1
DEF HEAD_LEFT_CAMERA VisionSensor {
name "LEFT_CAMERA"
translation 0.1005 0.035 0.05425
rotation 0.57735026919 -0.57735026919 -0.57735026919 2.094395102393
type "COLOR_DEPTH"
frontClipDistance 0.05
backClipDistance 30.0
width 640
height 480
frameRate 15
fieldOfView 1.5708
sensorId 0
}
DEF HEAD_RIGHT_CAMERA VisionSensor {
name "RIGHT_CAMERA"
translation 0.1005 -0.035 0.05425
rotation 0.57735026919 -0.57735026919 -0.57735026919 2.094395102393
type "COLOR"
frontClipDistance 0.05
backClipDistance 30.0
width 640
height 480
frameRate 15
fieldOfView 1.5708
sensorId 1
}
DEF HeadMainLight SpotLightDevice {
translation 0.1005 0.035 0.05425
# rotation
attenuation 1 0 0.01
beamWidth 0.7
# color
cutOffAngle 0.75
direction 1 0 0
# intensity
# on
}
DEF motor_joint Joint {
translation 0.0559 0 0.14425
#jointId 37
jointType "rotate"
jointAxis 1 0 0
#ulimit 0.144751
#llimit -1.4208
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 1
rotorInertia 0.8
children [
DEF RANGE_LINK Segment {
mass 0.4
centerOfMass 0.03 0 0
momentsOfInertia [0.00024 0 0 0 0.00024 0 0 0 0.00024 ]
children [
Surface {
visual [ Inline { url "RANGE_SENSOR.wrl" } ] # visual
collision [ Inline { url "collision_directory/RANGE_SENSOR.wrl" } ] # collision
} # surface
]
} #Segment RANGE_LINK
DEF HEAD_RANGE RangeSensor {
translation 0.03 0 0.015
rotation 0.57735026919 -0.57735026919 -0.57735026919 2.094395102393
sensorId 0
#scanAngle 2.3561944901923439 ## 135 deg
#scanStep 0.0026019423636569 ## 512 line
#scanRate 100
scanAngle 2.8797932657906435 ## 165 deg
scanStep 0.004363323129985825 ## 661 line
scanRate 40
minDistance 0.2
maxDistance 30.0
}
]
} #Joint motor_joint
]
} #Joint HEAD_JOINT1
]
} #Joint HEAD_JOINT0
DEF LARM_JOINT0 Joint {
translation 0 0.0875 0
jointId 25
jointType "rotate"
jointAxis 0 0 1
# with margin
ulimit 0.144751
llimit -1.4208
# actual measure
# ulimit 0.174751
# llimit -1.4508
# from CAD
# ulimit 0.349066
# llimit -1.5708
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF LARM_LINK0 Segment {
mass 1.048
centerOfMass -0.01745 0.00887 -0.00015
momentsOfInertia [0.0029762 0 0 0 0.00235085 0 0 0 0.00355486 ]
children [
Surface {
visual [ Inline { url "LARM_LINK0.wrl" } ] # visual
collision [ Inline { url "collision_directory/LARM_LINK0.wrl" } ] # collision
} # surface
]
} #Segment LARM_LINK0
DEF LARM_JOINT1 Joint {
translation 0 0.07275 0
jointId 26
jointType "rotate"
jointAxis 0 1 0
ulimit 3.14159
llimit -3.14159
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF LARM_LINK1 Segment {
mass 0.298
centerOfMass 0.00011 0.01799 0.00288
momentsOfInertia [0.000412035 0 0 0 0.000251611 0 0 0 0.000376771 ]
children [
Surface {
visual [ Inline { url "LARM_LINK1.wrl" } ] # visual
collision [ Inline { url "collision_directory/LARM_LINK1.wrl" } ] # collision
} # surface
]
} #Segment LARM_LINK1
DEF LARM_JOINT2 Joint {
translation 0 0.057 0
jointId 27
jointType "rotate"
jointAxis 1 0 0
# with margin
ulimit 3.14159
llimit 0.2762
# actual measure
# ulimit 3.27031
# llimit 0.2462
# from CAD
# ulimit 3.14159
# llimit 0
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF LARM_LINK2 Segment {
mass 2.168
centerOfMass 0.00845 0.00671 -0.0881
momentsOfInertia [0.0127408 0 0 0 0.0133751 0 0 0 0.00460362 ]
children [
Surface {
visual [ Inline { url "LARM_LINK2_detail.wrl" } ] # visual
collision [ Inline { url "collision_directory/LARM_LINK2_detail.wrl" } ] # collision
} # surface
]
} #Segment LARM_LINK2
DEF LARM_JOINT3 Joint {
translation 0 0 -0.1965
jointId 28
jointType "rotate"
jointAxis 0 0 1
ulimit 3.14159
llimit -3.14159
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF LARM_LINK3 Segment {
mass 1.315
centerOfMass 0.01393 4e-05 -0.07574
momentsOfInertia [0.00451716 0 0 0 0.0055237 0 0 0 0.00217053 ]
children [
Surface {
visual [ Inline { url "LARM_LINK3.wrl" } ] # visual
collision [ Inline { url "collision_directory/LARM_LINK3.wrl" } ] # collision
} # surface
]
} #Segment LARM_LINK3
DEF LARM_JOINT4 Joint {
translation 0 0 -0.126
jointId 29
jointType "rotate"
jointAxis 0 1 0
# with margin
ulimit 1.0472
llimit -2.19006
# actual measure
# ulimit 1.0821
# llimit -2.22006
# from CAD
# ulimit 1.0472
# llimit -2.35619
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF LARM_LINK4 Segment {
mass 1.641
centerOfMass 3e-05 0.00551 -0.0426
momentsOfInertia [0.00665559 0 0 0 0.00598857 0 0 0 0.00288237 ]
children [
Surface {
visual [ Inline { url "LARM_LINK4.wrl" } ] # visual
collision [ Inline { url "collision_directory/LARM_LINK4.wrl" } ] # collision
} # surface
]
} #Segment LARM_LINK4
DEF LARM_JOINT5 Joint {
translation 0 0 -0.1275
jointId 30
jointType "rotate"
jointAxis 0 0 1
ulimit 3.14159
llimit -3.14159
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF LARM_LINK5 Segment {
mass 1.305
centerOfMass 0.01271 2e-05 -0.08415
momentsOfInertia [0.00533939 0 0 0 0.00624028 0 0 0 0.00205604 ]
children [
Surface {
visual [ Inline { url "LARM_LINK5.wrl" } ] # visual
collision [ Inline { url "collision_directory/LARM_LINK5.wrl" } ] # collision
} # surface
]
} #Segment LARM_LINK5
DEF LARM_JOINT6 Joint {
translation 0 0 -0.146
jointId 31
jointType "rotate"
jointAxis 1 0 0
## with margin
ulimit 1.5708 # +90
llimit -1.54494 # -88.5
## actual measure
# ulimit 1.7643
# llimit -1.57494
## from CAD
# ulimit 1.5708
# llimit -1.5708
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF LARM_LINK6 Segment {
mass 0.505
centerOfMass 0.00013 0.01427 0.00188
momentsOfInertia [0.000901789 0 0 0 0.000626727 0 0 0 0.000593753 ]
children [
Surface {
visual [ Inline { url "LARM_LINK6.wrl" } ] # visual
collision [ Inline { url "collision_directory/LARM_LINK6.wrl" } ] # collision
} # surface
]
} #Segment LARM_LINK6
DEF LARM_JOINT7 Joint {
translation 0 0 -0.04
jointId 32
jointType "rotate"
jointAxis 0 1 0
## for min-max
ulimit 1.0471975511965976 # +60.0
llimit -1.413716694115407 # -90.0
## with margin
# ulimit 1.06977 # +61.3
# llimit -1.5708 # -90.0
## actual measure
# ulimit 1.09977
# llimit -1.66359
## from CAD
# ulimit 1.13446
# llimit -1.5708
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 463.68
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF LARM_LINK7 Segment {
#mass 0.5
#centerOfMass 0 0 -0.03
#momentsOfInertia [0.02 0 0 0 0.02 0 0 0 0.01 ]
## add hand mass
mass 2.257
centerOfMass 0 0 -0.085
momentsOfInertia [0.020752 -1.298590e-06 8.029880e-06 -1.298590e-06 0.0198 0.000501 8.029880e-06 0.000501 0.013089]
children [
Surface {
visual [ Inline { url "LARM_LINK7_JVRC.wrl" } ] # visual
collision [ Inline { url "collision_directory/LARM_LINK7_JVRC.wrl" } ] # collision
} # surface
### checkerboard for calibration
#Transform {
# translation 0.06 0 -0.33
# rotation 0 1 0 1.5707963267948966
# children [
# Inline { url "../models/checkerboard.wrl" }
# ]
#}
DEF lhsensor ForceSensor{
translation 0 0 -0.069
rotation 0.382683 -0.92388 -0 3.14159
sensorId 3
} #Sensor
]
} #Segment LARM_LINK7
DEF LARM_CAMERA VisionSensor {
translation 0.05 0 -0.16
rotation 0 0 1 -1.5707963267948966
type "COLOR"
frontClipDistance 0.03
width 640
height 640
frameRate 10
fieldOfView 1.309 ## 75 deg / wide
sensorId 5
}
DEF LARM_Light SpotLightDevice {
translation 0.05 0 -0.16
# rotation
attenuation 1 0 2
beamWidth 0.6
# color
cutOffAngle 0.67
direction 0 0 -1
# intensity
# on
}
DEF LARM_CAMERA_N VisionSensor {
translation -0.05 0 -0.16
rotation 0 1 0 1.5707963267948966
type "COLOR"
frontClipDistance 0.03
width 640
height 640
frameRate 10
fieldOfView 1.309 ## 75 deg / wide
sensorId 6
}
DEF LARM_Light_N SpotLightDevice {
translation -0.05 0 -0.16
# rotation
attenuation 1 0 2
beamWidth 0.6
# color
cutOffAngle 0.67
direction -1 0 0
# intensity
# on
}
DEF LARM_F_JOINT0 Joint {
translation 0 -0.06 -0.1725
rotation -0.7071067811865475 0 0.7071067811865475 3.1415926535897931
jointId 33
jointType "rotate"
jointAxis 0 0 1
## for min-max
ulimit 0.6108652381980151 # +35.0
llimit -1.3962634015954629 # -80.0
uvlimit 4
lvlimit -4
climit [20.0]
gearRatio 1
rotorInertia 0.4
children [
DEF LARM_FINGER0 Segment {
mass 0.15
centerOfMass 0.077 0.0138 0
momentsOfInertia [4.450495e-05 0.000156 0.0 0.000156 0.001245 0.0 0.0 0.0 0.00128]
children [
Surface {
visual [ Inline { url "FINGER_LINK0.wrl" } ] # visual
collision [ Inline { url "FINGER_BB_0.wrl" } ] # collision
} # surface
]
} #Segment LARM_FINGER0
]
} #Joint LARM_F_JOINT0
DEF LARM_F_JOINT1 Joint {
translation 0 0.06 -0.1725
rotation -0.7071067811865475 0 0.7071067811865475 3.1415926535897931
jointId 34
jointType "rotate"
jointAxis 0 0 1
## for min-max
ulimit 1.3962634015954629 # +80.0
llimit -0.6108652381980151 # -35.0
uvlimit 4
lvlimit -4
climit [20.0]
gearRatio 1
rotorInertia 0.4
children [
DEF LARM_FINGER1 Segment {
mass 0.3
centerOfMass 0.077 0.0138 0
momentsOfInertia [4.450495e-05 0.000156 0.0 0.000156 0.001245 0.0 0.0 0.0 0.00128]
children [
Surface {
visual [ Inline { url "FINGER_LINK1.wrl" } ] # visual
collision [ Inline { url "FINGER_BB_1.wrl" } ] # collision
} # surface
]
} #Segment LARM_FINGER1
]
} #Joint LARM_F_JOINT1
]
} #Joint LARM_JOINT7
]
} #Joint LARM_JOINT6
]
} #Joint LARM_JOINT5
]
} #Joint LARM_JOINT4
]
} #Joint LARM_JOINT3
]
} #Joint LARM_JOINT2
]
} #Joint LARM_JOINT1
]
} #Joint LARM_JOINT0
DEF RARM_JOINT0 Joint {
translation 0 -0.0875 0
jointId 17
jointType "rotate"
jointAxis 0 0 1
# actual measure with margin
ulimit 1.4208
llimit -0.144751
# actual measure
# ulimit 1.4508
# llimit -0.174751
# from CAD
# ulimit 1.5708
# llimit -0.349066
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF RARM_LINK0 Segment {
mass 1.048
centerOfMass -0.01745 -0.00887 -0.00015
momentsOfInertia [0.0029762 0 0 0 0.00235085 0 0 0 0.00355486 ]
children [
Surface {
visual [ Inline { url "RARM_LINK0.wrl" } ] # visual
collision [ Inline { url "collision_directory/RARM_LINK0.wrl" } ] # collision
} # surface
]
} #Segment RARM_LINK0
DEF RARM_JOINT1 Joint {
translation 0 -0.07275 0
jointId 18
jointType "rotate"
jointAxis 0 1 0
ulimit 3.14159
llimit -3.14159
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF RARM_LINK1 Segment {
mass 0.298
centerOfMass 0.00011 -0.01799 0.00288
momentsOfInertia [0.000412035 0 0 0 0.000251611 0 0 0 0.000376771 ]
children [
Surface {
visual [ Inline { url "RARM_LINK1.wrl" } ] # visual
collision [ Inline { url "collision_directory/RARM_LINK1.wrl" } ] # collision
} # surface
]
} #Segment RARM_LINK1
DEF RARM_JOINT2 Joint {
translation 0 -0.057 0
jointId 19
jointType "rotate"
jointAxis 1 0 0
# with margin
ulimit -0.2762
llimit -3.14159
# actual measure
# ulimit -0.2462
# llimit -3.27031
# from CAD
# ulimit 0
# llimit -3.14159
uvlimit 4
lvlimit -4
climit [50.0]
gearRatio 460.8
torqueConst 0.0205
rotorInertia 7.0e-6
children [
DEF RARM_LINK2 Segment {
mass 2.168
centerOfMass 0.00845 -0.00671 -0.0881
momentsOfInertia [0.0127408 0 0 0 0.0133751 0 0 0 0.00460362 ]
children [
Surface {
visual [ Inline { url "RARM_LINK2_detail.wrl" } ] # visual
collision [ Inline { url "collision_directory/RARM_LINK2_detail.wrl" } ] # collision
} # surface
]
} #Segment RARM_LINK2
DEF RARM_JOINT3 Joint {
translation 0 0 -0.1965