// Copyright (c) 2022 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;

    // List of choreography sequences the robot knows about.
    repeated string known_sequences = 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.
        STATUS_ANIMATION_VALIDATION_FAILED = 2; // The animated move is considered invalid, see the warnings.
    }
    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 excution 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 status = 3;
}

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;

    // 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;


        AnimateParams animate_params = 1000;
    }
}

// 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;
    bool controls_annotations = 18;

    // 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 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;
}

// 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 whithin 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;

    // Time everything exactly as animated, even at the expense of balance.
    // By default, the optimizer may adjust timing slightly.
    bool precise_timing = 18;

    // 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;
}

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;
}

// Descprition 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;
}
