Choreography¶
For clients to use the choreography service
-
class
bosdyn.choreography.client.choreography.
ChoreographyClient
[source]¶ Bases:
bosdyn.client.common.BaseClient
Client for Choreography Service.
-
default_service_name
= 'choreography'¶
-
license_name
= 'choreography'¶
-
service_type
= 'bosdyn.api.spot.ChoreographyService'¶
-
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.
-
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().
-
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.
-
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().
-
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.
-
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.
-
-
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::'¶
-
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:
bosdyn.client.exceptions.ResponseError
The uploaded choreography is invalid and unable to be performed.
-
exception
bosdyn.choreography.client.choreography.
RobotCommandIssuesError
(response, error_message=None)[source]¶ Bases:
bosdyn.client.exceptions.ResponseError
A problem occurred when issuing the robot command containing the dance.
-
exception
bosdyn.choreography.client.choreography.
LeaseError
(response, error_message=None)[source]¶ Bases:
bosdyn.client.exceptions.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:
bosdyn.client.exceptions.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:
bosdyn.client.exceptions.ResponseError
The choreography service has no logged robot state data.
-
exception
bosdyn.choreography.client.choreography.
UnknownRecordingSessionId
(response, error_message=None)[source]¶ Bases:
bosdyn.client.exceptions.ResponseError
The recording request contains an unknown recording session ID.
-
exception
bosdyn.choreography.client.choreography.
RecordingBufferFull
(response, error_message=None)[source]¶ Bases:
bosdyn.client.exceptions.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:
bosdyn.client.exceptions.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.