-
Notifications
You must be signed in to change notification settings - Fork 0
/
eus2wrl.l
2084 lines (1992 loc) · 78.6 KB
/
eus2wrl.l
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
;;;
;;; converter robot-model to euscollada-robot created 2018.8.11 M.I
;;;
;;; (eus2wrl object "file.wrl") -> wrls/file.wrl
;;; (eus2collada-robot robot {name}) -> wrls/robot.wrl daes/robot.dae models/robot.l
;;; (setup-robot-joint-method-name) -> put joint-method to :joint-method-name property
;;; (eus2proto *ri*/*robot*) -> protos/robot-name.proto 2021.4.8
;;;
(provide :eus2wrl)
(require :rcb4robots)
(eval-when (eval load)
(require :kxrextentions))
;; (setq *kxr-all-names* (mapcar #'car *kxr-all-options*))
;; (setq *kxr-l2s-names* (mapcar #'car *kxr-l2s-options*))
;; (setq *kxr-l2l5all-names* (mapcar #'car *kxr-l2l5all-options*))
;; (setq *kxr-l2l6all-names* (mapcar #'car *kxr-l2l6all-options*))
;; (setq *kxr-l2nl6all-names* (mapcar #'car *kxr-l2nl6all-options*))
;; (setq *kxr-l2wl6all-names* (mapcar #'car *kxr-l2wl6all-options*))
;; (setq *kxr-l4all-names* (mapcar #'car *kxr-l4all-options*))
;; (setq *kxr-l6all-names* (mapcar #'car *kxr-l6all-options*))
;; (load "llib/vrmlNodeSpec.l")
;; (in-package :vrml)
;; (defmethod vrml-object
;; (:dump (&optional (strm t))
;; )
;; )
(in-package :user)
(defun create-collada-robots (&key (robots *kxr-all-names*) (erase t) no-check)
(let ((len (length robots)) (i 0) rname)
(format t ";; convert ~A robots~%" len)
(catch :loop-exit
(do-until-key
(if (>= i len) (throw :loop-exit i))
(setq rname (elt robots i))
(cond
((and (null no-check) (probe-file (format nil "models/~A.l" rname)))
(format t ";; ---- ~A/~A ~A exists. ~%" i len rname))
(t
(eus2collada-robot rname :erase erase)
(unless (probe-file (format nil "models/~A.l" rname))
(format t ";; ---- ~A/~A ~A is not created.~%" i len rname)
(throw :loop-exit i))
(format t ";; ---- ~A/~A ~A created.~%" i len rname)))
(incf i)
))
)
)
(defun eus2collada-robot
(robo &key
head
(fname (string-downcase
(cond ((derivedp robo rcb4-interface)
(setq robo (send robo :robot))
(send robo :name))
((stringp robo)
(setq robo (send (kxr-make-robot-interface robo :model nil :head head) :robot))
(send robo :name))
(t (send robo :name)))))
(wrl (format nil "wrls/~A.wrl" fname))
(dae (format nil "daes/~A.dae" fname))
(yaml (format nil "yamls/~A.yaml" fname))
(mode :openhrp3)
(model (format nil "models/~A.l" fname))
(urdf t)
erase
(actuator-joint-check nil)
(joint-numbered-name t)
)
(unix::chdir *rcb4eus-dir*)
(if fname (send robo :name fname))
(when robo
(send robo :angle-vector (instantiate float-vector (length (send robo :angle-vector)))))
(mkdir-unless "wrls")
(when urdf (mkdir-unless "urdf")
(setq urdf (format nil "urdf/~A.urdf" fname)))
(cond
;;((substringp "khr" fname)
;;(khr2model fname))
((derivedp robo kxr-robot)
(eus2wrl robo wrl :mode mode :actuator-joint-check actuator-joint-check
:joint-numbered-name joint-numbered-name)
(export-collada wrl dae)
(eus2yaml robo :yaml yaml :actuator-joint-check actuator-joint-check)
(collada2eus fname :dae dae :yaml yaml :model model)
(when urdf (collada2urdf fname))
(when erase (eus2erase-files fname)))
((derivedp robo robot-model)
(eus2wrl robo wrl :mode mode :actuator-joint-check actuator-joint-check
:joint-numbered-name joint-numbered-name)
(export-collada wrl dae)
(eus2yaml robo :yaml yaml :actuator-joint-check actuator-joint-check)
(collada2eus fname :dae dae :yaml yaml :model model)
(when urdf (collada2urdf fname))
(when erase (eus2erase-files fname)))
))
(defun eus2erase-files (fname)
(unlink-format "daes/~A.dae" fname)
(unlink-format "wrls/~A.wrl" fname)
;;(unlink-format "urdf/~A.urdf" fname)
(unlink-format "protos/~A.proto" fname)
;;(unlink-format "yamls/~A.yaml" fname)
;;(unlink-format "dumped-robots/~A.l" fname)
)
(defun export-collada (wrl dae)
(unless (unix::getenv "ROS_DISTRO")
(error ";; You need ROS environment. install ROS and do again"))
(unless (read (piped-fork "rospack find openhrp3") nil nil)
(system-format "sudo apt-get install -y ros-~A-openhrp3" (unix::getenv "ROS_DISTRO")))
(mkdir-unless "daes")
(system-format "export-collada -i ~A -o ~A" wrl dae))
(defun joint-method-candidates (r)
(remove-if-not
#'(lambda (x)
(member (subseq (symbol-name x) 0 5)
'("LLEG-" "RLEG-" "LARM-" "RARM-" "HEAD-" "TORSO" "WING-" "LMARM" "RMARM")
:test #'string-equal))
(send r :methods)))
(defun setup-robot-joint-method-name (r)
(let ((meths (joint-method-candidates r)))
(dolist (j (send r :joint-list))
(send j :put :joint-method-name
(find-if #'(lambda (m) (eq j (send r m))) meths)))))
(defun active-joint-methods (r)
(let ((meths (joint-method-candidates r))
m res)
(dolist (j (send r :joint-list))
(if (setq m (find-if #'(lambda (m)
(and (eq j (send r m))
(get j :active)))
meths))
(push m res)))
res))
(defun joint-methods (r)
(mapcar #'(lambda (j) (get j :joint-method-name))
(send r :joint-list)))
(defun find-joint-method (r j)
(find-if #'(lambda (m) (eq j (send r m)))
(joint-method-candidates r)))
(defun eus2yaml (robo &key
(name (string-downcase (send robo :name)))
(yaml (format nil "yamls/~A.yaml" name))
(scale 0.001)
(actuator-joint-check nil)
(limbs '(:head :larm :rarm :lleg :rleg :torso))
&aux av)
(when (derivedp robo robot-model)
(send robo :angle-vector)
(mkdir-unless "yamls")
(with-open-file
(strm yaml :direction :output)
(if (find-method robo :limbs) (setq limbs (send robo :limbs)))
(format strm "#~%# this file is automatically generated by eus2yaml ~A robot~%#~%" yaml)
(dolist (lim limbs) ;;'(:head :torso :larm :rarm :lleg :rleg)
(when (send robo lim)
(format strm "~A:~%" (string-downcase (string lim))))
(dolist (l (send robo lim)) ;;(assocdr lim (robo . lst-alist)) ;;(slot robo (class robo) lim))
(when (if actuator-joint-check
(get (send l :joint) :active) ;; (get (send l :joint) :servo-index)
t)
(format strm " - ~A : ~A~%"
(send (send l :joint) :name)
(read-from-string
(symbol-name
(or
(get (send l :joint) :joint-method-name)
(find-joint-method robo (send l :joint))
)
))))))
;;
(format strm "#~%# end-coords ~%#~%")
(if (find-method robo :limbs) (setq limbs (send robo :limbs)))
(dolist (lim limbs) ;; (rleg lleg rarm larm head))
(when (send robo lim)
(let* ((sym (read-from-string (format nil "~A-end-coords" (string lim))))
(ec (send robo (intern (symbol-name sym) *keyword-package*)))
par pos ori v a)
(when ec
(setq par (send ec :parent))
(setq pos (send par :inverse-transform-vector (send ec :worldpos)))
(setq ori (matrix-log (send ec :rot)))
(setq v (normalize-vector ori) a (norm ori))
(if (= a 0.0) (setf (elt v 0) 1.0))
(scale scale pos pos)
(format strm "~A:~% translate : [~A, ~A, ~A]~% rotate : [~A, ~A, ~A, ~A]~% parent : ~A~%"
sym (elt pos 0) (elt pos 1) (elt pos 2)
(elt v 0) (elt v 1) (elt v 2) (rad2deg a) ;; notice!!
(send par :name)))))
)
;;
(format strm "~%angle-vector:~%")
(dolist (m (list :reset-pose :reset-manip-pose :neutral))
(when
(find-method robo m)
(send robo m)
(format strm " ~A: [" (read-from-string (symbol-name m)))
(dolist (lim ;;'(head torso larm rarm lleg rleg))
;;'(:head :torso :larm :rarm :lleg :rleg))
limbs)
(format strm "~% " )
(dolist (l ;;(slot robo (class robo) lim))
(send robo lim))
(when (if actuator-joint-check
;;(get (send l :joint) :servo-index)
(get (send l :joint) :active)
t)
(format strm "~A, " (send (send l :joint) :joint-angle))))
(format strm "## ~A" lim)
)
(format strm "~% ]~%")
)))
(send robo :angle-vector av)
))
#|
(defun eus2proto (ri &key joint-numbered-name)
(eus2collada-robot ri :joint-numbered-name joint-numbered-name)
(if (derivedp ri rcb4-interface) (setq ri (send ri :robot)))
(collada2proto (send ri :name)))
|#
(defun eus2proto (scene &key
(robot-name (if (stringp scene) scene (string-downcase (send scene :name))))
(wrl (format nil "protos/~A-test.proto" robot-name))
(fixed nil) (actuator-joint-check t)
(joint-numbered-name t))
(if (stringp scene) (setq scene (kxr-make-robot scene)))
(with-open-file
(f wrl :direction :output)
(when (derivedp scene robot-model)
(if joint-numbered-name
(change-joint-names-to-limb-numbered scene)
(change-joint-names-to-downcase-string scene)) )
(format f "#VRML V2.0 utf8~%~%")
(format f "# Produced by ~A~%" (lisp-implementation-version))
(format f "# Date: ~A~%~%" (unix:asctime (unix:localtime)))
(print-webots-proto f (format nil "~A-test" robot-name))
(print-webots-header
f (format nil "~A" (if robot-name robot-name (string-downcase (send scene :name)))))
(setq *eus2wrl-camera-index* 0)
(if (not (find-method scene :dump-to-wrl))
(progn
(when (not (send scene :name))
(warn "Abort!! Please set :name to bodies~%")
(return-from eus2proto nil))
(dump-object-to-wrl scene f))
(send scene :dump-to-wrl :strm f :mode :webots :fixed fixed :robot scene
:actuator-joint-check actuator-joint-check)
)
(print-webots-footer f))
)
(defun eus2wrl (scene wrl &key (mode :openhrp3) (fixed nil)
robot-name
(actuator-joint-check nil)
(joint-numbered-name t))
(if (stringp scene)
(setq robot-name scene scene (kxr-make-robot robot-name))
(setq robot-name (send scene :name)))
(with-open-file
(f wrl :direction :output)
(when (derivedp scene robot-model)
(if joint-numbered-name
(change-joint-names-to-limb-numbered scene)
(change-joint-names-to-downcase-string scene)))
(format f "#VRML V2.0 utf8~%~%")
(format f "# Produced by ~A~%" (lisp-implementation-version))
(format f "# Date: ~A~%~%" (unix:asctime (unix:localtime)))
(print-hanim-proto f mode)
(print-hrp-setting f)
(print-hanim-header
f
(string-left-trim
":"
(format nil "~A" (if robot-name
robot-name (string-downcase (send scene :name))))))
(setq *eus2wrl-camera-index* 0)
(setq *eus2wrl-kjs-index* 0)
(if (not (find-method scene :dump-to-wrl))
(progn
(when (not (send scene :name))
(warn "Abort!! Please set :name to bodies~%")
(return-from eus2wrl nil))
(dump-object-to-wrl scene f))
(send scene :dump-to-wrl :strm f :mode mode :fixed fixed :robot scene
:actuator-joint-check actuator-joint-check)
)
(if (memq mode (list :openhrp2 :openhrp3)) (print-hanim-footer scene f))
)
)
(defun change-joint-names-to-limb-numbered (robo &aux
(limbs
(if (find-method robo :limbs)
(send robo :limbs)
(list :rleg :lleg :mrarm :mlarm :rarm :larm :head :torso))))
(dolist (limb limbs)
(when (find-method robo limb)
(dolist (l (send robo limb))
(send l :name (format nil "~A_LINK~A" (symbol-name limb)
(position l (send robo limb))))
(when (send l :joint)
(send (send l :joint) :name (format nil "~A_JOINT~A" (symbol-name limb)
(position l (send robo limb))))))))
;;(dolist (j (send robo :joint-list))
;;(send j :name (string-left-trim ":" (send j :name))))
)
(defun change-joint-names-to-downcase-string (robo)
(dolist (j (send robo :joint-list))
(send j :name (string-downcase (string (send j :joint-method-name)))))
)
;;;
(defmethod cascaded-link
(:dump-to-wrl
(&key (strm t) (mode :normal) (fixed nil) robot actuator-joint-check)
;; set joint-id tempolariry because robot-model's joints do not have :servo :no
(let ((jl joint-list))
;;(remove-if-not
;;#'(lambda (x) (and actuator-joint-check (get x :servo-index)))
;;joint-list)))
;;(format t ";; cascaded-link :dump-to-wrl is called, jl=~A~%" jl)
(mapc #'(lambda (x)
(send x :put :joint-id-for-dump (position x jl)))
jl)
(send
(send self :body-link)
:dump-to-wrl :strm strm :mode mode :fixed fixed :robot robot)
#|
(send (find-if
#'(lambda (x) (derivedp x bodyset-link))
(send self :descendants))
:dump-to-wrl :strm strm :mode mode :fixed fixed :robot robot)
|#
(mapc #'(lambda (x) (send x :remprop :joint-id-for-dump)) jl)
)
)
)
;;
;; (make-kxr-robot "khr3")
;; (eus2collada-robot *robot* :fname "khr" :wrl "KHR/KHRmain.wrl")
;; -> models/khr.l
(defun gen-khrh2u (&key (replace t) (names *khr-ufunc-names*) (lego-bar 13))
(gen-khrh2-aux (m5unitv-stereo :m5stack 0 :n lego-bar) "HEAD_LINK3"
names "" replace #f(-4 0 15)))
(defun gen-khrh2u2 (&key (replace t) (names *khr-u2func-names*) (lego-bar 13))
(gen-khrh2-aux (m5unitv2-stereo :n lego-bar)
"HEAD_LINK3" names "" replace #f(-4 0 15)))
(defun gen-khrh2u3 (&key (replace t) (names *khr-u3func-names*) (lego-bar 13))
(gen-khrh2-aux (m5unitv-stereo :n lego-bar :m5unitv2 t)
"HEAD_LINK3" names "" replace #f(-4 0 15)))
(defun gen-khrh2v (&key (replace t) (names *khr-vfunc-names*))
(gen-khrh2-aux (m5stickv-stereo) "HEAD_LINK3" names "" replace #f(-4 0 24)))
(defun gen-khrh2v3 (&key (replace t) (names *khr-v3func-names*))
(gen-khrh2-aux (m5stickv-stereo :m5unitv2 t) "HEAD_LINK3" names "" replace #f(-4 0 24)))
(defun gen-khrh2-aux (h-model &optional (fname "HEAD_LINK3")
(func-names *khr-func-names*)
(type "") (replace t) (offset #f(0 0 0)))
(gen-camera-wrl h-model offset)
(with-open-file (f (format nil "KHR/~A.wrl" fname) :direction :output)
(send h-model :dump-to-wrl :strm f :wpos offset))
(dolist (func func-names)
(khr2model func type replace)))
(defun gen-camera-wrl (&optional (h-model (m5stickv-stereo)) (offset #f(0 0 0)))
(let* ((cams (get h-model :cameras))
(lcam (car cams))
(rcam (cadr cams)))
(with-open-file (f "KHR/HEAD_CAMERA.wrl" :direction :output)
(send lcam :translate offset :world)
(send lcam :rotate pi :x)
;;(send lcam :rotate -pi/2 :z)
(send lcam :rotate -pi :z)
(dump-camera (send lcam :worldcoords) :name "camera0" :sensor-id 0 :strm f)
(send rcam :rotate pi :x)
;;(send rcam :rotate -pi/2 :z)
(send rcam :rotate -pi :z)
(send rcam :translate offset :world)
(dump-camera (send rcam :worldcoords) :name "camera1" :sensor-id 1 :strm f)
)
))
(defun khr2collada-robot (&key (fname "KHRmain")
(wrl (format nil "KHR/~A.wrl" fname))
(dae (format nil "daes/~A.dae" fname))
(yaml (format nil "yamls/~A.yaml" fname))
(model (format nil "models/~A.l" fname))
)
(export-collada wrl dae)
(collada2eus fname :dae dae :yaml yaml :model model)
fname)
(defun khr2model (robo-name &optional (type "") (replace t))
(mkdir-unless "yamls")
(unix:system (format nil "cp KHR/~A~A.yaml yamls" robo-name type))
(mkdir-unless "daes")
(export-collada (format nil "KHR/~A~Amain.wrl" robo-name type)
(format nil "daes/~A~A.dae" robo-name type))
(collada2eus (format nil "~A~A" robo-name type))
(if replace (unix:system (format nil "cp models/~A~A.l KHR" robo-name type))))
(setq *khr-ufunc-names*
'(khrh2u khr20h2u khr22h2u khrl6a3h2u khrl6a4h2u khrt1l6a3h2u khrt1l6a4h2u))
(setq *khr-u2func-names*
'(khrh2u2 khr20h2u2 khr22h2u2 khrl6a3h2u2 khrl6a4h2u2 khrt1l6a3h2u2 khrt1l6a4h2u2))
(setq *khr-u3func-names*
'(khrh2u3 khr20h2u3 khr22h2u3 khrl6a3h2u3 khrl6a4h2u3 khrt1l6a3h2u3 khrt1l6a4h2u3))
(setq *khr-vfunc-names*
'(khrh2v khr20h2v khr22h2v khrl6a3h2v khrl6a4h2v khrt1l6a3h2v khrt1l6a4h2v))
(setq *khr-v3func-names*
'(khrh2v3 khr20h2v3 khr22h2v3 khrl6a3h2v3 khrl6a4h2v3 khrt1l6a3h2v3 khrt1l6a4h2v3))
(setq *khr-no-h2* '(khr khr20 khr22))
(setq *khr-func-names*
'(khrh2 khr20h2 khr22h2 khrl6a3h2 khrl6a4h2 khrt1l6a3h2 khrt1l6a4h2))
(defun check-khrh2 (&key (xs 400) (ys 400))
(require :kxranimate)
(setq *khr-robots* nil)
(dolist (f *khr-func-names*)
(load (format nil "models/~A.l"f))
(push (funcall f) *khr-robots*))
(show-2d-arrange *khr-robots* :xs xs :ys ys)
)
(defun bodyset2wrl (bs fname &optional (wpos (send bs :worldpos)))
(with-open-file (f fname :direction :output)
(send bs :dump-to-wrl :strm f :wpos wpos))
)
(defun dump-camera (coord &key (name "camera") (sensor-id 0) (strm t) (scale 0.001))
(let* ((wpos (scale scale (send coord :worldpos)))
(lrot (let ((rx (matrix-log (send coord :rot))))
(list (norm rx) (normalize-vector rx))))
rot-v rot-a)
(if (eps= (car lrot) 0.0)
(setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (cadr lrot) rot-a (car lrot)))
(format strm " DEF ~A VisionSensor {~%" name)
(format strm " translation ~8,6f ~8,6f ~8,6f~%"
(elt wpos 0) (elt wpos 1) (elt wpos 2))
(format strm " rotation ~A ~A ~A ~A~%"
(elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a)
(format strm " name \"~A\"~%" name)
(format strm " sensorId ~A }~%" sensor-id)
))
(defmethod bodyset
(:dump-to-wrl-old
(&rest args
&key (strm t) (mode :normal) robot
(wpos (send self :worldpos))
(scale 0.001) (name (string (send self :name)))
&allow-other-keys)
(dolist (b (send self :bodies))
(send* b :dump-to-wrl :wpos wpos :robot robot args))
)
(:dump-to-wrl
(&rest args
&key (strm t) (mode :normal) robot
(wpos (send self :worldpos))
(scale 0.001) (name (string (send self :name)))
&allow-other-keys)
(let ((lrot (let ((rx (matrix-log (send self :rot))))
(list (norm rx) (normalize-vector rx))))
rot-v rot-a)
(if (eps= (car lrot) 0.0)
(setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (cadr lrot) rot-a (car lrot)))
(format strm "DEF ~A Transform {~%" name)
;;(setq pos (scale scale (v- wpos (send parent :worldpos))))
;;(setq pos (scale scale (send self :pos)))
(setq wpos (scale scale wpos))
(format strm " translation ~8,6f ~8,6f ~8,6f~%"
(elt wpos 0) (elt wpos 1) (elt wpos 2))
(format strm " rotation ~A ~A ~A ~A~%"
(elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a)
(format strm " children [~%")
;;(send* self :dump-imu-sensors :robot robot args)
;; dump shapes
(dolist (b (send self :bodies))
(send* b :dump-to-wrl :wpos wpos :robot robot args))
(format strm "] # children of ~%")
(format strm "} #~%")
))
)
(defmethod bodyset-link
(:dump-to-wrl
(&rest
args
&key (strm t) (mode :openhrp3) robot (fixed nil) (scale 0.001) &allow-other-keys)
(let* ((name (if (get self :abbrev-name)(get self :abbrev-name)
(if (send self :name) (string (send self :name)))))
(wpos (send self :worldpos))
pos
(rot (let ((rx (matrix-log (send self :rot))))
(list (norm rx) (normalize-vector rx))))
(vnum 0)
(jname (if joint (send (send self :joint) :name) "WAIST"))
rot-v rot-a diffuse link-vs centroid im)
(if (eps= (car rot) 0.0)
(setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (cadr rot) rot-a (car rot)))
(case mode
((:openhrp2 :openhrp3)
(setq centroid (scale scale (or (get self :centroid) (self . acentroid)))
im (scale-matrix
(* scale scale scale)
(or (get self :inertia-tensor) (send self :inertia-tensor)))
)
;;(format strm "DEF ~A Joint {~%" (if (send self :parent-link) name "WAIST"))
(format strm "DEF ~A Joint { # ~A ~%" jname jname)
(if (derivedp parent bodyset-link)
(if (derivedp (send self :joint) linear-joint)
(format strm " jointType \"slide\"~%")
(format strm " jointType \"rotate\"~%"))
(if fixed
(format strm " jointType \"fixed\"~%")
(format strm " jointType \"free\"~%")))
(format strm " dh [0 0 0 0]~%")
;;
(when (derivedp parent bodyset-link)
(let* ((ajoint (send self :joint))
(tmpid (if (find-method ajoint :servo)
(send ajoint :servo :no)
(send ajoint :get :joint-id-for-dump))))
(when ajoint
(format strm " jointAxis ~A~%"
(if (eq mode :openhrp2)
(format nil "\"~A\"" (string (ajoint . axis)))
(let ((tmp-axis ;; if eq mode :openhrp3
(case (ajoint . axis)
(:x #f(1 0 0)) (:y #f(0 1 0)) (:z #f(0 0 1))
(:-x #f(-1 0 0)) (:-y #f(0 -1 0)) (:-z #f(0 0 -1))
(t (ajoint . axis)))))
(setq tmp-axis (send self :rotate-vector tmp-axis))
(format nil "~A ~A ~A" (elt tmp-axis 0) (elt tmp-axis 1) (elt tmp-axis 2)))))
(format strm " jointId ~A~%" tmpid)
(format strm " ulimit [~A]~%" (deg2rad (send ajoint :max-angle)))
;;(send ajoint :angle-to-speed (send ajoint :max-angle)))
(format strm " llimit [~A]~%" (deg2rad (send ajoint :min-angle)))
;;(send ajoint :angle-to-speed (send ajoint :min-angle)))
(format strm " uvlimit [~A]~%" (send ajoint :max-joint-velocity))
(format strm " lvlimit [~A]~%" (- (send ajoint :max-joint-velocity)))
(when
tmpid
(format strm " climit [~A]~%" (get ajoint :climit))
(format strm " torqueConst ~A~%" (get ajoint :torque-const))
(format strm " gearRatio ~A~%" (get ajoint :gear-ratio))
(format strm " rotorInertia ~A~%" (get ajoint :rotor-inertia)))
)))
;;(setq pos (scale scale (if (derivedp parent bodyset-link)
;;(send self :pos) (send self :worldpos))))
(setq pos (scale scale (v- wpos (send parent :worldpos))))
(format strm " translation ~8,6f ~8,6f ~8,6f~%"
(elt pos 0) (elt pos 1) (elt pos 2))
;;(format strm " translation 0.0 0.0 0.0~%")
;;(format strm " rotation ~A ~A ~A ~A~%"
;;(elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a)
(format strm " rotation 0.0 0.0 1.0 0.0~%")
(format strm " children [ # ~A~%" jname)
;; segments
(format strm "DEF ~A Segment {~%" name)
(format strm " centerOfMass ~A ~A ~A~%"
(elt centroid 0)(elt centroid 1) (elt centroid 2))
(format strm " mass ~A~%" (* scale (or (get self :weight) (send self :weight))))
(format strm " momentsOfInertia [ ~A ~A ~A ~A ~A ~A ~A ~A ~A ]~%"
(aref im 0 0) (aref im 0 1) (aref im 0 2)
(aref im 1 0) (aref im 1 1) (aref im 1 2)
(aref im 2 0) (aref im 2 1) (aref im 2 2))
)
;;
((:webots)
(setq centroid (scale scale (or (get self :centroid) (self . acentroid)))
im (scale-matrix
(* scale scale scale)
(or (get self :inertia-tensor) (send self :inertia-tensor)))
)
;;(format strm "DEF ~A Joint {~%" (if (send self :parent-link) name "WAIST"))
(when (derivedp parent bodyset-link)
(let* ((ajoint (send self :joint))
(tmpid (if (find-method ajoint :servo)
(send ajoint :servo :no)
(send ajoint :get :joint-id-for-dump))))
(when ajoint
(format strm "HingeJoint { # ~A ~%" jname)
(format strm " jointParameters HingeJointParameters {~%")
(format strm " axis ~A~%"
(let ((tmp-axis
(case (ajoint . axis)
(:x #f(1 0 0)) (:y #f(0 1 0)) (:z #f(0 0 1))
(:-x #f(-1 0 0)) (:-y #f(0 -1 0)) (:-z #f(0 0 -1))
(t (ajoint . axis)))))
(setq tmp-axis (send self :rotate-vector tmp-axis))
(format nil "~A ~A ~A"
(elt tmp-axis 0) (elt tmp-axis 1) (elt tmp-axis 2))))
(format strm "anchor 0 0 0~%")
(format strm "}~%")
(when
tmpid
(format strm " device [~%")
(format strm " RotationalMotor{~%")
(format strm " name ~S~%" (string (send ajoint :name)))
(format strm " maxVelocity ~A~%" (send ajoint :max-joint-velocity))
(format strm " maxTorque ~A~%" (send ajoint :max-joint-torque))
(format strm " }~%")
(format strm " PositionSensor {~%")
(format strm " name ~S~%" (format nil "~A_Sensor" (send ajoint :name)))
(format strm " }~%]")
)
(setq pos (scale scale (v- wpos (send parent :worldpos))))
(format strm " endPoint Solid {~%")
(format strm " children [ # ~A~%" jname)
(format strm " Transform {~%")
(format strm " translation ~8,6f ~8,6f ~8,6f~%"
(elt pos 0) (elt pos 1) (elt pos 2))
(format strm " rotation 0.0 0.0 1.0 0.0~%")
))))
((:normal)
(format strm "DEF ~A Transform {~%" name)
(setq pos (scale scale (send self :pos)))
(format strm " translation ~8,6f ~8,6f ~8,6f~%"
(elt pos 0)(elt pos 1) (elt pos 2))
(format strm " rotation ~A ~A ~A ~A~%"
(elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a))
(:robotbrowser
(format strm "DEF ~A Transform {~%" name)
(setq pos (scale scale (v- wpos (send parent :worldpos))))
(format strm " translation ~8,6f ~8,6f ~8,6f~%"
(- (elt pos 0)) (elt pos 2) (elt pos 1))
(format strm " rotation 0.0 0.0 1.0 0.0~%"))
) ;; case mode
(format strm " children [~%")
(send* self :dump-animation args)
;;; dump sensors
(send* self :dump-camera-sensors :robot robot args)
(send* self :dump-force-sensors :robot robot args)
(send* self :dump-imu-sensors :robot robot args)
;;(send* self :dump-KJS-sensors :robot robot args)
;; dump shapes
(dolist (b (send self :bodies))
(send* b :dump-to-wrl :wpos wpos :robot robot args))
;;
(when (memq mode (list :openhrp2 :openhrp3))
(format strm " ]~%") ;; children[
(format strm "} #Segment ~A~%" name)
)
(dolist (d child-links) ;;(d (send self :descendants))
(when (derivedp d bodyset-link)
(send d :dump-to-wrl :strm strm :mode mode :robot robot))
)
(format strm "] # children of ~A~%" jname)
(format strm "} # ~A~%" jname)
))
(:dump-camera-sensors ;;
(&rest args &key strm (mode :openhrp3) robot (scale 0.001) &allow-other-keys)
(let* (sensor-names sensors (i 0) pos ori v a)
(dolist (c (send robot :cameras))
(when (null (send c :name))
(send c :name (format nil "camera~A" i))
(incf i))
(push (send c :name) sensor-names))
(setq sensors (remove-if-not #'(lambda (x) (member (send x :name) sensor-names :test #'equal))
descendants))
(case mode
((:openhrp2 :openhrp3)
(when sensors
(dotimes (i (length sensors))
(setq pos (scale 0.001 (send (elt sensors i) :pos)))
;;(setq ori (matrix-log (send (elt sensors i) :rot))) 2022.10.21
(setq ori (matrix-log (rotate-matrix (send (elt sensors i) :rot) pi :x)))
(setq v (normalize-vector ori) a (norm ori))
(if (eps= a 0) (setq v (float-vector 1 0 0)))
(if (eq mode :webots)
(format strm " DEF camera~A Camera {~% translation " (+ i *eus2wrl-camera-index*))
(format strm " DEF camera~A VisionSensor {~% translation " (+ i *eus2wrl-camera-index*)))
(format strm "~A ~A ~A~%" (elt pos 0) (elt pos 1) (elt pos 2))
(format strm " rotation ~A ~A ~A ~A~%" (elt v 0) (elt v 1) (elt v 2) a)
(format strm " name \"camera~A\" ~%" (+ i *eus2wrl-camera-index*))
;; (format strm " type \"base_pinhole_camera\" ~%")
(format strm " sensorId ~A }~%" (+ i *eus2wrl-camera-index*)))
(setq *eus2wrl-camera-index* (length sensors))))
((:webots)
(when sensors
(dotimes (i (length sensors))
(setq pos (scale 0.001 (send (elt sensors i) :pos)))
(setq ori (matrix-log (send (elt sensors i) :rot)))
(setq v (normalize-vector ori) a (norm ori))
(if (eps= a 0) (setq v (float-vector 1 0 0)))
(if (eq mode :webots)
(format strm " DEF camera~A Camera {~% translation " (+ i *eus2wrl-camera-index*))
(format strm " DEF camera~A VisionSensor {~% translation " (+ i *eus2wrl-camera-index*)))
(format strm "~A ~A ~A~%" (elt pos 0) (elt pos 1) (elt pos 2))
(format strm " rotation ~A ~A ~A ~A~%" (elt v 0) (elt v 1) (elt v 2) a)
(format strm " name \"camera~A\" ~%}~%" (+ i *eus2wrl-camera-index*))
(setq *eus2wrl-camera-index* (length sensors))))
))
))
(:dump-force-sensors ;;
(&rest args &key strm (mode :openhrp3) robot (scale 0.001) &allow-other-keys)
(let* ((sensor-names (send-all (send robot :force-sensors) :name))
(sensor (find-if #'(lambda (x) (member (send x :name) sensor-names :test #'equal))
descendants))
pos)
(case mode
((:openhrp2 :openhrp3)
(when sensor
(format strm " DEF ~A ForceSensor {~% translation " (send sensor :name))
(format strm "~A ~A ~A~%" 0.0 0.0 0.0)
(format strm " rotation ~A ~A ~A ~A~%" 1 0 0 0)
(format strm " sensorId ~A }~%" (position (send sensor :name)
sensor-names :test #'equal))
))
((:webots)
(when sensor
(format strm " DEF ~A TouchSensor {~% translation " (send sensor :name))
(format strm "~A ~A ~A~%" 0.0 0.0 0.0)
(format strm " rotation ~A ~A ~A ~A~%" 1 0 0 0)
(format strm " type \"force-3d\"~%")
(format strm " name ~A }~%" (position (send sensor :name)
sensor-names :test #'equal))
)))
)
)
(:dump-imu-sensors ;;
(&rest args &key strm (mode :openhrp3) robot (scale 0.001) &allow-other-keys)
(let* ((sensor-names (send-all (send robot :imu-sensors) :name))
(sensors (remove-if-not #'(lambda (x) (member (send x :name) sensor-names :test #'equal))
descendants))
pos rx rot-v rot-a)
(case mode
((:openhrp2 :openhrp3)
;;(format t ";; dump descendants=~A~%;; imus=~A~%;; sensors=~A~%" descendants (send robot :imu-sensors) sensors))
(dolist (sensor sensors)
(when sensor
(if (eq mode :webots)
(if (string-equal (send sensor :name) "gyrometer")
(format strm " DEF ~A Gyro {~% translation " (send sensor :name))
(format strm " DEF ~A Accelerometer {~% translation " (send sensor :name)))
(if
(string-equal (send sensor :name) "gyrometer")
(format strm " DEF ~A Gyro {~% translation " (send sensor :name))
(format strm " DEF ~A AccelerationSensor {~% translation " (send sensor :name))))
;;(setq pos (scale scale (send sensor :pos)))
(setq pos (scale scale (v- (send sensor :worldpos) (send (send sensor :parent) :worldpos))))
(setq rx (matrix-log (send sensor :worldrot)))
(if (eps= (norm rx) 0.0) (setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (normalize-vector rx) rot-a (norm rx)))
(format strm "~A ~A ~A~%" (elt pos 0) (elt pos 1) (elt pos 2))
(format strm " rotation ~A ~A ~A ~A~%" (elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a)
(format strm " sensorId ~A }~%" (or (send sensor :get :sensor-id) 0)))
))
((:webots)
(dolist (sensor sensors)
(when sensor
(if (eq mode :webots)
(if
(string-equal (send sensor :name) "gyrometer")
(format strm " DEF ~A Gyro {~% translation " (send sensor :name))
(format strm " DEF ~A Accelerometer {~% translation " (send sensor :name)))
(if
(string-equal (send sensor :name) "gyrometer")
(format strm " DEF ~A Gyro {~% translation " (send sensor :name))
(format strm " DEF ~A AccelerationSensor {~% translation " (send sensor :name))))
(setq pos (scale scale (send sensor :pos)))
(setq rx (matrix-log (send sensor :worldrot)))
(if (eps= (norm rx) 0.0)
(setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (normalize-vector rx) rot-a (norm rx)))
(format strm "~A ~A ~A~%" (elt pos 0) (elt pos 1) (elt pos 2))
(format strm " rotation ~A ~A ~A ~A~%}~%"
(elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a))
)))
)
)
(:dump-KJS-sensors ;;
(&rest args &key strm (mode :openhrp3) robot (scale 0.001) &allow-other-keys)
(let* ((kjss (send robot :kjs-sensors))
(sensor-names (send-all kjss :name))
(dess (send self :find-named-objects "KJS" :method :bodies))
(sensor (find-if #'(lambda (x) (member (send x :name) sensor-names :test #'substringp))
dess))
sensor-name pos rx rot-a rot-v)
;;(format t ";; pressure-sensors=~A~%" sensor-names)
;;(format t ";; dess=~A~%" dess)
;;(format t ";; pressure-sensors parent=~A~%" (send-all (send robot :pressure-sensors) :parent))
;;(format t ";; descendants=~A~%" dess) ;; (send-all descendants :name)
(case mode
((:openhrp2 :openhrp3)
(when sensor
(setq sensor-name (send sensor :name))
;;(format t ";; sensor=~A kjs=~A~%" (send sensor :name) *eus2wrl-kjs-index*)
(format strm " DEF ~A Gyro {~% translation "
sensor-name
;;(format nil "~A-~A" (send sensor :name) *eus2wrl-kjs-index*)
)
(setq pos (scale scale (send sensor :pos)))
(setq rx (matrix-log (send sensor :worldrot)))
(if (eps= (norm rx) 0.0) (setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (normalize-vector rx) rot-a (norm rx)))
(format strm "~A ~A ~A~%" (elt pos 0) (elt pos 1) (elt pos 2))
(format strm " rotation ~A ~A ~A ~A~%" (elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a)
(format strm " sensorId ~A }~%"
(or (send sensor :get :sensor-id)
(position (send sensor :name) sensor-names :test #'substringp)
0))
#|
(format strm " DEF ~A AccelerationSensor {~% translation "
(format nil "gsensor-~A-~A" (send sensor :name) *eus2wrl-kjs-index*))
(setq pos (scale scale (send sensor :pos)))
(setq rx (matrix-log (send sensor :worldrot)))
(if (eps= (norm rx) 0.0) (setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (normalize-vector rx) rot-a (norm rx)))
(format strm "~A ~A ~A~%" (elt pos 0) (elt pos 1) (elt pos 2))
(format strm " rotation ~A ~A ~A ~A~%" (elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a)
(format strm " sensorId ~A }~%"
(or (send sensor :get :sensor-id)
(position (send sensor :name) sensor-names :test #'substringp)
0))
;;
(format strm " DEF ~A PressureSensor {~% translation " (send sensor :name))
(setq pos (scale scale (send sensor :pos)))
(setq rx (matrix-log (send sensor :worldrot)))
(if (eps= (norm rx) 0.0)
(setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (normalize-vector rx) rot-a (norm rx)))
(format strm "~A ~A ~A~%" (elt pos 0) (elt pos 1) (elt pos 2))
(format strm " rotation ~A ~A ~A ~A~%"
(elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a)
;;(format strm "~A ~A ~A~%" 0.0 0.0 0.0)
;;(format strm " rotation ~A ~A ~A ~A~%" 1 0 0 0)
(format strm " sensorId ~A }~%"
(or (position (send sensor :name) sensor-names :test #'substringp)
0))
|#
(incf *eus2wrl-kjs-index*)
))
((:webots)
(when sensor
(format strm " DEF ~A TouchSensor {~% translation " (send sensor :name))
(format strm "~A ~A ~A~%" 0.0 0.0 0.0)
(format strm " rotation ~A ~A ~A ~A~%" 1 0 0 0)
(format strm " type \"force-3d\"~%")
(format strm " name ~A }~%" (position (send sensor :name)
sensor-names :test #'equal))
)))
)
)
(:dump-animation
(&rest args &key strm name &allow-other-keys)
(when
(get self :animation)
(let (p r ang v)
(format strm " DEF ~A-POS-INTERP PositionInterpolator {~%" name)
(format strm " key [")
(dolist (a (get self :animation))
(format strm "~A, ") (car a))
(format strm " ~%]~%")
(format strm " keyvalue [")
(dolist (a (get self :animation))
(setq p (send (cdr a) :pos))
(format strm "~A ~A ~A, " (elt p 0) (elt p 1) (elt p 2)))
(format strm " ] },~%")
;;
(format strm " DEF ~A-ROT-INTERP OrientationInterpolator {~%" name)
(format strm " key [")
(dolist (a (get self :animation))
(format strm "~A, ") (car a))
(format strm " ~%]~%")
(format strm " keyvalue [")
(dolist (a (get self :animation))
(setq r (send (cdr a) :rotation-angle))
(if (null r) (setq r 0 v #f(1 0 0))
(setq ang (car r) v (cadr r)))
(format strm "~A ~A ~A ~A, "
ang (elt v 0) (elt v 1) (elt v 2)))
(format strm " ] },~%")
))
)
)
(defmethod faceset
(:dump-to-wrl
(&rest args &key wpos (strm t) robot (mode :openhrp3) (scale 0.001) &allow-other-keys)
(let ((glb (generate-glbody self)))
(send* glb :dump-to-wrl args)
self)
))
(defun generate-glbody (bod)
(let (mat (col (get bod :face-color)) (glbod (instantiate gl::glbody)))
(when col
(unless (vectorp col) (setq col (gl::find-color col)))
(setq mat
(list
(list :ambient
(float-vector (elt col 0) (elt col 1) (elt col 2)))
(list :diffuse
(float-vector (elt col 0) (elt col 1) (elt col 2))))))
(replace-object glbod bod)
(send glbod :set-color col)
(send glbod :init-mass-property)
(setq (glbod . gl::aglvertices) (gl::make-glvertices-from-faceset bod :material mat))
(setf (get (glbod . gl::aglvertices) :face-color) (get bod :face-color))
glbod))
(defmethod gl::glbody
(:dump-to-wrl
(&rest args &key wpos strm robot (mode :openhrp3) (scale 0.001) &allow-other-keys)
#|
(when
(get self :dump-to-wrl)
(format t ";; :dump-to-wrl glbody ~A already?=~A~%" (send self :name) (get self :dump-to-wrl))
(return-from :dump-to-wrl nil))
|#
(let* ((glv (send self :glvertices))
;;(name (symbol-name (gensym (string (send self :name))))))
(name (string (send self :name))))
(dolist (minfo (glv . gl::mesh-list))
(when
(string-equal name "wheel")
(if (eq mode :webots)
(format strm " Solid {~%")
(format strm " Surface {~%"))
(format strm " collision [~%")
(let (offset cyl r h b rot-a rot-v rotav)
(cond
((assoc :revolution csg)
(setq b (revolution2cylinder self))
(setq cyl (assoc :cylinder (b . csg))))
(t (setq b self) (setq cyl (assoc :cylinder csg))))
;;
(setq offset
(scale scale
(v- (send self :worldpos) (send (send self :parent) :worldpos))))
(setq rotav (rotation-angle (m* rot (send b :rot))))
(if (or (null rotav) (memq *nan* (coerce (cadr rotav) cons)))
(setq rot-v (float-vector 0 0 1) rot-a 0)
(setq rot-v (cadr rotav) rot-a (car rotav)))
(setq r (cadr cyl) h (caddr cyl))
(format strm " Transform {~%")
(format strm " translation ~A ~A ~A~%"
(elt offset 0) (elt offset 1) (elt offset 2))
(format strm " rotation ~A ~A ~A ~A~%"
(elt rot-v 0) (elt rot-v 1) (elt rot-v 2) rot-a)
;;
(format strm " children [~%" )
(format strm " Shape {~%")
(format strm " geometry Cylinder {~%")
(format strm " radius ~A~%" (* scale r))
(format strm " height ~A }~%" (* scale h))
(format strm "} # Shape~%" )
(format strm " ] # children~%")
(format strm "} # Transform~%" )
(format strm "] # collision~%" ))
(format strm " visual [~%")
)
(format strm " Shape {~%")
(format strm " appearance Appearance {~%")
;; FIXME: use other material info
(let ((mat (cadr (assoc :material minfo))))
(let ((diff (cadr (assoc :diffuse mat))))
(format strm " material Material {~%")
#|
(cond
((= (length diff) 4)
(format strm " diffuseColor ~A ~A ~A ~A~%"
(elt diff 0) (elt diff 1) (elt diff 2) (elt diff 3)))
((= (length diff) 3)
(format strm " diffuseColor ~A ~A ~A~%"
(elt diff 0) (elt diff 1) (elt diff 2))))