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

option java_outer_classname = "RobotCommandProto";

import "bosdyn/api/full_body_command.proto";
import "bosdyn/api/header.proto";
import "bosdyn/api/lease.proto";
import "bosdyn/api/mobility_command.proto";
import "bosdyn/api/synchronized_command.proto";

// A command for a robot to execute.
// The server decides if a set of commands is valid for a given robot and configuration.
message RobotCommand {
    oneof command {
        // Commands which require control of entire robot.
        FullBodyCommand.Request full_body_command = 1;

        // A synchronized command, for partial or full control of robot.
        SynchronizedCommand.Request synchronized_command = 3;

        // *** Deprecation Warning ***
        // DEPRECATED as of 2.1.0: A mobility command for a robot to execute.
        // The following fields will be deprecated and moved to 'reserved' in a future release.
        MobilityCommand.Request mobility_command = 2 [deprecated=true];
    }
}

// Command specific feedback. Distance to goal, estimated time remaining, probability of
// success, etc. Note that the feedback should directly mirror the command request.
message RobotCommandFeedback {
    oneof command {
        // Commands which require control of entire robot.
        FullBodyCommand.Feedback full_body_feedback = 2;

        // A synchronized command, for partial or full control of robot.
        SynchronizedCommand.Feedback synchronized_feedback = 3;

        // *** Deprecation Warning ***
        // DEPRECATED as of 2.1.0: Command to control mobility system of a robot.
        // The following fields will be deprecated and moved to 'reserved' in a future release.
        MobilityCommand.Feedback mobility_feedback = 1 [deprecated=true];
    }
}



// A RobotCommand request message includes the lease and command as well as a clock
// identifier to ensure timesync when issuing commands with a fixed length.
message RobotCommandRequest {
    // Common request header.
    RequestHeader header = 1;

    // The Lease to show ownership of the robot.
    Lease lease = 2;

    // A command for a robot to execute. A command can be comprised of several subcommands.
    RobotCommand command = 3;

    // Identifier provided by the time sync service to verify time sync between robot and client.
    string clock_identifier = 4;
}

// The RobotCommand response message contains a robot command id that can be used to poll the
// robot command service for feedback on the state of the command.
message RobotCommandResponse {
    // Common response header.
    ResponseHeader header = 1;

    // Details about how the lease was used.
    LeaseUseResult lease_use_result = 2;

    enum Status {
        STATUS_UNKNOWN = 0;          // An unknown / unexpected error occurred.
        STATUS_OK = 1;               // Request was accepted.

        STATUS_INVALID_REQUEST = 2;  // [Programming Error] Request was invalid / malformed in some way.
        STATUS_UNSUPPORTED = 3;      // [Programming Error] The robot does not understand this command.

        STATUS_NO_TIMESYNC = 4;      // [Timesync Error] Client has not done timesync with robot.
        STATUS_EXPIRED = 5;          // [Timesync Error] The command was received after its end_time had already passed.
        STATUS_TOO_DISTANT = 6;      // [Timesync Error] The command end time was too far in the future.

        STATUS_NOT_POWERED_ON = 7;   // [Hardware Error] The robot must be powered on to accept a command.
        STATUS_BEHAVIOR_FAULT = 9;   // [Robot State Error] The robot must not have behavior faults.
        STATUS_DOCKED = 10;          // [Robot State Error] The robot cannot be docked for certain commands.

        STATUS_UNKNOWN_FRAME = 8;    // [Frame Error] The frame_name for a command was not a known frame.
    }
    // Return status for a request.
    Status status = 3;

    // Human-readable error description.  Not for programmatic analysis.
    string message = 4;

    // Unique identifier for the command, If empty, command was not accepted.
    uint32 robot_command_id = 5;
}

// The RobotCommandFeedback request message, which can get the feedback for a specific
// robot command id number.
message RobotCommandFeedbackRequest {
    // Common request header.
    RequestHeader header = 1;

    // Unique identifier for the command, provided by StartRequest.
    uint32 robot_command_id = 2;
}

// The RobotCommandFeedback response message, which contains the progress of the robot command.
message RobotCommandFeedbackResponse {
    // Common response header.
    ResponseHeader header = 1;

    // Details about how the lease was used.
    LeaseUseResult lease_use_result = 5;

    enum Status {
        // Status enum is DEPRECATED as of 2.1.0. Behavior execution is in an unknown / unexpected state.
        STATUS_UNKNOWN = 0;

        // Status enum is DEPRECATED as of 2.1.0. The robot is actively working on the command
        STATUS_PROCESSING = 1;

        // Status enum is DEPRECATED as of 2.1.0. The command was replaced by a new command
        STATUS_COMMAND_OVERRIDDEN = 2;

        // Status enum is DEPRECATED as of 2.1.0. The command expired
        STATUS_COMMAND_TIMED_OUT = 3;

        // Status enum is DEPRECATED as of 2.1.0. The robot is in an unsafe state, and will only respond to known safe commands.
        STATUS_ROBOT_FROZEN = 4;
    }
    // DEPRECATED as of 2.1.0: General status whether or not command is still processing.
    Status status = 2 [deprecated=true];

    // DEPRECATED as of 2.1.0: Human-readable status message.  Not for programmatic analysis.
    string message = 3 [deprecated=true];

    // Command specific feedback.
    RobotCommandFeedback feedback = 4;
}

// A ClearBehaviorFault request message has the associated behavior fault id to be cleared.
message ClearBehaviorFaultRequest {
    // Common request header.
    RequestHeader header = 1;

    // The Lease to show ownership of the robot.
    Lease lease = 2;

    // Unique identifier for the error
    uint32 behavior_fault_id = 3;
}

// A ClearBehaviorFault response message has status indicating whether the service cleared
// the fault or not.
message ClearBehaviorFaultResponse {
    // Common response header.
    ResponseHeader header = 1;

    // Details about how the lease was used.
    LeaseUseResult lease_use_result = 2;

    enum Status {
        // An unknown / unexpected error occurred.
        STATUS_UNKNOWN = 0;

        // The BehaviorFault has been cleared.
        STATUS_CLEARED = 1;

        // The BehaviorFault could not be cleared.
        STATUS_NOT_CLEARED = 2;
    }
    // Return status for a request.
    Status status = 3;
}

