spot/choreography_params.proto

ArmMoveParams

Parameters specific to ArmMove move.

Field Type Description
shoulder_0 google.protobuf.DoubleValue Joint angles in radians for the arm joints.
shoulder_1 google.protobuf.DoubleValue
elbow_0 google.protobuf.DoubleValue
elbow_1 google.protobuf.DoubleValue
wrist_0 google.protobuf.DoubleValue
wrist_1 google.protobuf.DoubleValue
easing Easing The easing pattern for how the "slices" (beats/sub-beats) should be spaced.
gripper google.protobuf.DoubleValue Movement for the gripper.

BodyHoldParams

Parameters specific to the BodyHold move.

Field Type Description
rotation EulerZYXValue The robot will rotate its body to the specified orientation (roll/pitch/yaw) [rad].
translation bosdyn.api.Vec3Value The positional offset to the robot's current location [m].
entry_slices google.protobuf.DoubleValue How many "slices" (beats or sub-beats) are allowed before reaching the desired pose.
exit_slices google.protobuf.DoubleValue How many "slices" (beats or sub-beats) are allowed for the robot to return to the original pose.

ButtCircleParams

Parameters specific to the ButtCircle DanceMove.

Field Type Description
radius google.protobuf.DoubleValue How big a circle the robutt will move in. Described in meters.
beats_per_circle google.protobuf.DoubleValue The number of beats that elapse while performing the butt circle.
number_of_circles google.protobuf.DoubleValue The number of circles that will be performed. If non-zero, takes precedence over beats_per_circle.
pivot Pivot The pivot point the butt circles should be centered around.

ChickenHeadParams

Parameters specific to the chicken head move.

Field Type Description
bob_magnitude bosdyn.api.Vec3Value Bobs the head in this direction in the robot footprint frame.
bob_frequency google.protobuf.DoubleValue Bobs with this frequency such that each bob falls on this many slices. If negative, does not bob.
bounce google.protobuf.DoubleValue In the middle of the trajectory, add this much z height [m].

ClapParams

Parameters specific to clapping.

Field Type Description
direction bosdyn.api.Vec3Value Direction in a gravity-aligned body frame of clapping motion. A typical value for the location is (0, 1, 0).
location bosdyn.api.Vec3Value Location in body frame of the clap. A typical value for the location is (0.4, 0, -0.5).
speed google.protobuf.DoubleValue Speed of the clap [m/s].
clap_distance google.protobuf.DoubleValue How far apart the limbs are before clapping [m].

CrawlParams

Parameters for the robot’s crawling gait.

Field Type Description
swing_slices google.protobuf.DoubleValue The number of slices (beats/sub-beats) the duration of a leg swing in the crawl gait should be.
velocity bosdyn.api.Vec2Value The speed at which we should crawl [m/s]. X is forward. Y is left.

EulerRateZYXValue

Euler Angle rates (yaw->pitch->roll) vector that uses wrapped values so we can tell which elements are set.

Field Type Description
roll google.protobuf.DoubleValue
pitch google.protobuf.DoubleValue
yaw google.protobuf.DoubleValue

EulerZYXValue

Euler Angle (yaw->pitch->roll) vector that uses wrapped values so we can tell which elements are set.

Field Type Description
roll google.protobuf.DoubleValue
pitch google.protobuf.DoubleValue
yaw google.protobuf.DoubleValue

FrontUpParams

Parameters specific to FrontUp move.

Field Type Description
mirror google.protobuf.BoolValue Should we raise the hind feet instead.

GripperParams

Parameters for open/close of gripper.

Field Type Description
angle google.protobuf.DoubleValue Angle in radians at which the gripper is open. Note that a 0 radian angle correlates to completely closed.
speed google.protobuf.DoubleValue Speed in m/s at which the gripper should open/close to achieve the desired angle.

HopParams

Parameters specific to Hop move.

Field Type Description
velocity bosdyn.api.Vec2Value The velocity of the hop gait (X is forward; y is left)[m/s].
yaw_rate google.protobuf.DoubleValue How fast the hop gait should turn [rad/s].
stand_time google.protobuf.DoubleValue How long the robot should stand in between each hop.

JumpParams

Parameters for the robot making a jump.

Field Type Description
yaw google.protobuf.DoubleValue The amount in radians that the robot will turn while in the air.
flight_slices google.protobuf.DoubleValue The amount of time in slices (beats) that the robot will be in the air.
stance_width google.protobuf.DoubleValue The distance between the robot's left and right feet [m].
stance_length google.protobuf.DoubleValue The distance between the robot's front and back feet [m].
absolute google.protobuf.BoolValue Should we turn to a yaw in choreography sequence frame?
translation bosdyn.api.Vec2Value How far the robot should jump [m].
split_fraction google.protobuf.DoubleValue How much it should lo/td the first pair of lets ahead of the other pair. In fraction of flight time.
lead_leg_pair JumpParams.Lead

KneelCircleParams

Parameters specific to the kneel_circles move.

Field Type Description
location bosdyn.api.Vec3Value Location in body frame of the circle center. A typical value for the location is (0.4, 0, -0.5).
beats_per_circle google.protobuf.Int32Value How beats per circle. One or two are reasonable values.
number_of_circles google.protobuf.DoubleValue How many circles to perform. Mutually exclusive with beats_per_circle.
offset google.protobuf.DoubleValue How far apart the feet are when circling [m].
radius google.protobuf.DoubleValue Size of the circles [m].
reverse google.protobuf.BoolValue Which way to circle.

KneelLegMoveParams

Parameters specific to KneelLegMove move.

Field Type Description
hip_x google.protobuf.DoubleValue Joint angles of the left front leg in radians. If mirrored, the joints will be flipped for the other leg.
hip_y google.protobuf.DoubleValue
knee google.protobuf.DoubleValue
mirror google.protobuf.BoolValue If mirrored is true, the joints will be flipped for the leg on the other side (right vs left) of the body.
easing Easing The easing pattern for how the "slices" (beats/sub-beats) should be spaced.

Pace2StepParams

Parameters specific to pace translation.

Field Type Description
motion bosdyn.api.Vec2Value Where to move.
swing_height google.protobuf.DoubleValue Swing parameters to describe the footstep pattern during the pace translation gait. Note, a zero (or nearly zero) value will be considered as an unspecified parameter.
swing_velocity google.protobuf.DoubleValue
absolute google.protobuf.BoolValue Should the motion be relative to where the dance started (true) rather than relative to the current position (false).

RandomRotateParams

Parameters specific to the RandomRotate move.

Field Type Description
amplitude EulerZYXValue The amplitude [rad] of the rotation in each axis.
speed EulerRateZYXValue The speed [rad/s] of the motion in each axis.
speed_variation google.protobuf.DoubleValue The amount of variation allowed in the speed of the random rotations [m/s]. Note, this must be a positive value.
num_speed_tiers google.protobuf.Int32Value The specified speed values will be split into this many number of tiers between the bounds of [speed - speed_variation, speed + speed variation]. Then a tier (with a specified speed) will be randomly choosen and performed for each axis.
tier_variation google.protobuf.DoubleValue How much can the output speed vary from the choosen tiered speed.

RotateBodyParams

Parameters for the robot rotating the body.

Field Type Description
rotation EulerZYXValue The robot will rotate its body to the specified orientation (roll/pitch/yaw).
return_to_start_pose google.protobuf.BoolValue If true, the robot will transition back to the initial pose we started at before this choreography sequence move begin execution, and otherwise it will remain in whatever pose it is in after completing the choreography sequence move.

RunningManParams

Parameters specific to RunningMan move.

Field Type Description
velocity bosdyn.api.Vec2Value
swing_height google.protobuf.DoubleValue How high to pick up the forward-moving feet [m].
spread google.protobuf.DoubleValue How far to spread the contralateral pair of feet [m].
reverse google.protobuf.BoolValue Should we reverse the motion?
pre_move_cycles google.protobuf.Int32Value How many full running man cycles should the robot complete in place before starting to move with the desired velocity.

SideParams

Parameters for moves that can go to either side.

Field Type Description
side SideParams.Side

StepParams

Field Type Description
foot Leg Which foot to use (FL = 1, FR = 2, HL = 3, HR = 4).
offset bosdyn.api.Vec2Value Offset of the foot from it's nominal position, in meters.
second_foot Leg Should we use a second foot? (None = 0, FL = 1, FR = 2, HL = 3, HR = 4).
mirror google.protobuf.BoolValue Should we mirror the offset for the second foot? Ignored if second_foot is set to None
swing_waypoint bosdyn.api.Vec3Value Where should the swing foot go? This vector should be described in a gravity-aligned body frame relative to the centerpoint of the swing. If set to {0,0,0}, uses the default swing path.
swing_height google.protobuf.DoubleValue Parameter for altering the swing height [meters]. Will not have an effect if swing_waypoint is specified. As well, a zero (or nearly zero) value will be considered as an unspecified parameter.
liftoff_velocity google.protobuf.DoubleValue Parameter for altering the liftoff velocity [m/s]. Will not have an effect if swing_waypoint is specified. As well, a zero (or nearly zero) value will be considered as an unspecified parameter.
touchdown_velocity google.protobuf.DoubleValue Parameter for altering the touchdown velocity [m/s]. Will not have an effect if swing_waypoint is specified. As well, a zero (or nearly zero) value will be considered as an unspecified parameter.

SwayParams

Parameters specific to Sway move.

Field Type Description
vertical google.protobuf.DoubleValue How far to move up/down [m].
horizontal google.protobuf.DoubleValue How far to move left/right [m].
roll google.protobuf.DoubleValue How much to roll [rad].
pivot Pivot What point on the robot's body should the swaying be centered at. For example, should the head move instead of the butt?
style SwayParams.SwayStyle What style motion should we use?
pronounced google.protobuf.DoubleValue How pronounced should the sway-style be? The value is on a scale from [0,1.0].
hold_zero_axes google.protobuf.BoolValue Should the robot hold previous values for the vertical, horizontal, and roll axes if the value is left unspecified (value of zero).

TurnParams

Parameters specific to turning.

Field Type Description
yaw google.protobuf.DoubleValue How far to turn, described in radians with a positive value representing a turn to the left.
absolute google.protobuf.BoolValue Should we turn to a yaw in choreography sequence frame?
swing_height google.protobuf.DoubleValue Swing parameters to describe the footstep pattern during the turning [height in meters]. Note, a zero (or nearly zero) value will be considered as an unspecified parameter.
swing_velocity google.protobuf.DoubleValue Swing parameter to describe the foot's swing velocity during the turning [m/s]. Note, a zero (or nearly zero) value will be considered as an unspecified parameter.

TwerkParams

Parameters specific to twerking

Field Type Description
height google.protobuf.DoubleValue How far the robot should twerk in meters.

Easing

Enum to describe the type of easing to perform for the slices at either (or both) the beginning and end of a move.

Name Number Description
EASING_UNKNOWN 0
EASING_LINEAR 1
EASING_QUADRATIC_INPUT 2
EASING_QUADRATIC_OUTPUT 3
EASING_QUADRATIC_IN_OUT 4
EASING_CUBIC_INPUT 5
EASING_CUBIC_OUTPUT 6
EASING_CUBIC_IN_OUT 7
EASING_EXPONENTIAL_INPUT 8
EASING_EXPONENTIAL_OUTPUT 9
EASING_EXPONENTIAL_IN_OUT 10

JumpParams.Lead

If split_fraction is non-zero, which legs to lift first.

Name Number Description
LEAD_UNKNOWN 0
LEAD_AUTO 1
LEAD_FRONT 2
LEAD_HIND 3
LEAD_LEFT 4
LEAD_RIGHT 5

Leg

Enum to describe which leg is being referenced in specific choreography sequence moves.

Name Number Description
LEG_UNKNOWN 0
LEG_FRONT_LEFT 1
LEG_FRONT_RIGHT 2
LEG_HIND_LEFT 3
LEG_HIND_RIGHT 4
LEG_NO_LEG -1

Pivot

Enum for the pivot point for certain choreography sequence moves.

Name Number Description
PIVOT_UNKNOWN 0
PIVOT_FRONT 1
PIVOT_HIND 2
PIVOT_CENTER 3

SideParams.Side

Name Number Description
SIDE_UNKNOWN 0
SIDE_LEFT 1
SIDE_RIGHT 2

SwayParams.SwayStyle

The type of motion used by the Sway sequence move.

Name Number Description
SWAY_STYLE_UNKNOWN 0
SWAY_STYLE_STANDARD 1
SWAY_STYLE_FAST_OUT 2
SWAY_STYLE_FAST_RETURN 3
SWAY_STYLE_SQUARE 4
SWAY_STYLE_SPIKE 5
SWAY_STYLE_PLATEAU 6

spot/choreography_sequence.proto

ChoreographerDisplayInfo

Information for the Choreographer to display.

Field Type Description
color ChoreographerDisplayInfo.Color
markers int32 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.
description string Textual description to be displayed in the GUI.
image string Image path (local to the UI) to display as an icon. May be an animated gif.
category ChoreographerDisplayInfo.Category

ChoreographerDisplayInfo.Color

Color of the object. Set it to override the default category color.

Field Type Description
r int32 RGB values for color ranging from [0,255].
g int32
b int32
a double Alpha value for the coloration ranges from [0,1].

ChoreographerSave

Describes the metadata and information only used by the Choreographer GUI, which isn’t used in the API

Field Type Description
choreography_sequence ChoreographySequence The main ChoreographySequence that makes up the dance and is sent to the robot.
music_file string If specified this is the UI local path of the music to load.
music_start_slice double UI specific member that describes exactly when the music should start, in slices. This is for time sync issues.

ChoreographySequence

Represents a particular choreography sequence, made up of MoveParams.

Field Type Description
name string Display name or file name associated with the choreography sequence.
slices_per_minute double Number of slices per minute in the choreography sequence. Typically a slice will correspond to 1/4 a beat.
moves MoveParams All of the moves in this choreography sequence.

ExecuteChoreographyRequest

Field Type Description
header bosdyn.api.RequestHeader Common request header
choreography_sequence_name string The string name of the ChoreographySequence to use.
start_time google.protobuf.Timestamp 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.
choreography_starting_slice double The slice (betas/sub-beats) that the choreography should begin excution at.
lease bosdyn.api.Lease The Lease to show ownership of the robot body.

ExecuteChoreographyResponse

Field Type Description
header bosdyn.api.ResponseHeader Common response header
lease_use_result bosdyn.api.LeaseUseResult
status ExecuteChoreographyResponse.Status

ListAllMovesRequest

Request a list of all possible moves and the associated parameters (min/max values).

Field Type Description
header bosdyn.api.RequestHeader Common request header

ListAllMovesResponse

Response for ListAllMoves that defines the list of available moves and their parameter types.

Field Type Description
header bosdyn.api.ResponseHeader Common response header
moves MoveInfo List of moves that the robot knows about
move_param_config string A copy of the MoveParamsConfig.txt that the robot is using.

MoveInfo

Defines properties of a choreography move.

Field Type Description
name string Unique ID of the move type.
move_length_slices int32 The number of "slices" (beats or sub-beats) that this move takes up.
is_extendable bool If true, the user can extend the move beyond the requested length.
entrance_states MoveInfo.TransitionState The admissible states the robot can be in currently for this move to execute.
exit_state MoveInfo.TransitionState The state of the robot after the move is complete.
min_time double The absolute minimum and maximum times of the move in seconds.
max_time double
controls_arm bool Indicators as to which parts of the robot that the move controls.
controls_legs bool
controls_body bool
display ChoreographerDisplayInfo Information for the GUI tool to visualize the sequence move info.

MoveParams

Defines varying parameters for a particular instance of a move.

Field Type Description
type string Unique ID of the move type that these params are associated with.
start_slice int32 How many slices since the start of the song this move should be executed at.
requested_slices int32 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.
jump_params JumpParams
rotate_body_params RotateBodyParams
step_params StepParams
butt_circle_params ButtCircleParams
turn_params TurnParams
pace_2step_params Pace2StepParams
twerk_params TwerkParams
chicken_head_params ChickenHeadParams
clap_params ClapParams
front_up_params FrontUpParams
sway_params SwayParams
body_hold_params BodyHoldParams
arm_move_params ArmMoveParams
kneel_leg_move_params KneelLegMoveParams
running_man_params RunningManParams
kneel_circle_params KneelCircleParams
gripper_params GripperParams
hop_params HopParams
random_rotate_params RandomRotateParams
crawl_params CrawlParams
side_params SideParams

UploadChoreographyRequest

Field Type Description
header bosdyn.api.RequestHeader Common request header
choreography_sequence ChoreographySequence ChoreographySequence to upload and store in memory
non_strict_parsing bool Should we run a script that has correctable errors? If true, the service will fix any correctable errors and run the corrected choreography script. If false, the service will reject a choreography script that has any errors.

UploadChoreographyResponse

Field Type Description
header bosdyn.api.ResponseHeader 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.
warnings string 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.

ChoreographerDisplayInfo.Category

Move Category affects the grouping in the choreographer list view, as well as the color it’s displayed with.

Name Number Description
CATEGORY_UNKNOWN 0
CATEGORY_BODY 1
CATEGORY_STEP 2
CATEGORY_DYNAMIC 3
CATEGORY_TRANSITION 4
CATEGORY_KNEEL 5
CATEGORY_ARM 6

ExecuteChoreographyResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_INVALID_UPLOADED_CHOREOGRAPHY 2
STATUS_ROBOT_COMMAND_ISSUES 3
STATUS_LEASE_ERROR 4

MoveInfo.TransitionState

The state that the robot is in at the start or end of a move.

Name Number Description
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.

spot/choreography_service.proto

ChoreographyService

Method Name Request Type Response Type Description
ListAllMoves ListAllMovesRequest ListAllMovesResponse List the available dance moves and their parameter information.
UploadChoreography UploadChoreographyRequest UploadChoreographyResponse Upload a dance to the robot.
ExecuteChoreography ExecuteChoreographyRequest ExecuteChoreographyResponse Execute the uploaded dance.

Standard Types

.proto Type Notes C++ Java Python Go C# PHP Ruby
double double double float float64 double float Float
float float float float float32 float float Float
int32 Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint32 instead. int32 int int int32 int integer Bignum or Fixnum (as required)
int64 Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint64 instead. int64 long int/long int64 long integer/string Bignum
uint32 Uses variable-length encoding. uint32 int int/long uint32 uint integer Bignum or Fixnum (as required)
uint64 Uses variable-length encoding. uint64 long int/long uint64 ulong integer/string Bignum or Fixnum (as required)
sint32 Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int32s. int32 int int int32 int integer Bignum or Fixnum (as required)
sint64 Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int64s. int64 long int/long int64 long integer/string Bignum
fixed32 Always four bytes. More efficient than uint32 if values are often greater than 2^28. uint32 int int uint32 uint integer Bignum or Fixnum (as required)
fixed64 Always eight bytes. More efficient than uint64 if values are often greater than 2^56. uint64 long int/long uint64 ulong integer/string Bignum
sfixed32 Always four bytes. int32 int int int32 int integer Bignum or Fixnum (as required)
sfixed64 Always eight bytes. int64 long int/long int64 long integer/string Bignum
bool bool boolean boolean bool bool boolean TrueClass/FalseClass
string A string must always contain UTF-8 encoded or 7-bit ASCII text. string String str/unicode string string string String (UTF-8)
bytes May contain any arbitrary sequence of bytes. string ByteString str []byte ByteString string String (ASCII-8BIT)