spot-sdk-ts
Version:
TypeScript bindings based on protobufs (proto3) provided by Boston Dynamics
1,312 lines (1,244 loc) • 128 kB
text/typescript
/* eslint-disable */
import {
RobotCommandFeedbackStatus_Status,
ArmDragCommand_Request,
ArmDragCommand_Feedback,
robotCommandFeedbackStatus_StatusFromJSON,
robotCommandFeedbackStatus_StatusToJSON,
} from "./basic_command";
import { Timestamp } from "../../google/protobuf/timestamp";
import { CylindricalCoordinate, Vec3, SE3Pose } from "./geometry";
import { SE3Trajectory, WrenchTrajectory, Vec3Trajectory } from "./trajectory";
import { Duration } from "../../google/protobuf/duration";
import _m0 from "protobufjs/minimal";
import { BoolValue, DoubleValue } from "../../google/protobuf/wrappers";
export const protobufPackage = "bosdyn.api";
/**
* The synchronized command message for commanding the arm to move.
* A synchronized commands is one of the possible robot command messages for controlling the robot.
*/
export interface ArmCommand {}
/** The arm request must be one of the basic command primitives. */
export interface ArmCommand_Request {
/** Control the end-effector in Cartesian space. */
armCartesianCommand: ArmCartesianCommand_Request | undefined;
/** Control joint angles of the arm. */
armJointMoveCommand: ArmJointMoveCommand_Request | undefined;
/** Move the arm to some predefined configurations. */
namedArmPositionCommand: NamedArmPositionsCommand_Request | undefined;
/** Velocity control of the end-effector. */
armVelocityCommand: ArmVelocityCommand_Request | undefined;
/** Point the gripper at a point in the world. */
armGazeCommand: GazeCommand_Request | undefined;
/** Stop the arm in place with minimal motion. */
armStopCommand: ArmStopCommand_Request | undefined;
/** Use the arm to drag something held in the gripper. */
armDragCommand: ArmDragCommand_Request | undefined;
/** Any arm parameters to send, common across all arm commands */
params: ArmParams | undefined;
}
/**
* The feedback for the arm command that will provide information on the progress
* of the command.
*/
export interface ArmCommand_Feedback {
/** Feedback for the end-effector Cartesian command. */
armCartesianFeedback: ArmCartesianCommand_Feedback | undefined;
/** Feedback for the joint move command. */
armJointMoveFeedback: ArmJointMoveCommand_Feedback | undefined;
/** Feedback for the named position move command. */
namedArmPositionFeedback: NamedArmPositionsCommand_Feedback | undefined;
armVelocityFeedback: ArmVelocityCommand_Feedback | undefined;
/** Feedback for the gaze command. */
armGazeFeedback: GazeCommand_Feedback | undefined;
armStopFeedback: ArmStopCommand_Feedback | undefined;
/** Feedback for the drag command. */
armDragFeedback: ArmDragCommand_Feedback | undefined;
status: RobotCommandFeedbackStatus_Status;
}
/** Parameters common across arm commands. */
export interface ArmParams {
/**
* / Whether or not to disable the body force limiter running on the robot. By default, this is
* / on, and the chance that the body falls over because the arm makes contact in the world is
* / low. If this is purposely disabled (by setting disable_body_force_limiter to True), the arm
* / may be able to accelerate faster, and apply more force to the world and to objects than usual,
* / but there is also added risk of the robot falling over.
*/
disableBodyForceLimiter: boolean | undefined;
}
/**
* When controlling the arm with a joystick, because of latency it can often be better to send
* velocity commands rather than position commands. Both linear and angular velocity can be
* specified. The linear velocity can be specified in a cylindrical frame around the shoulder or
* with a specified frame.
*/
export interface ArmVelocityCommand {}
export interface ArmVelocityCommand_CylindricalVelocity {
/**
* / The linear velocities for the end-effector are specified in unitless cylindrical
* / coordinates. The origin of the cylindrical coordinate system is the base of the arm
* / (shoulder). The Z-axis is aligned with gravity, and the X-axis is the unit vector from
* / the shoulder to the hand-point. This construction allows for 'Z'-axis velocities to
* / raise/lower the hand, 'R'-axis velocities will cause the hand to move towards/away from
* / the shoulder, and 'theta'-axis velocities will cause the hand to travel
* / clockwise/counter-clockwise around the shoulder. Lastly, the command is unitless, with
* / values for each axis specified in the range [-1, 1]. A value of 0 denotes no velocity
* / and values of +/- 1 denote maximum velocity (see max_linear_velocity).
*/
linearVelocity: CylindricalCoordinate | undefined;
/**
* / The maximum velocity in meters / second for the hand.
* / If unset and default value of 0 received, will set max_linear_velocity to 0.5 m/s.
*/
maxLinearVelocity: number | undefined;
}
export interface ArmVelocityCommand_CartesianVelocity {
/** The frame to express our velocities in */
frameName: string;
/** The x-y-z velocity of the hand (m/s) with respect to the frame */
velocityInFrameName: Vec3 | undefined;
}
export interface ArmVelocityCommand_Request {
cylindricalVelocity: ArmVelocityCommand_CylindricalVelocity | undefined;
cartesianVelocity: ArmVelocityCommand_CartesianVelocity | undefined;
/**
* The angular velocity of the hand frame measured with respect to the odom frame, expressed
* in the hand frame. A 'X' rate will cause the hand to rotate about its x-axis, e.g. the
* final wrist twist joint will rotate. And similarly, 'Y' and 'Z' rates will cause the hand
* to rotate about its y and z axis respectively. \
* The units should be rad/sec.
*/
angularVelocityOfHandRtOdomInHand: Vec3 | undefined;
/** Optional maximum acceleration magnitude of the end-effector. (m/s^2) */
maximumAcceleration: number | undefined;
/**
* The timestamp (in robot time) by which a command must finish executing.
* This is a required field and used to prevent runaway commands.
*/
endTime: Date | undefined;
}
/** ArmVelocityCommand provides no feedback */
export interface ArmVelocityCommand_Feedback {}
/** Command the arm move to a predefined configuration. */
export interface NamedArmPositionsCommand {}
export enum NamedArmPositionsCommand_Positions {
/** POSITIONS_UNKNOWN - Invalid request; do not use. */
POSITIONS_UNKNOWN = 0,
/**
* POSITIONS_CARRY - The carry position is a damped, force limited position close to stow, with the hand
* slightly in front of the robot.
*/
POSITIONS_CARRY = 1,
/**
* POSITIONS_READY - Move arm to ready position. The ready position is defined with the hand directly in
* front of and slightly above the body, with the hand facing forward in the robot body +X
* direction.
*/
POSITIONS_READY = 2,
/**
* POSITIONS_STOW - Stow the arm, safely. If the robot is holding something, it will freeze the arm instead
* of stowing. Overriding the carry_state to CARRY_STATE_CARRIABLE_AND_STOWABLE, will allow
* the robot to stow the arm while grasping an item.
*/
POSITIONS_STOW = 3,
UNRECOGNIZED = -1,
}
export function namedArmPositionsCommand_PositionsFromJSON(
object: any
): NamedArmPositionsCommand_Positions {
switch (object) {
case 0:
case "POSITIONS_UNKNOWN":
return NamedArmPositionsCommand_Positions.POSITIONS_UNKNOWN;
case 1:
case "POSITIONS_CARRY":
return NamedArmPositionsCommand_Positions.POSITIONS_CARRY;
case 2:
case "POSITIONS_READY":
return NamedArmPositionsCommand_Positions.POSITIONS_READY;
case 3:
case "POSITIONS_STOW":
return NamedArmPositionsCommand_Positions.POSITIONS_STOW;
case -1:
case "UNRECOGNIZED":
default:
return NamedArmPositionsCommand_Positions.UNRECOGNIZED;
}
}
export function namedArmPositionsCommand_PositionsToJSON(
object: NamedArmPositionsCommand_Positions
): string {
switch (object) {
case NamedArmPositionsCommand_Positions.POSITIONS_UNKNOWN:
return "POSITIONS_UNKNOWN";
case NamedArmPositionsCommand_Positions.POSITIONS_CARRY:
return "POSITIONS_CARRY";
case NamedArmPositionsCommand_Positions.POSITIONS_READY:
return "POSITIONS_READY";
case NamedArmPositionsCommand_Positions.POSITIONS_STOW:
return "POSITIONS_STOW";
case NamedArmPositionsCommand_Positions.UNRECOGNIZED:
default:
return "UNRECOGNIZED";
}
}
export interface NamedArmPositionsCommand_Request {
position: NamedArmPositionsCommand_Positions;
}
export interface NamedArmPositionsCommand_Feedback {
/** Current status of the request. */
status: NamedArmPositionsCommand_Feedback_Status;
}
export enum NamedArmPositionsCommand_Feedback_Status {
/** STATUS_UNKNOWN - STATUS_UNKNOWN should never be used. If used, an internal error has happened. */
STATUS_UNKNOWN = 0,
/** STATUS_COMPLETE - The arm is at the desired configuration. */
STATUS_COMPLETE = 1,
/** STATUS_IN_PROGRESS - Robot is re-configuring arm to get to desired configuration. */
STATUS_IN_PROGRESS = 2,
/**
* STATUS_STALLED_HOLDING_ITEM - Some positions may refuse to execute if the gripper is holding an item, for example
* stow.
*/
STATUS_STALLED_HOLDING_ITEM = 3,
UNRECOGNIZED = -1,
}
export function namedArmPositionsCommand_Feedback_StatusFromJSON(
object: any
): NamedArmPositionsCommand_Feedback_Status {
switch (object) {
case 0:
case "STATUS_UNKNOWN":
return NamedArmPositionsCommand_Feedback_Status.STATUS_UNKNOWN;
case 1:
case "STATUS_COMPLETE":
return NamedArmPositionsCommand_Feedback_Status.STATUS_COMPLETE;
case 2:
case "STATUS_IN_PROGRESS":
return NamedArmPositionsCommand_Feedback_Status.STATUS_IN_PROGRESS;
case 3:
case "STATUS_STALLED_HOLDING_ITEM":
return NamedArmPositionsCommand_Feedback_Status.STATUS_STALLED_HOLDING_ITEM;
case -1:
case "UNRECOGNIZED":
default:
return NamedArmPositionsCommand_Feedback_Status.UNRECOGNIZED;
}
}
export function namedArmPositionsCommand_Feedback_StatusToJSON(
object: NamedArmPositionsCommand_Feedback_Status
): string {
switch (object) {
case NamedArmPositionsCommand_Feedback_Status.STATUS_UNKNOWN:
return "STATUS_UNKNOWN";
case NamedArmPositionsCommand_Feedback_Status.STATUS_COMPLETE:
return "STATUS_COMPLETE";
case NamedArmPositionsCommand_Feedback_Status.STATUS_IN_PROGRESS:
return "STATUS_IN_PROGRESS";
case NamedArmPositionsCommand_Feedback_Status.STATUS_STALLED_HOLDING_ITEM:
return "STATUS_STALLED_HOLDING_ITEM";
case NamedArmPositionsCommand_Feedback_Status.UNRECOGNIZED:
default:
return "UNRECOGNIZED";
}
}
/**
* Command the end effector of the arm. Each axis in the task frame is allowed to be set to
* position mode (default) or Force mode. If the axis is set to position, the desired value is read
* from the pose_trajectory_in_task. If the axis is set to force, the desired value is read from
* the wrench_trajectory. This supports hybrid control of the arm where users can specify, for
* example, Z to be in force control with X and Y in position control.
*/
export interface ArmCartesianCommand {}
export interface ArmCartesianCommand_Request {
/**
* The root frame is used to set the optional task frame that all trajectories are
* specified with respect to. If the optional task frame is left un-specified it defaults
* to the identity transform and the root frame becomes the task frame.
*/
rootFrameName: string;
/**
* The tool pose relative to the parent link (wrist).
* Defaults to
* [0.19557 0 0]
* [1 0 0 0]
* a frame with it's origin slightly in front of the gripper's palm plate aligned with
* wrist's orientation.
*/
wristTformTool: SE3Pose | undefined;
/**
* The fields below are specified in this optional task frame. If unset it defaults
* to the identity transform and all quantities are therefore expressed in the
* root_frame_name.
*/
rootTformTask: SE3Pose | undefined;
/**
* A 3D pose trajectory for the tool expressed in the task frame, e.g. task_T_tool.
* This pose trajectory is optional if requesting a pure wrench at the end-effector,
* otherwise required for position or mixed force/position end-effector requests.
*/
poseTrajectoryInTask: SE3Trajectory | undefined;
/**
* Optional Maximum acceleration magnitude of the end-effector.
* Valid ranges (0, 20]
*/
maximumAcceleration: number | undefined;
/** Optional Maximum linear velocity magnitude of the end-effector. (m/s) */
maxLinearVelocity: number | undefined;
/** Optional Maximum angular velocity magnitude of the end-effector. (rad/s) */
maxAngularVelocity: number | undefined;
/**
* Maximum allowable tracking error of the tool frame from the desired trajectory
* before the arm will stop moving and cancel the rest of the trajectory. When this limit is
* exceeded, the hand will stay at the pose it was at when it exceeded the tracking error,
* and any other part of the trajectory specified in the rest of this message will be
* ignored. max position tracking error in meters
*/
maxPosTrackingError: number | undefined;
/** max orientation tracking error in radians */
maxRotTrackingError: number | undefined;
forceRemainNearCurrentJointConfiguration: boolean | undefined;
preferredJointConfiguration: ArmJointPosition | undefined;
xAxis: ArmCartesianCommand_Request_AxisMode;
yAxis: ArmCartesianCommand_Request_AxisMode;
zAxis: ArmCartesianCommand_Request_AxisMode;
rxAxis: ArmCartesianCommand_Request_AxisMode;
ryAxis: ArmCartesianCommand_Request_AxisMode;
rzAxis: ArmCartesianCommand_Request_AxisMode;
/**
* A force/torque trajectory for the tool expressed in the task frame.
* This trajectory is optional if requesting a pure pose at the end-effector,
* otherwise required for force or mixed force/position end-effector requests.
*/
wrenchTrajectoryInTask: WrenchTrajectory | undefined;
}
/**
* If an axis is set to position mode (default), read desired from SE3Trajectory trajectory
* command. If mode is set to Force, read desired from WrenchTrajectory wrench_trajectory
* command. This supports hybrid control of the arm where users can specify, for example, Z
* to be in force control with X and Y in position control. The elements are expressed in
* the same task_frame as the trajectories.
*/
export enum ArmCartesianCommand_Request_AxisMode {
AXIS_MODE_POSITION = 0,
AXIS_MODE_FORCE = 1,
UNRECOGNIZED = -1,
}
export function armCartesianCommand_Request_AxisModeFromJSON(
object: any
): ArmCartesianCommand_Request_AxisMode {
switch (object) {
case 0:
case "AXIS_MODE_POSITION":
return ArmCartesianCommand_Request_AxisMode.AXIS_MODE_POSITION;
case 1:
case "AXIS_MODE_FORCE":
return ArmCartesianCommand_Request_AxisMode.AXIS_MODE_FORCE;
case -1:
case "UNRECOGNIZED":
default:
return ArmCartesianCommand_Request_AxisMode.UNRECOGNIZED;
}
}
export function armCartesianCommand_Request_AxisModeToJSON(
object: ArmCartesianCommand_Request_AxisMode
): string {
switch (object) {
case ArmCartesianCommand_Request_AxisMode.AXIS_MODE_POSITION:
return "AXIS_MODE_POSITION";
case ArmCartesianCommand_Request_AxisMode.AXIS_MODE_FORCE:
return "AXIS_MODE_FORCE";
case ArmCartesianCommand_Request_AxisMode.UNRECOGNIZED:
default:
return "UNRECOGNIZED";
}
}
export interface ArmCartesianCommand_Feedback {
/** Current status of the pose trajectory. */
status: ArmCartesianCommand_Feedback_Status;
/** Current linear tracking error of the tool frame [meters]. */
measuredPosTrackingError: number;
/** Current rotational tracking error of the tool frame [radians]. */
measuredRotTrackingError: number;
/** Linear distance from the tool to the tool trajectory's end point [meters]. */
measuredPosDistanceToGoal: number;
/** Rotational distance from the tool to the trajectory's end point [radians]. */
measuredRotDistanceToGoal: number;
}
export enum ArmCartesianCommand_Feedback_Status {
/** STATUS_UNKNOWN - STATUS_UNKNOWN should never be used. If used, an internal error has happened. */
STATUS_UNKNOWN = 0,
/** STATUS_TRAJECTORY_COMPLETE - Tool frame has reached the end of the trajectory within tracking error bounds. */
STATUS_TRAJECTORY_COMPLETE = 1,
/** STATUS_IN_PROGRESS - Robot is attempting to reach the target. */
STATUS_IN_PROGRESS = 2,
/** STATUS_TRAJECTORY_CANCELLED - Tool frame exceeded maximum allowable tracking error from the desired trajectory. */
STATUS_TRAJECTORY_CANCELLED = 3,
/**
* STATUS_TRAJECTORY_STALLED - The arm has stopped making progress to the goal. Note, this does not cancel the
* trajectory. For example, if the requested goal is too far away, walking the base
* robot closer to the goal will cause the arm to continue along the trajectory once the
* goal point is inside the workspace.
*/
STATUS_TRAJECTORY_STALLED = 4,
UNRECOGNIZED = -1,
}
export function armCartesianCommand_Feedback_StatusFromJSON(
object: any
): ArmCartesianCommand_Feedback_Status {
switch (object) {
case 0:
case "STATUS_UNKNOWN":
return ArmCartesianCommand_Feedback_Status.STATUS_UNKNOWN;
case 1:
case "STATUS_TRAJECTORY_COMPLETE":
return ArmCartesianCommand_Feedback_Status.STATUS_TRAJECTORY_COMPLETE;
case 2:
case "STATUS_IN_PROGRESS":
return ArmCartesianCommand_Feedback_Status.STATUS_IN_PROGRESS;
case 3:
case "STATUS_TRAJECTORY_CANCELLED":
return ArmCartesianCommand_Feedback_Status.STATUS_TRAJECTORY_CANCELLED;
case 4:
case "STATUS_TRAJECTORY_STALLED":
return ArmCartesianCommand_Feedback_Status.STATUS_TRAJECTORY_STALLED;
case -1:
case "UNRECOGNIZED":
default:
return ArmCartesianCommand_Feedback_Status.UNRECOGNIZED;
}
}
export function armCartesianCommand_Feedback_StatusToJSON(
object: ArmCartesianCommand_Feedback_Status
): string {
switch (object) {
case ArmCartesianCommand_Feedback_Status.STATUS_UNKNOWN:
return "STATUS_UNKNOWN";
case ArmCartesianCommand_Feedback_Status.STATUS_TRAJECTORY_COMPLETE:
return "STATUS_TRAJECTORY_COMPLETE";
case ArmCartesianCommand_Feedback_Status.STATUS_IN_PROGRESS:
return "STATUS_IN_PROGRESS";
case ArmCartesianCommand_Feedback_Status.STATUS_TRAJECTORY_CANCELLED:
return "STATUS_TRAJECTORY_CANCELLED";
case ArmCartesianCommand_Feedback_Status.STATUS_TRAJECTORY_STALLED:
return "STATUS_TRAJECTORY_STALLED";
case ArmCartesianCommand_Feedback_Status.UNRECOGNIZED:
default:
return "UNRECOGNIZED";
}
}
/** Specify a set of joint angles to move the arm. */
export interface ArmJointMoveCommand {}
export interface ArmJointMoveCommand_Request {
/**
* Note: Sending a single point empty trajectory will cause the arm to freeze in place. This
* is an easy way to lock the arm in its current configuration.
*/
trajectory: ArmJointTrajectory | undefined;
}
export interface ArmJointMoveCommand_Feedback {
/** Current status of the request. */
status: ArmJointMoveCommand_Feedback_Status;
/** Current status of the trajectory planner. */
plannerStatus: ArmJointMoveCommand_Feedback_PlannerStatus;
/**
* Based on the user trajectory, the planned knot points that obey acceleration and
* velocity constraints. If these knot points don't match the requested knot points,
* consider increasing velocity/acceleration limits, and/or staying further away from
* joint position limits. In situations where we've modified you last point, we append
* a minimum time trajectory (that obeys the velocity and acceleration limits) from the
* planner's final point to the requested final point. This means that the length of
* planned_points may be one point larger than the requested.
*/
plannedPoints: ArmJointTrajectoryPoint[];
/**
* Returns amount of time remaining until the joints are at the goal position. For
* multiple point trajectories, this is the time remaining to the final point.
*/
timeToGoal: Duration | undefined;
}
export enum ArmJointMoveCommand_Feedback_Status {
/** STATUS_UNKNOWN - STATUS_UNKNOWN should never be used. If used, an internal error has happened */
STATUS_UNKNOWN = 0,
/** STATUS_COMPLETE - The arm is at the desired configuration. */
STATUS_COMPLETE = 1,
/** STATUS_IN_PROGRESS - Robot is re-configuring arm to get to desired configuration. */
STATUS_IN_PROGRESS = 2,
UNRECOGNIZED = -1,
}
export function armJointMoveCommand_Feedback_StatusFromJSON(
object: any
): ArmJointMoveCommand_Feedback_Status {
switch (object) {
case 0:
case "STATUS_UNKNOWN":
return ArmJointMoveCommand_Feedback_Status.STATUS_UNKNOWN;
case 1:
case "STATUS_COMPLETE":
return ArmJointMoveCommand_Feedback_Status.STATUS_COMPLETE;
case 2:
case "STATUS_IN_PROGRESS":
return ArmJointMoveCommand_Feedback_Status.STATUS_IN_PROGRESS;
case -1:
case "UNRECOGNIZED":
default:
return ArmJointMoveCommand_Feedback_Status.UNRECOGNIZED;
}
}
export function armJointMoveCommand_Feedback_StatusToJSON(
object: ArmJointMoveCommand_Feedback_Status
): string {
switch (object) {
case ArmJointMoveCommand_Feedback_Status.STATUS_UNKNOWN:
return "STATUS_UNKNOWN";
case ArmJointMoveCommand_Feedback_Status.STATUS_COMPLETE:
return "STATUS_COMPLETE";
case ArmJointMoveCommand_Feedback_Status.STATUS_IN_PROGRESS:
return "STATUS_IN_PROGRESS";
case ArmJointMoveCommand_Feedback_Status.UNRECOGNIZED:
default:
return "UNRECOGNIZED";
}
}
export enum ArmJointMoveCommand_Feedback_PlannerStatus {
/** PLANNER_STATUS_UNKNOWN - PLANNER_STATUS_UNKNOWN should never be used. If used, an internal error has happened. */
PLANNER_STATUS_UNKNOWN = 0,
/** PLANNER_STATUS_SUCCESS - A solution passing through the desired points and obeying the constraints was found. */
PLANNER_STATUS_SUCCESS = 1,
/**
* PLANNER_STATUS_MODIFIED - The planner had to modify the desired points in order to obey the constraints. For
* example, if you specify a 1 point trajectory, and tell it to get there in a really short
* amount of time, but haven't set a high allowable max velocity / acceleration, the planner
* will do its best to get as close as possible to the final point, but won't reach it. In
* situations where we've modified you last point, we append a minimum time trajectory (that
* obeys the velocity and acceleration limits) from the planner's final point to the requested
* final point.
*/
PLANNER_STATUS_MODIFIED = 2,
/**
* PLANNER_STATUS_FAILED - Failed to compute a valid trajectory, will go to first point instead. It is possible
* that our optimizer till fail to solve the problem instead of returning a sub-optimal
* solution. This is un-likely to occur.
*/
PLANNER_STATUS_FAILED = 3,
UNRECOGNIZED = -1,
}
export function armJointMoveCommand_Feedback_PlannerStatusFromJSON(
object: any
): ArmJointMoveCommand_Feedback_PlannerStatus {
switch (object) {
case 0:
case "PLANNER_STATUS_UNKNOWN":
return ArmJointMoveCommand_Feedback_PlannerStatus.PLANNER_STATUS_UNKNOWN;
case 1:
case "PLANNER_STATUS_SUCCESS":
return ArmJointMoveCommand_Feedback_PlannerStatus.PLANNER_STATUS_SUCCESS;
case 2:
case "PLANNER_STATUS_MODIFIED":
return ArmJointMoveCommand_Feedback_PlannerStatus.PLANNER_STATUS_MODIFIED;
case 3:
case "PLANNER_STATUS_FAILED":
return ArmJointMoveCommand_Feedback_PlannerStatus.PLANNER_STATUS_FAILED;
case -1:
case "UNRECOGNIZED":
default:
return ArmJointMoveCommand_Feedback_PlannerStatus.UNRECOGNIZED;
}
}
export function armJointMoveCommand_Feedback_PlannerStatusToJSON(
object: ArmJointMoveCommand_Feedback_PlannerStatus
): string {
switch (object) {
case ArmJointMoveCommand_Feedback_PlannerStatus.PLANNER_STATUS_UNKNOWN:
return "PLANNER_STATUS_UNKNOWN";
case ArmJointMoveCommand_Feedback_PlannerStatus.PLANNER_STATUS_SUCCESS:
return "PLANNER_STATUS_SUCCESS";
case ArmJointMoveCommand_Feedback_PlannerStatus.PLANNER_STATUS_MODIFIED:
return "PLANNER_STATUS_MODIFIED";
case ArmJointMoveCommand_Feedback_PlannerStatus.PLANNER_STATUS_FAILED:
return "PLANNER_STATUS_FAILED";
case ArmJointMoveCommand_Feedback_PlannerStatus.UNRECOGNIZED:
default:
return "UNRECOGNIZED";
}
}
/**
* Position of our 6 arm joints in radians. If a joint angle is not specified,
* we will use the joint position at time the message is received on robot.
*/
export interface ArmJointPosition {
sh0: number | undefined;
sh1: number | undefined;
el0: number | undefined;
el1: number | undefined;
wr0: number | undefined;
wr1: number | undefined;
}
/**
* Velocity of our 6 arm joints in radians / second. If a velocity
* for a joint is specified, velocities for all joints we are
* trying to move must be specified.
*/
export interface ArmJointVelocity {
sh0: number | undefined;
sh1: number | undefined;
el0: number | undefined;
el1: number | undefined;
wr0: number | undefined;
wr1: number | undefined;
}
/** A set of joint angles and velocities that can be used as a point within a joint trajectory. */
export interface ArmJointTrajectoryPoint {
/** Desired joint angles in radians */
position: ArmJointPosition | undefined;
/** Optional desired joint velocities in radians / sec */
velocity: ArmJointVelocity | undefined;
/** The time since reference at which we wish to achieve this position / velocity */
timeSinceReference: Duration | undefined;
}
/**
* This allows a user to move the arm's joints directly. Each of the arm's joints will never move
* faster than maximum_velocity and never accelerate faster than maximum_acceleration. The user can
* specify a trajectory of joint positions and optional velocities for the arm to follow. The
* trajectory will be acted upon as follows. If a single trajectory point with no time is provided,
* the arm will take the joint currently furthest away from the goal pose and plan a minimum time
* trajectory such that the joint accelerates at maximum_acceleration, coasts at maximum_velocity,
* and decelerates at maximum_acceleration. The other joints will accelerate at
* maximum_acceleration, but then coast at a slower speed such that all joints arrive at the goal
* pose simultaneously with zero velocity. If the user provides trajectory times, the robot will fit
* a piece-wise cubic trajectory (continuous position and velocity) to the user's requested
* positions and (optional) velocities. If the requested trajectory is not achievable because it
* will violate position limits or the maximum_velocity or maximum_acceleration, the robot will pick
* a trajectory that is as close as possible to the user requested without violating velocity or
* acceleration limits.
*
* If the robot is not hitting the desired trajectory, try increasing the time between knot points,
* increasing the max velocity and acceleration, or only specifying joint position goals without a
* velocity
*/
export interface ArmJointTrajectory {
/** The points in our trajectory. (positions, (optional) velocity, (optional) time) */
points: ArmJointTrajectoryPoint[];
/**
* All trajectory points specify times relative to this reference time. The reference
* time should be in robot clock. If this field is not included, this time will be
* the receive time of the command.
*/
referenceTime: Date | undefined;
/**
* The maximum velocity in rad/s that any joint is allowed to achieve.
* If this field is not set, a default value will be used.
*/
maximumVelocity: number | undefined;
/**
* The maximum acceleration in rad/s^2 that any joint is allowed to
* achieve. If this field is not set, a default value will be used.
*/
maximumAcceleration: number | undefined;
}
/** / Move the hand in such a way to point it at a position in the world. */
export interface GazeCommand {}
export interface GazeCommand_Request {
/** Point(s) to look at expressed in frame1. */
targetTrajectoryInFrame1: Vec3Trajectory | undefined;
frame1Name: string;
/**
* Optional, desired pose of the tool expressed in frame2. Will be constrained to 'look at'
* the target regardless of the requested orientation.
*/
toolTrajectoryInFrame2: SE3Trajectory | undefined;
frame2Name: string;
/**
* The transformation of the tool pose relative to the parent link (wrist).
* If the field is left unset, the transform will default to:
* The position is wrist_tform_hand.position() [20 cm translation in wrist x].
* The rotation is wrist_tform_hand_camera.rotation() [-9 degree pitch about wrist y].
*/
wristTformTool: SE3Pose | undefined;
/**
* Optional velocity to move the target along the shortest path from the gaze's starting
* position to the first point in the target trajectory.
*/
targetTrajectoryInitialVelocity: number | undefined;
/**
* Optional Maximum acceleration magnitude of the end-effector.
* Valid ranges (0, 20]
*/
maximumAcceleration: number | undefined;
/** Optional Maximum linear velocity magnitude of the end-effector. (m/s) */
maxLinearVelocity: number | undefined;
/** Optional Maximum angular velocity magnitude of the end-effector. (rad/s) */
maxAngularVelocity: number | undefined;
}
export interface GazeCommand_Feedback {
/** Current status of the command. */
status: GazeCommand_Feedback_Status;
/**
* If we are gazing at the target
* Rotation from the current gaze point to the trajectory's end [radians]
*/
gazingAtTarget: boolean;
gazeToTargetRotationMeasured: number;
/**
* If the hand's position is at the goal.
* Distance from the hand's current position to the trajectory's end [meters]
*/
handPositionAtGoal: boolean;
handDistanceToGoalMeasured: number;
/**
* If the hand's roll is at the goal.
* Rotation from the current hand position to the desired roll at the trajectory's end
* [radians]
*/
handRollAtGoal: boolean;
handRollToTargetRollMeasured: number;
}
export enum GazeCommand_Feedback_Status {
/** STATUS_UNKNOWN - STATUS_UNKNOWN should never be used. If used, an internal error has happened. */
STATUS_UNKNOWN = 0,
/** STATUS_TRAJECTORY_COMPLETE - Robot is gazing at the target at the end of the trajectory. */
STATUS_TRAJECTORY_COMPLETE = 1,
/** STATUS_IN_PROGRESS - Robot is re-configuring arm to gaze at the target. */
STATUS_IN_PROGRESS = 2,
/**
* STATUS_TOOL_TRAJECTORY_STALLED - The arm has stopped making progress to the goal pose for the tool.
* Note, this does not cancel the trajectory. For example, if the requested goal is too
* far away, walking the base robot closer to the goal will cause the arm to continue
* along the trajectory once it can continue.
*/
STATUS_TOOL_TRAJECTORY_STALLED = 3,
UNRECOGNIZED = -1,
}
export function gazeCommand_Feedback_StatusFromJSON(
object: any
): GazeCommand_Feedback_Status {
switch (object) {
case 0:
case "STATUS_UNKNOWN":
return GazeCommand_Feedback_Status.STATUS_UNKNOWN;
case 1:
case "STATUS_TRAJECTORY_COMPLETE":
return GazeCommand_Feedback_Status.STATUS_TRAJECTORY_COMPLETE;
case 2:
case "STATUS_IN_PROGRESS":
return GazeCommand_Feedback_Status.STATUS_IN_PROGRESS;
case 3:
case "STATUS_TOOL_TRAJECTORY_STALLED":
return GazeCommand_Feedback_Status.STATUS_TOOL_TRAJECTORY_STALLED;
case -1:
case "UNRECOGNIZED":
default:
return GazeCommand_Feedback_Status.UNRECOGNIZED;
}
}
export function gazeCommand_Feedback_StatusToJSON(
object: GazeCommand_Feedback_Status
): string {
switch (object) {
case GazeCommand_Feedback_Status.STATUS_UNKNOWN:
return "STATUS_UNKNOWN";
case GazeCommand_Feedback_Status.STATUS_TRAJECTORY_COMPLETE:
return "STATUS_TRAJECTORY_COMPLETE";
case GazeCommand_Feedback_Status.STATUS_IN_PROGRESS:
return "STATUS_IN_PROGRESS";
case GazeCommand_Feedback_Status.STATUS_TOOL_TRAJECTORY_STALLED:
return "STATUS_TOOL_TRAJECTORY_STALLED";
case GazeCommand_Feedback_Status.UNRECOGNIZED:
default:
return "UNRECOGNIZED";
}
}
/**
* Stop the arm applying minimal forces to the world. For example, if the arm is in the middle of
* opening a heavy door and a stop command is sent, the arm will comply and let the door close.
*/
export interface ArmStopCommand {}
/** Stop command takes no arguments. */
export interface ArmStopCommand_Request {}
/** Stop command provides no feedback */
export interface ArmStopCommand_Feedback {}
function createBaseArmCommand(): ArmCommand {
return {};
}
export const ArmCommand = {
encode(_: ArmCommand, writer: _m0.Writer = _m0.Writer.create()): _m0.Writer {
return writer;
},
decode(input: _m0.Reader | Uint8Array, length?: number): ArmCommand {
const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input);
let end = length === undefined ? reader.len : reader.pos + length;
const message = createBaseArmCommand();
while (reader.pos < end) {
const tag = reader.uint32();
switch (tag >>> 3) {
default:
reader.skipType(tag & 7);
break;
}
}
return message;
},
fromJSON(_: any): ArmCommand {
return {};
},
toJSON(_: ArmCommand): unknown {
const obj: any = {};
return obj;
},
fromPartial<I extends Exact<DeepPartial<ArmCommand>, I>>(_: I): ArmCommand {
const message = createBaseArmCommand();
return message;
},
};
function createBaseArmCommand_Request(): ArmCommand_Request {
return {
armCartesianCommand: undefined,
armJointMoveCommand: undefined,
namedArmPositionCommand: undefined,
armVelocityCommand: undefined,
armGazeCommand: undefined,
armStopCommand: undefined,
armDragCommand: undefined,
params: undefined,
};
}
export const ArmCommand_Request = {
encode(
message: ArmCommand_Request,
writer: _m0.Writer = _m0.Writer.create()
): _m0.Writer {
if (message.armCartesianCommand !== undefined) {
ArmCartesianCommand_Request.encode(
message.armCartesianCommand,
writer.uint32(26).fork()
).ldelim();
}
if (message.armJointMoveCommand !== undefined) {
ArmJointMoveCommand_Request.encode(
message.armJointMoveCommand,
writer.uint32(34).fork()
).ldelim();
}
if (message.namedArmPositionCommand !== undefined) {
NamedArmPositionsCommand_Request.encode(
message.namedArmPositionCommand,
writer.uint32(42).fork()
).ldelim();
}
if (message.armVelocityCommand !== undefined) {
ArmVelocityCommand_Request.encode(
message.armVelocityCommand,
writer.uint32(50).fork()
).ldelim();
}
if (message.armGazeCommand !== undefined) {
GazeCommand_Request.encode(
message.armGazeCommand,
writer.uint32(66).fork()
).ldelim();
}
if (message.armStopCommand !== undefined) {
ArmStopCommand_Request.encode(
message.armStopCommand,
writer.uint32(74).fork()
).ldelim();
}
if (message.armDragCommand !== undefined) {
ArmDragCommand_Request.encode(
message.armDragCommand,
writer.uint32(82).fork()
).ldelim();
}
if (message.params !== undefined) {
ArmParams.encode(message.params, writer.uint32(90).fork()).ldelim();
}
return writer;
},
decode(input: _m0.Reader | Uint8Array, length?: number): ArmCommand_Request {
const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input);
let end = length === undefined ? reader.len : reader.pos + length;
const message = createBaseArmCommand_Request();
while (reader.pos < end) {
const tag = reader.uint32();
switch (tag >>> 3) {
case 3:
message.armCartesianCommand = ArmCartesianCommand_Request.decode(
reader,
reader.uint32()
);
break;
case 4:
message.armJointMoveCommand = ArmJointMoveCommand_Request.decode(
reader,
reader.uint32()
);
break;
case 5:
message.namedArmPositionCommand =
NamedArmPositionsCommand_Request.decode(reader, reader.uint32());
break;
case 6:
message.armVelocityCommand = ArmVelocityCommand_Request.decode(
reader,
reader.uint32()
);
break;
case 8:
message.armGazeCommand = GazeCommand_Request.decode(
reader,
reader.uint32()
);
break;
case 9:
message.armStopCommand = ArmStopCommand_Request.decode(
reader,
reader.uint32()
);
break;
case 10:
message.armDragCommand = ArmDragCommand_Request.decode(
reader,
reader.uint32()
);
break;
case 11:
message.params = ArmParams.decode(reader, reader.uint32());
break;
default:
reader.skipType(tag & 7);
break;
}
}
return message;
},
fromJSON(object: any): ArmCommand_Request {
return {
armCartesianCommand: isSet(object.armCartesianCommand)
? ArmCartesianCommand_Request.fromJSON(object.armCartesianCommand)
: undefined,
armJointMoveCommand: isSet(object.armJointMoveCommand)
? ArmJointMoveCommand_Request.fromJSON(object.armJointMoveCommand)
: undefined,
namedArmPositionCommand: isSet(object.namedArmPositionCommand)
? NamedArmPositionsCommand_Request.fromJSON(
object.namedArmPositionCommand
)
: undefined,
armVelocityCommand: isSet(object.armVelocityCommand)
? ArmVelocityCommand_Request.fromJSON(object.armVelocityCommand)
: undefined,
armGazeCommand: isSet(object.armGazeCommand)
? GazeCommand_Request.fromJSON(object.armGazeCommand)
: undefined,
armStopCommand: isSet(object.armStopCommand)
? ArmStopCommand_Request.fromJSON(object.armStopCommand)
: undefined,
armDragCommand: isSet(object.armDragCommand)
? ArmDragCommand_Request.fromJSON(object.armDragCommand)
: undefined,
params: isSet(object.params)
? ArmParams.fromJSON(object.params)
: undefined,
};
},
toJSON(message: ArmCommand_Request): unknown {
const obj: any = {};
message.armCartesianCommand !== undefined &&
(obj.armCartesianCommand = message.armCartesianCommand
? ArmCartesianCommand_Request.toJSON(message.armCartesianCommand)
: undefined);
message.armJointMoveCommand !== undefined &&
(obj.armJointMoveCommand = message.armJointMoveCommand
? ArmJointMoveCommand_Request.toJSON(message.armJointMoveCommand)
: undefined);
message.namedArmPositionCommand !== undefined &&
(obj.namedArmPositionCommand = message.namedArmPositionCommand
? NamedArmPositionsCommand_Request.toJSON(
message.namedArmPositionCommand
)
: undefined);
message.armVelocityCommand !== undefined &&
(obj.armVelocityCommand = message.armVelocityCommand
? ArmVelocityCommand_Request.toJSON(message.armVelocityCommand)
: undefined);
message.armGazeCommand !== undefined &&
(obj.armGazeCommand = message.armGazeCommand
? GazeCommand_Request.toJSON(message.armGazeCommand)
: undefined);
message.armStopCommand !== undefined &&
(obj.armStopCommand = message.armStopCommand
? ArmStopCommand_Request.toJSON(message.armStopCommand)
: undefined);
message.armDragCommand !== undefined &&
(obj.armDragCommand = message.armDragCommand
? ArmDragCommand_Request.toJSON(message.armDragCommand)
: undefined);
message.params !== undefined &&
(obj.params = message.params
? ArmParams.toJSON(message.params)
: undefined);
return obj;
},
fromPartial<I extends Exact<DeepPartial<ArmCommand_Request>, I>>(
object: I
): ArmCommand_Request {
const message = createBaseArmCommand_Request();
message.armCartesianCommand =
object.armCartesianCommand !== undefined &&
object.armCartesianCommand !== null
? ArmCartesianCommand_Request.fromPartial(object.armCartesianCommand)
: undefined;
message.armJointMoveCommand =
object.armJointMoveCommand !== undefined &&
object.armJointMoveCommand !== null
? ArmJointMoveCommand_Request.fromPartial(object.armJointMoveCommand)
: undefined;
message.namedArmPositionCommand =
object.namedArmPositionCommand !== undefined &&
object.namedArmPositionCommand !== null
? NamedArmPositionsCommand_Request.fromPartial(
object.namedArmPositionCommand
)
: undefined;
message.armVelocityCommand =
object.armVelocityCommand !== undefined &&
object.armVelocityCommand !== null
? ArmVelocityCommand_Request.fromPartial(object.armVelocityCommand)
: undefined;
message.armGazeCommand =
object.armGazeCommand !== undefined && object.armGazeCommand !== null
? GazeCommand_Request.fromPartial(object.armGazeCommand)
: undefined;
message.armStopCommand =
object.armStopCommand !== undefined && object.armStopCommand !== null
? ArmStopCommand_Request.fromPartial(object.armStopCommand)
: undefined;
message.armDragCommand =
object.armDragCommand !== undefined && object.armDragCommand !== null
? ArmDragCommand_Request.fromPartial(object.armDragCommand)
: undefined;
message.params =
object.params !== undefined && object.params !== null
? ArmParams.fromPartial(object.params)
: undefined;
return message;
},
};
function createBaseArmCommand_Feedback(): ArmCommand_Feedback {
return {
armCartesianFeedback: undefined,
armJointMoveFeedback: undefined,
namedArmPositionFeedback: undefined,
armVelocityFeedback: undefined,
armGazeFeedback: undefined,
armStopFeedback: undefined,
armDragFeedback: undefined,
status: 0,
};
}
export const ArmCommand_Feedback = {
encode(
message: ArmCommand_Feedback,
writer: _m0.Writer = _m0.Writer.create()
): _m0.Writer {
if (message.armCartesianFeedback !== undefined) {
ArmCartesianCommand_Feedback.encode(
message.armCartesianFeedback,
writer.uint32(26).fork()
).ldelim();
}
if (message.armJointMoveFeedback !== undefined) {
ArmJointMoveCommand_Feedback.encode(
message.armJointMoveFeedback,
writer.uint32(34).fork()
).ldelim();
}
if (message.namedArmPositionFeedback !== undefined) {
NamedArmPositionsCommand_Feedback.encode(
message.namedArmPositionFeedback,
writer.uint32(42).fork()
).ldelim();
}
if (message.armVelocityFeedback !== undefined) {
ArmVelocityCommand_Feedback.encode(
message.armVelocityFeedback,
writer.uint32(50).fork()
).ldelim();
}
if (message.armGazeFeedback !== undefined) {
GazeCommand_Feedback.encode(
message.armGazeFeedback,
writer.uint32(66).fork()
).ldelim();
}
if (message.armStopFeedback !== undefined) {
ArmStopCommand_Feedback.encode(
message.armStopFeedback,
writer.uint32(74).fork()
).ldelim();
}
if (message.armDragFeedback !== undefined) {
ArmDragCommand_Feedback.encode(
message.armDragFeedback,
writer.uint32(82).fork()
).ldelim();
}
if (message.status !== 0) {
writer.uint32(800).int32(message.status);
}
return writer;
},
decode(input: _m0.Reader | Uint8Array, length?: number): ArmCommand_Feedback {
const reader = input instanceof _m0.Reader ? input : new _m0.Reader(input);
let end = length === undefined ? reader.len : reader.pos + length;
const message = createBaseArmCommand_Feedback();
while (reader.pos < end) {
const tag = reader.uint32();
switch (tag >>> 3) {
case 3:
message.armCartesianFeedback = ArmCartesianCommand_Feedback.decode(
reader,
reader.uint32()
);
break;
case 4:
message.armJointMoveFeedback = ArmJointMoveCommand_Feedback.decode(
reader,
reader.uint32()
);
break;
case 5:
message.namedArmPositionFeedback =
NamedArmPositionsCommand_Feedback.decode(reader, reader.uint32());
break;
case 6:
message.armVelocityFeedback = ArmVelocityCommand_Feedback.decode(
reader,
reader.uint32()
);
break;
case 8:
message.armGazeFeedback = GazeCommand_Feedback.decode(
reader,
reader.uint32()
);
break;
case 9:
message.armStopFeedback = ArmStopCommand_Feedback.decode(
reader,
reader.uint32()
);
break;
case 10:
message.armDragFeedback = ArmDragCommand_Feedback.decode(
reader,
reader.uint32()
);
break;
case 100:
message.status = reader.int32() as any;
break;
default:
reader.skipType(tag & 7);
break;
}
}
return message;
},
fromJSON(object: any): ArmCommand_Feedback {
return {
armCartesianFeedback: isSet(object.armCartesianFeedback)
? ArmCartesianCommand_Feedback.fromJSON(object.armCartesianFeedback)
: undefined,
armJointMoveFeedback: isSet(object.armJointMoveFeedback)
? ArmJointMoveCommand_Feedback.fromJSON(object.armJointMoveFeedback)
: undefined,
namedArmPositionFeedback: isSet(object.namedArmPositionFeedback)
? NamedArmPositionsCommand_Feedback.fromJSON(
object.namedArmPositionFeedback
)
: undefined,
armVelocityFeedback: isSet(object.armVelocityFeedback)
? ArmVelocityCommand_Feedback.fromJSON(object.armVelocityFeedback)
: undefined,
armGazeFeedback: isSet(object.armGazeFeedback)
? GazeCommand_Feedback.fromJSON(object.armGazeFeedback)
: undefined,
armStopFeedback: isSet(object.armStopFeedback)
? ArmStopCommand_Feedback.fromJSON(object.armStopFeedback)
: undefined,
armDragFeedback: isSet(object.armDragFeedback)
? ArmDragCommand_Feedback.fromJSON(object.armDragFeedback)
: undefined,
status: isSet(object.status)
? robotCommandFeedbackStatus_StatusFromJSON(object.status)
: 0,
};
},
toJSON(message: ArmCommand_Feedback): unknown {
const obj: any = {};
message.armCartesianFeedback !== undefined &&
(obj.armCartesianFeedback = message.armCartesianFeedback
? ArmCartesianCommand_Feedback.toJSON(message.armCartesianFeedback)
: undefined);
message.armJointMoveFeedback !== undefined &&
(obj.armJointMoveFeedback = message.armJointMoveFeedback
? ArmJointMoveCommand_Feedback.toJSON(message.armJointMoveFeedback)
: undefined);
message.namedArmPositionFeedback !== undefined &&
(obj.namedArmPositionFeedback = message.namedArmPositionFeedback
? NamedArmPositionsCommand_Feedback.toJSON(
message.namedArmPositionFeedback
)
: undefined);
message.armVelocityFeedback !== undefined &&
(obj.armVelocityFeedback = message.armVelocityFeedback
? ArmVelocityCommand_Feedback.toJSON(message.armVelocityFeedback)
: undefined);
message.armGazeFeedback !== undefined &&
(obj.armGazeFeedback = message.armGazeFeedback
? GazeCommand_Feedback.toJSON(message.armGazeFeedback)
: undefined);
message.armStopFeedback !== undefined &&
(obj.armStopFeedback = message.armStopFeedback
? ArmStopCommand_Feedback.toJSON(message.armStopFeedback)
: undefined);
message.armDragFeedback !== undefined &&
(obj.armDragFeedback = message.armDragFeedback
? ArmDragCommand_Feedback.toJSON(message.armDragFeedback)
: undefined);
message.status !== undefined &&
(obj.status = robotCommandFeedbackStatus_StatusToJSON(message.status));
return obj;
},
fromPartial<I extends Exact<DeepPartial<ArmCommand_Feedback>, I>>(
object: I
): ArmCommand_Feedback {
const message = createBaseArmCommand_Feedback();
message.armCartesianFeedback =
object.armCartesianFeedback !== undefined &&
object.armCartesianFeedback !== null
? ArmCartesianCommand_Feedback.fromPartial(object.armCartesianFeedback)
: undefined;
message.armJointMoveFeedback =
object.armJointMoveFeedback !== undefined &&
object.armJointMoveFeedback !== null
? ArmJointMoveCommand_Feedback.fromPartial(object.armJointMoveFeedback)
: undefined;
message.namedArmPositionFeedback =
object.namedArmPositionFeedback !== undefined &&
object.namedArmPositionFeedback !== null
? NamedArmPositionsCommand_Feedback.fromPartial(
object.namedArmPositionFeedback
)
: undefined;
message.armVelocityFeedback =
object.armVelocityFeedback !== undefined &&
object.armVelocityFeedback !== null
? ArmVelocityCommand_Feedback.fromPartial(object.armVelocityFeedback)
: undefined;
message.armGazeFeedback =
object.armGazeFeedback !== undefined && object.armGazeFeedback !== null
? GazeCommand_Feedback.fromPartial(object.armGazeFeedback)
: