-
Notifications
You must be signed in to change notification settings - Fork 41
/
robot-interface.l
1865 lines (1836 loc) · 87.1 KB
/
robot-interface.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
;;;
;;; robot interface to ROS based pr2 system
;;;
(ros::load-ros-manifest "roseus")
(ros::load-ros-manifest "rosgraph_msgs")
(ros::load-ros-manifest "control_msgs")
;;(ros::roseus-add-msgs "sensor_msgs") ;; roseus depends on sensor_msgs
;;(ros::roseus-add-msgs "visualization_msgs") ;; roseus depends on visualization_msgs
(ros::roseus-add-msgs "move_base_msgs")
(ros::roseus-add-msgs "nav_msgs")
;; add ros-joint-angle method using meter/radian
(defmethod rotational-joint
(:ros-joint-angle
(&optional v &rest args)
(if v (setq v (rad2deg v)))
(setq v (send* self :joint-angle v args))
(deg2rad v))
)
(defmethod linear-joint
(:ros-joint-angle
(&optional v &rest args)
(if v (setq v (* 1000.0 v)))
(setq v (send* self :joint-angle v args))
(* 0.001 v))
)
(defclass controller-action-client
:super ros::simple-action-client
:slots (time-to-finish last-feedback-msg-stamp
ri angle-vector-sequence timer-sequence current-time current-angle-vector previous-angle-vector scale-angle-vector;; slot for angle-vector-sequence
))
(defmethod controller-action-client
(:init (r &rest args)
(setq ri r) ;; robot-interface
(setq time-to-finish 0)
(setq last-feedback-msg-stamp (ros::time-now)) ;; this is for real robot
(send-super* :init args))
(:last-feedback-msg-stamp () last-feedback-msg-stamp)
(:time-to-finish ()
(ros::ros-debug "[~A] time-to-fnish ~A" ros::name-space time-to-finish)
time-to-finish)
(:action-feedback-cb (msg)
(let ((finish-time) (current-time))
(ros::ros-debug "[~A] feedback-cb ~A" ros::name-space msg)
(setq last-feedback-msg-stamp (send msg :header :stamp))
(unless (and (send ros::comm-state :action-goal) (not (equal (send (class ros::action-spec) :name) 'control_msgs::SingleJointPositionAction))) (return-from :action-feedback-cb nil))
(cond ((derivedp msg control_msgs::followjointtrajectoryactionfeedback)
(setq current-time (send msg :feedback :error :time_from_start)))
(t
(ros::ros-warn "feedback message type is not control_msgs/FollowJointTrajectoryActionFeedback.")
;; e.g. Type: pr2_controllers_msgs/JointTrajectoryActionFeedback does not have :error
(setq current-time (ros::time- (ros::time-now) (send msg :status :goal_id :stamp)))))
(setq finish-time (send (car (last (send (send ros::comm-state :action-goal) :goal :trajectory :points))) :time_from_start))
(if (string= (send (send ros::comm-state :action-goal) :goal_id :id)
(send msg :status :goal_id :id))
(setq time-to-finish (send (ros::time- finish-time current-time) :to-sec))
(progn
(ros::ros-warn "[~A] feedback-cb ~A received wrong goal" ros::name-space msg)
(setq time-to-finish 0.0)))
))
;; method for simulatio-modep
(:push-angle-vector-simulation (av tm &optional prev-av)
(setq previous-angle-vector prev-av)
(setq angle-vector-sequence (append angle-vector-sequence (list av)))
(setq timer-sequence (append timer-sequence (list tm)))
(setq current-time 0)
av)
(:pop-angle-vector-simulation ()
(let ((av (car angle-vector-sequence)) (tm (car timer-sequence)) scale-av)
(when tm
(setq scale-av (send ri :sub-angle-vector av previous-angle-vector))
(setq av (v+ previous-angle-vector (scale (/ current-time tm) scale-av)))
(incf current-time 100.0)
(when (> current-time tm)
(pop timer-sequence)
(pop angle-vector-sequence)
(setq previous-angle-vector av)
(setq current-time 0)
)
av)))
(:interpolatingp () (not (null timer-sequence)))
)
(defclass robot-interface
:super propertied-object
:slots (robot objects robot-state joint-action-enable warningp
controller-type controller-actions controller-timeout
namespace controller-table ;; hashtable :type -> (action)
visualization-topic simulation-default-look-all-p
joint-states-topic pub-joint-states-topic
viewer groupname)
:documentation "robot-interface is object for interacting real robot thorugh JointTrajectoryAction servers and JointState topics, this function uses old nervous-style interface for histrical reason. If JointTrajectoryAcion serve is not found, this instance runs as simulation mode, see \"Kinematics Simulator\" view as simulatied robot,
(setq *ri* (instance robot-interface :init))
(send *ri* :angle-vector (send *robot* :joint-angle) 2000)
(send *ri* :wait-interpolation)
(send *ri* :state :potentio-vector)
")
(defmethod robot-interface
(:init
(&rest args &key ((:robot r)) ((:objects objs)) (type :default-controller)
(use-tf2) ((:groupname nh) "robot_multi_queue") ((:namespace ns))
((:joint-states-topic jst) "joint_states")
((:joint-states-queue-size jsq) 1)
((:publish-joint-states-topic pjst) nil)
((:controller-timeout ct) 3)
((:visuzlization-marker-topic vmt) "robot_interface_marker_array")
((:simulation-look-all sim-look-all) t)
&allow-other-keys)
"Create robot interface
- robot : class name of robot
- objects : objects to be displayed in simulation (only for simulation)
- type : method name for defineing controller type
- use-tf2 : use tf2
- groupname : ros nodehandle group name
- namespace : ros nodehandle name space
- joint-states-topic jst : name for subscribing joint state topic
- joint-states-queue-size : queue size of joint state topic. if you have two different node publishing joint_state, better to use 2. default is 1
- publish-joint-state-topic : name for publishing joint state topic (only for simulation)
- conter-timeout : timeout seconds for controller lookup
- visualizatoin-marker-topic : topic name for visualize
"
(setq joint-states-topic jst)
(setq pub-joint-states-topic pjst)
(setq joint-action-enable t)
(setq controller-timeout ct)
(setq namespace ns)
(setq robot (cond ((derivedp r metaclass) (instance r :init))
(t r)))
(setq groupname nh)
(unless (ros::ok)
(ros::roseus "default_robot_interface"))
(ros::create-nodehandle groupname)
;;
(setq visualization-topic vmt)
(ros::advertise visualization-topic visualization_msgs::MarkerArray 100)
;;
(let ((start-time (now))
(ros-now (ros::time-now))
(wait-seconds 180)
diff-time)
(when (and (ros::get-param "use_sim_time" nil)
(= 0 (send ros-now :sec))
(= 0 (send ros-now :nsec)))
(ros::ros-debug "[~A] /use_sim_time is TRUE, check if /clock is pusblished" (ros::get-name))
(while (and (= 0 (send ros-now :sec)) (= 0 (send ros-now :nsec)))
(setq diff-time (send (now) :subtract start-time))
(unix:usleep (* 500 1000))
(when (> (send diff-time :second) wait-seconds)
(ros::ros-fatal "[~A] /use_sim_time is TRUE but /clock is NOT PUBLISHED" (ros::get-name))
(ros::ros-fatal "[~A] ~d seconds elapsed. aborting..." (ros::get-name) wait-seconds)
(exit 1))
(ros::ros-warn "[~A] waiting /clock... ~d seconds elapsed." (ros::get-name)
(+ (send diff-time :second) (* 1e-6 (send diff-time :micro))))
(setq ros-now (ros::time-now)))
(ros::ros-info "[~A] /clock is now published." (ros::get-name))))
(cond
(use-tf2
(unless (boundp '*tfl*)
(defvar *tfl* (instance ros::buffer-client :init))))
(t
(unless (boundp '*tfl*)
(defvar *tfl* (instance ros::transform-listener :init)))))
(ros::subscribe (if namespace (format nil "~A/~A" namespace joint-states-topic)
joint-states-topic) sensor_msgs::JointState
#'send self :ros-state-callback jsq :groupname groupname)
;;
(setq controller-table (make-hash-table :size 14 :test #'eq :rehash-size 1.2))
(setq controller-type type)
(setq controller-actions
(send self :add-controller controller-type :joint-enable-check t :create-actions t))
;;
(when (send self :simulation-modep)
(let ((old-viewer user::*viewer*))
(when (and x::*display* (> x::*display* 0))
(setq viewer (get (geo::find-viewer (send robot :name)) :pickviewer))
(unless viewer
(setq viewer (instance x::irtviewer :create :title (format nil "~A Kinematics Simulator" (send robot :name)) :view-name (send robot :name) :draw-floor t)))
(send viewer :objects (list robot))
(send self :draw-objects)
(if old-viewer (setq user::*viewer* old-viewer)))
(send self :objects objs)
(ros::advertise (cond
(pub-joint-states-topic pub-joint-states-topic)
(namespace
(format nil "~A/~A" namespace joint-states-topic))
(t joint-states-topic))
sensor_msgs::JointState)
(setq *top-selector-interval* 0.01)
(setq simulation-default-look-all-p sim-look-all)
(pushnew `(lambda () (send ,self :robot-interface-simulation-callback)) *timer-job*) ;; FIXME need to remove old one
(print *timer-job*)
))
self)
;;
(:add-controller (ctype &key (joint-enable-check) (create-actions))
(let (tmp-actions)
(cond
(create-actions
(mapcar
#'(lambda (param)
(let* ((controller-action (cdr (assoc :controller-action param)))
(action-type (cdr (assoc :action-type param)))
(action (instance controller-action-client :init self
(if namespace (format nil "~A/~A" namespace controller-action)
controller-action) action-type
:groupname groupname)))
(push action tmp-actions)))
(send self ctype))
(setq tmp-actions (nreverse tmp-actions))
;;
(dolist (action tmp-actions)
(unless controller-timeout
(ros::ros-warn "Waiting for actionlib interface forever because controler-timeout is nil"))
(unless (and joint-action-enable (send action :wait-for-server controller-timeout))
(ros::ros-warn "~A is not respond, ~A-interface is disabled" action (send robot :name))
(ros::ros-warn "~C[3~CmStarting 'Kinematics Simulator'~C[0m" #x1b 49 #x1b)
(ros::ros-warn "~C[3~Cm (If you do not intend to start Kinematics Simulator, make sure that you can run 'rostopic echo /~A/goal' and 'rostopic info /~A/goal')~C[0m" #x1b 52 (send action :name) (send action :name) #x1b)
(when joint-enable-check
(setq joint-action-enable nil)
(return))))
;;
(dolist (param (send self ctype))
(let* ((controller-state (cdr (assoc :controller-state param)))
(key (intern (string-upcase controller-state) *keyword-package*)))
(ros::subscribe (if namespace (format nil "~A/~A" namespace controller-state)
controller-state)
control_msgs::JointTrajectoryControllerState
#'send self :set-robot-state1 key :groupname groupname)))
)
(t ;; not creating actions, just search
(mapcar
#'(lambda (param)
(let* ((controller-action (cdr (assoc :controller-action param)))
(action-type (cdr (assoc :action-type param)))
(name (if namespace (format nil "~A/~A" namespace controller-action)
controller-action))
action)
(setq action (find-if #'(lambda (ac) (string= name (send ac :name)))
controller-actions))
(if action (push action tmp-actions))
))
(send self ctype))
(setq tmp-actions (nreverse tmp-actions))
))
;;
(setf (gethash ctype controller-table) tmp-actions)
tmp-actions
))
;;
(:robot-interface-simulation-callback ()
(let* ((joint-list (send robot :joint-list))
(all-joint-names (send-all joint-list :name)))
(send self :publish-joint-state)
(dolist (param (send self controller-type)) ;; assuming all action is stored in controller-type (:default-controller)
;(print (list 'p param))
(let* ((joint-names (cdr (assoc :joint-names param)))
(action-name (cdr (assoc :controller-action param)))
(action-client (find action-name controller-actions :key #'(lambda (x) (send x :name)) :test #'string=))
(av (send action-client :pop-angle-vector-simulation))
)
(when av
(dolist (j joint-names)
(if (find j all-joint-names :test #'string=)
(let ((i (position j all-joint-names :test #'string=)))
(send (elt joint-list i) :joint-angle (elt av i))))))
))
;;
(if viewer (send self :draw-objects))
))
(:publish-joint-state ;; for simulation mode (joint-action-enable is nil)
(&optional (joint-list (send robot :joint-list)))
(let (msg names positions velocities efforts)
(setq msg (joint-list->joint_state joint-list))
(send msg :header :stamp (ros::time-now))
(when (send self :simulation-modep)
(ros::publish (cond
(pub-joint-states-topic pub-joint-states-topic)
(namespace
(format nil "~A/~A" namespace joint-states-topic))
(t joint-states-topic))
msg))
msg))
(:angle-vector-safe
(av tm &key (simulation) (yes) (wait t) (norm-threshold 120) (angle-threshold 80) (velocity-threshold 240))
"send joint angle to robot with user-level confirmation. This method requires key input"
(let* ((q (send self :state :potentio-vector))
(jlst (send robot :joint-list))
(diff-q (v- av q))
(qv (scale (/ 1000.0 tm) diff-q))
(jqlst (mapcar #'(lambda (ang j) (cons ang (send j :name)))
(coerce diff-q cons) jlst))
(jvlst (mapcar #'(lambda (ang j) (cons ang (send j :name)))
(coerce qv cons) jlst))
warning)
(warn "angle-vector: ~A~%" av)
(when (> (norm diff-q) norm-threshold)
(setq warning t)
(warning-message 1 "WARNING: WARNING: diff angle-vector norm is ~d [deg]~%" (norm diff-q)))
(setq jqlst (sort jqlst #'(lambda (x y) (>= (abs (car x)) (abs (car y))))))
(setq jqlst (remove-if-not #'(lambda (x) (> (abs (car x)) angle-threshold)) jqlst))
(when jqlst
(setq warning t)
(warning-message 1 "WARNING: WARNING: typical diff angles (diff [deg] . Joint) are ~a~%" jqlst))
(setq jvlst (sort jvlst #'(lambda (x y) (>= (abs (car x)) (abs (car y))))))
(setq jvlst (remove-if-not #'(lambda (x) (> (abs (car x)) velocity-threshold)) jvlst))
(when jvlst
(setq warning t)
(warning-message 1 "WARNING: WARNING: typical velocities (velocity [deg/sec] . Joint) are ~a~%" jvlst))
(when (and (not simulation) (or yes (y-or-n-p "Do you send this angles to the robot ? ")))
(warn ";; send angle-vector~%")
(send self :angle-vector av tm)
(when wait
(warn ";; wait interpolation~%")
(send self :wait-interpolation))
(warn ";; done~%")
)
warning))
(:angle-vector-duration
(start end &optional (scale 1) (min-time 1.0) (ctype controller-type))
(let* ((unordered-joint-names
(flatten (mapcar #'(lambda (joint-param)
(cdr (assoc :joint-names joint-param)))
(send self ctype))))
(joint-list (send robot :joint-list)))
(let ((diff (coerce (v- end start) cons)))
(let ((time-list (mapcar #'(lambda (d j)
;; check if j is included in unordered-joint-names
(if (find (send j :name) unordered-joint-names
:test #'string=)
;; calculate time to reach the goal for each joint
;; using (scale * (j[m/rad] / max-joint-velocity))
(* scale (/ (if (derivedp j linear-joint) (* 0.001 (abs d)) (deg2rad (abs d)))
(send j :max-joint-velocity)))
0))
diff joint-list)))
;; find maximum time to reach goal for all joint
(let ((max-time (apply #'max time-list)))
(max max-time min-time))))))
(:angle-vector-simulation
(av tm ctype)
(let* ((prev-av (send robot :angle-vector)))
(send-all (gethash ctype controller-table) :push-angle-vector-simulation av tm prev-av)))
(:angle-vector
(av &optional (tm nil) (ctype controller-type) (start-time 0) &key (scale 1) (min-time 1.0) (end-coords-interpolation nil))
"Send joind angle to robot, this method retuns immediately, so use :wait-interpolation to block until the motion stops.
- av : joint angle vector [deg]
- tm : (time to goal in [msec])
if designated tm is faster than fastest speed, use fastest speed
if not specified, it will use 1/scale of the fastest speed .
if :fastest is specefied use fastest speed calcurated from max speed
- ctype : controller method name
- start-time : time to start moving
- scale : if tm is not specified, it will use 1/scale of the fastest speed
- min-time : minimum time for time to goal
- end-coords-interpolation : set t if you want to move robot in cartesian space interpolation
"
(if end-coords-interpolation
(return-from :angle-vector (send self :angle-vector-sequence (list av) (list tm) ctype start-time :scale scale :min-time min-time :end-coords-interpolation t)))
(setq ctype (or ctype controller-type)) ;; use default controller-type if ctype is nil
(unless (gethash ctype controller-table)
(warn ";; controller-type: ~A not found" ctype)
(return-from :angle-vector))
;;Check and decide tm
(let ((fastest-tm (* 1000 (send self :angle-vector-duration
(send self :state :potentio-vector) av scale min-time ctype))))
(cond
;;Fastest time Mode
((equal tm :fast)
(setq tm fastest-tm))
;;Normal Number disgnated Mode
((numberp tm)
(if (< tm fastest-tm)
(setq tm fastest-tm)))
;;Safe Mode (Speed will be 5 * fastest-time)
((null tm)
(setq tm (* 5 fastest-tm)))
;;Error Not Good Input
(t
(ros::ros-error ":angle-vector tm is invalid. args: ~A" tm)
(error ":angle-vector tm is invalid. args: ~A" tm)))
)
;; for simulation mode
(when (send self :simulation-modep)
(if av (send self :angle-vector-simulation av tm ctype)))
(send robot :angle-vector av)
(let ((cacts (gethash ctype controller-table)))
(mapcar
#'(lambda (action param)
(send self :send-ros-controller
action (cdr (assoc :joint-names param)) ;; action server and joint-names
start-time ;; start time
(list
(list av ;; positions
(instantiate float-vector (length av)) ;; velocities
(/ tm 1000.0))))) ;; duration
cacts (send self ctype)))
av)
(:angle-vector-sequence
(avs &optional (tms (list 3000)) (ctype controller-type) (start-time 0.1) &key (scale 1) (min-time 0.0) (end-coords-interpolation nil))
"Send sequence of joind angle to robot, this method retuns immediately, so use :wait-interpolation to block until the motion stops.
- avs: sequence of joint angles(float-vector) [deg], (list av0 av1 ... avn)
- tms: sequence of duration(float) from previous angle-vector to next goal [msec], (list tm0 tm1 ... tmn)
if tms is atom, then use (list (make-list (length avs) :initial-element tms))) for tms
if designated each tmn is faster than fastest speed, use fastest speed
if tmn is nil, then it will use 1/scale of the fastest speed .
if :fastest is specefied, use fastest speed calcurated from max speed
- ctype : controller method name
- start-time : time to start moving
- scale : if tms is not specified, it will use 1/scale of the fastest speed
- min-time : minimum time for time to goal
- end-coords-interpolation : set t if you want to move robot in cartesian space interpolation
"
(setq ctype (or ctype controller-type)) ;; use default controller-type if ctype is nil
(unless (gethash ctype controller-table)
(warn ";; controller-type: ~A not found" ctype)
(return-from :angle-vector-sequence))
(send self :spin-once) ;; for :state :potentio-vector
(let ((st 0) (traj-points nil)
(av-prev (send self :state :potentio-vector)) av av-next
tm tm-next fastest-tm
(vel (instantiate float-vector (length (car avs)))))
(if (atom tms) (setq tms (make-list (length avs) :initial-element tms)))
(cond
((< (length tms) (length avs))
(nconc tms (make-list (- (length avs) (length tms)) :initial-element (car (last tms)))))
((> (length tms) (length avs))
(ros::ros-warn "length of tms should be the same or smaller than avs")
(setq tms (subseq tms 0 (length avs)))))
(when end-coords-interpolation ;; set end-coords interpolation
(let ((av-orig (send robot :angle-vector)) ;; initial av, restore at end
(c-orig (send robot :copy-worldcoords)) ;; inital coords, restore at end
(av-prev-orig av-prev) ;; prev-av
(limbs '(:larm :rarm :lleg :rleg :torso :head)) ;; defined in https://github.com/euslisp/jskeus/blob/master/irteus/irtrobot.l#L79
target-limbs
(minjerk (instance minjerk-interpolator :init))
end-coords-prev end-coords-current ec-prev ec-current
interpolated-avs interpolated-tms
tm i p (ret t)) ;; if nil failed to interpolate
;; set prev-av
(send robot :angle-vector av-prev)
(setq end-coords-prev (mapcar #'(lambda (limb) (send robot limb :end-coords :copy-worldcoords)) limbs))
;; choose moved end-coords
(setq i 0)
(dolist (av avs)
(send robot :angle-vector av)
(setq end-coords-current (mapcar #'(lambda (limb) (send robot limb :end-coords :copy-worldcoords)) limbs))
(setq target-limbs nil)
(dotimes (l (length limbs))
(setq ec-prev (elt end-coords-prev l) ec-current (elt end-coords-current l))
(when (and ec-prev ec-current
(or (> (norm (send ec-prev :difference-position ec-current)) 1)
(> (norm (send ec-prev :difference-rotation ec-current)) (deg2rad 1))))
(push (elt limbs l) target-limbs)))
(send minjerk :reset :position-list (list #f(0) #f(1)) :time-list (list (elt tms i)))
(send robot :angle-vector av-prev)
(if target-limbs
(progn
(send minjerk :start-interpolation)
(while (send minjerk :interpolatingp)
(send minjerk :pass-time 100)
(setq p (elt (send minjerk :position) 0))
;; set midpoint of av as initial pose of IK
(send robot :angle-vector (midpoint p av-prev av))
(dolist (limb target-limbs)
;; don't move arm by IK when interpolation is already ended
(if (>= p 1) (return))
(setq ec-prev (elt end-coords-prev (position limb limbs))
ec-current (elt end-coords-current (position limb limbs)))
(setq ret (and ret
(send robot limb :inverse-kinematics (midcoords p ec-prev ec-current)))))
(push (send robot :angle-vector) interpolated-avs)
(push 100 interpolated-tms)
))
(progn
(push av interpolated-avs)
(push 50 interpolated-tms)))
(setq end-coords-prev end-coords-current)
(setq av-prev av)
(incf i)) ;; dolist (av avs)
;; restore states
(setq avs (nreverse interpolated-avs) tms (nreverse interpolated-tms))
(send robot :move-to c-orig :world)
(send robot :angle-vector av-orig)
(setq av-prev av-prev-orig)
(unless ret
(warning-message 1 ":anlge-vector-sequnce fail to generate end-coords-interpolation motion~%")
(return-from :angle-vector-sequence nil))
))
(prog1 ;; angle-vector-sequence returns avs
avs
(while avs
(setq av (pop avs))
(setq fastest-tm (* 1000 (send self :angle-vector-duration av-prev av scale min-time ctype)))
(setq tm (pop tms))
(cond
((equal tm :fast)
(setq tm fastest-tm))
((null tm)
(setq tm (* 5 fastest-tm)))
((numberp tm)
(if (< tm fastest-tm)
(setq tm fastest-tm)))
(t (ros::ros-error ":angle-vector-sequence tm is invalid. args: ~A" tm)
(error ":angle-vector-sequence tm is invalid. args: ~A" tm)))
(if (car tms)
(progn
(setq tm-next ( car tms))
(setq fastest-tm-next (* 1000 (send self :angle-vector-duration av (car avs) scale min-time ctype)))
(cond
((equal tm-next :fast)
(setq tm-next fastest-tm-next))
((null tm)
(setq tm (* 5 fastest-tm)))
((numberp tm-next)
(if (< tm-next fastest-tm-next)
(setq tm-next fastest-tm-next)))
(t (ros::ros-error ":angle-vector-sequence tm is invalid. args: ~A" tm)
(error ":angle-vector-sequence tm is invalid. args: ~A" tm)))
)
(setq tm-next 1)
)
(if (and (setq av-next (car avs)) (> tm 0) (> tm-next 0))
(let ((v0 (send self :sub-angle-vector av av-prev))
(v1 (send self :sub-angle-vector av-next av)))
(dotimes (i (length vel))
(setf (elt vel i)
(if (>= (* (elt v0 i) (elt v1 i)) 0)
(* 0.5 (+ (* (/ 1000.0 tm) (elt v0 i))
(* (/ 1000.0 tm-next) (elt v1 i))))
0.0)))
)
(fill vel 0))
;; for simulation mode
(if (send self :simulation-modep)
(send self :angle-vector-simulation av tm ctype))
;;
;; update only joints with in current controller instaed of (send robot :angle-vector av)
(unless (send self :simulation-modep)
(let* ((joint-names (flatten (mapcar #'(lambda (c) (cdr (assoc :joint-names c))) (send self ctype))))
(joint-ids (mapcar #'(lambda (joint-name) (position joint-name (send robot :joint-list) :test #'(lambda (n j) (equal n (send j :name))))) joint-names)))
(mapcar #'(lambda (name id)
(if (and (send robot :joint name) id (> (length av) id))
(send (send robot :joint name) :joint-angle (elt av id))
(warning-message 3 "[robot-interface.l] (angle-vector-sequence) could not find joint-name '~A' (~A) or joint-id ~A (av length ~A)~%" name (send robot :joint name) id (length av))))
joint-names joint-ids)))
; (when (send self :simulation-modep)
; (send self :publish-joint-state)
; (if viewer (send self :draw-objects)))
(push (list av
(copy-seq vel) ;; velocities
(/ (+ st tm) 1000.0)) ;; tm + duration
traj-points)
(setq av-prev av)
(incf st tm))
;;
(let ((cacts (gethash ctype controller-table)))
(unless cacts
(warn ";; controller-type: ~A not found" ctype)
(return-from :angle-vector-sequence))
(mapcar
#'(lambda (action param)
(send self :send-ros-controller
action (cdr (assoc :joint-names param)) ;; action server and joint-names
start-time ;; start time
traj-points))
cacts (send self ctype)))
)))
(:wait-interpolation (&optional (ctype) (timeout 0)) ;; controller-type
"Wait until last sent motion is finished
- ctype : controller to be wait
- timeout : max time of for waiting
- return values is a list of interpolatingp for all controllers, so (null (some #'identity (send *ri* :wait-interpolation))) -> t if all interpolation has stopped"
(if (send self :simulation-modep)
(while (send self :interpolatingp)
(send self :robot-interface-simulation-callback))
(cond ;; real robot
(ctype
(let ((cacts (gethash ctype controller-table)))
(send-all cacts :wait-for-result :timeout timeout)))
(t (send-all controller-actions :wait-for-result :timeout timeout))))
(send-all controller-actions :interpolatingp))
(:interpolatingp (&optional (ctype)) ;; controller-type ;; check someone is moving
"Check if the last sent motion is executing
return t if interpolating"
(when (send self :simulation-modep)
(return-from :interpolatingp
(some #'(lambda (a) (send a :interpolatingp)) controller-actions)))
(send self :spin-once)
(cond
(ctype
(let ((cacts (gethash ctype controller-table)))
(some #'(lambda (x) (eq x ros::*simple-goal-state-active*))
(send-all cacts :get-state))))
(t (some #'(lambda (x) (eq x ros::*simple-goal-state-active*))
(send-all controller-actions :get-state)))))
(:wait-interpolation-smooth (time-to-finish &optional (ctype))
"Return time-to-finish [msec] before the sent command is finished. Example code are:
(dolist (av (list av1 av2 av3 av4))
(send *ri* :angle-vector av)
(send *ri* :wait-interpolation-smooth 300))
Return value is a list of interpolatingp for all controllers, so (null (some #'identity (send *ri* :wait-interpolation))) -> t if all interpolation has stopped"
(when (not (send self :simulation-modep))
(let ((tm (ros::time-now))
(cacts (cond
(ctype (gethash ctype controller-table))
(t controller-actions))))
(while (some #'(lambda (x)
(and
(<= (send (ros::time- (send x :last-feedback-msg-stamp) tm) :to-sec) 0)
(let ((goal (send (x . ros::comm-state) :action-goal)))
(>= (send (ros::time- (ros::time+ (send goal :header :stamp)
(cond ((derivedp goal control_msgs::singlejointpositionactiongoal)
(send goal :goal :min_duration))
(t
(send (car (last (send goal :goal :trajectory :points))) :time_from_start))))
(ros::time-now)) :to-sec) 0))))
cacts)
(send self :spin-once) ;; need to wait for feedback
(send self :ros-wait 0.005))))
(while (null (send self :interpolating-smoothp time-to-finish ctype))
(send self :ros-wait 0.005)))
(:interpolating-smoothp (time-to-finish &optional (ctype)) ;; controller-type
"Check inf the last sent motion will stops for next time-to-finish [msec]"
(when (send self :simulation-modep)
(return-from :interpolating-smoothp t))
(send self :spin-once)
(every #'(lambda (x) (< x (/ time-to-finish 1000.0)))
(cond
(ctype
(let ((cacts (gethash ctype controller-table)))
(send-all cacts :time-to-finish)))
(t
(send-all controller-actions :time-to-finish)))))
(:stop-motion (&key (stop-time 0))
"Stop current executing motion"
(let ((av (send self :state :potentio-vector)))
(send self :angle-vector av stop-time)
(send self :wait-interpolation)))
(:cancel-angle-vector
(&key ((:controller-actions ca))
((:controller-type ct))
(wait))
"Cancel current joint trajetory action"
(when (null (or ca ct)) (setq ca controller-actions))
(when ca (send-all ca :cancel-all-goals))
(when ct (send-all (gethash ct controller-table) :cancel-all-goals))
(when wait
(send self :wait-interpolation)
(send self :spin-once))
t)
;;
(:worldcoords () "Returns world coords of robot, This method uses caced data" (send robot :copy-worldcoords))
(:torque-vector
()
"Return torque vector of robot, This method uses caced data"
(coerce (send-all (send robot :joint-list) :joint-torque) float-vector))
(:potentio-vector () "Retuns current robot angle vector, This method uses caced data" (send robot :angle-vector))
(:reference-vector () "Return reference joint angle vector, This method uread current state." (send self :state-vector :desired))
(:actual-vector () "Returns current robot angle vector, This method read curren tstate." (send self :state-vector :actual))
(:error-vector () "Returns error vector of the robot, This method read current state." (send self :state-vector :error))
(:state-vector
(type &key ((:controller-actions ca) controller-actions)
((:controller-type ct) controller-type))
(let* ((joint-list (send robot :joint-list))
(av (instantiate float-vector (length joint-list))))
(dolist (param (send self controller-type))
(let* ((ctrl (cdr (assoc :controller-state param)))
(key (intern (string-upcase ctrl) *keyword-package*))
(msg (send self :state key))
(idx 0))
;;(print (list ctrl key msg))
(unless msg (return-from :state-vector nil))
(dolist (jname (send msg :joint_names))
(let ((jangle (elt (send msg type :positions) idx))
(j (find-if #'(lambda (jn) (string= (send jn :name) jname))
joint-list)))
(incf idx)
(when j
(setf (elt av (position j joint-list))
(cond ((derivedp j linear-joint) (* jangle 1000))
((derivedp j rotational-joint) (rad2deg jangle))))))
)))
av))
(:stamp () "Returns the stamp which was read at latest callback" (send self :get-robot-state :stamp))
;;
(:send-ros-controller
(action joint-names starttime trajpoints)
(when (send self :simulation-modep)
(return-from :send-ros-controller nil))
(if (and warningp
(yes-or-no-p (format nil "~C[3~CmAre you sure to move the real robot? (~A) ~C[0m" #x1b 49 (send action :name) #x1b)))
(return-from :send-ros-controller nil))
(let* ((goal (send action :make-goal-instance))
(goal-points nil)
(st (if (numberp starttime)
(ros::time+ (ros::time-now) (ros::time starttime))
starttime))
(joints (mapcar #'(lambda (x)
(send robot (intern (string-upcase x) *keyword-package*)))
joint-names)))
(send goal :header :seq 1)
(send goal :header :stamp st)
(cond
((equal (class goal) control_msgs::SingleJointPositionActionGoal)
(let* ((joint (car joints))
(id (position joint (send robot :joint-list)))
(pos (deg2rad (elt (elt (car trajpoints) 0) id)))
)
(send goal :goal :position pos)
(send goal :goal :max_velocity 5)
(send self :spin-once)
)
)
(t
(send goal :goal :trajectory :joint_names joint-names)
(send goal :goal :trajectory :header :stamp st)
(dolist (trajpt trajpoints)
(let* ((all-positions (elt trajpt 0))
(all-velocities (elt trajpt 1))
(duration (elt trajpt 2))
(positions (instantiate float-vector (length joint-names)))
(velocities (instantiate float-vector (length joint-names))))
(dotimes (i (length joints))
(let* ((joint (elt joints i))
(id (position joint (send robot :joint-list)))
p v)
(setq p (elt all-positions id)
v (elt all-velocities id))
(cond
((derivedp joint rotational-joint)
(setq p (deg2rad p))
(setq v (deg2rad v)))
(t
(setq p (* 0.001 p))
(setq v (* 0.001 v))))
(setf (elt positions i) p)
(setf (elt velocities i) v)))
(push (instance trajectory_msgs::JointTrajectoryPoint
:init
:positions positions
:velocities velocities
:time_from_start (ros::time duration))
goal-points)
))
(send self :spin-once)
(send goal :goal :trajectory :points goal-points)
))
(send action :send-goal goal)
))
;;
(:set-robot-state1
(key msg)
(if (assoc key robot-state)
(setf (cdr (assoc key robot-state)) msg)
(push (cons key msg) robot-state)))
(:get-robot-state
(key)
(cdr (assoc key robot-state)))
(:ros-state-callback
(msg)
(let ((robot-state-names (cdr (assoc :name robot-state))))
;; set joint name
(cond
(robot-state-names
;; merge robot-state name list
(let ((diff (set-difference (send msg :name) robot-state-names :test #'string=)))
(when diff
(setq robot-state-names (append robot-state-names diff))
;; resize joint-state data list
(dolist (key '(:position :velocity :effort))
(setf (cdr (assoc key robot-state))
(concatenate float-vector
(cdr (assoc key robot-state))
(instantiate float-vector (- (length robot-state-names)
(length (cdr (assoc key robot-state))))))))
;; resize stamp-list
(setf (cdr (assoc :stamp-list robot-state))
(concatenate cons
(cdr (assoc :stamp-list robot-state))
(make-list (- (length robot-state-names) (length (cdr (assoc :stamp-list robot-state))))))))
))
(t
(push (cons :name (send msg :name)) robot-state)
(setq robot-state-names (send msg :name))
(dolist (key '(:position :velocity :effort))
(push (cons key (instantiate float-vector (length robot-state-names))) robot-state))
(push (cons :stamp-list (make-list (length robot-state-names))) robot-state)))
;; set joint data
(let ((joint-names (send msg :name))
(stamp-list (cdr (assoc :stamp-list robot-state)))
(idx 0) joint-idx joint-data data-vec)
(dolist (key '(:position :velocity :effort))
(setq joint-data (send msg key) idx 0)
(when (= (length joint-names) (length joint-data))
(setq data-vec (cdr (assoc key robot-state)))
(dolist (jn joint-names)
(setq joint-idx (position jn robot-state-names :test #'string=))
(setf (elt data-vec joint-idx) (elt joint-data idx))
(incf idx)
;; update stamp
(when (eq key :position)
(setf (elt stamp-list joint-idx) (send msg :header :stamp)))
))))
(setf (cdr (assoc :name robot-state)) robot-state-names)
;; (dolist (key '(:name :position :velocity :effort))
;; (send self :set-robot-state1 key (send msg key)))
(send self :set-robot-state1 :stamp (send msg :header :stamp))))
(:wait-until-update-all-joints
(tgt-tm)
(let ((initial-time))
(if (equal (class tgt-tm) (class (ros::time 0)))
(setq initial-time (send tgt-tm :to-nsec))
(setq initial-time (send (send (ros::time) :now) :to-nsec)))
(while t
(when (every #'identity (mapcar #'(lambda (ts) (> (send ts :to-nsec) initial-time)) (cdr (assoc :stamp-list robot-state))))
(return-from nil nil))
(if (send self :simulation-modep) (send self :robot-interface-simulation-callback)) ;; to update robot-state
(send self :spin-once)
)))
(:update-robot-state
(&key (wait-until-update nil))
(let (joint-names positions velocities efforts)
(send self :spin-once)
(when wait-until-update
(send self :wait-until-update-all-joints wait-until-update))
;; (unless joint-action-enable
;; (return-from :update-robot-state (send robot :angle-vector)))
(unless robot-state (return-from :update-robot-state))
(setq joint-names (cdr (assoc :name robot-state))
positions (cdr (assoc :position robot-state))
velocities (cdr (assoc :velocity robot-state))
efforts (cdr (assoc :effort robot-state)))
(let ((joint-num (length joint-names)))
(when (not (eq joint-num (length velocities)))
(setq velocities (instantiate float-vector joint-num)))
(when (not (eq joint-num (length efforts)))
(setq efforts (instantiate float-vector joint-num))))
(mapcar #'(lambda (n p v e)
(let (j (kn (intern (string-upcase n) *keyword-package*)))
(when (and (find-method robot kn) (setq j (send robot kn)))
(send j :ros-joint-angle p)
;; velocity
(send j :joint-velocity v)
;; effort
(send j :joint-torque e))))
(coerce joint-names cons)
(coerce positions cons)
(coerce velocities cons)
(coerce efforts cons))))
(:state
(&rest args)
"Read robot state and update internal robot instance
- :wait-until-update nil wait until joint_state is updated"
(send self :update-robot-state
:wait-until-update (when (position :wait-until-update args) (elt args (+ (position :wait-until-update args) 1))))
(unless args (return-from :state))
(case (car args)
((:potentio-vector :angle-vector)
(send robot :angle-vector))
(:torque-vector
(send self :torque-vector))
(:gripper
(apply #'send self :gripper (cdr args)))
(t
(let ((mm (find (car args) (remove-if-not #'(lambda (x) (substringp "-VECTOR" (string x))) (send self :methods)))))
(if mm ;; if xx-vector method exists
(send* self mm (cdr args))
(let ((cur robot-state))
(dolist (key args cur)
(setq cur (cdr (assoc key cur))))))
))))
;;
(:default-controller
()
(list
(list
(cons :controller-action "fullbody_controller/follow_joint_trajectory_action")
(cons :controller-state "fullbody_controller/state")
(cons :action-type control_msgs::FollowJointTrajectoryAction)
(cons :joint-names (mapcar #'(lambda (n) (if (symbolp n) (symbol-name n) n)) (send-all (send robot :joint-list) :name))))))
;;
(:sub-angle-vector (v0 v1)
(let ((ret (v- v0 v1))
(joint-list (send robot :joint-list))
(i 0) j)
(while (setq j (pop joint-list))
(if (and (= (send j :min-angle) *-inf*) (= (send j :max-angle) *inf*))
(cond ((> (elt ret i) 180.0)
(setf (elt ret i) (- (elt ret i) 360.0)))
((< (elt ret i) -180.0)
(setf (elt ret i) (+ (elt ret i) 360.0)))))
(incf i))
ret))
;;
(:robot (&rest args) (forward-message-to robot args))
(:viewer (&rest args) (forward-message-to viewer args))
(:objects (&optional objs)
(when objs
(setq objects (mapcar #'(lambda (o) (let ((p (send o :parent))) (if p (send p :dissoc o)) (setq o (copy-object o)) (if p (send p :assoc o)) o)) objs))
(mapcar #'(lambda (o) (setf (get o :GL-DISPLAYLIST-ID) nil)) (x::draw-things objects))
(when viewer
(send viewer :objects (append (list robot) objects))
(send self :draw-objects)))
objects)
(:set-simulation-default-look-at (look-at-p)
(setq simulation-default-look-all-p look-at-p))
(:draw-objects (&key look-all)
(when viewer
(when (or simulation-default-look-all-p look-all)
(send viewer :look-all (send (geo::make-bounding-box (flatten (send-all (x::draw-things robot) :vertices))) :grow 0.3)))
(send viewer :draw-objects)
(x::window-main-one)))
(:find-object (name-or-obj) "Returns objects with given name or object of the same name."
(let ((name (if (derivedp name-or-obj cascaded-link) (send name-or-obj :name) name-or-obj)))
(append
(mapcan #'(lambda (x) (if (derivedp x scene-model) (send x :find-object name) nil)) objects)
(mapcan #'(lambda (x) (if (string= name (send x :name)) (list x))) objects))))
;;
(:joint-action-enable (&optional (e :dummy)) (if (not (eq e :dummy)) (setq joint-action-enable e)) joint-action-enable)
(:simulation-modep () "Check if simulation mode" (null joint-action-enable))
(:warningp (&optional (w :dummy)) "When warning mode, it wait for user's key input before sending angle-vector to the robot" (if (not (eq w :dummy)) (setq warningp w)) warningp)
(:spin-once () (ros::spin-once groupname))
(:send-trajectory (joint-trajectory-msg
&key ((:controller-type ct) controller-type) (starttime 1) &allow-other-keys)
(unless (gethash ct controller-table)
(warn ";; controller-type: ~A not found" ct)
(return-from :send-trajectory))
(mapcar
#'(lambda (action param)
(send self :send-trajectory-each
action (cdr (assoc :joint-names param)) ;; action server and joint-names
joint-trajectory-msg
starttime))
(gethash ct controller-table) (send self ct)))
(:send-trajectory-each
(action joint-names traj &optional (starttime 0.2))
(let* ((jnames (send traj :joint_names))
(ilst (mapcar #'(lambda (jn) (position jn jnames :test #'string=)) joint-names))
points-lst)
(when (some #'identity ilst)
(setq ilst (mapcar #'(lambda (jn)
(let ((p (position jn jnames :test #'string=)))
(unless p
(setq p (send robot (intern (string-upcase jn) *keyword-package*))))
p))
joint-names))
(dolist (p (send traj :points))
(let ((poss (send p :positions))
(vels (send p :velocities))
(effs (send p :accelerations))
plst vlst elst)
(dolist (i ilst)
(cond
((numberp i)
(push (elt poss i) plst)
(if (and vels (> (length vels) i)) (push (elt vels i) vlst))
(if (and effs (> (length effs) i)) (push (elt effs i) elst)))
(t
(push (send i :ros-joint-angle) plst)
(if vels (push 0 vlst))
(if effs (push 0 elst))
(ros::ros-warn ";; trajectory contains lacking joint names")
)))
(push
(instance trajectory_msgs::JointTrajectoryPoint :init
:positions (coerce (nreverse plst) float-vector)
:velocities (if vels (coerce (nreverse vlst) float-vector))
:accelerations (if effs (coerce (nreverse elst) float-vector))
:time_from_start (send p :time_from_start)) points-lst)
))
(let ((goal (send action :make-goal-instance))
(st (ros::time+ (ros::time-now) (ros::time starttime))))
(send goal :header :stamp st)
(send goal :header :seq 1)
(send goal :goal :trajectory :header :stamp st)
(send goal :goal :trajectory :header :seq 1)
(send goal :goal :trajectory :joint_names joint-names)
(send goal :goal :trajectory :points (nreverse points-lst))
(send self :spin-once)
(send action :send-goal goal))
(apply-trajectory_point joint-names (car (last points-lst)) robot)
) ;;; /when ilst
))
(:ros-wait (tm &key (spin) (spin-self) (finish-check) &allow-other-keys) ;; just wait in ros-time
(ros::rate 100) ;;
(let ((st (ros::time-now)))
(if spin (ros::spin-once))
(if spin-self (send self :spin-once))
(while t
(when finish-check
(if (funcall finish-check self)
(return)))