-
Notifications
You must be signed in to change notification settings - Fork 561
/
Copy pathnodes.proto
1113 lines (947 loc) · 46.6 KB
/
nodes.proto
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
// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved.
//
// Downloading, reproducing, distributing or otherwise using the SDK Software
// is subject to the terms and conditions of the Boston Dynamics Software
// Development Kit License (20191101-BDSDK-SL).
syntax = "proto3";
package bosdyn.api.mission;
option java_outer_classname = "NodesProto";
import "google/protobuf/any.proto";
import "google/protobuf/duration.proto";
import "google/protobuf/struct.proto";
import "bosdyn/api/alerts.proto";
import "bosdyn/api/docking/docking.proto";
import "bosdyn/api/geometry.proto";
import "bosdyn/api/gripper_camera_param.proto";
import "bosdyn/api/spot/choreography_sequence.proto";
import "bosdyn/api/spot_cam/camera.proto";
import "bosdyn/api/spot_cam/logging.proto";
import "bosdyn/api/spot_cam/ptz.proto";
import "bosdyn/api/robot_command.proto";
import "bosdyn/api/power.proto";
import "bosdyn/api/data_acquisition.proto";
import "bosdyn/api/data_acquisition_store.proto";
import "bosdyn/api/data_buffer.proto";
import "bosdyn/api/graph_nav/graph_nav.proto";
import "bosdyn/api/graph_nav/nav.proto";
import "bosdyn/api/manipulation_api.proto";
import "bosdyn/api/mission/util.proto";
import "bosdyn/api/service_customization.proto";
// Wrapper for a mission node. Contains the basics common to all mission nodes.
// Specifics of what the node does are contained in the "impl" field.
message Node {
// Human-readable name of this node, e.g. "Goto waypoint 1", or "Power On".
string name = 1;
// Collection of user data associated with this node.
UserData user_data = 2;
// Reference identifier of this node.
// Set iff another node references this one.
string reference_id = 3;
oneof type {
// DEPRECATED as of 4.0.
// Implementation of this node. For example, this may be a Sequence.
google.protobuf.Any impl = 4 [deprecated = true];
// Unique identifier of another node. If this is filled out, rather than the "impl", then
// the referenced node will be used in place of this one.
string node_reference = 5;
Condition condition = 9;
Sequence sequence = 10;
Selector selector = 11;
Repeat repeat = 12;
RetainLease retain_lease = 13;
Retry retry = 14;
ForDuration for_duration = 15;
BosdynDockState bosdyn_dock_state = 16;
BosdynPowerRequest bosdyn_power_request = 17;
BosdynRobotState bosdyn_robot_state = 18;
BosdynRobotCommand bosdyn_robot_command = 19;
RemoteGrpc remote_grpc = 20;
Sleep sleep = 21;
Prompt prompt = 22;
SetBlackboard set_blackboard = 23;
DateToBlackboard date_to_blackboard = 24;
DefineBlackboard define_blackboard = 25;
FormatBlackboard format_blackboard = 26;
ConstantResult constant_result = 27;
BosdynNavigateRoute bosdyn_navigate_route = 29;
BosdynNavigateTo bosdyn_navigate_to = 30;
BosdynGraphNavState bosdyn_graph_nav_state = 31;
BosdynGraphNavLocalize bosdyn_graph_nav_localize = 32;
BosdynRecordEvent bosdyn_record_event = 33;
SimpleParallel simple_parallel = 34;
SpotCamPtz spot_cam_ptz = 35;
SpotCamStoreMedia spot_cam_store_media = 36;
SpotCamLed spot_cam_led = 37;
SpotCamFocusState spot_cam_focus_state = 58;
SpotCamResetAutofocus spot_cam_reset_autofocus = 38;
StoreMetadata store_metadata = 39;
Switch switch = 40;
DataAcquisition data_acquisition = 41;
DataAcquisitionOnInterruption data_acquisition_on_interruption = 42;
Dock dock = 43;
RestartWhenPaused restart_when_paused = 49;
ClearBehaviorFaults clear_behavior_faults = 50;
BosdynGripperCameraParamsState bosdyn_gripper_camera_params_state = 51;
SetGripperCameraParams set_gripper_camera_params = 52;
ParallelAnd parallel_and = 54;
SetGraspOverride set_grasp_override = 55;
ExecuteChoreography execute_choreography = 56;
MissionUploadChoreography mission_upload_choreography = 57;
CreateMissionText create_mission_text = 59;
BosdynQueryStoredCaptures bosdyn_query_stored_captures = 60;
}
// Defines parameters, used by this node or its children.
// The "key" in KeyValue is the name of the parameter being defined.
// The value can be a constant or another parameter value.
repeated KeyValue parameter_values = 6;
// Overwrites a protobuf field in this node's implementation.
// The "key" in KeyValue is the name of the field to override.
// The value to write can be sourced from a constant, or a parameter value.
repeated KeyValue overrides = 7;
// Declares parameters needed at compile time by this node, or children of this node.
// This is a way for a node to communicate what parameters its implementation and/or children
// require, without unpacking the entire subtree.
repeated VariableDeclaration parameters = 8;
}
// Run all children in order until a child fails.
message Sequence {
// Forces the execution to always begin with the first child. If false, and
// the Sequence ran last tick, it will continue with the node it was ticking.
bool always_restart = 1;
// List of all children to iterate through.
repeated Node children = 2;
}
// Run all children in order until a child succeeds.
message Selector {
// Forces the execution to always begin with the first child. If false, and
// the Selector ran last tick, it will continue with the node it was ticking.
bool always_restart = 1;
// List of all children to iterate through.
repeated Node children = 2;
}
// Run a specific child based on a specified pivot_value.
//
// This node exists because of a subtle implementation detail in Selector(always_restart = true).
// The astute reader might believe that they can construct a switch node by using a selector
// with sequences & conditions as children. This is ALMOST true, EXCEPT that a selector
// (with always_restart = true) can leave multiple children in the running state IF:
//
// - A later selector child was RUNNING last tick
// - An earlier selector child returns RUNNING this tick
//
// Even though the later selector child won't be ticked, it will still be left in the running state
// and not restart when the selector advances to it again later. Sometimes this is desirable,
// sometimes it isn't. Switch is constrained to only have one child running, and if the switch ever
// switches children and return to a previously running child, that child will be restarted.
message Switch {
// Expresses an integer value that decides which child to run.
Value pivot_value = 1;
// If false, this node will read the pivot_value once when its starts, and execute
// the specified child until it finishes even if the pivot_value changes.
//
// If true, this node will read from the pivot_value every tick, and change
// which child it's ticking when an underlying blackboard variable changes.
bool always_restart = 2;
// List of all children to possibly run.
map<int32, Node> int_children = 3;
// If none of the above cases match, use this child
Node default_child = 4;
}
// Repeat a child node.
message Repeat {
// Start the child node exactly this many times.
// Note that a value of 1 makes the Repeat node a no-op.
int32 max_starts = 1;
// Child to repeat max_starts times.
Node child = 4;
// If set, the node will write the start index to the blackboard.
string start_counter_state_name = 5;
// If set to false, this repeat node will keep running its child regardless of whether
// or not the child succeeds or fails.
// If set to true, this repeat node will only keep running its child when the child
// succeeds. If the child fails, the repeat node will fail.
bool respect_child_failure = 6;
}
// Retry a child node until it succeeds, or exceeds a number of attempts.
message Retry {
// Only allow this many attempts. Note that a value of 1 makes this Retry node a no-op.
int32 max_attempts = 1;
// Child to retry up to max_attempts.
Node child = 2;
// If set, the node will write the attempt index to the blackboard.
string attempt_counter_state_name = 5;
}
// Run this child for a maximum amount of mission execution time.
// Will exit with child's status if the child finishes early,
// FAILURE if the child remains in RUNNING state for too long
// and no timeout_child is specified, or the status of the
// timeout_child.
message ForDuration {
// Maximum duration of mission execution time.
oneof duration_type {
google.protobuf.Duration duration = 1;
// Blackboard variable name that specifies duration. The value of this variable should be of
// type google.protobuf.Duration.
string duration_name_in_blackboard = 5;
}
// Child to execute for the duration.
Node child = 2;
// Optional blackboard variable name. If specified, this node will define a blackboard
// variable that its child has access to, and write the number of seconds remaining as
// a double to the blackboard under this name.
string time_remaining_name = 3;
// Optional node that will run if the child times out. If not specified, this node
// will return FAILURE when the child times out. If specified, and the
// child times out, this node will return the status of the timeout_child.
// The timeout_child does not respect the original timeout.
Node timeout_child = 4;
}
// Run two child nodes together, returning the primary child's result when it completes.
message SimpleParallel {
// Primary node, whose completion will end the execution of SimpleParallel.
// The secondary node will be ticked at least once.
Node primary = 1;
// Secondary node, which will be ticked as long as the primary is still running.
Node secondary = 2;
// By default, if the secondary node finishes before the primary node, the secondary node
// will be restarted. If this flag is set to true, and the secondary node completes before
// the primary node, it will never be restarted.
bool run_secondary_node_once = 3;
}
// Run many child nodes together, returning only after they have all completed or an
// early exit is triggered.
message ParallelAnd {
repeated Node children = 1;
// Boolean to finish every child node. If this is false, if one of the nodes fails, the whole
// ParallelAnd will stop & return the failure immediately.
// If this is true, if one of the nodes fails, the ParallelAnd will continue to run until all
// the children have exited, then report the failure.
// If a node raises an error, the error will always be reported immediately.
// Default false.
bool finish_every_node = 2;
}
// Checks a simple comparison statement.
message Condition {
// Options for where to retrieve values from.
message Operand {
oneof type {
// Reference an existing variable.
VariableDeclaration var = 1;
// Use a constant value.
ConstantValue const = 2;
}
}
// Left-hand side of the comparison.
Operand lhs = 1;
// Right-hand side of the comparison.
Operand rhs = 2;
// Comparison operator.
enum Compare {
// Invalid, do not use.
COMPARE_UNKNOWN = 0;
// Equal.
COMPARE_EQ = 1;
// Not equal.
COMPARE_NE = 2;
// Less than.
COMPARE_LT = 3;
// Greater than.
COMPARE_GT = 4;
// Less than or equal.
COMPARE_LE = 5;
// Greater than or equal.
COMPARE_GE = 6;
}
// Comparison operator to compare lhs and rhs.
Compare operation = 5;
// When comparing runtime values in the blackboard, some values might be "stale" (i.e too old).
// This defines how the comparator should behave when a read value is stale.
enum HandleStaleness {
HANDLE_STALE_UNKNOWN = 0; // acts like READ_ANYWAY for backwards compatibility.
HANDLE_STALE_READ_ANYWAY = 1; // ignore how stale this data is.
HANDLE_STALE_RUN_UNTIL_FRESH =
2; // return the RUNNING status until the data being read is not stale.
HANDLE_STALE_FAIL = 3; // return FAILURE status if stale data is read.
}
HandleStaleness handle_staleness = 6;
}
// Get state from the robot.
message BosdynRobotState {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// Child node. Children will have access to the state gathered by this node.
Node child = 3;
// Name of the bosdyn.api.RobotState object in the blackboard. For example, if this is set to
// "robot", children can look up "robot.power_state.motor_power_state" in the blackboard.
string state_name = 4;
}
// Get the state of the docking service from the robot.
message BosdynDockState {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// Child node. Children will have access to the state gathered by this node.
Node child = 3;
// Name of the bosdyn.api.DockState object in the blackboard. For example, if this is set to
// "power_status", children can look up "power_status" in the blackboard.
string state_name = 4;
}
// Execute a RobotCommand.
// These nodes will "succeed" once a feedback response is received indicating success. Any commands
// that require an "end time" will have that information set based on the end time of the mission.
message BosdynRobotCommand {
// Name of the service to use.
string service_name = 1;
// Host machine the directory is running on.
string host = 2;
// The command to execute. See the RobotCommand documentation for details.
RobotCommand command = 3;
}
// Make a robot power request
message BosdynPowerRequest {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// The request to make. See the PowerCommandRequest documentation for details.
bosdyn.api.PowerCommandRequest.Request request = 4;
}
// Tell the robot to navigate to a waypoint.
message BosdynNavigateTo {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// ID of the waypoint to go to.
string destination_waypoint_id = 3;
// Preferences on how to pick the route.
bosdyn.api.graph_nav.RouteGenParams route_gen_params = 4;
// Parameters that define how to traverse and end the route.
bosdyn.api.graph_nav.TravelParams travel_params = 5;
// If provided, this will write the last NavigationFeedbackResponse message
// to a blackboard variable with this name.
string navigation_feedback_response_blackboard_key = 6;
// If provided, this will write the last NavigateToResponse message to
// a blackboard variable with this name.
string navigate_to_response_blackboard_key = 7;
// Defines robot behavior when route is blocked. Defaults to reroute when route is blocked.
bosdyn.api.graph_nav.RouteFollowingParams.RouteBlockedBehavior route_blocked_behavior = 8;
}
// Tell the robot to navigate a route.
message BosdynNavigateRoute {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// A route for the robot to follow.
bosdyn.api.graph_nav.Route route = 3;
// What should the robot do if it is not at the expected point in the route, or the route is
// blocked.
bosdyn.api.graph_nav.RouteFollowingParams route_follow_params = 4;
// Parameters that define how to traverse and end the route.
bosdyn.api.graph_nav.TravelParams travel_params = 5;
// If provided, this will write the last NavigationFeedbackResponse message
// to a blackboard variable with this name.
string navigation_feedback_response_blackboard_key = 6;
// If provided, this will write the last NavigateRouteResponse message to
// a blackboard variable with this name.
string navigate_route_response_blackboard_key = 7;
// If provided, parameters from this request will be merged with the other parameters defined in
// the node and be used in the NavigateRoute RPC.
string navigate_route_request_blackboard_key = 8;
}
// Get GraphNav state from the robot and save it to the blackboard.
message BosdynGraphNavState {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// Child node. Children will have access to the state gathered by this node.
Node child = 3;
// Name of the bosdyn.api.GetLocalizationStateResponse object in the blackboard. For example,
// if this is set to "nav", children can look up "nav.localization.waypoint_id" in the
// blackboard to get the waypoint the robot is localized to.
string state_name = 4;
// Id of the waypoint that we want the localization to be relative to.
// If this is empty, the localization will be relative to the waypoint that the
// robot is currently localized to.
string waypoint_id = 5;
}
// Tell GraphNav to re-localize the robot using a SetLocalizationRequest. This overrides whatever
// the current localization is. This can be useful to reinitialize the system at a known state.
message BosdynGraphNavLocalize {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// If no localization_request is provided, the default options used
// are FIDUCIAL_INIT_NEAREST (the system will initialize to the nearest fiducial).
// Otherwise, the options inside the set_localization_request will be used.
// Note that ko_tform_body in the request will be ignored (it will be recalculated at runtime).
bosdyn.api.graph_nav.SetLocalizationRequest localization_request = 3;
// If true, a poor quality check will not result in the node returning FAILURE.
// If false, the localization will be checked for quality by comparing against the map data, and
// if the localization is poor quality, the node returns FAILURE.
bool allow_bad_quality = 4;
// If non-empty, the blackboard variable with this name will contain the response of the
// graph nav SetLocalization request after this node receives it.
string response_bb_key = 5;
// If specified, the value of this blackboard variable will be merged with the
// localization_request. The value of this variable must be a
// bosdyn.api.graph_nav.SetLocalizationRequest proto.
string localization_request_bb_key = 6;
}
// Record an APIEvent
message BosdynRecordEvent {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// The event to be logged. Note that everything should be populated except the id, start_time
// and end_time. The start and end time will be populated by the mission, using the node's start
// time. The id field shouldn't be set when the start and end times are the same.
bosdyn.api.Event event = 3;
// If set to false, this node will wait for the RecordEvents rpc to complete. If set to true,
// this node will send the RecordEventsRequest, and then return SUCCESS without waiting for
// the RecordEventsResponse.
bool succeed_early = 4;
// In addition to the parameters specified in the event field, this field can be used
// to specify events only known at runtime. Map key will be parameter label, map value will be
// evaluated then packed into parameter value.
map<string, Value> additional_parameters = 5;
}
// Call out to another system using the RemoteMission service.
message RemoteGrpc {
// Host that is running the directory server. Usually, this is just the robot.
string host = 1;
// Name of the service in the directory.
string service_name = 3;
// Timeout of any single RPC. If the timeout is exceeded, the RPC will fail. The mission service
// treats each failed RPC differently:
// - EstablishSession: An error is returned in LoadMission.
// - Tick: The RPC is retried.
// - Stop: The error is ignored, and the RPC is not retried.
// Omit for a default of 60 seconds.
float timeout = 4;
// Resources that we will need leases on.
repeated string lease_resources = 5;
// The list of variables the remote host should receive.
// Variables given can be available at either run-time or compile-time.
// The "key" in KeyValue is the name of the variable as used by the remote system.
repeated KeyValue inputs = 6;
// Define a format string that will be used together with the blackboard to generate
// a group_name. If a value is specified in this field, it will override the group_name value
// specified in the group_name of the TickRequest. Values from the blackboard will
// replace the keys in braces {}.
// Example: "teleop-{date}", where "date" is a blackboard variable.
// Example: "{date}_loop_{loop_counter}", where "loop_counter" is a blackboard variable from a
// Repeat node.
string group_name_format = 8;
// Should match the advertised spec for the RemoteMissionService in question.
DictParam params = 9;
}
// When started, begins a sleep timer for X seconds. Returns "success" after the timer elapses,
// "running" otherwise.
message Sleep {
oneof duration {
// Number of seconds to sleep for.
float seconds = 1;
// Blackboard variable name that specifies duration. The value of this variable should be of
// type google.protobuf.Duration.
string duration_name_in_blackboard = 5;
}
// If this node is stopped, should it restart the timer?
bool restart_after_stop = 2;
}
// Sends a request to play a choreography sequence with the given name, and then monitors
// the state of the dancing robot.
message ExecuteChoreography {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// The name of the sequence to play.
string sequence_name = 3;
}
// Uploads the given set of animations and choreography sequences to the robot.
message MissionUploadChoreography {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// Choreography sequences to be loaded (required by the mission).
repeated bosdyn.api.spot.ChoreographySequence choreography_sequences = 3;
// Any animations we need to load if we want to play the sequences.
repeated bosdyn.api.spot.Animation animated_moves = 4;
}
// Prompt the world at large to answer a question.
// This node represents a request for information from ANY listeners that may be out there.
message Prompt {
// Should we always re-prompt when this node is started?
// If false, this node will only ever prompt if it is started and its question is unanswered.
// This may be used, for example, to ask the user to check the robot after any self-right.
// If true, this node will prompt whenever it is started.
// This may be used, for example, to tell the user to perform some one-time action, like open a
// door for the robot.
bool always_reprompt = 1;
// The text of the question itself. The question text may contain formatted blackboard
// variables. Please see the documentation in FormatBlackboard for more information
// about supported string formats.
string text = 2;
// Metadata describing the source of the question.
// The answer will be written into the state blackboard with this as the variable name.
string source = 3;
// Data about the options to choose from.
message Option {
// Text associated with this option. Should be displayed to the user.
string text = 1;
// Numeric code corresponding to this option. Passed as part of the answer.
int64 answer_code = 2;
}
message OptionsList {
repeated Prompt.Option options = 1;
}
// The set of options that can be chosen for this prompt.
repeated Option options = 4 [deprecated = true];
oneof answer_spec {
// The set of options that can be chosen for this prompt.
OptionsList options_list = 9;
// Key to an OptionsList protobuf object on the blackboard. The variable is only read when
// the node starts meaning options cannot change while the node is running.
string options_list_in_blackboard = 11;
// Custom parameter specification for the answer expected for this prompt.
DictParam.Spec custom_params = 10;
}
// Child node, run after the prompt has been responded to.
// Children will have access to the answer code provided by the response.
Node child = 5;
// Hint that Question posed by this Prompt is meant to be answered by some automated system.
// See the Question message for details.
bool for_autonomous_processing = 6;
oneof severity_spec {
// Severity for this prompt. Used to determine what sort of alerting
// this prompt will trigger.
// Here are guidelines for severity as it pertains to missions:
// INFO: Normal operation. For example, waiting for charge; waiting on the dock for logs to
// download. WARN: Something went wrong, but the mission will try to recover autonomously.
// ERROR: Something went wrong, and the mission can't recover without human intervention.
// Intervention is not time sensitive and can be resolved when convenient.
// CRITICAL: Something went wrong, and the mission can't recover without human intervention.
// Human needs to rescue the robot before battery runs out because it's not charging.
AlertData.SeverityLevel severity = 7;
// If specified, this node will read the severity out of the blackboard at
// the specified location.
string severity_in_blackboard = 12;
}
// If specified, this node will write its current question (bosdyn.api.mission.Question proto)
// to the blackboard while it is being ticked.
string question_name_in_blackboard = 8;
}
// Get the state of the gripper camera params from the robot.
message BosdynGripperCameraParamsState {
// Name of the service to use.
string service_name = 1;
// Host machine the service is running on.
string host = 2;
// Child node. Children will have access to the state gathered by this node.
Node child = 3;
// Name of the bosdyn.api.GripperCameraParams object in the blackboard. For example, if this is
// set to "gripper_params", children can look up "gripper_params.camera_mode" in the blackboard.
string state_name = 4;
}
// Set gripper camera params
message SetGripperCameraParams {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the gripper camera param service is registered
// with.
string host = 2;
oneof params {
string params_in_blackboard_key = 3;
bosdyn.api.GripperCameraParams new_params = 4;
}
}
// Set grasp override and carry state override requests
message SetGraspOverride {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the gripper camera param service is registered
// with.
string host = 2;
bosdyn.api.ApiGraspOverrideRequest grasp_override_request = 3;
}
// Point the PTZ to a specified orientation
message SpotCamPtz {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the Spot CAM registered with.
string host = 2;
// The rest of the fields are from bosdyn.api.spot_cam.ptz.SetPtzPositionRequest, see that
// message for details.
bosdyn.api.spot_cam.PtzPosition ptz_position = 3;
message AdjustParameters {
// Variable name to retrieve the graph nav state from.
string localization_varname = 4;
// Waypoint ID where this PTZ configuration was originally set up.
string waypoint_id = 5;
// Pose of body in waypoint frame at the time this PTZ configuration was originally set up.
SE3Pose waypoint_tform_body = 6;
}
// Setting adjust_parameters will enable auto-adjusting the PTZ pan and tilt at playback time,
// based on where the robot is, relative to the waypoint. Leave empty to disable auto-adjust
// features.
AdjustParameters adjust_parameters = 4;
}
// Store media using the Spot CAM.
message SpotCamStoreMedia {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the Spot CAM registered with.
string host = 2;
// The rest of the fields are from bosdyn.api.spot_cam.logging.StoreRequest, see that message
// for details.
bosdyn.api.spot_cam.Camera camera = 3;
// What type of media should be stored from this action.
bosdyn.api.spot_cam.Logpoint.RecordType type = 4;
// Extra metadata to store alongside the captured media.
string tag = 5;
}
// Set the LEDs to a specified brightness
message SpotCamLed {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the Spot CAM registered with.
string host = 2;
// Brightnesses of the LEDs, from SetLEDBrightnessRequest
map<int32, float> brightnesses = 3;
}
// Set the focus on the Spot CAM PTZ
message SpotCamFocusState {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the Spot CAM registered with.
string host = 2;
// Focus State to set the Spot CAM PTZ to, from SetPtzFocusStateRequest
bosdyn.api.spot_cam.PtzFocusState focus_state = 3;
}
// Reset the autofocus on the Spot CAM PTZ
message SpotCamResetAutofocus {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the Spot CAM registered with.
string host = 2;
}
message Dock {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the docking service is registered with.
string host = 2;
// ID of docking station to dock at.
oneof id {
uint32 docking_station_id = 3;
// Blackboard variable key that contains the docking station id.
string docking_station_id_blackboard_key = 11;
}
// Optional child node. Children will have access to the status variables gathered by this node.
// If specified, child node will determine success/failure of this node.
//
// DEPRECATED as of 3.0.0. Use docking_command_response_blackboard_key and
// docking_command_feedback_response_blackboard_key instead.
Node child = 4 [deprecated = true];
// Name of the command status variable in the blackboard. This is the status of the docking
// command request made to the robot. Please refer to
// bosdyn.api.docking.DockingCommandResponse.Status for more details. Children can use this
// name to look up docking command status in the blackboard. If no name is provided, status will
// not be available.
//
// DEPRECATED as of 3.0.0. Use docking_command_response_blackboard_key and
// docking_command_feedback_response_blackboard_key instead.
string command_status_name = 5 [deprecated = true];
// Name of the feedback status variable in the blackboard. This is the feedback provided while
// docking is in progress. Please refer to
// bosdyn.api.docking.DockingCommandFeedbackResponse.Status for a list of possible status
// values. Children can use this name to look up docking status in the blackboard. If no name
// is provided, status will not be available.
//
// DEPRECATED as of 3.0.0. Use docking_command_response_blackboard_key and
// docking_command_feedback_response_blackboard_key instead.
string feedback_status_name = 6 [deprecated = true];
// Defines how we use the "pre-docking" behavior.
docking.PrepPoseBehavior prep_pose_behavior = 7;
// If provided, this will write the last DockingCommandFeedbackResponse message
// to a blackboard variable with this name.
string docking_command_feedback_response_blackboard_key = 8;
// If provided, this will write the last DockingCommandResponse message to
// a blackboard variable with this name.
string docking_command_response_blackboard_key = 9;
// Require the detection of the dock's fiducial
bool require_fiducial = 10;
}
// Triggers a StoreMetadataRequest to the data acquisition store.
message StoreMetadata {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the data acquisition service is registered with.
string host = 2;
// The name of the blackboard variable that holds the associated AcquireDataRequest. The
// reference ID that this metadata is associated with will be copied from the request.
string acquire_data_request_name = 3;
oneof data {
// The name of the metadata object in the blackboard to be stored.
// The metadata object can be any protobuf message.
string metadata_name = 5;
// JSON representation of metadata
google.protobuf.Struct metadata_json = 7;
}
// The data buffer channel on which to store the metadata.
string metadata_channel = 6;
}
// Trigger the acquisition and storage of data.
message DataAcquisition {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the data acquisition service is registered with.
string host = 2;
// Specification of the data and metadata to store.
AcquireDataRequest request = 3;
enum CompletionBehavior {
COMPLETE_UNKNOWN = 0;
// Node is complete after all data has been saved.
COMPLETE_AFTER_SAVED = 1;
// Node is complete after all data is acquired, but before processing and storage.
// This allows the robot to continue on with the mission sooner, but
// it will be unaware of failures in processing or storage.
COMPLETE_AFTER_ACQUIRED = 2;
}
CompletionBehavior completion_behavior = 4;
// Define a format string that will be used together with the blackboard to generate
// a group_name. If a value is specified in this field, it will override the group_name value
// specified in the CaptureActionId of the AcquireDataRequest. Values from the blackboard will
// replace the keys in braces {}.
// Example: "teleop-{date}", where "date" is a blackboard variable.
// Example: "{date}_loop_{loop_counter}", where "loop_counter" is a blackboard variable from a
// Repeat node.
string group_name_format = 5;
// If populated, name of the variable in the blackboard in which to store the AcquireDataRequest
// after it's created, and sent to the Data Acquisition service.
string request_name_in_blackboard = 6;
// The name of the metadata object in the blackboard to be stored.
// The metadata object can be any protobuf message.
// The metadata will be merged with the AcquireDataRequest's metadata field.
string metadata_name_in_blackboard = 9;
// Define a format string that will be used together with the blackboard to generate
// an action_name. If a value is specified in this field, it will override the action_name
// value specified in the CaptureActionId of the AcquireDataRequest. Values from the blackboard
// will replace the keys in braces {}.
// Example: "element 0 attempt {loop_counter}", where "loop_counter" is a blackboard variable
// from a Retry.
string action_name_format = 7;
// If set to false (default), this node will cancel an outgoing AcquireDataRequest when the node
// is paused / stopped. When the node is resumed, it will restart the AcquireDataRequest.
//
// If set to true, this node will NOT cancel outgoing AcquireDataRequest's when the node is
// paused / stopped. When the node is resumed, it will check feedback on the original outgoing
// AcquireDataRequest.
bool disable_cancel_on_pause_or_stop = 8;
// If true, metadata string values may contain formatted blackboard variables.
// Please see the documentation in FormatBlackboard for more information about supported string
// formats.
bool format_metadata = 10;
}
// Send RetainLease for every Lease the mission service is given via PlayMissionRequest.
// Returns RUNNING while there are more leases to retain, SUCCESS once a lease for each resource has
// been retained, and FAILURE if any one lease cannot be retained.
message RetainLease {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the lease service is registered with.
string host = 2;
}
// Defines new blackboard variables within the scope of the child. Shadows blackboard
// variables in the parent scope.
message DefineBlackboard {
// The list of variables that should be defined for this subtree,
// with initial values.
//
// Note: Currently the mission service supports blackboard variable keys that contain ".", "[]",
// and "()". In a future release, this will no longer be supported. Boston Dynamics recommends
// using letters, numbers, and underscores for blackboard keys.
repeated KeyValue blackboard_variables = 1;
// The blackboard variables will only persist in the subtree defined by this
// child node. The child's tick() will be called on the child until it
// returns either SUCCESS or FAILURE.
Node child = 2;
}
// Sets existing blackboard variables within this scope to specific values, returning SUCCESS.
message SetBlackboard {
// The key of the KeyValue is the name of the blackboard variable.
// The value will be dereferenced and converted into a value type at runtime
// inside this node's tick function. For example, if the value is a runtime
// variable, that variable will be evaluated at tick time, and then stored into
// the blackboard. If the value is another blackboard variable, that blackboard
// variable's value will be copied into the variable specified by the key.
//
// Note: Currently the mission service supports blackboard variable keys that contain ".", "[]",
// and "()". In a future release, this will no longer be supported. Boston Dynamics recommends
// using letters, numbers, and underscores for blackboard keys.
repeated KeyValue blackboard_variables = 1;
}
// Sets a blackboard variable to a formatted string, reading from other blackboard vars.
message FormatBlackboard {
// The key of the variable that will be written.
string key = 1;
// Define a format string that will be used together with the blackboard to generate
// string value. Values from the blackboard will replace the keys in braces {}, i.e.
// {blackboard_variable_name}. We also allow some string formatting options, namely:
//
// 1) Floating point decimal places: {float_variable:.2f}
// 2) TBD
//
// Select examples:
//
// Format String: "teleop-{date}"
// Blackboard: "date" is a blackboard variable with string value: "2021-05-13"
// Output: "teleop-2021-05-13"
//
// Format String: "{date}_loop_{loop_counter}"
// Blackboard: "date" is a blackboard variable with string value: "2021-05-13"
// Blackboard: "loop_counter" is a blackboard variable with integer value: "3"
// Output: "2021-05-13_loop_3"
//
// Format String: "battery charge is: {state.power_state.locomotion_charge_percentage.value}"
// Blackboard: "state" is a protobuf message in the blackboard from a BosdynRobotState, and
// the power_state submessage has a charge percentage of 30.2148320923085
// Output: "battery charge is: 30.2158320923085"
//
// Format String: "battery charge is:
// {state.power_state.locomotion_charge_percentage.value:.2f}"
// Blackboard: "state" is a protobuf message in the blackboard from a BosdynRobotState, and
// the power_state submessage has a charge percentage of 30.2148320923085
// Output: "battery charge is: 30.21"
//
// Format String: "the value is {x:.0f}"
// Blackboard: "x" is a blackboard variable with float value: "2.71828"
// Output: "the value is 3"
//
string format = 2;
}
// Record a datetime string into the blackboard. Writes the date according to ISO8601 format.
message DateToBlackboard {
// The key of the variable that will be written.
string key = 1;
}
// Write the QueryStoredCapturesResponse for a given QueryParameters message to the blackboard.
message BosdynQueryStoredCaptures {
// Name of the service to use.
string service_name = 1;
// Host machine of the directory server that the data acquisition service is registered with.
string host = 2;
// The key of the variable that the QueryStoredCapturesResponse will be written to.
string key = 3;
// The QueryParameters message for the QueryStoredCapturesRequest that will be made.
QueryParameters query_params = 4;
// Format strings that will be used together with the blackboard to generate
// a CaptureActionId.
message CaptureActionIdFormat {
string action_name_format = 1;
string group_name_format = 2;
}
// If specified, these CaptureActionIds will be added to the QueryParameters at runtime.
repeated CaptureActionIdFormat capture_action_ids_format = 5;
}
// Just returns a constant when calling tick().