forked from boston-dynamics/spot-sdk
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathchoreography_sequence.proto
1099 lines (912 loc) · 40.5 KB
/
choreography_sequence.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.spot;
option java_outer_classname = "ChoreographyProto";
import "google/protobuf/duration.proto";
import "google/protobuf/timestamp.proto";
import "google/protobuf/wrappers.proto";
import "bosdyn/api/geometry.proto";
import "bosdyn/api/header.proto";
import "bosdyn/api/lease.proto";
import "bosdyn/api/spot/choreography_params.proto";
import "bosdyn/api/data_chunk.proto";
// Request a list of all possible moves and the associated parameters (min/max values).
message ListAllMovesRequest {
// Common request header
RequestHeader header = 1;
}
// Response for ListAllMoves that defines the list of available moves and their parameter types.
message ListAllMovesResponse {
// Common response header
ResponseHeader header = 1;
// List of moves that the robot knows about.
repeated MoveInfo moves = 2;
// A copy of the MoveParamsConfig.txt that the robot is using.
string move_param_config = 3;
}
// Request a list of all playable choreography sequences that the robot knows about
message ListAllSequencesRequest {
// Common request header
RequestHeader header = 1;
}
//
message ListAllSequencesResponse {
// Common response header.
ResponseHeader header = 1;
// DEPRECATED as of 3.2.0: The string list of known sequence names has been
// deprecated and replaced by the repeated field sequence_info.
repeated string known_sequences = 2 [deprecated = true];
// List of choreography sequences the robot knows about.
repeated SequenceInfo sequence_info = 3;
}
message SequenceInfo {
string name = 1;
repeated string labels = 2;
enum SavedState {
// Status unknown; do not use
SAVED_STATE_UNKNOWN = 0;
// Sequence will be forgotten on reboot
SAVED_STATE_TEMPORARY = 1;
// A file for this sequence is stored on the robot; the sequence will be loaded
// to memory each time the robot boots
SAVED_STATE_RETAINED = 2;
// Sequence was built into the release and can't be deleted
SAVED_STATE_PERMANENT = 3;
}
// Use temporary sequences during development with choreographer, and then tell the robot to
// retain the final version of the sequence so that it can be played back later from other
// interfaces, like the tablet
SavedState saved_state = 3;
// The exit transition state of the sequence.
MoveInfo.TransitionState exit_state = 4;
}
// Request all the information needed to play a choreography sequence, this includes the sequence
// itself and any animations the sequence uses.
message GetChoreographySequenceRequest {
// Common request header
RequestHeader header = 1;
// Name of the requested sequence.
string sequence_name = 2;
// If true, skip returning the animation protos and only return the names of the
// required animations. Individual Animations can be requested with GetAnimationRequest.
bool return_animation_names_only = 3;
}
//
message GetChoreographySequenceResponse {
// Common response header.
ResponseHeader header = 1;
enum Status {
STATUS_UNKNOWN = 0; // Do not use.
STATUS_OK = 1; // Finding + returning the sequence succeeded.
// The requested sequence was not found.
STATUS_UNKNOWN_SEQUENCE = 2;
}
Status status = 2;
// ChoreographySequence with the name of the requested sequence.
ChoreographySequence choreography_sequence = 3;
// All Animations used in the returned ChoreographySequence.
repeated Animation animated_moves = 4;
// The string names of all the animations used in the choreography sequence.
repeated string animation_names = 5;
}
// Request an Animation proto using a given animation name.
message GetAnimationRequest {
// Common request header
RequestHeader header = 1;
// Name of the requested animated move.
string name = 2;
}
message GetAnimationResponse {
// Common response header.
ResponseHeader header = 1;
enum Status {
STATUS_UNKNOWN = 0; // Do not use.
STATUS_OK = 1; // Finding + returning the animation succeeded.
// The requested sequence was not found.
STATUS_UNKNOWN_ANIMATION = 2;
}
Status status = 2;
// Animation with the name of the requested animation.
Animation animated_move = 3;
}
// Delete the retained file for a choreography sequence so the sequence will be forgotten on reboot
message DeleteSequenceRequest {
// Common request header
RequestHeader header = 1;
// Name of the sequence to delete.
string sequence_name = 2;
}
//
message DeleteSequenceResponse {
// Common response header.
ResponseHeader header = 1;
enum Status {
// Do not use.
STATUS_UNKNOWN = 0;
// The sequence was successfully deleted
STATUS_OK = 1;
// The sequence does not exist
STATUS_UNKNOWN_SEQUENCE = 2;
// The sequence is already temporary and will be removed at the next reboot.
STATUS_ALREADY_TEMPORARY = 3;
// Permanent sequences cannot be deleted
STATUS_PERMANENT_SEQUENCE = 4;
}
Status status = 2;
}
// Write a choreography sequence as a file to robot memory so it will be retained through reboot
message SaveSequenceRequest {
// Common request header
RequestHeader header = 1;
// Name of the sequence to be added to the selection of retained sequences
string sequence_name = 2;
// List of labels to add to the sequence when it is being saved
repeated string add_labels = 3;
}
//
message SaveSequenceResponse {
// Common response header.
ResponseHeader header = 1;
enum Status {
// Do not use.
STATUS_UNKNOWN = 0;
// The sequence was successfully saved
STATUS_OK = 1;
// The requested sequence was not found
STATUS_UNKNOWN_SEQUENCE = 2;
// This sequence is already saved in the release
STATUS_PERMANENT_SEQUENCE = 3;
// We failed to save a file with the sequence information to robot
STATUS_FAILED_TO_SAVE = 4;
}
Status status = 2;
}
// Edit the metadata of a choreography sequence and update any retained files for
// that sequence with the new metadata
message ModifyChoreographyInfoRequest {
// Common request header
RequestHeader header = 1;
// Name of the sequence to be modified
string sequence_name = 2;
// Labels to be added to the sequence's metadata
repeated string add_labels = 3;
// Labels to be removed from the sequence's metadata
repeated string remove_labels = 4;
}
message ModifyChoreographyInfoResponse {
// Common response header.
ResponseHeader header = 1;
enum Status {
// Do not use.
STATUS_UNKNOWN = 0;
// The sequence was successfully modified
STATUS_OK = 1;
// The sequence does not exist
STATUS_UNKNOWN_SEQUENCE = 2;
// Permanent sequences cannot be modified
STATUS_PERMANENT_SEQUENCE = 3;
// The changes were made, but the retained sequence file was not updated and
// changes were reverted
STATUS_FAILED_TO_UPDATE = 4;
}
Status status = 2;
}
// Reset to a clean slate with no retained files by deleting all non-permanent
// choreography related files
message ClearAllSequenceFilesRequest {
// Common request header
RequestHeader header = 1;
}
message ClearAllSequenceFilesResponse {
// Common response header.
ResponseHeader header = 1;
enum Status {
// Do not use.
STATUS_UNKNOWN = 0;
// All retained sequences were successfully removed from robot memory
STATUS_OK = 1;
// Deletion of all retained files failed
STATUS_FAILED_TO_DELETE = 2;
}
Status status = 2;
}
message UploadChoreographyRequest {
// Common request header.
RequestHeader header = 1;
// ChoreographySequence to upload and store in memory
ChoreographySequence choreography_sequence = 2;
// Should we run a sequences that has correctable errors?
// If true, the service will fix any correctable errors and run the corrected choreography
// sequence. If false, the service will reject a choreography sequence that has any errors.
bool non_strict_parsing = 3;
}
message UploadChoreographyResponse {
// Common response header. If the dance upload is invalid, the header INVALID request error will
// be set, which means that the choreography did not respect bounds of the parameters or has
// other attributes missing or incorrect.
ResponseHeader header = 1;
// If the uploaded choreography is invalid (will throw a header InvalidRequest status), then
// certain warning messages will be populated here to indicate which choreography moves or
// parameters violated constraints of the robot.
repeated string warnings = 3;
}
message UploadAnimatedMoveRequest {
// Common request header
RequestHeader header = 1;
// Unique ID for the animated moves. This will be automatically generated by the client
// and is used to uniquely identify the entire animation by creating a hash from the Animation
// protobuf message after serialization. The ID will be conveyed within the MoveInfo protobuf
// message in the ListAllMoves RPC. This ID allows the choreography client to only reupload
// animations that have changed or do not exist on robot already.
google.protobuf.StringValue animated_move_generated_id = 3;
// AnimatedMove to upload to the robot and create a dance move from.
Animation animated_move = 2;
}
message UploadAnimatedMoveResponse {
// Common response header.
ResponseHeader header = 1;
enum Status {
STATUS_UNKNOWN = 0; // Do not use.
STATUS_OK = 1; // Uploading + parsing the animated move succeeded.
// The animated move is considered invalid, see the warnings.
STATUS_ANIMATION_VALIDATION_FAILED = 2;
// Treated this message as a ping. Responding to demonstrate connectivity.
STATUS_PING_RESPONSE = 3;
}
Status status = 2;
// If the uploaded animated move is invalid (will throw a STATUS_ANIMATION_VALIDATION_FAILED),
// then warning messages describing the failure cases will be populated here to indicate which
// parts of the animated move failed. Note: there could be some warning messages even when an
// animation is marked as ok.
repeated string warnings = 3;
}
message ExecuteChoreographyRequest {
// Common request header
RequestHeader header = 1;
// The string name of the ChoreographySequence to use.
string choreography_sequence_name = 2;
// The absolute time to start the choreography at. This should be in the robot's clock so we can
// synchronize music playing and the robot's choreography.
google.protobuf.Timestamp start_time = 3;
// The slice (betas/sub-beats) that the choreography should begin execution at.
double choreography_starting_slice = 4;
/// The Lease to show ownership of the robot body.
Lease lease = 6;
}
message ExecuteChoreographyResponse {
// Common response header
ResponseHeader header = 1;
LeaseUseResult lease_use_result = 2;
enum Status {
STATUS_UNKNOWN = 0;
STATUS_OK = 1;
STATUS_INVALID_UPLOADED_CHOREOGRAPHY = 2;
STATUS_ROBOT_COMMAND_ISSUES = 3;
STATUS_LEASE_ERROR = 4;
STATUS_UNKNOWN_SEQUENCE = 5;
}
Status status = 3;
// Unique ID for the execution.
// Will increment whenever an ExecuteChoreographyRequest is received.
// Will reset upon robot boot.
int32 execution_id = 4;
}
message StartRecordingStateRequest {
// Common request header
RequestHeader header = 1;
// How long should the robot record for if no stop RPC is sent. A recording session can be
// extended by setting the recording_session_id below to a non-zero value matching the ID for
// the current recording session. For both start and continuation commands, the service will
// stop recording at end_time = (system time when the Start/Continue RPC is received) +
// (continue_recording_duration), unless another continuation request updates this end time. The
// robot has an internal maximum recording time of 5 minutes for the complete session log.
google.protobuf.Duration continue_recording_duration = 2;
// Provide the unique identifier of the recording session to extend the recording end time for.
// If the recording_session_id is 0, then it will create a new session and the robot will clear
// the recorded robot state buffer and restart recording.
// If this is a continuation of an existing recording session, than the robot will continue
// to record until the specified end time.
uint64 recording_session_id = 3;
}
message StartRecordingStateResponse {
// Common response header
ResponseHeader header = 1;
// The status for the start recording request.
enum Status {
// Status unknown; do not use.
STATUS_UNKNOWN = 0;
// The request succeeded and choreography has either started, or continued with an extended
// duration based on if a session_id was provided.
STATUS_OK = 1;
// The provided recording_session_id is unknown: it must either be 0 (start a new recording
// log) or it can match the current recording session id returned by the most recent start
// recording request.
STATUS_UNKNOWN_RECORDING_SESSION_ID = 2;
// The Choreography Service's internal buffer is filled. It will record for a maximum of 5
// minutes. It will stop recording, but save the recorded data until
STATUS_RECORDING_BUFFER_FULL = 3;
}
Status status = 2;
// Unique identifier for the current recording session
uint64 recording_session_id = 3;
}
message StopRecordingStateRequest {
// Common request header
RequestHeader header = 1;
}
message StopRecordingStateResponse {
// Common response header
ResponseHeader header = 1;
}
message DownloadRobotStateLogRequest {
// Common request header
RequestHeader header = 1;
enum LogType {
// Unknown. Do not use.
LOG_TYPE_UNKNOWN = 0;
// The robot state information recorded from the time of the manual start RPC
// (StartRecordingState) to either {the time of the manual stop RPC (StopRecordingState),
// the time of the download logs RPC, or the time of the internal service's buffer filling
// up}.
LOG_TYPE_MANUAL = 1;
// The robot will automatically record robot state information for the entire duration of an
// executing choreography in addition to any manual logging. This log type will download
// this information for the last completed choreography.
LOG_TYPE_LAST_CHOREOGRAPHY = 2;
}
// Which data should we download.
LogType log_type = 2;
}
message LoggedJoints {
LegJointAngles fl = 1; // front left leg joint angles.
LegJointAngles fr = 2; // front right leg joint angles.
LegJointAngles hl = 3; // hind left leg joint angles.
LegJointAngles hr = 4; // hind right leg joint angles.
// Full set of joint angles for the arm and gripper.
ArmJointAngles arm = 5;
google.protobuf.DoubleValue gripper_angle = 6;
}
message LoggedFootContacts {
// Boolean indicating whether or not the robot's foot is in contact with the ground.
bool fr_contact = 1;
bool fl_contact = 2;
bool hr_contact = 3;
bool hl_contact = 4;
}
message LoggedStateKeyFrame {
// Full set of joint angles for the robot.
LoggedJoints joint_angles = 1;
// Foot contacts for the robot.
LoggedFootContacts foot_contact_state = 4;
// The current pose of the robot body in animation frame. The animation frame is defined
// based on the robot's footprint when the log first started recording.
SE3Pose animation_tform_body = 2;
// The timestamp (in robot time) for the key frame.
google.protobuf.Timestamp timestamp = 3;
}
message ChoreographyStateLog {
// A set of key frames recorded at a high rate. The key frames can be for the duration of an
// executing choreography or for the duration of a manual recorded log (triggered by the
// StartRecordingState and StopRecordingState RPCs). The specific set of keyframes is specified
// by the LogType when requesting to download the data.
repeated LoggedStateKeyFrame key_frames = 1;
}
message DownloadRobotStateLogResponse {
// Common response header
ResponseHeader header = 1;
enum Status {
// Status unknown. Do not use.
STATUS_UNKNOWN = 0;
// The log data downloaded successfully and is complete.
STATUS_OK = 1;
// Error where there is no robot state information logged in the choreography service.
STATUS_NO_RECORDED_INFORMATION = 2;
// Error where the complete duration of the recorded session caused the service's recording
// buffer to fill up. When full, the robot will stop recording but preserve whatever was
// recorded until that point. The robot has an internal maximum recording time of 5 minutes.
// The data streamed in this response will go from the start time until the time the buffer
// was filled.
STATUS_INCOMPLETE_DATA = 3;
}
// Return status for the request.
Status status = 2;
// Chunk of data to download. Responses are sent in sequence until the
// data chunk is complete. After receiving all chunks, concatenate them
// into a single byte string. Then, deserialize the byte string into an
// ChoreographyStateLog object.
DataChunk chunk = 3;
}
// Defines varying parameters for a particular instance of a move.
message MoveParams {
// Unique ID of the move type that these params are associated with.
string type = 1;
// How many slices since the start of the song this move should be executed at.
int32 start_slice = 2;
// The number of slices (beats/sub-beats) that this move is supposed to last for. If the move
// was extendable, then this corresponds to the number of slices that the user requested.
int32 requested_slices = 3;
// The ID number can be optionally set by the client as part of the UploadChoreographyRequest.
// If not set by the client, the robot will assign an id to each move that is unique within the
// sequence. The ID (either set by the client or the robot) will be reported in the ActiveMoves
// in the ChoreographyStatusResponse. The ID can be used to specify which move a Command is
// intended for.
int32 id = 4;
// Each move type can define its own parameters which get stored here. Only a single parameter
// set can be used to describe a move instance.
oneof params {
JumpParams jump_params = 11;
RotateBodyParams rotate_body_params = 12;
StepParams step_params = 13;
ButtCircleParams butt_circle_params = 14;
TurnParams turn_params = 15;
Pace2StepParams pace_2step_params = 16;
TwerkParams twerk_params = 17;
ChickenHeadParams chicken_head_params = 18;
ClapParams clap_params = 19;
FrontUpParams front_up_params = 20;
SwayParams sway_params = 21;
BodyHoldParams body_hold_params = 22;
ArmMoveParams arm_move_params = 23;
KneelLegMoveParams kneel_leg_move_params = 24;
RunningManParams running_man_params = 25;
KneelCircleParams kneel_circle_params = 26;
GripperParams gripper_params = 27;
HopParams hop_params = 28;
RandomRotateParams random_rotate_params = 29;
CrawlParams crawl_params = 30;
SideParams side_params = 31;
BourreeParams bourree_params = 32;
WorkspaceArmMoveParams workspace_arm_move_params = 33;
Figure8Params figure8_params = 34;
KneelLegMove2Params kneel_leg_move2_params = 35;
FidgetStandParams fidget_stand_params = 36;
GotoParams goto_params = 37;
FrameSnapshotParams frame_snapshot_params = 38;
SetColorParams set_color_params = 39;
RippleColorParams ripple_color_params = 40;
FadeColorParams fade_color_params = 41;
IndependentColorParams independent_color_params = 42;
CustomGaitParams custom_gait_params = 43;
SetAudioVisualColorParams set_audio_visual_color_params = 44;
SetAllColorParams set_all_color_params = 45;
BuzzerNoteParams buzzer_note_params = 46;
LegJointParams leg_joint_params = 100;
AnimateParams animate_params = 1000;
}
}
message MoveCommand {
// Either, both, or neither of move_type and move_id can be used to specify which move this
// command is intended for.
// Name of the move type this command is intended for.
string move_type = 1;
// ID of the move this command is intended for.
int32 move_id = 2;
// Different move types will accept different types of commands.
oneof command {
CustomGaitCommand custom_gait_command = 3;
}
}
message ChoreographyCommandRequest {
// Common request header
RequestHeader header = 1;
// Commands intended for individual moves.
// Repeated because multiple moves may be playing simultaneously and we may want to command
// multiple of them.
repeated MoveCommand commands = 2;
// The Lease to show ownership of the robot body.
Lease lease = 3;
// When the commands expire. In the robot's clock.
google.protobuf.Timestamp command_end_time = 4;
}
message ChoreographyCommandResponse {
// Common response header
ResponseHeader header = 1;
LeaseUseResult lease_use_result = 2;
enum Status {
STATUS_UNKNOWN = 0;
STATUS_OK = 1;
STATUS_ACCEPTED_WITH_MODIFICATION = 2;
STATUS_LEASE_ERROR = 3;
STATUS_NO_MATCHING_MOVE = 4;
STATUS_INVALID_COMMAND = 5;
STATUS_ALREADY_EXPIRED = 6;
}
// One status for each command sent.
repeated Status status = 3;
}
// Defines properties of a choreography move.
message MoveInfo {
// Unique ID of the move type.
string name = 1;
// The duration of this move in slices (usually 1/4 beats).
int32 move_length_slices = 2;
// The duration of this move in seconds. If specified, overrides move_length_slices.
double move_length_time = 15;
// If true, the duration may be adjusted from the default specified by move_length_slices or
// move_length_time.
bool is_extendable = 3;
// Bounds on the duration may be adjusted in slices (usually 1/4 beats).
// These apply to extendable moves, but may also override move_length_time for some BPM.
int32 min_move_length_slices = 13;
int32 max_move_length_slices = 14;
// Bounds on the duration in time.
// These apply to extendable moves, but may also override move_length_slices for some BPM.
double min_time = 6;
double max_time = 7;
// If the slice bounds and time bounds do not overlap for a particular bpm,
// the duration will be set to the minimum, violating the specified maximum.
// The state that the robot is in at the start or end of a move.
enum TransitionState {
TRANSITION_STATE_UNKNOWN = 0; // Unknown or unset state.
TRANSITION_STATE_STAND = 1; // The robot is in a normal (standing) state.
TRANSITION_STATE_KNEEL = 2; // The robot is kneeling down.
TRANSITION_STATE_SIT = 3; // The robot is sitting.
TRANSITION_STATE_SPRAWL = 4; // The robot requires a self-right.
}
// The admissible states the robot can be in currently for this move to execute.
repeated TransitionState entrance_states = 4;
// The state of the robot after the move is complete.
TransitionState exit_state = 5;
// Indicators as to which parts of the robot that the move controls.
bool controls_arm = 8;
bool controls_legs = 9;
bool controls_body = 10;
bool controls_gripper = 12;
bool controls_lights = 17; // Controls the face (status) lights.
bool controls_annotations = 18;
bool controls_audio_visual_lights = 20;
bool controls_audio_visual_buzzer = 21;
bool is_looping = 19;
// Information for the GUI tool to visualize the sequence move info.
ChoreographerDisplayInfo display = 11;
// Unique ID for the animated moves. This is sent with the UploadAnimatedMove request and use
// to track which version of the animated move is currently saved on robot. The ID can be unset,
// meaning the RPC which uploaded the animation did not provide an identifying hash.
google.protobuf.StringValue animated_move_generated_id = 16;
}
// Information for the Choreographer to display.
message ChoreographerDisplayInfo {
// Color of the object. Set it to override the default category color.
message Color {
// RGB values for color ranging from [0,255].
int32 r = 1;
int32 g = 2;
int32 b = 3;
// Alpha value for the coloration ranges from [0,1].
double a = 4;
}
Color color = 1;
// For the GUI, these are marked events in steps. For example if the move puts a foot down, the
// mark might be exactly when the foot is placed on the ground, relative to the start of the
// move.
repeated int32 markers = 13;
// Textual description to be displayed in the GUI.
string description = 14;
// Image path (local to the UI) to display as an icon. May be an animated gif.
string image = 15;
// Move Category affects the grouping in the choreographer list view, as well as the color it's
// displayed with.
enum Category {
CATEGORY_UNKNOWN = 0;
CATEGORY_BODY = 1;
CATEGORY_STEP = 2;
CATEGORY_DYNAMIC = 3;
CATEGORY_TRANSITION = 4;
CATEGORY_KNEEL = 5;
CATEGORY_ARM = 6;
CATEGORY_ANIMATION = 7;
CATEGORY_MPC = 8;
CATEGORY_LIGHTS = 9;
CATEGORY_ANNOTATIONS = 10;
CATEGORY_AUDIO_VISUAL_LIGHTS = 11;
CATEGORY_AUDIO_VISUAL_BUZZER = 12;
}
Category category = 16;
}
// Represents a particular choreography sequence, made up of MoveParams.
message ChoreographySequence {
// Display name or file name associated with the choreography sequence.
string name = 1;
// Number of slices per minute in the choreography sequence. Typically a slice will correspond
// to 1/4 a beat.
double slices_per_minute = 2;
// All of the moves in this choreography sequence.
repeated MoveParams moves = 3;
// Metadata associated with the sequence.
ChoreographyInfo choreography_info = 4;
// Can be used to specify an explicit entrance_state in the case where the first legs-track move
// accepts multiple entrance_states.
// Will also be used if the sequence contains no legs-track moves.
// Can otherwise be left unset.
// If set and not within the set of acceptable entrance_states for the first legs-track move,
// the Sequence will be considered invalid.
MoveInfo.TransitionState entrance_state = 5;
}
// Describes metadata for the Choreography sequence that can be used for a number of different UIs
message ChoreographyInfo {
// the list of user assigned categories that the sequence belongs to
repeated string labels = 4;
}
// Describes the metadata and information only used by the Choreographer GUI, which isn't used in
// the API
message ChoreographerSave {
// The main ChoreographySequence that makes up the dance and is sent to the robot.
ChoreographySequence choreography_sequence = 1;
// If specified this is the UI local path of the music to load.
string music_file = 2;
// UI specific member that describes exactly when the music should start, in slices. This is for
// time sync issues.
double music_start_slice = 3;
// The start slice for the choreographer save.
double choreography_start_slice = 4;
}
// Represents an animated dance move that can be used within choreographies after uploading.
message Animation {
// The name of the animated move, which is how it will be referenced in choreographies.
string name = 1;
// The animated move is composed of animation keyframes, which specify the duration of
// each frame. The keyframe describes the position of the body/arms/gripper.
repeated AnimationKeyframe animation_keyframes = 2;
// Indicators as to which parts of the robot that the move controls.
bool controls_arm = 3;
bool controls_legs = 4;
bool controls_body = 5;
bool controls_gripper = 6;
// Track animated swing trajectories. Otherwise, takes standard swings between animated liftoff
// and touchdown locations.
bool track_swing_trajectories = 16;
// For moves that control the legs, but not the body.
// If legs are specified by joint angles, we still need body roll and pitch to know the foot
// height. If `assume_zero_roll_and_pitch` is true, they needn't be explicitly specified.
bool assume_zero_roll_and_pitch = 19;
// Mode for hand trajectory playback
enum ArmPlayback {
// Playback as specified. Arm animations specified with joint angles playback in jointspace
// and arm animations specified as hand poses playback in workspace.
ARM_PLAYBACK_DEFAULT = 0;
// Playback in jointspace. Arm animation will be most consistent relative to the body
ARM_PLAYBACK_JOINTSPACE = 1;
// Playback in workspace. Hand pose animation will be most consistent relative to the
// current footprint. Reference frame is animation frame.
ARM_PLAYBACK_WORKSPACE = 2;
// Playback in workspace with poses relative to the dance frame. hand pose animation will be
// most consistent relative to a fixed point in the world.
ARM_PLAYBACK_WORKSPACE_DANCE_FRAME = 3;
}
ArmPlayback arm_playback = 17;
// Optional bpm that the animation is successful at.
double bpm = 7;
// When true, rescales the time of each keyframe slightly such that the move takes an
// integer number of slices. If false/absent, the move will be padded or truncated slightly
// to fit an integer number of slices.
bool retime_to_integer_slices = 8;
// The different parameters (minimum, default, and maximum) that can change the move.
// The min/max bounds are used by Choreographer to constrain the parameter widget, and will
// also be used when uploading a ChoreographySequence containing the animation to validate
// that the animated move is allowed.
AnimateParams minimum_parameters = 9;
AnimateParams default_parameters = 10;
AnimateParams maximum_parameters = 11;
// Indicates if the animated moves can be shortened (the animated move will be cut off). Not
// supported for leg moves.
bool truncatable = 12;
// Indicates if the animated moves can be stretched (animated move will loop). Not supported for
// leg moves.
bool extendable = 13;
// Indicates if the move should start in a neutral stand position.
bool neutral_start = 14;
// Step exactly at the animated locations, even at the expense of balance.
// By default, the optimizer may adjust step locations slightly.
bool precise_steps = 15;
// DEPRECATED as of 3.3.0: The boolean field has been replaced by the more fine-grained control
// of timing_adjustability. The following field will be deprecated and moved to 'reserved' in a
// future release.
bool precise_timing = 18 [deprecated = true];
// How much the optimizer is allowed to adjust the timing.
// On the range [-1, 1].
// -1: Everything will be timed exactly as animated, even at the expense of balance.
// 0: Default value: some timing adjust allowed.
// 1: Timing can be adjusted drastically.
double timing_adjustability = 23;
// If set true, this animation will not run unless the robot has an arm.
bool arm_required = 20;
// If set true, this animation will not run unless the robot has no arm.
bool arm_prohibited = 22;
// If the animation completes before the move's duration, freeze rather than looping.
bool no_looping = 21;
// If the animation starts from a sit pose. Default starting pose is stand.
bool starts_sitting = 24;
// If true, this animation can be used as direct input to custom gait
// to define the gait style
bool custom_gait_cycle = 27;
}
message AnimationKeyframe {
// Time from the start of the animation for this frame.
double time = 1;
// Different body parts the animated move can control.
// It can control multiple body parts at once.
AnimateGripper gripper = 2;
AnimateArm arm = 3;
AnimateBody body = 4;
AnimateLegs legs = 5;
}
message AnimateGripper {
google.protobuf.DoubleValue gripper_angle = 1;
}
message AnimateArm {
// An SE3 Pose for the hand where orientation is specified using either a quaternion or
// euler angles
message HandPose {
Vec3Value position = 1;
oneof orientation {
// The hand's orientation described with euler angles (yaw, pitch, roll).
EulerZYXValue euler_angles = 3;
// The hand's orientation described with a quaternion.
Quaternion quaternion = 4;
}
}
// For the animated arm, the arm can be described using either the joint angles or
// the pose of the hand. NOTE: each keyframe within a single Animation proto must always
// specify the arm using the same format for all frames.
oneof arm {
// Full arm joint angle specification.
ArmJointAngles joint_angles = 1;
// The hand position in the animation frame
HandPose hand_pose = 2;
}
}
// The AnimateArm keyframe describes the joint angles of the arm joints in radians.
// Any joint not specified, will hold the previous angle it was at when the keyframe
// begins. At least one arm joint must be specified.
message ArmJointAngles {
google.protobuf.DoubleValue shoulder_0 = 1;
google.protobuf.DoubleValue shoulder_1 = 2;
google.protobuf.DoubleValue elbow_0 = 3;
google.protobuf.DoubleValue elbow_1 = 4;
google.protobuf.DoubleValue wrist_0 = 5;
google.protobuf.DoubleValue wrist_1 = 6;
}
// The AnimateBody keyframe describes the body's position and orientation. At least
// one dimension of the body must be specified.
message AnimateBody {
// For the animated body keyframe, describe the body position using either the body position or
// the center of mass position. NOTE: each keyframe within a single Animation proto must always
// specify the body position using the same format for all frames.
oneof position {
// The body position in the animation frame.
Vec3Value body_pos = 1;
// The body's center of mass position in the animation frame.
Vec3Value com_pos = 2;
}
// For the animated body keyframe, describe the body orientation using either euler angles or a
// quaternion. NOTE: each keyframe within a single Animation proto must always
// specify the body orientation using the same format for all frames.
oneof orientation {
// The body's orientation described with euler angles (yaw, pitch, roll).
EulerZYXValue euler_angles = 3;
// The body's orientation described with a quaternion.
Quaternion quaternion = 4;
}
}
// The AnimateLegs keyframe describes each leg using either joint angles or the foot position.
message AnimateLegs {
AnimateSingleLeg fl = 1; // Front left leg.
AnimateSingleLeg fr = 2; // Front right leg.
AnimateSingleLeg hl = 3; // Hind left leg.
AnimateSingleLeg hr = 4; // Hind right leg.
}
// A single leg keyframe to describe the leg motion.
message AnimateSingleLeg {
// For the animated single legs, the leg can be described using either the joint angles or
// the position of the foot. NOTE: each keyframe within a single Animation proto must always
// specify a single leg using the same format for all frames.
oneof leg {
// Full leg joint angle specification.
LegJointAngles joint_angles = 1;
// The foot position of the leg in the animation frame.
Vec3Value foot_pos = 2;
}
// If true, the foot is in contact with the ground and standing. If false, the
// foot is in swing. If unset, the contact will be inferred from the leg joint angles
// or foot position.
google.protobuf.BoolValue stance = 3;
}
// Description of each leg joint angle (hip x/y and knee) in radians.
message LegJointAngles {
double hip_x = 1;
double hip_y = 2;
double knee = 3;
}
message ActiveMove {
// Any parameters that had to be adjusted into the legal range will have their adjusted values.
MoveParams move = 1;
// Give information about the commands the move can accept.
// For example: Minimum and maximum values.
oneof command_limits {
CustomGaitCommandLimits custom_gait_command_limits = 2;