-
Notifications
You must be signed in to change notification settings - Fork 25
/
robot.js
2305 lines (2125 loc) · 107 KB
/
robot.js
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
/* Created by Fry on 3/29/16. */
var Robot = class Robot {
constructor (){
}
/*static robot_names(){
var result = []
for(var name in Robot){
if (Robot[name] instanceof Robot){
result.push(name)
}
}
return result
}
*/
static all_robots(){
let result = []
for(let robot_name of Robot.all_names) { result.push(Robot[robot_name]) }
return result
}
static default_robot_name(){
if (Robot.all_names.length > 0){
return Robot.all_names[Robot.all_names.length - 1]
}
else {
return "r1"
}
}
//put the new item on the end, even if ypu have to remove it from the middle,
//because we want the latest on the end for default_robot_name
static set_robot_name(name, robot_instance){
Robot[name] = robot_instance
//ensure name is on end of all_names
let i = Robot.all_names.indexOf(name)
if (i != -1){ Robot.all_names.splice(i, 1) }
Robot.all_names.push(name)
if (i == -1) {
$("#videos_id").prepend("<option>Robot: " + name + "</option>")
}
}
static get_simulate_actual(simulate_val){
if (simulate_val === true) { return true }
else if (simulate_val === false) { return false }
else if (simulate_val === "both") { return "both" }
else if (simulate_val === null) { return persistent_get("default_dexter_simulate") }
else { shouldnt("get_simulate_actual passed illegal value: " + simulate_val) }
}
jobs_using_this_robot(){
let result = []
for (let j of Job.all_jobs()){
if (j.robot === this){ result.push(j) }
}
return result
}
active_jobs_using_this_robot(){
let result = []
for (let j of Job.all_jobs()){
if ((j.robot === this) &&
j.is_active()){
result.push(j)
}
}
return result
}
is_initialized(){ return true }
//pretty weak. Only will work as long as Robots don't overlap in oplets
//used in robot_history_status
static instruction_type_to_function_name(ins_type){
let fn_name = Dexter.instruction_type_to_function_name_map[ins_type]
if (fn_name) {return "Dexter." + fn_name}
fn_name = Serial.instruction_type_to_function_name_map[ins_type]
if (fn_name) {return "Serial." + fn_name}
return null
}
//Control Instructions
static error(reason){ //declare that an error happened. This will cause the job to stop.
return new Instruction.Control.error(reason) //["error", reason]
}
static go_to(instruction_location){
return new Instruction.Control.go_to(instruction_location)
}
static grab_robot_status(user_data_variable,
starting_index = Serial.DATA0,
ending_index=null){
return new Instruction.Control.grab_robot_status(user_data_variable,
starting_index,
ending_index)
}
static if_any_errors(job_names=[], instruction_if_error=null){
return new Instruction.Control.if_any_errors(job_names, instruction_if_error)
}
static label(name){
return new Instruction.Control.label(name)
}
static out(val, color="black", temp){
return new Instruction.Control.out(val, color, temp)
}
/* Warning the below is at least somewhat obsolete as of new arch Aug 25, 2016
The workflow for sent_to_job.
job.sent_to_job calls Instruction.Contol.sent_to_job as for all control instructions.
That creates an instance to sent_to_job and sticks it on the source_job do_list.
When that instruction is run, its do_item calls
to_job_instance.destination_do_send_to_job(this) which sticks the
do_list_item onto the destination job's do list,
and, if the source job is going to wait for the instruction to be done,
an additonal control instruction of type
Instruction.Control.destination_send_to_job_is_done is stuck on the do_list
of the desitination job.
Then the destination job runs those items
and when the instruction destination_send_to_job_is_done is run,
it calls the fns to get the values for the vars to set in from_instance,
and calls from_job_instance.send_to_job_receive_done(this.params)
passing those values to the from_instance.
Then send_to_job_receive_done sets the user_data vars in the from job.
*/
static send_to_job({do_list_item = null,
where_to_insert = null,
wait_until_done = false, //if true, a_job.send_to_job_receive_done will be called withthe do_list_item is done by the to_job
start = false,
unsuspend = false,
status_variable_name = null} = {}){
return new Instruction.Control.send_to_job(arguments[0])
}
//rarely used, but can be used to customize a job with additional do_list items at the start.
static sent_from_job ({do_list_item = null, //can be null, a single instruction, or an array of instructions
from_job_name = null,
from_instruction_id = null,
where_to_insert = "next_top_level", //just for debugging
wait_until_done = false} = {}){
return new Instruction.Control.sent_from_job(arguments[0])
}
static start_job(job_name, start_options={}, if_started="ignore"){
return new Instruction.Control.start_job(job_name, start_options, if_started)
}
static stop_job(instruction_location, reason, perform_when_stopped = false){
return new Instruction.Control.stop_job(instruction_location, reason, perform_when_stopped)
}
static suspend(){
return new Instruction.Control.suspend()
}
//unsuspend is a instance meth on Job and should be!
static sync_point(name, job_names=[]){
return new Instruction.Control.sync_point(name, job_names)
}
static wait_until(fn_date_dur){
return new Instruction.Control.wait_until(fn_date_dur)
}
//arg order is a bit odd because the headers come after the response_variable_name.
//but the response_variable_name is takes the place of the primary callback,
//and that's the order I have for get_page (headers on end) which very often
//default to undefined.
static get_page(url_or_options, response_variable_name="http_response"){
return new Instruction.Control.Get_page(url_or_options, response_variable_name)
}
static play(note_or_phrase){
return new Instruction.Control.play_notes(note_or_phrase)
}
close_robot(){ //overridden in Serial and Dexter
}
}
Robot.all_names = []
Robot.robot_status_labels = [] //overridden by Serial and Dexter, needed by Show robot status history button
/*simulate vs non-simulate makes no difference so set simulate to false */
var Brain = class Brain extends Robot { /*no associated hardware */
constructor({name = "b1"}={}){
super()
this.name = name
Robot.set_robot_name(this.name, this)
let i = Brain.all_names.indexOf(this.name)
if (i != -1) { Brain.all_names.splice(i, 1) }
Brain.all_names.push(this.name) //ensures the last name on the list is the latest with no redundancy
Brain.last_robot = this
this.simulate = false
//the_job //a Robot can have at most 1 current job associated with it.
}
toString(){
return "{instance of Brain:: name: " + this.name + "}"
}
stringify(){
return "Brain: <i>name</i>: " + this.name
}
start(job_instance) {
job_instance.set_status_code("running")
job_instance.set_up_next_do(0)
}
finish_job() {}
send(inst_array_with_inst_id) {
let job_id = inst_array_with_inst_id[Instruction.JOB_ID]
var job_instance = Job.job_id_to_job_instance(job_id)
var reason = "An instruction intended for a physical robot: " + inst_array_with_inst_id + "<br/>was sent to a Robot.Human: " + this.name + ",<br/> which has no physical robot."
job_instance.stop_for_reason("errored", reason)
out(reason, "red")
throw new Error("send called on Robot.Brain, which has no physical robot.")
}
}
Brain.all_names = []
var Human = class Human extends Brain { /*no associated hardware */
constructor({name = "h1"}={}){
super()
this.name = name
Robot.set_robot_name(this.name, this)
let i = Human.all_names.indexOf(this.name)
if (i != -1) { Human.all_names.splice(i, 1) }
Human.all_names.push(this.name) //ensures the last name on the list is the latest with no redundancy
Human.last_robot = this
this.simulate = false
//the_job //a Robot can have at most 1 current job associated with it.
}
toString(){
return "{instance of Human:: name: " + this.name + "}"
}
stringify(){
return "Human: <i>name</i>: " + this.name
}
start(job_instance) {
job_instance.set_status_code("running")
job_instance.set_up_next_do(0)
}
finish_job() {}
send(inst_array_with_inst_id) {
let job_id = inst_array_with_inst_id[Instruction.JOB_ID]
var job_instance = Job.job_id_to_job_instance(job_id)
var reason = "An instruction intended for a physical robot: " + inst_array_with_inst_id + "<br/>was sent to a Robot.Human: " + this.name + ",<br/> which has no physical robot."
job_instance.stop_for_reason("errored", reason)
out(reason, "red")
throw new Error("send called on Robot.Brain, which has no physical robot.")
}
//the human instructions
static task({task = "", dependent_job_names=[],
title, x=200, y=200, width=400, height=400, background_color = "rgb(238, 238, 238)"} = {}){
return new Instruction.Control.human_task(arguments[0])
}
static enter_choice({task = "", choices=[],
show_choices_as_buttons=false,
one_button_per_line=false,
user_data_variable_name="choice", dependent_job_names=[],
title, x=200, y=200, width=400, height=400, background_color = "rgb(238, 238, 238)"} = {}){
return new Instruction.Control.human_enter_choice(arguments[0])
}
static enter_instruction({task = "Enter a next instruction for this Job.",
instruction_type = "Dexter.move_all_joints",
instruction_args = "5000, 5000, 5000, 5000, 5000",
dependent_job_names = [],
title, x=200, y=200, width=400, height=400, background_color = "rgb(238, 238, 238)"}={}){
return new Instruction.Control.human_enter_instruction(arguments[0])
}
static enter_number({task="",
user_data_variable_name="a_number",
initial_value=0,
min=0,
max=100,
step=1,
dependent_job_names=[],
title, x=200, y=200, width=400, height=400, background_color = "rgb(238, 238, 238)"}={}) {
return new Instruction.Control.human_enter_number(arguments[0])
}
static enter_text({task="",
user_data_variable_name="a_text",
initial_value="OK",
line_count=1, //if 1, makes an input type=text. If > 1 makes a resizeable text area.
dependent_job_names=[],
title, x=200, y=200, width=400, height=400, background_color = "rgb(238, 238, 238)"}={}){
return new Instruction.Control.human_enter_text(arguments[0])
}
static notify({task="",
window=true,
output_pane=true,
beep_count=0,
speak=false,
title, x=200, y=200, width=400, height=400, background_color = "rgb(238, 238, 238)"
}={}){
return new Instruction.Control.human_notify(arguments[0])
}
static show_window({content="", title="DDE Information",
x=200, y=200, width=400, height=400,
background_color = "rgb(238, 238, 238)",
is_modal = false,
show_close_button = true,
show_collapse_button = true,
trim_strings = true,
callback = window.show_window_values,
user_data_variable_name="show_window_vals"
}={}){
return new Instruction.Control.human_show_window({
content: content,
title: title,
x: x, y: y, width: width, height: height,
background_color: background_color,
is_modal: is_modal,
show_close_button: show_close_button,
show_collapse_button: show_collapse_button,
trim_strings: trim_strings,
callback: callback,
user_data_variable_name: user_data_variable_name
})
}
}
Human.all_names = []
Serial = class Serial extends Robot {
constructor({name = "s1", simulate = null, //get sim val from Jobs menu item check box.
sim_fun = return_first_arg, path = "required", connect_options={},
capture_n_items = 1, item_delimiter="\n", trim_whitespace=true,
parse_items = true, capture_extras = "error", /*"ignore", "capture", "error"*/
instruction_callback = Job.prototype.set_up_next_do }={}){
super()
let keyword_args = {name: name, simulate: simulate, sim_fun: sim_fun, path: path, connect_options: connect_options,
capture_n_items: capture_n_items, item_delimiter: item_delimiter, trim_whitespace: trim_whitespace,
parse_items: parse_items, capture_extras: capture_extras,
instruction_callback: instruction_callback}
this.make_new_robot_1(keyword_args)
let old_same_named_robot = Robot[name]
let old_same_path_robot = Serial.get_robot_with_path(path)
if (old_same_named_robot){
if (old_same_named_robot.active_jobs_using_this_robot().length > 0){
if(Serial.robots_equivalent(old_same_named_robot, this)){
warning("There's already a robot with the name: " + name +
",<br/>that is a serial robot that has an active job " +
"<br/>so that's being used instead of a new Robot.serial instance.<br/>" +
"Stop a job by clicking on its button in the Output pane's header.")
return old_same_named_robot
}
else { //same name, active jobs, different robot characteristics
dde_error("Attempt to create Robot.Serial with name: " + name +
"<br/>but there is already a robot with that name with different properties " +
"that is active.<br/>" +
"Stop a job by clicking on its button in the Output pane's header."
)
}
}
else { //same name but no active jobs
old_same_named_robot.close_robot()
return this.make_new_robot_2()
}
}
else if(old_same_path_robot) {
if (old_same_path_robot.active_jobs_using_this_robot().length > 0){
dde_error("There's already a robot named: " + old_same_path_robot.name +
" that has an active job.")
}
else {
old_same_path_robot.close_robot()
return this.make_new_robot_2()
}
}
else { //no same named or same pathed robot
return this.make_new_robot_2()
}
}
make_new_robot_1(keyword_args){
this.name = keyword_args.name
this.path = keyword_args.path
this.connect_options = keyword_args.connect_options
this.capture_n_items = keyword_args.capture_n_items
this.item_delimiter = keyword_args.item_delimiter
this.trim_whitespace = keyword_args.trim_whitespace
this.parse_items = keyword_args.parse_items
this.capture_extras = keyword_args.capture_extras
this.simulate = keyword_args.simulate
this.sim_fun = keyword_args.sim_fun
this.instruction_callback = keyword_args.instruction_callback
}
make_new_robot_2(){
this.is_connected = false
this.robot_status = null
Robot.set_robot_name(this.name, this)
let i = Serial.all_names.indexOf(this.name)
if (i != -1) { Serial.all_names.splice(i, 1) }
Serial.all_names.push(this.name) //ensures the last name on the list is the latest with no redundancy
Serial.last_robot = this
//if (this.simulate){
// let callback_number = cbr.store_callback(this.sim_fun)
// this.sim_fun_number = callback_number
//}
return this
}
static robots_equivalent(rob1, rob2){
if (rob1.constructor != rob2.constructor) { return false }
if (rob1.name != rob2.name) { return false }
if (rob1.simulate != rob2.simulate) { return false }
if (rob1.path != rob2.path) { return false }
if (!similar(rob1.connect_options, rob2.connect_options)) { return false }
if (rob1.capture_n_items != rob2.capture_n_items) { return false }
if (rob1.item_delimiter != rob2.item_delimiter) { return false }
if (rob1.trim_whitespace != rob2.trim_whitespace) { return false }
if (rob1.parse_items != rob2.parse_items) { return false }
if (rob1.capture_extras != rob2.capture_extras) { return false }
if (!similar(rob1.instruction_callback, rob2.instruction_callback)) { return false }
if (!similar(rob1.sim_fun, rob2.sim_fun)) { return false }
return true
}
static get_robot_with_path(path){
for(let robot_name of Serial.all_names){
let rob = Robot[robot_name]
if (rob.path == path) { return rob} //there should be at most 1
}
return null
}
static get_job_with_robot_path(path){
for(let job_name of Job.all_names){
let job_instance = Job[job_name]
if (job_instance.robot.path == path) { return job_instance} //there should be at most 1
}
return null
}
is_initialized(){ return this.is_connected }
start(job_instance) { //fill in initial robot_status
if (this.is_initialized()) {
Serial.set_a_robot_instance_socket_id(this.path) //we don't now actually use socket_id outside of serial.js
}
else {
serial_connect(this.path, this.connect_options, this.simulate, this.capture_n_items, this.item_delimiter, this.parse_items, this.capture_extras)
}
}
close_robot(){
serial_disconnect(this.path)
this.is_connected = false
}
//called when a job is finished.
//returns true if no jobs are connected to this robot, false otherwise
finish_job(){
if(this.active_jobs_using_this_robot().length == 0) {
this.close_robot() //don't do as we may want to use this serial robot for some other job.
return true //nope. close_robot just like Dexter robot does.
//starting a job with this robot will reconnect the serial port
}
else { return false }
}
///called from serial_new_socket_callback
static set_a_robot_instance_socket_id(path){ //do I really need the socket_id of a serial?
let rob = Serial.get_robot_with_path(path)
//rob.socket_id = socket_id
rob.is_connected = true
let job_instance = Serial.get_job_with_robot_path(path) //beware, this means only 1 job can use this robot!
if (job_instance.status_code === "starting") {
job_instance.set_status_code("running")
job_instance.set_up_next_do(0) //we don't want to increment because PC is at 0, so we just want to do the next instruction, ie 0.
}
//before setting it should be "starting"
else if (job_instance.status_code === "running") {
rob.perform_instruction_callback(job_instance) //job_instance.set_up_next_do() //initial pc value is 0.
}
}
send(ins_array){
if (this.is_connected) {
serial_send(ins_array, this.path, this.simulate, this.sim_fun)
}
else {
const job_inst = Instruction.job_of_instruction_array(ins_array)
job_inst.stop_for_reason("errored",
"Series Robot: " + this.name +
" was sent an instruction to execute on path: " + this.path +
" but this robot is not connected")
}
}
perform_instruction_callback(job_instance){
if (this.instruction_callback) { this.instruction_callback.call(job_instance) }
}
stringify(){
return "Serial: <i>name</i>: " + this.name + ", " +
", <i>path</i>: " + this.path + ", <i>is_connected</i>: " + this.is_connected +
Serial.robot_status_to_html(this.robot_status, " on robot: " + this.name)
}
static robot_status_to_html(rs, where_from){
return where_from + " robot_status: " + rs
}
static robot_done_with_instruction(robot_status){ //must be a class method, "called" from UI sockets
let stop_time = Date.now() //the DDE stop time for the instruction, NOT Dexter's stop time for the rs.
let job_id = robot_status[Serial.JOB_ID]
var job_instance = Job.job_id_to_job_instance(job_id)
if (job_instance == null){
job_instance.stop_for_reason("errored",
"Serial.robot_done_with_instruction passed job_id: " + job_id +
" but couldn't find a Job instance with that job_id.")
}
var rob = job_instance.robot
var ins_id = robot_status[Serial.INSTRUCTION_ID] //-1 means the initiating status get, before the first od_list instruction
let op_let = robot_status[Serial.INSTRUCTION_TYPE]
//let op_let = String.fromCharCode(op_let_number)
job_instance.record_sent_instruction_stop_time(ins_id, stop_time)
if (!rob.is_connected) {} //ignore any residual stuff coming back from Serial robot
//we don't want to change robot_status for instance because that will confuse
//debugging in the case that we've had an error and want to close.
//on the other hand, we want accurate info. Hmm, maybe the "residual" is
//only comming for simulation and not from read dexter.
//else if (ins_id == -1) {}
else if (!(Array.isArray(robot_status))) {
job_instance.stop_for_reason("errored",
"Serial.robot_done_with_instruction recieved a robot_status array: " +
robot_status + " that is not an array.")
if (job_instance.wait_until_instruction_id_has_run == ins_id){ //we've done it!
job_instance.wait_until_instruction_id_has_run = null //but don't increment PC
}
rob.perform_instruction_callback(job_instance)
return
}
else if (robot_status.length < Serial.DATA0){
job_instance.stop_for_reason("errored",
"Serial.robot_done_with_instruction recieved a robot_status array: " +
robot_status + "<br/> of length: " + robot_status.length +
" that is less than the : " + (Serial.DATA0 - 1) + " required.<br/>" + stringify_value(robot_status))
if (job_instance.wait_until_instruction_id_has_run == ins_id){ //we've done it!
job_instance.wait_until_instruction_id_has_run = null //but don't increment PC
}
rob.perform_instruction_callback(job_instance)
return
}
else {
//job_instance.highest_completed_instruction_id = ins_id //now always done by set_up_next_do
//job_instance.robot_status = robot_status
rob.robot_status = robot_status //thus rob.robot_status always has the latest rs we got from Dexter.
if (job_instance.keep_history){
job_instance.rs_history.push(robot_status)
}
// if (job_instance.name === Dexter.updating_robot_status_job_name) { //don't update the table if it isn't shown
// Dexter.update_robot_status_table(robot_status)
// }
var error_code = robot_status[Serial.ERROR_CODE]
if (error_code != 0){ //we've got an error
job_instance.stop_for_reason("errored", "Robot status got error: " + error_code)
if (job_instance.wait_until_instruction_id_has_run == ins_id){ //we've done it!
job_instance.wait_until_instruction_id_has_run = null //but don't increment PC
}
rob.perform_instruction_callback(job_instance) //job_instance.set_up_next_do()
}
/* just for dexter
else if (ins_id == -1) { //this is the get_robot_status always called at the very beginning
if (job_instance.status_code === "starting") {
job_instance.status_code = "running"
// if(rob.enable_heartbeat && (rob.heartbeat_timeout_obj == null)) { //enabled but not already running
//beware multiple jobs could be using this robot, and we only want at most 1 heartbeat going
// rob.run_heartbeat()
// }
}
//before setting it should be "starting"
if (job_instance.status_code === "running") {
rob.perform_instruction_callback(job_instance) //job_instance.set_up_next_do() //initial pc value is -1. this is the first call to
//set_up_next_do (and do_next_item) in this job's life.
}
} */
else { //the normal, no error, not initial case
if (job_instance.wait_until_instruction_id_has_run == ins_id){ //we've done it!
job_instance.wait_until_instruction_id_has_run = null
if (ins_id == job_instance.program_counter) {
rob.perform_instruction_callback(job_instance)// job_instance.set_up_next_do() //note before doing this, pc might be on last do_list item.
//but that's ok. increment pc and call do_next_item.
}
else {
shouldnt("In job: " + job_instance.name +
" \n robot_done_with_instruction got ins_id: " + ins_id +
" \n which matched wait_until_instruction_id_has_run " +
" \n but the PC wasn't the same. Its: " + job_instance.program_counter)
}
}
else { //instr coming back is not a wait for,
// so its just a non-last instr in a group, so we shouldn't call do_next_item for it
//and don't even set robot_status from it. May 2016 decided to set robot status
//and history ... see above. status and history should be consistent
//but still status can get into a race condition with user code so
//am not fond of setting it. ask kent.
rob.perform_instruction_callback(job_instance) //job_instance.set_up_next_do() //calling this is mostly a no-op, because
//job_instance.wait_until_instruction_id_has_run should be set to
//something higher than this instr coming back.
//BUT in case the user has stopped the job or another job does so,
//then calling do_next_item here would actually stop the job.
//so this call to do_next_item will at most get down to the
//this.wait_until_instruction_id_has_run clause but never further.
}
}
}
}
} //end Serial class
Serial.all_names = []
Serial.last_name = null
Serial.robot_status_labels = [
"JOB_ID", // 0
"INSTRUCTION_ID", // 1
"START_TIME", // 2 //ms since jan 1, 1970? From Dexter's clock
"STOP_TIME", // 3 //ms since jan 1, 1970? From Dexter's clock
"INSTRUCTION_TYPE", // 4 //"oplet"
"ERROR_CODE", // 5 0 means no error.
"DATA0", // 6 data coming back from the board
"DATA1",
"DATA2",
"DATA3",
"DATA4",
"DATA5",
"DATA6",
"DATA7",
"DATA8",
"DATA9"
]
Serial.robot_status_index_labels = []
//its inefficient to have effectively 3 lists, but the sans-index list is good for
//short labels used in tables, and the index is nice and explicit
//for robot.robot_status[Dexter.foo_index] access
//The explicit Dexter.robot_status_index_labels is needed for a series.
Serial.make_robot_status_indices = function(){
for(var i = 0; i < Serial.robot_status_labels.length; i++){
var label = Serial.robot_status_labels[i]
var index_label = "Series." + label //+ "_INDEX"
Serial[label] = i
Serial.robot_status_index_labels.push(index_label)
}
}
Serial.make_robot_status_indices()
Serial.instruction_type_to_function_name_map = {
I:"string_instruction" // "S" is used by Dexter and I isn't so use I just in case it helps in debugging.
}
Serial.string_instruction = function(instruction_string){
if (typeof(instruction_string) != "string") {
instruction_string = JSON.stringify(instruction_string)
}
return make_ins("I", instruction_string)
}
/*anticipate classes for Dexter2, etc. */
Dexter = class Dexter extends Robot {
constructor({name = "dex1", simulate = null,
ip_address = null, port = null,
pose = Vector.identity_matrix(4), //default position and orientation
enable_heartbeat=true, instruction_callback=Job.prototype.set_up_next_do }={}){ //"192.168.1.144"
//because arguments[0] doesn't work like it does for fns, I have to resort to this redundancy
if(!ip_address) { ip_address = persistent_get("default_dexter_ip_address") }
if(!port) { port = persistent_get("default_dexter_port") }
let keyword_args = {name: name, simulate: simulate, ip_address: ip_address, port: port,
pose: pose,
enable_heartbeat: enable_heartbeat, instruction_callback: instruction_callback }
let old_same_named_robot = Robot[name]
if (old_same_named_robot){
if ((old_same_named_robot.ip_address === ip_address) &&
(old_same_named_robot.port === port)){
if (old_same_named_robot.active_jobs_using_this_robot().length > 0){
warning("There's already a robot with the name: " + name +
", with same ip_address and port that has active jobs " +
" so that's being used instead of a new Robot.Dexter instance.")
return old_same_named_robot
}
else {
old_same_named_robot.close_robot()
super()
return this.make_new_robot(keyword_args)
}
}
else {//old_same_named_robot is same_named but has different ip address
if (old_same_named_robot.active_jobs_using_this_robot().length > 0){
dde_error("Attempt to create a robot named: " + name +
" but there is already robot with that name that has active jobs " +
" but a different ip_address and/or port.")
}
else {
old_same_named_robot.close_robot()
super()
return this.make_new_robot(keyword_args)
}
}
}
else {//there's no same-named robot
let old_same_ip_address_robot = Dexter.get_robot_with_ip_address_and_port(ip_address, port)
if (old_same_ip_address_robot){
if (old_same_ip_address_robot.active_jobs_using_this_robot().length > 0){
dde_error("Attempt to create a robot named: " + name +
" but a robot named: " + old_same_ip_address_robot.name +
" is already using that ip_address and port and has active jobs.")
}
else {
old_same_ip_address_robot.close_robot()
super()
return this.make_new_robot(keyword_args)
}
}
else {//different name, unused ip_address and port
super()
return this.make_new_robot(keyword_args)
}
}
}
make_new_robot(keyword_args){
this.name = keyword_args.name
this.ip_address = keyword_args.ip_address
this.port = keyword_args.port
this.pose = keyword_args.pose
this.simulate = keyword_args.simulate
this.instruction_callback = keyword_args.instruction_callback
this.robot_status = null //now contains the heartbeat rs
this.is_connected = false
this.enable_heartbeat = keyword_args.enable_heartbeat
this.waiting_for_heartbeat = false
this.heartbeat_timeout_obj = null
this.angles = [0, 0, 0, 0, 0] //used by move_to_relative, set by move_all_joints, move_to, and move_to_relative
this.processing_flush = false //primarily used as a check. a_robot.send shouldn't get called while this var is true
Robot.set_robot_name(this.name, this)
//ensures the last name on the list is the latest with no redundancy
let i = Dexter.all_names.indexOf(this.name)
if (i != -1) { Dexter.all_names.splice(i, 1) }
Dexter.all_names.push(this.name)
Dexter.last_robot = this
//Socket.init(this.name, this.ip_address, this.port)
return this
}
start(job_instance) { //fill in initial robot_status
//if (!this.is_initialized()) {
Socket.init(this.name, this.simulate, this.ip_address, this.port)
//}
this.processing_flush = false
let this_robot = this
let this_job = job_instance
//give it a bit of time in case its in the process of initializing
setTimeout(function(){ //give robot a chance to get its socket before doing th initial "g" send.
const sim_actual = Robot.get_simulate_actual(this_robot.simulate)
if(!this_robot.is_initialized()){
if (this_robot.simulate === true){
this_job.stop_for_reason("errored", "The job: " + this_job.name + " is using robot: " + this_robot.name +
"<br/>\nwith simulate=true, but could not connect with the Dexter simulator.")
}
else if ((this_robot.simulate === false) || (this_robot.simulate === "both")){
this_job.stop_for_reason("errored", "The job: " + this_job.name + " is using robot: " + this_robot.name +
"<br/>\nbut could not connect with a Dexter robot at: " +
this_robot.ip_address + " port: " + this_robot.port +
"<br/>\nYou can change this robot to <code>simulate=true</code> and run it.")
}
else if (this_robot.simulate === null){
if ((sim_actual === false) || (sim_actual === "both")){
this_job.stop_for_reason("errored", "The job: " + this_job.name + " is using robot: " + this_robot.name +
'<br/>\nwith the Jobs menu "Simulate?" item being: ' + sim_actual +
"<br/>\nbut could not connect with Dexter." +
"<br/>\nYou can use the simulator by switching the menu item to 'true'. ")
}
else {
this_job.stop_for_reason("errored", "The job: " + this_job.name + " is using robot: " + this_robot.name +
"<br/>\nwith a Jobs menu, 'Simulate?' value of 'true', " +
"<br/>\nbut could not connect with the Dexter simulator.")
}
}
else {
shouldnt("Dexter.start got invalid simulate value of: " + this_robot.simulate +
'.<br/>\nThe value values are: true, false, "both" and null.')
}
}
else { this_job.send(Dexter.get_robot_status())}
},
200)
}
static get_robot_with_ip_address_and_port(ip_address, port){
for(let robot_name of Dexter.all_names){
let dex = Robot[robot_name]
if (dex.ip_address && //note: if we have 2 Dexter instances that have the default ip_address of null and port of 5000, then we DON'T want to call them "at the same ip_address"
(dex.ip_address == ip_address) &&
(dex.port == port)){
return dex //there should be at most 1
}
}
return null
}
run_heartbeat(){
let this_dex = this
this.heartbeat_timeout_obj =
setTimeout(function(){
if (this_dex.finish_job()) {//If this returns true, that means no more jobs active on this robot, so don't continue the heartbeat.
//If there are more jobs, finish_job does nothing except return false
}
else if (this_dex.waiting_for_heartbeat){ //stop recursive timeout
out("Dexter " + this_dex.name + " did not recieve a response to the heartbeat. Stopping Job.")
//this_dex.is_connected = false //should be done by stop_for_reaason and next item
//this_dex.socket_id = null //should be done by stop_for_reaason and next item
for (let job_instance of this.active_jobs_using_this_robot()){
job_instance.stop_for_reason("errored", "No heartbeat response from dexter hardware.")
job_instance.do_next_item()
}
}
// else if (!this_dex.socket_id) { //this should never hit because heartbeat isn't started until
// the initial "g" instruction returns with a status in Dexter.robot_done_with_instruction
// when this robot must already have a socket_id
// let job_instance = Job.job_id_to_job_instance(this_dex.job_id)
// job_instance.stop_for_reason("errored", "Dexter " + this_dex.name + " does not have a socket_id in heartbeat")
//}
else if (this_dex.enable_heartbeat) { //everything ok. Note: user might disable heartbeat during a job so check here.
let h_ins = Dexter.get_robot_status_heartbeat()
let job_instance = this_dex.active_jobs_using_this_robot()[0]
h_ins[Instruction.JOB_ID] = job_instance.job_id
h_ins[Instruction.INSTRUCTION_ID] = -4
this_dex.send(h_ins) //heartbeat associated with the last job created using this robot as its robot.
this.waiting_for_heartbeat = true
this_dex.run_heartbeat()
}
}, Dexter.heartbeat_dur)
}
//called when a job is finished.
//returns true if no jobs are connected to this robot, false otherwise
finish_job(){
if(this.active_jobs_using_this_robot().length == 0) {
this.close_robot()
return true
}
else { return false }
}
close_robot(){
clearTimeout(this.heartbeat_timeout_obj) //looks like not working
this.waiting_for_heartbeat = false
this.heartbeat_timeout_obj = null
this.is_connected = false
Socket.close(this.name, this.simulate) //must be before setting socket_id to null
// delete Dexter[this.name] //don't do this. If the robot is still part of a Job,
//and that job is inactive, then we can still "restart" the job,
//and as such we want that binding of Robot.this_name to still be around.
}
empty_instruction_queue_now(){
Socket.empty_instruction_queue_now(this.name, this.simulate)
}
send(ins_array){
//var is_heartbeat = ins_array[Instruction.INSTRUCTION_TYPE] == "h"
let oplet = ins_array[Instruction.INSTRUCTION_TYPE]
if (oplet == "F") { this.processing_flush = true } //ok even if flush is already true. We can send 2 flushes in a row if we like, that's ok. essentially only 1 matters
if (this.processing_flush && (oplet != "F")) {
shouldnt(this.name + ".send called with oplet: " + oplet +
", but " + this.name + ".processing_flush is true so send shouldn't have been called.")
}
/*else if (oplet == "z"){ //converstin done in sockets.
ins_array = ins_array.slice()
const sleep_in_ms = ins_array[Dexter.INSTRUCTION_TYPE + 1]
const sleep_in_ns = Math.round(sleep_in_ms * 1000000)
ins_array[Dexter.INSTRUCTION_TYPE + 1] = sleep_in_ns //because Dexter expects nanoseconds
}*/
//note: we send F instructions through the below.
Socket.send(this.name, ins_array, this.simulate)
}
perform_instruction_callback(job_instance){
if (this.instruction_callback) { this.instruction_callback.call(job_instance) }
}
stringify(){
return "Dexter: <i>name</i>: " + this.name +
", <i>ip_address</i>: " + this.ip_address + ", <i>port</i>: " + this.port + ",<br/>" +
"<i>socket_id</i> " + this.socket_id + ", <i>is_connected</i>: " + this.is_connected + ", <i>waiting_for_heartbeat</i>: " + this.waiting_for_heartbeat +
Dexter.robot_status_to_html(this.robot_status, " on robot: " + this.name)
}
///called from Socket in ui
static set_a_robot_instance_socket_id(robot_name){
let rob = Dexter[robot_name]
//rob.socket_id = socket_id
if ([false, "both"].includes(Robot.get_simulate_actual(rob.simulate))) {
out("Succeeded connection to Dexter: " + robot_name + " at ip_address: " + rob.ip_address + " port: " + rob.port, "green")
}
rob.is_connected = true
}
//is_initialized(){ return ((this.socket_id || (this.socket_id === 0)) ? true : false ) }
is_initialized(){
return this.is_connected
}
//beware, robot_status could be an ack, can could be called by sim or real AND
//will be called twice if simulate == "both"
static robot_done_with_instruction(robot_status){ //must be a class method, "called" from UI sockets
if (!(Array.isArray(robot_status))) {
throw(TypeError("Dexter.robot_done_with_instruction recieved a robot_status array: " +
robot_status + " that is not an array."))
}
else if ((robot_status.length != Dexter.robot_status_labels.length) &&
(robot_status.length != Dexter.robot_ack_labels.length)){
throw(TypeError("Dexter.robot_done_with_instruction recieved a robot_status array: " +
robot_status + "<br/> of length: " + robot_status.length +
" that is not the proper length of: " + Dexter.robot_status_labels.length +
" or: " + Dexter.robot_ack_labels.length))
}
let got_ack = (robot_status.length == Dexter.robot_ack_labels.length) //if we have an "acknowledgent, it means we DON"T have in robot_status all we need to render the joint positions
let stop_time = Date.now() //the DDE stop time for the instruction, NOT Dexter's stop time for the rs.
let job_id = robot_status[Dexter.JOB_ID]
let job_instance = Job.job_id_to_job_instance(job_id)
if (job_instance == null){
throw new Error("Dexter.robot_done_with_instruction passed job_id: " + job_id +
" but couldn't find a Job instance with that job_id.")
}
let rob = job_instance.robot
let ins_id = robot_status[Dexter.INSTRUCTION_ID] //-1 means the initiating status get, before the first od_list instruction
let op_let = robot_status[Dexter.INSTRUCTION_TYPE]
//let op_let = String.fromCharCode(op_let_number)
if (op_let == "h") { //we got heartbeat acknowledgement of reciept by phys or sim so now no longer waiting for that acknowledgement
rob.waiting_for_heartbeat = false
//rob.robot_status = robot_status
//if (rob.name === Dexter.updating_robot_status_robot_name) { //don't update the table if it isn't shown
// Dexter.update_robot_status_table(robot_status)
//}
//SimUtils.render_once(robot_status, "Robot: " + rob.name)
return
}
else if (op_let == "F"){
if (rob.processing_flush) { rob.processing_flush = false }
else { shouldnt("robot_done_with_instruction passed a returned instruction oplet of: F " +
"but " + this.name + ".processing_flush is false. " +
"It should be true if we get an F oplet.")
}
}
job_instance.record_sent_instruction_stop_time(ins_id, stop_time)
if (!rob.is_connected) {} //ignore any residual stuff coming back from dexter
//we don't want to change robot_status for instance because that will confuse
//debugging in the case that we've had an error and want to close.
//on the other hand, we want accurate info. Hmm, maybe the "residual" is
//only comming for simulation and not from read dexter.
//else if (ins_id == -1) {}
else {
//job_instance.highest_completed_instruction_id = ins_id //now always done by set_up_next_do
if (!got_ack){
//job_instance.robot_status = robot_status
rob.robot_status = robot_status //thus rob.robot_status always has the latest rs we got from Dexter.
if((ins_id === -1) && (op_let == "g")){
rob.angles = rob.joint_angles() //must happen after rob.robot_status = robot_status because extracts angles from the robot_status which is ok for this FIRST time init of rob.angles
}
if (job_instance.keep_history && (op_let == "g")){ //don't do it for oplet "G", get_robot_status_immediate
job_instance.rs_history.push(robot_status)
}
/*Don't do this rob.angles is set by move_all_joints BEFORE sending it to robot and should not
be set by a move_all_joints coming back from robot.
else if (op_let == "a"){ //no robot_status so I must get the pos we tried to move_to. This works for orign insturctions of move_to, move_to_relative, and move_all_joints
//rob.xy used by move_to_relative
const full_inst = job_instance.do_list[ins_id]
rob.angles = [full_inst[Dexter.J1_ANGLE], full_inst[Dexter.J2_ANGLE], full_inst[Dexter.J3_ANGLE], full_inst[Dexter.J4_ANGLE], full_inst[Dexter.J5_ANGLE]]
}*/
if (job_instance.name === Dexter.updating_robot_status_job_name) { //don't update the table if it isn't shown
Dexter.update_robot_status_table(robot_status)
}
// if(rob.simulate) { SimUtils.render_once(robot_status, "Job: " + job_instance.name) } //now in dextersim where it really belongs
}
var error_code = robot_status[Dexter.ERROR_CODE]
if (error_code != 0){ //we've got an error
job_instance.stop_for_reason("errored", "Robot status got error: " + error_code)
if (job_instance.wait_until_instruction_id_has_run == ins_id){ //we've done it!
job_instance.wait_until_instruction_id_has_run = null //but don't increment PC
}
rob.perform_instruction_callback(job_instance) //job_instance.set_up_next_do()
}
else if (job_instance.status_code === "starting") { //at least usually ins_id is -1
job_instance.set_status_code("running")
//rob.perform_instruction_callback(job_instance)