Choreography

For clients to use the choreography service

class bosdyn.choreography.client.choreography.ChoreographyClient[source]

Bases: BaseClient

Client for Choreography Service.

default_service_name = 'choreography'
license_name = 'choreography'
service_type = 'bosdyn.api.spot.ChoreographyService'
update_from(other)[source]

Adopt key objects like processors, logger, and wallet from other.

property timesync_endpoint

Accessor for timesync-endpoint that was grabbed via ‘update_from()’.

list_all_moves(**kwargs)[source]

Get a list of the different choreography sequence moves and associated parameters.

list_all_moves_async(object_type=None, time_start_point=None, **kwargs)[source]

Async version of list_all_moves().

list_all_sequences(**kwargs)[source]

Get a list of all sequences currently known about by the robot.

list_all_sequences_async(**kwargs)[source]

Async version of list_all_sequences().

upload_choreography(choreography_seq, non_strict_parsing=True, **kwargs)[source]

Upload the choreography sequence to the robot.

Parameters:
  • choreography_seq (choreography_sequence_pb2.ChoreographySequence proto) – The dance sequence to be sent and stored on the robot.

  • non_strict_parsing (boolean) – If true, the robot will fix any correctable errors within the choreography and allow users to run the dance. If false, if there are errors the robot will reject the choreography when attempting to run the dance.

Returns:

The UploadChoreographyResponse message, which includes any warnings generated from the validation process for the choreography. If non_strict_parsing=False and there are warnings, then the dance will not be able to run.

upload_choreography_async(choreography_seq, non_strict_parsing=True, **kwargs)[source]

Async version of upload_choreography().

upload_animated_move(animation, generated_id='', **kwargs)[source]

Upload the animation proto to the robot to be used as a move in choreography sequences.

Parameters:
  • animation (choreography_sequence_pb2.Animation) – The animated move protobuf message. This can be generated by converting a cha file using the animation_file_to_proto helpers.

  • generated_id (string) – The ID hash generated for the animation based on the serialization of the protobuf message. This can be left empty, and the robot will re-parse and validate the message. This will be filled out automatically when using the AnimationUploadHelper.

Returns:

The UploadAnimatedMoveResponse message, which includes warnings if the uploaded animation was invalid.

upload_animated_move_async(animation, generated_id='', **kwargs)[source]

Async version of upload_animated_move().

get_choreography_status(**kwargs)[source]

Get the dance related status information for a robot and the local time for which it was valid.

get_choreography_status_async(**kwargs)[source]

Async version of get_choreography_status.

choreography_log_to_animation_file(name, fpath, has_arm, *args)[source]

Turn the choreography log from the proto into an animation cha file type.

Parameters:
  • name (string) – Name that the cha file will be saved as.

  • fpath (string) – Location where the new cha file will be saved.

  • has_arm (boolean) – True if the robot has an arm, False if the robot doesn’t have an arm. When False arm motion won’t be added to the cha file.

  • *args (string(s) or list) – String(s), list of strings, or a mix of string(s) and list(s) that are the options to be included in the cha file. (ex. ‘truncatable’)

Returns:

The filename of the new animation cha file for the most recent choreography log.

choreography_time_adjust(override_client_start_time, time_difference=None, validity_time=None, **kwargs)[source]

Provide a time to execute the choreography sequence instead the value passed in by execute_choreography. Useful for when multiple robots are performing a synced performance, and all robots should begin dancing at the same time.

Parameters:
  • override_client_start_time (float) – The time (in seconds) that the dance should start. This time should be provided in the local clock’s timeframe and the client will convert it to the required robot’s clock timeframe.

  • time_difference (float) – The acceptable time difference in seconds between an ExecuteChoreographyRequest start time and the override time where the override_client_start_time will be used instead of the start time specified by the ExecuteChoreographyRequest. If not set will default to 20s. Maximum time_difference is 2 minutes.

  • validity_time (float) – How far in the future, in seconds from the current time, can the override_client_start_time be. If not set will default to 60s. Maximum validity_time is 5 minutes.

choreography_time_adjust_async(override_client_start_time, time_difference=None, validity_time=None, **kwargs)[source]

Async version of choreography_time_adjust()

execute_choreography(choreography_name, client_start_time, choreography_starting_slice, lease=None, **kwargs)[source]

Execute the current choreography sequence loaded on the robot by name.

Parameters:
  • choreography_name (string) – The name of the uploaded choreography to run. The robot only stores a single choreography at a time, so this name should match the last uploaded choreography.

  • client_start_time (float) – The time (in seconds) that the dance should start. This time should be provided in the local clock’s timeframe and the client will convert it to the required robot’s clock timeframe.

  • choreography_starting_slice (int) – Which slice to start the dance at when the start time is reached. By default, it will start with the first slice.

  • lease (lease_pb2.Lease protobuf) – A specific lease to use for the request. If nothing is provided, the client will append the next lease sequence in this field by default.

Returns:

The full ExecuteChoreographyResponse message.

execute_choreography_async(choreography_name, client_start_time, choreography_starting_slice, lease=None, **kwargs)[source]

Async version of execute_choreography().

choreography_command(command_list, client_end_time, lease=None, **kwargs)[source]

Sends commands to interact with individual choreography moves.

Parameters:
  • command_list (list of choreography_sequence_pb2.MoveCommand protobuf) – The commands. Each command interacts with a single individual move.

  • client_end_time (float) – The time (in seconds) that the command stops being valid. This time should be provided in the local clock’s timeframe and the client will convert it to the required robot’s clock timeframe.

  • lease (lease_pb2.Lease protobuf) – A specific lease to use for the request. If nothing is provided, the client will append the next lease sequence in this field by default.

Returns:

The full ChoreographyCommandResponse message.

choreography_command_async(command_list, client_end_time, lease=None, **kwargs)[source]

Async version of choreography_command().

start_recording_state(duration_secs, continue_session_id=0, **kwargs)[source]

Start (or continue) a manually recorded robot state log.

Parameters:
  • duration_secs (float) – The duration of the recording request in seconds. This will apply from when the StartRecording rpc is received.

  • continue_session_id (int) – If provided, the RPC will continue the recording session associated with that ID.

Returns:

The full StartRecordingStateResponse proto.

start_recording_state_async(duration_secs, continue_session_id=0, **kwargs)[source]

Async version of start_recording_state().

stop_recording_state(**kwargs)[source]

Stop recording a manual choreography log.

Returns:

The full StopRecordingStateResponse proto.

stop_recording_state_async(**kwargs)[source]

Async version of stop_recording_state().

get_choreography_sequence(seq_name, **kwargs)[source]
Get a sequence currently known by the robot, response includes

the full ChoreographySequence with the given name and any Animations used in the sequence.

Args:

seq_name (string): the name of the sequence to return.

Returns:

The full GetChoreographySequenceResponse proto.

get_choreography_sequence_async(seq_name, **kwargs)[source]

Async version of get_choreography_sequence().

save_sequence(seq_name, labels=[], **kwargs)[source]

Save an uploaded sequence to the robot. Saved sequences are automatically uploaded to the robot when it boots.

Returns:

The full SaveSequenceResponse proto.

save_sequence_async(seq_name, labels=[], **kwargs)[source]

Async version of save_sequence().

delete_sequence(seq_name, **kwargs)[source]

Delete a sequence from temporary robot memory and delete any copies of the sequence saved to disk.

Returns:

The full DeleteSequenceResponse proto.

delete_sequence_async(seq_name, **kwargs)[source]

Async version of delete_sequence().

modify_choreography_info(seq_name, add_labels=[], remove_labels=[], **kwargs)[source]

Modifies a sequence’s ChoreographyInfo field to remove or add any labels attached to the sequence.

Returns:

The full ModifyChoreographyInfoResponse proto.

modify_choreography_info_async(seq_name, add_labels=[], remove_labels=[], **kwargs)[source]

Async version of modify_choreography_info().

clear_all_sequence_files(**kwargs)[source]

Completely clears all choreography files that are saved on the robot, including animation proto files.

Returns:

The full ClearAllSequenceFilesResponse proto.

clear_all_sequence_files_async(**kwargs)[source]

Async version of clear_all_sequence_files().

static build_start_recording_state_request(duration_seconds=None, continue_session_id=0)[source]

Generate a StartRecordingStateRequest proto.

Parameters:
  • duration_seconds (float) – The duration of the recording request in seconds. This will apply from when the StartRecording rpc is received.

  • continue_session_id (int) – If provided, the RPC will continue the recording session associated with that ID.

Returns:

The full StartRecordingStateRequest proto with fields populated based on the input arguments.

download_robot_state_log(log_type, **kwargs)[source]

Download the manual or automatically collected logs for choreography robot state.

Parameters:

log_type (choreography_sequence_pb2.LogType) – Type of log, either manual or the automatically generated log for the latest choreography.

Returns:

A tuple containing the response status (choreography_sequence_pb2.DownloadRobotStateLogResponse.Status) and the choreography_sequence_pb2.ChoreographyStateLog constructed from the streaming response message.

build_choreography_time_adjust_request(override_client_start_time, time_difference, validity_time)[source]

Generate the ChoreographyTimeAdjustRequest rpc with the timestamp converted into robot time.

build_execute_choreography_request(choreography_name, client_start_time, choreography_starting_slice, lease=None)[source]

Generate the ExecuteChoreographyRequest rpc with the timestamp converted into robot time.

build_choreography_command_request(command_list, client_end_time, lease=None)[source]
build_save_sequence_request(sequence_name, labels=[])[source]
build_modify_choreography_info_request(sequence_name, add_labels=[], remove_labels=[])[source]
class bosdyn.choreography.client.choreography.AnimationUploadHelper(robot)[source]

Bases: object

Helper class to reduce re-uploading animations to a robot multiple times.

This class will generate a hash (unique ID built from the animation protobuf message’s contents) for each animation proto, and include this hash when initially uploading animations. It will track the animations sent to the robot and the hashes, and only sends RPCs to upload an animation when the incoming animation proto is different from the one on robot.

It initializes the set of known animations on robot already by using the ListAllMoves RPC and reading the existing animation names and hashes.

The hash function is generated using a library which guarantees consistency, even when restarting the program. As well, the hash is built from the serialized protobuf, and proto guarantees that within the language that the serialized message will be consistent.

Parameters:

robot (Robot sdk instance) – The robot to upload animations to.

ANIMATION_MOVE_PREFIX = 'animation::'
initialize()[source]

Determine which animations are already uploaded on robot.

upload_animated_move(animation, **kwargs)[source]

Uploads the animation to robot if the animation protobuf has changed.

This will only send an UploadAnimatedMove RPC if the incoming animation has a new hash that differs from the current hash for this animation on robot, which indicates that the animation protobuf has changed since the last one uploaded to robot.

Parameters:

animation (choreography_sequence_pb2.Animation) – Animation to maybe upload.

Returns:

The UploadAnimateMoveResponse protobuf message if the animation is actually sent. If the animation protobuf has not changed and is not sent to the robot, then this function returns None.

generate_animation_id(animation_proto)[source]

Serialize an Animation protobuf message and create a hash from the binary string.

NOTE: Protobuf’s serialization will not be consistent across protobuf versions or even just different languages serializing the same protobuf message. This means that for a single protobuf message, there could be multiple different serializations. This is ok for the use-case of the AnimationUploadHelper since the ids are only used for a specific “session” of Choreographer and the robot’s boot session. These are not meant to be the same for forever and ever due to the potential inconsistencies mentioned, and should not be used with that expectation.

Further, if a single animation proto does not generate the same ID for one “session”, then it will just be re-uploaded and processed by the robot again.

Parameters:

animation_proto (choreography_sequence_pb2.Animation) – Animation to generate a hash for.

Returns:

A string representing a unique hash built from the animation proto.

exception bosdyn.choreography.client.choreography.InvalidUploadedChoreographyError(response, error_message=None)[source]

Bases: ResponseError

The uploaded choreography is invalid and unable to be performed.

exception bosdyn.choreography.client.choreography.RobotCommandIssuesError(response, error_message=None)[source]

Bases: ResponseError

A problem occurred when issuing the robot command containing the dance.

exception bosdyn.choreography.client.choreography.LeaseError(response, error_message=None)[source]

Bases: ResponseError

Incorrect or invalid leases for data acquisition. Check the lease use results.

exception bosdyn.choreography.client.choreography.AnimationValidationFailedError(response, error_message=None)[source]

Bases: ResponseError

The uploaded animation file is invalid and cannot be used in choreography sequences.

exception bosdyn.choreography.client.choreography.NoRecordedInformation(response, error_message=None)[source]

Bases: ResponseError

The choreography service has no logged robot state data.

exception bosdyn.choreography.client.choreography.UnknownRecordingSessionId(response, error_message=None)[source]

Bases: ResponseError

The recording request contains an unknown recording session ID.

exception bosdyn.choreography.client.choreography.RecordingBufferFull(response, error_message=None)[source]

Bases: ResponseError

The recording buffer is full and the current manual log will be truncated.

exception bosdyn.choreography.client.choreography.IncompleteData(response, error_message=None)[source]

Bases: ResponseError

The recording buffer filled up, the returned log will be truncated.

bosdyn.choreography.client.choreography.load_choreography_sequence_from_binary_file(file_path)[source]

Read a choreography sequence file into a protobuf ChoreographySequence message.

bosdyn.choreography.client.choreography.load_choreography_sequence_from_txt_file(file_path)[source]
bosdyn.choreography.client.choreography.save_choreography_sequence_to_file(file_path, file_name, choreography)[source]

Saves a choreography sequence to a file.