Protocol Documentation

Table of Contents

Top

bosdyn/api/alerts.proto

AlertData

Structured data indicating an alert detected off the robot that can be stored in the DataBuffer and associated with with previously stored data.

Field Type Label Description
severity AlertData.SeverityLevel Severity of this alert.
title string Human readable alert title/summary.
source string The source that triggered the alert.
additional_data google.protobuf.Struct JSON data for any additional info attached to this alert.

AlertData.SeverityLevel

Name Number Description
SEVERITY_LEVEL_UNKNOWN 0 Do not use. If severity is unknown, must assume issue is
highest severity.
SEVERITY_LEVEL_INFO 1 Informational message that requires no action.
SEVERITY_LEVEL_WARN 2 An error may occur in the future if no action is taken, but no action
presently required.
SEVERITY_LEVEL_ERROR 3 Action required. Error fatal to operation.
SEVERITY_LEVEL_CRITICAL 4 Action required. Severe error that requires immediate
attention.

Top

bosdyn/api/arm_command.proto

ArmCartesianCommand

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.

ArmCartesianCommand.Feedback

Field Type Label Description
status ArmCartesianCommand.Feedback.Status Current status of the pose trajectory.
measured_pos_tracking_error double Current linear tracking error of the tool frame [meters].
measured_rot_tracking_error double Current rotational tracking error of the tool frame [radians].
measured_pos_distance_to_goal double Linear distance from the tool to the tool trajectory's end point [meters].
measured_rot_distance_to_goal double Rotational distance from the tool to the trajectory's end point [radians].

ArmCartesianCommand.Request

Field Type Label Description
root_frame_name string 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.
wrist_tform_tool SE3Pose 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.
root_tform_task SE3Pose 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.
pose_trajectory_in_task SE3Trajectory 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.
maximum_acceleration google.protobuf.DoubleValue Optional Maximum acceleration magnitude of the end-effector.
Valid ranges (0, 20]
max_linear_velocity google.protobuf.DoubleValue Optional Maximum linear velocity magnitude of the end-effector. (m/s)
max_angular_velocity google.protobuf.DoubleValue Optional Maximum angular velocity magnitude of the end-effector. (rad/s)
max_pos_tracking_error google.protobuf.DoubleValue 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
max_rot_tracking_error google.protobuf.DoubleValue max orientation tracking error in radians
force_remain_near_current_joint_configuration bool
preferred_joint_configuration ArmJointPosition
x_axis ArmCartesianCommand.Request.AxisMode
y_axis ArmCartesianCommand.Request.AxisMode
z_axis ArmCartesianCommand.Request.AxisMode
rx_axis ArmCartesianCommand.Request.AxisMode
ry_axis ArmCartesianCommand.Request.AxisMode
rz_axis ArmCartesianCommand.Request.AxisMode
wrench_trajectory_in_task WrenchTrajectory 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.
disable_velocity_limiting google.protobuf.BoolValue Disables protection that prevents the arm from moving unexpectedly fast. If you are
commanding an especially aggressive arm trajectory, you may need to disable this
protection.
WARNING: setting disable_velocity_limiting to true may result in fast arm motions!

ArmCommand

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.

ArmCommand.Feedback

The feedback for the arm command that will provide information on the progress of the command.

Field Type Label Description
arm_cartesian_feedback ArmCartesianCommand.Feedback Feedback for the end-effector Cartesian command.
arm_joint_move_feedback ArmJointMoveCommand.Feedback Feedback for the joint move command.
named_arm_position_feedback NamedArmPositionsCommand.Feedback Feedback for the named position move command.
arm_velocity_feedback ArmVelocityCommand.Feedback
arm_gaze_feedback GazeCommand.Feedback Feedback for the gaze command.
arm_stop_feedback ArmStopCommand.Feedback
arm_drag_feedback ArmDragCommand.Feedback Feedback for the drag command.
arm_impedance_feedback ArmImpedanceCommand.Feedback Feedback for impedance command.
status RobotCommandFeedbackStatus.Status

ArmCommand.Request

The arm request must be one of the basic command primitives.

Field Type Label Description
arm_cartesian_command ArmCartesianCommand.Request Control the end-effector in Cartesian space.
arm_joint_move_command ArmJointMoveCommand.Request Control joint angles of the arm.
named_arm_position_command NamedArmPositionsCommand.Request Move the arm to some predefined configurations.
arm_velocity_command ArmVelocityCommand.Request Velocity control of the end-effector.
arm_gaze_command GazeCommand.Request Point the gripper at a point in the world.
arm_stop_command ArmStopCommand.Request Stop the arm in place with minimal motion.
arm_drag_command ArmDragCommand.Request Use the arm to drag something held in the gripper.
arm_impedance_command ArmImpedanceCommand.Request Impedance control of arm (beta)
params ArmParams Any arm parameters to send, common across all arm commands

ArmImpedanceCommand

Specify impedance about the end-effector. Users can set up frames along with stiffness and damping parameters to control how the end-effector will respond to external contact as it moves along a specified trajectory

ArmImpedanceCommand.Feedback

Field Type Label Description
status ArmImpedanceCommand.Feedback.Status Current status of the pose trajectory.
transforms_snapshot FrameTreeSnapshot A tree-based collection of transformations relevant to the current impedance operation.
In addition to the common frames ("vision", "body", "odom"), this snapshot contains the
following:
"task": The task frame that the impedance action is specified in.
"desired_tool": The pose of the desired_tool frame at the current time.
"tool": The current measured pose of the tool.
"desired_tool_at_end": The desired tool pose at the end of the requested trajectory.
"measured_tool_at_start": The measured pose of the tool when this command was first sent.

While these poses can be used in any way the user sees fit, here are some useful ideas:
desired_tool_tform_tool: The current measured tool pose relative to the desired_tool
frame [meters, quaternion]. This is our "tracking error".
Multiplying this error by diagonal_stiffness_matrix should
yield commanded_wrench_from_stiffness_at_tool_in_desired_tool.
desired_tool_at_end_tform_tool: The current measured tool pose relative to the
desired_tool frame at the end of the user trajectory
[meters, quaternion]. This is our "distance to goal",
and can be used for checking when an impedance move is
"complete".
measured_tool_at_start_tform_tool_in_task: The current measured tool pose relative to
the measured tool frame at the start,
expressed in the task frame
[meters, quaternion]. This can be used to
see how far the tool has moved since the
beginning of the command.
commanded_wrench_from_stiffness_at_tool_in_desired_tool Wrench The component of our commanded wrench at the tool expressed with respect to the
desired_tool frame from our stiffness matrix [Newtons / Nm]
commanded_wrench_from_damping_at_tool_in_desired_tool Wrench The component of our commanded wrench at the tool expressed with respect to the
desired_tool frame from our damping matrix [Newtons / Nm]
commanded_wrench_from_feed_forward_at_tool_in_desired_tool Wrench The component of our commanded wrench at the tool expressed with respect to the
desired_tool frame from our feed forward wrench [Newtons / Nm]
total_commanded_wrench_at_tool_in_desired_tool Wrench The commanded total wrench at the tool expressed with respect to the desired_tool
frame. This wrench has been saturated to obey max_force_mag and max_torque_mag
[Newtons / Nm]
total_measured_wrench_at_tool_in_desired_tool Wrench Sometimes the arm cannot achieve the commanded wrench exactly because of the
underlying controller or arm pose. This looks at the joint torque sensors to
determine the actual force and torque being applied at the tool. [Newtons / Nm]

ArmImpedanceCommand.Request

Field Type Label Description
root_frame_name string Name of the frame relative to which the task frame is defined for this command.
Common frames for this include "odom", "vision", "body", and "flat_body".
root_tform_task SE3Pose This transform specifies the pose of the task frame relative to the root frame.
If unset, it defaults to identity, and the task frame coincides with the root frame.
The desired_tool frame will be specified relative to the task frame. For peg in
hole tasks for example, the task frame could be a frame attached to the top of the
hole with z-axis aligned with the hole axis, and the desired_tool frame could
move in z to direct the peg deeper into the hole.
wrist_tform_tool SE3Pose The tool pose relative to the parent link (link_wr1). This can also be thought of as the
"remote center" frame. For peg in hole tasks for example, one might put the tool frame
at the tip of the peg, or slightly below the tip floating in space, at the point on which
we want our virtual springs to pull.
Defaults to
[0.19557 0 0]
[1 0 0 0]
which is a frame aligned with the wrist frame, with its origin slightly in front of
the gripper's palm plate.
task_tform_desired_tool SE3Trajectory Trajectory of where we want the tool to be relative to the task frame. Note that this
desired_tool frame is not the same as the tool frame attached to the wrist link. If our
tool deviates from this desired_tool pose, it will be subject to a wrench determined by
our stiffness and damping matrices.
feed_forward_wrench_at_tool_in_desired_tool Wrench Feed forward wrench to apply at the tool, expressed with respect to the desired_tool
frame
diagonal_stiffness_matrix Vector Stiffness matrix in the desired_tool frame. The matrix is parameterized by a vector of
6 doubles, representing the diagonal of this 6x6 matrix: [x,y,z,tx,ty,tz] (N/m, N/m, N/m,
Nm/rad, Nm/rad, Nm/rad). All other entries will be set to 0. All stiffness values along
the diagonal should be non-negative.
diagonal_damping_matrix Vector Damping matrix in the desired_tool frame. The matrix is parameterized by a vector of 6
doubles, representing the diagonal of this 6x6 matrix: [x,y,z,tx,ty,tz] (Ns/m, Ns/m,
Ns/m, Nms/rad, Nms/rad, Nms/rad) All other entries will be set to 0. All damping values
along the diagonal should be non-negative.
max_force_mag google.protobuf.DoubleValue Maximum force magnitude in Newtons we're allowed to exert. If the tool deviates such that
the magnitude of the requested force would exceed this threshold, saturate the requested
force. If this value is not set, a default of 60N will be used.
max_torque_mag google.protobuf.DoubleValue Maximum torque magnitude in Newton meters we're allowed to exert. If the tool deviates
such that the magnitude of the requested torque would exceed this threshold, saturate the
requested torque. If this value is not set, a default of 15Nm will be used.
disable_safety_check google.protobuf.BoolValue Set to True to disable cancelling the trajectory for unsafe behaviors. NOTE: If
disable_safety_check is set to True, the robot may damage itself or the environment.
Extreme caution should be used when setting disable_safety_check to True.

ArmJointMoveCommand

Specify a set of joint angles to move the arm.

ArmJointMoveCommand.Feedback

Field Type Label Description
status ArmJointMoveCommand.Feedback.Status Current status of the request.
planner_status ArmJointMoveCommand.Feedback.PlannerStatus Current status of the trajectory planner.
planned_points ArmJointTrajectoryPoint repeated 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. The planner works on a
moving window of up to 10 points from the input trajectory, so the length of planned
points will be at most 10, and its contents will change over time for long trajectories.
time_to_goal google.protobuf.Duration 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.

ArmJointMoveCommand.Request

Field Type Label Description
trajectory ArmJointTrajectory 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.

ArmJointPosition

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.

Field Type Label Description
sh0 google.protobuf.DoubleValue
sh1 google.protobuf.DoubleValue
el0 google.protobuf.DoubleValue
el1 google.protobuf.DoubleValue
wr0 google.protobuf.DoubleValue
wr1 google.protobuf.DoubleValue

ArmJointTrajectory

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

Field Type Label Description
points ArmJointTrajectoryPoint repeated The points in our trajectory. (positions, (optional) velocity, (optional) time)
reference_time google.protobuf.Timestamp 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.
maximum_velocity google.protobuf.DoubleValue 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.
maximum_acceleration google.protobuf.DoubleValue 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.

ArmJointTrajectoryPoint

A set of joint angles and velocities that can be used as a point within a joint trajectory.

Field Type Label Description
position ArmJointPosition Desired joint angles in radians
velocity ArmJointVelocity Optional desired joint velocities in radians / sec
time_since_reference google.protobuf.Duration The time since reference at which we wish to achieve this position / velocity

ArmJointVelocity

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.

Field Type Label Description
sh0 google.protobuf.DoubleValue
sh1 google.protobuf.DoubleValue
el0 google.protobuf.DoubleValue
el1 google.protobuf.DoubleValue
wr0 google.protobuf.DoubleValue
wr1 google.protobuf.DoubleValue

ArmParams

Parameters common across arm commands.

Field Type Label Description
disable_body_force_limiter google.protobuf.BoolValue 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.

ArmStopCommand

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.

ArmStopCommand.Feedback

Stop command provides no feedback

ArmStopCommand.Request

Stop command takes no arguments.

ArmVelocityCommand

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.

ArmVelocityCommand.CartesianVelocity

Field Type Label Description
frame_name string The frame to express our velocities in
velocity_in_frame_name Vec3 The x-y-z velocity of the hand (m/s) with respect to the frame

ArmVelocityCommand.CylindricalVelocity

Field Type Label Description
linear_velocity CylindricalCoordinate 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).
max_linear_velocity google.protobuf.DoubleValue 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.

ArmVelocityCommand.Feedback

ArmVelocityCommand provides no feedback

ArmVelocityCommand.Request

Field Type Label Description
cylindrical_velocity ArmVelocityCommand.CylindricalVelocity
cartesian_velocity ArmVelocityCommand.CartesianVelocity
angular_velocity_of_hand_rt_odom_in_hand Vec3 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.
maximum_acceleration google.protobuf.DoubleValue Optional maximum acceleration magnitude of the end-effector. (m/s^2)
end_time google.protobuf.Timestamp The timestamp (in robot time) by which a command must finish executing.
This is a required field and used to prevent runaway commands.

GazeCommand

Move the hand in such a way to point it at a position in the world.

GazeCommand.Feedback

Field Type Label Description
status GazeCommand.Feedback.Status Current status of the command.
gazing_at_target bool If we are gazing at the target
Rotation from the current gaze point to the trajectory's end [radians]
gaze_to_target_rotation_measured float
hand_position_at_goal bool If the hand's position is at the goal.
Distance from the hand's current position to the trajectory's end [meters]
hand_distance_to_goal_measured float
hand_roll_at_goal bool 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]
hand_roll_to_target_roll_measured float

GazeCommand.Request

Field Type Label Description
target_trajectory_in_frame1 Vec3Trajectory Point(s) to look at expressed in frame1.
frame1_name string
tool_trajectory_in_frame2 SE3Trajectory Optional, desired pose of the tool expressed in frame2. Will be constrained to 'look at'
the target regardless of the requested orientation.
frame2_name string
wrist_tform_tool SE3Pose 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].
target_trajectory_initial_velocity google.protobuf.DoubleValue Optional velocity to move the target along the shortest path from the gaze's starting
position to the first point in the target trajectory.
maximum_acceleration google.protobuf.DoubleValue Optional Maximum acceleration magnitude of the end-effector.
Valid ranges (0, 20]
max_linear_velocity google.protobuf.DoubleValue Optional Maximum linear velocity magnitude of the end-effector. (m/s)
max_angular_velocity google.protobuf.DoubleValue Optional Maximum angular velocity magnitude of the end-effector. (rad/s)

NamedArmPositionsCommand

Command the arm move to a predefined configuration.

NamedArmPositionsCommand.Feedback

Field Type Label Description
status NamedArmPositionsCommand.Feedback.Status Current status of the request.

NamedArmPositionsCommand.Request

Field Type Label Description
position NamedArmPositionsCommand.Positions

ArmCartesianCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_TRAJECTORY_COMPLETE 1 Tool frame has reached the end of the trajectory within tracking error bounds.
STATUS_IN_PROGRESS 2 Robot is attempting to reach the target.
STATUS_TRAJECTORY_CANCELLED 3 Tool frame exceeded maximum allowable tracking error from the desired trajectory.
STATUS_TRAJECTORY_STALLED 4 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.

ArmCartesianCommand.Request.AxisMode

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.

Name Number Description
AXIS_MODE_POSITION 0
AXIS_MODE_FORCE 1

ArmImpedanceCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_TRAJECTORY_COMPLETE 1 Tool frame has reached the end of the trajectory, and is close to the desired_tool
in directions with high stiffness and no feed forwards
STATUS_IN_PROGRESS 2 Robot is moving along the desired_tool trajectory
STATUS_TRAJECTORY_STALLED 3 The arm has stopped making progress to the goal and the measured tool frame is far
from the desired_tool along directions where we expect good tracking
STATUS_TRAJECTORY_CANCELLED 4 Detected an arm instability, so the commanded motion was cancelled. Consider lowering
stiffness or lowering both stiffness and damping to improve stability.

ArmJointMoveCommand.Feedback.PlannerStatus

Name Number Description
PLANNER_STATUS_UNKNOWN 0 PLANNER_STATUS_UNKNOWN should never be used. If used, an internal error has happened.
PLANNER_STATUS_SUCCESS 1 A solution passing through the desired points and obeying the constraints was found.
PLANNER_STATUS_MODIFIED 2 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_FAILED 3 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.

ArmJointMoveCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened
STATUS_COMPLETE 1 The arm is at the desired configuration.
STATUS_IN_PROGRESS 2 Robot is re-configuring arm to get to desired configuration.
STATUS_STALLED 3 The arm has stopped making progress towards the goal. This could be because it is
avoiding a collision or joint limit.

GazeCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_TRAJECTORY_COMPLETE 1 Robot is gazing at the target at the end of the trajectory.
STATUS_IN_PROGRESS 2 Robot is re-configuring arm to gaze at the target.
STATUS_TOOL_TRAJECTORY_STALLED 3 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.

NamedArmPositionsCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_COMPLETE 1 The arm is at the desired configuration.
STATUS_IN_PROGRESS 2 Robot is re-configuring arm to get to desired configuration.
STATUS_STALLED_HOLDING_ITEM 3 Some requests may not execute if the gripper is holding an item declared not
stowable, e.g. POSITIONS_STOW with carry_state == CARRY_STATE_CARRIABLE. In these
situations, Spot will instead run an ArmStopCommand request while the blocking
condition remains true. Clearing the condition will cause the request to proceed and
the arm will start moving.

NamedArmPositionsCommand.Positions

Name Number Description
POSITIONS_UNKNOWN 0 Invalid request; do not use.
POSITIONS_CARRY 1 The carry position is a damped, force limited position close to stow, with the hand
slightly in front of the robot.
POSITIONS_READY 2 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_STOW 3 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.

Top

bosdyn/api/arm_surface_contact.proto

ArmSurfaceContact

ArmSurfaceContact lets you accurately move the robot’s arm in the world while having some ability to perform force control. This mode is useful for drawing, wiping, and other similar behaviors.

The message is similar to the ArmCartesianCommand message, which you can look at for additional details.

ArmSurfaceContact.Feedback

ArmSurfaceContact.Request

Field Type Label Description
root_frame_name string 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.
wrist_tform_tool SE3Pose 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 wrists orientation.
root_tform_task SE3Pose The fields below are specified in this optional task frame. If unset int defaults
to the identity transform and all quantities are therefore expressed in the root_frame_name.
pose_trajectory_in_task SE3Trajectory 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.
maximum_acceleration google.protobuf.DoubleValue Optional Maximum acceleration magnitude of the end-effector.
Valid ranges (0, 20]
max_linear_velocity google.protobuf.DoubleValue Optional Maximum linear velocity magnitude of the end-effector. (m/s)
max_angular_velocity google.protobuf.DoubleValue Optional Maximum angular velocity magnitude of the end-effector. (rad/s)
max_pos_tracking_error google.protobuf.DoubleValue 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
max_rot_tracking_error google.protobuf.DoubleValue max orientation tracking error in radians
force_remain_near_current_joint_configuration bool
preferred_joint_configuration ArmJointPosition
x_axis ArmSurfaceContact.Request.AxisMode
y_axis ArmSurfaceContact.Request.AxisMode
z_axis ArmSurfaceContact.Request.AxisMode
press_force_percentage Vec3 Amount of force to use on each axis, from 0 (no force) to 1.0 (maximum force), can also
be negative. Full range: [-1.0, 1.0]
xy_admittance ArmSurfaceContact.Request.AdmittanceSetting Admittance settings for each axis in the admittance frame.
z_admittance ArmSurfaceContact.Request.AdmittanceSetting
xy_to_z_cross_term_admittance ArmSurfaceContact.Request.AdmittanceSetting Cross term, making force in the XY axis cause movement in the z-axis.
By default is OFF
Setting this value will make the arm move in the negative Z-axis whenever it feels force in
the XY axis.
bias_force_ewrt_body Vec3 Specifies a force that the body should expect to feel. This allows the robot to "lean into"
an external force. Be careful using this field, because if you lie to the robot, it can
fall over.
gripper_command ClawGripperCommand.Request Gripper control
is_robot_following_hand bool Set to true to have robot is walk around to follow the hand.

ArmSurfaceContact.Request.AdmittanceSetting

Parameters for controlling admittance. By default, the robot will stop moving the arm when it encounters resistance. You can control that reaction to make the robot stiffer or less stiff by changing the parameters.

Name Number Description
ADMITTANCE_SETTING_UNKNOWN 0
ADMITTANCE_SETTING_OFF 1 No admittance.
ADMITTANCE_SETTING_NORMAL 2 Normal reaction to touching things in the world
ADMITTANCE_SETTING_LOOSE 3 Robot will not push very hard against objects
ADMITTANCE_SETTING_STIFF 4 Robot will push hard against the world
ADMITTANCE_SETTING_VERY_STIFF 5 Robot will push very hard against the world

ArmSurfaceContact.Request.AxisMode

If an axis is set to position mode (default), read desired from SE3Trajectory command. If mode is set to force, use the “press_force_percentage” field to determine force.

Name Number Description
AXIS_MODE_POSITION 0
AXIS_MODE_FORCE 1

Top

bosdyn/api/arm_surface_contact_service.proto

ArmSurfaceContactCommand

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to show ownership of the robot.
request ArmSurfaceContact.Request

ArmSurfaceContactResponse

Field Type Label Description
header ResponseHeader Common response header.

ArmSurfaceContactService

Method Name Request Type Response Type Description
ArmSurfaceContact ArmSurfaceContactCommand ArmSurfaceContactResponse

Top

bosdyn/api/auth.proto

GetAuthTokenRequest

The GetAuthToken request message includes login information for the robot.

Field Type Label Description
header RequestHeader Common request header.
username string Username to authenticate with. Must be set if password is set.
password string Password to authenticate with. Not necessary if token is set.
token string Token to authenticate with. Can be used in place of the password, to re-mint a token.

GetAuthTokenResponse

The GetAuthToken response message includes an authentication token if the login information is correct and succeeds.

Field Type Label Description
header ResponseHeader
status GetAuthTokenResponse.Status The status of the grpc GetAuthToken request.
token string Token data. Only specified if status == STATUS_OK.

GetAuthTokenResponse.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_OK 1 STATUS_OK indicates that authentication has succeeded. The 'token' field field will
be populated with a session token that can be used to authenticate the user.
STATUS_INVALID_LOGIN 2 STATUS_INVALID_LOGIN indicates that authentication has failed since an invalid
username and/or password were provided.
STATUS_INVALID_TOKEN 3 STATUS_INVALID_TOKEN indicates that authentication has failed since the 'token'
provided in the request is invalid. Reasons for the token being invalid could be
because it has expired, because it is improperly formed, for the wrong robot, the
user that the token is for has changed a password, or many other reasons. Clients
should use username/password-based authentication when refreshing the token fails.
STATUS_TEMPORARILY_LOCKED_OUT 4 STATUS_TEMPORARILY_LOCKED_OUT indicates that authentication has failed since
authentication for the user is temporarily locked out due to too many unsuccessful
attempts. Any new authentication attempts should be delayed so they may happen after
the lock out period ends.

Top

bosdyn/api/auth_service.proto

AuthService

The AuthService provides clients the ability to convert a user/password pair into a token. The token can then be added to the http2 headers for future requests in order to establish the identity of the requester.

Method Name Request Type Response Type Description
GetAuthToken GetAuthTokenRequest GetAuthTokenResponse Request to get the auth token for the robot.

Top

bosdyn/api/auto_return/auto_return.proto

ConfigureRequest

Configure the AutoReturn system.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
leases bosdyn.api.Lease repeated Leases that AutoReturn may use to accomplish its goals when AutoReturn automatically
triggers. If left empty, AutoReturn will not automatically trigger.
params Params Parameters to use when AutoReturn automatically triggers.
clear_buffer bool Forget any buffered locations the robot may be remembering. Defaults to false.
Set to true if the robot has just crossed an area it should not traverse in AutoReturn.

ConfigureResponse

Response to a configuration request.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status ConfigureResponse.Status Return status for the request.
invalid_params Params If status is STATUS_INVALID_PARAMS, this contains the settings that were invalid.

GetConfigurationRequest

Ask for the current configuration.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetConfigurationResponse

Response to a “get configuration” request.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
enabled bool A simple yes/no, will AutoReturn automatically trigger.
request ConfigureRequest The most recent successful ConfigureRequest.
Will be empty if service has not successfully been configured.

Params

Parameters to AutoReturn actions.

Field Type Label Description
mobility_params google.protobuf.Any Robot-specific mobility parameters to use.
For example, see bosdyn.api.spot.MobilityParams.
max_displacement float Allow AutoReturn to move the robot this far in the XY plane from the location where
AutoReturn started. Travel along the Z axis (which is gravity-aligned) does not count.
Must be > 0.

meters
max_duration google.protobuf.Duration Optionally specify the maximum amount of time AutoReturn can take.
If this duration is exceeded, AutoReturn will stop trying to move the robot.
Omit to try indefinitely. Robot may become stuck and never take other comms loss actions!

StartRequest

Start AutoReturn behavior now.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
leases bosdyn.api.Lease repeated Leases that AutoReturn may use to accomplish its goals.
If left empty, use the leases specified in ConfigureRequest.
If empty and no leases have been specified by ConfigureRequest, the response will have a
CODE_INVALID_REQUEST in the header.
params Params Parameters to use.
If left empty, use the params specified in ConfigureRequest.
If empty and no params have been specified by ConfigureRequest, the response will have a
CODE_INVALID_REQUEST in the header.

StartResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status StartResponse.Status
invalid_params Params If status is STATUS_INVALID_PARAMS, this contains the settings that were invalid.

ConfigureResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_INVALID_PARAMS 2

StartResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_INVALID_PARAMS 2

Top

bosdyn/api/auto_return/auto_return_service.proto

AutoReturnService

Method Name Request Type Response Type Description
Configure ConfigureRequest ConfigureResponse Configure the service.
GetConfiguration GetConfigurationRequest GetConfigurationResponse Get the current configuration.
Start StartRequest StartResponse Start AutoReturn now.

Top

bosdyn/api/autowalk/autowalk.proto

CompileAutowalkRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
walk Walk Walk to compile.
treat_warnings_as_errors bool If this is set to true, mission compilation will fail if the Walk contains parameters that
are set incorrectly. This can be useful during development to help the developer find issues
with their client (e.g., suppose the client UI allows a user to set a parameter incorrectly).
If this is set to false, mission compilation is more likely to succeed for the same Walk
because any parameters that are both incorrect and modifiable are modified during mission
compilation.

CompileAutowalkResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status CompileAutowalkResponse.Status Result of compiling the mission.
root bosdyn.api.mission.Node Root node of compiled walk.
element_identifiers ElementIdentifiers repeated There will be one ElementIdentifier for each Element in the input Walk.
The index of each ElementIdentifier corresponds to the index of the Element in the input
Walk. Skipped elements will have default values for id's. (0 and empty string)
failed_elements CompileAutowalkResponse.FailedElementsEntry repeated If certain elements failed compilation, they will be reported back in this field.
The map correlates the index of the Element in the input Walk to the FailedElement.
docking_node NodeIdentifier Final docking node.
loop_node NodeIdentifier Node that contains the main sequence of actions performed in the walk.
In continuous playback mode, the walk repeats when this node completes.

CompileAutowalkResponse.FailedElementsEntry

Field Type Label Description
key int32
value FailedElement

ElementIdentifiers

Field Type Label Description
root_id NodeIdentifier Deprecated. Identifiable data for the root node of the element.
Deprecated as of 4.0. Please use navigation_id instead.
action_id NodeIdentifier Identifiable data for action node of the element.
navigation_id NodeIdentifier Identifiable data for the navigation node of the element.

FailedElement

Field Type Label Description
errors string repeated The reasons why this element failed. May not be provided by all elements.
warnings string repeated Compile time modification that resolved error(s).

LoadAutowalkRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
walk Walk Walk to compile
leases bosdyn.api.Lease repeated Leases that will be needed to validate the mission.
Usually, no leases are necessary for validation, and this can be left empty.
treat_warnings_as_errors bool If this is set to true, mission compilation will fail if the Walk contains parameters that
are set incorrectly. This can be useful during development to help the developer find issues
with their client (e.g., suppose the client UI allows a user to set a parameter incorrectly).
If this is set to false, mission compilation is more likely to succeed for the same Walk
because any parameters that are both incorrect and modifiable are modified during mission
compilation.

LoadAutowalkResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status LoadAutowalkResponse.Status Result of loading the mission.
lease_use_results bosdyn.api.LeaseUseResult repeated Results from any leases that may have been used.
As part of mission validation, some of the non-mission leases may have been used.
failed_nodes bosdyn.api.mission.FailedNode repeated If certain nodes failed compilation or validation, they will be reported back in this field.
element_identifiers ElementIdentifiers repeated There will be one ElementIdentifier for each Element in the input Walk.
The index of each ElementIdentifier corresponds to the index of the Element in the input
Walk. Skipped elements will have default values for id's. (0 and empty string)
failed_elements LoadAutowalkResponse.FailedElementsEntry repeated If certain elements failed compilation, they will be reported back in this field.
The map correlates the index of the Element in the input Walk to the FailedElement.
mission_id int64 Mission ID assigned by the mission service.
docking_node NodeIdentifier Final docking node.
loop_node NodeIdentifier Node that contains the main sequence of actions performed in the walk.
In continuous playback mode, the walk repeats when this node completes.

LoadAutowalkResponse.FailedElementsEntry

Field Type Label Description
key int32
value FailedElement

NodeIdentifier

Field Type Label Description
node_id int64 Unique integer set by the mission service when loading a mission.
user_data_id string Unique string set by the autowalk service when compiling a walk.

CompileAutowalkResponse.Status

Possible results of compiling a walk to mission.

Name Number Description
STATUS_UNKNOWN 0 Invalid status, do not use.
STATUS_OK 1 Compilation succeeded.
STATUS_COMPILE_ERROR 2 Compilation failed. The walk was malformed.

LoadAutowalkResponse.Status

Possible results of loading a mission.

Name Number Description
STATUS_UNKNOWN 0 Invalid status, do not use.
STATUS_OK 1 The mission was loaded successfully.
STATUS_COMPILE_ERROR 2 Compilation failed. The walk was malformed.
STATUS_VALIDATE_ERROR 3 Load-time validation failed. Some part of the mission was unable to initialize.

Top

bosdyn/api/autowalk/autowalk_service.proto

AutowalkService

Method Name Request Type Response Type Description
CompileAutowalk .bosdyn.api.DataChunk stream .bosdyn.api.DataChunk stream Compile a walk into a mission.
Input DataChunks should deserialize into a CompileAutowalkRequest.
Output DataChunks should deserialize into a CompileAutowalkResponse.
This rpc is stateless.
LoadAutowalk .bosdyn.api.DataChunk stream .bosdyn.api.DataChunk stream Compile a walk into a mission then load to mission service.
Input DataChunks should deserialize into a LoadAutowalkRequest.
Output DataChunks should deserialize into a LoadAutowalkResponse.

Top

bosdyn/api/autowalk/walks.proto

Action

An Action is what the robot should do at a location. For example, the user may desire that the robot perform a laser scan at a given waypoint.

Field Type Label Description
sleep Action.Sleep
data_acquisition Action.DataAcquisition
remote_grpc Action.RemoteGrpc
execute_choreography Action.ExecuteChoreography
node bosdyn.api.mission.Node This field can be used to specify a behavior tree as an action. If the user had
two callbacks they would like to run simultaneously at the waypoint this action
is associated with, they could use create a behavior tree inside Node with both
callbacks embedded in a simple parallel.
The downside of using node, is that editors might not support editing parameters
directly.

Action.DataAcquisition

For actions associated with the Data Acquisition Service.

Field Type Label Description
acquire_data_request bosdyn.api.AcquireDataRequest The autowalk service replaces the action_name field in the CaptureActionId with the
element name.
completion_behavior bosdyn.api.mission.DataAcquisition.CompletionBehavior
last_known_capabilities bosdyn.api.AcquisitionCapabilityList Last known Data Acquisition capabilities.
record_time_images bosdyn.api.ImageCaptureAndSource repeated Any images taken at action creation time. For DataAcquisition actions, this includes:
- Any images in the Data Acquisition capture.
- Any images that are inputs to NCB workers that are in the Data Acquisition capture.
- Any images that a Data Acquisition plugin in the Data Acquisition capture requests a
region of interest for.

Note that both this message and AcquisitionCapabilityList will contain the
Spec for images sources. This message will contain the spec at record time,
while last_known_capabilities should be updated as time progresses and services
evolve.

This data is meant to allow UI's to give users context about their actions, AND
provide them a canvas to edit region of interests with after the fact. It is
not used at mission playback time.

Action.ExecuteChoreography

Field Type Label Description
sequence_name string The name of the sequence to play.

Action.RemoteGrpc

Field Type Label Description
service_name string Name of the service in the directory.
rpc_timeout google.protobuf.Duration Timeout of any single RPC. If the timeout is exceeded, the RPC will fail. The mission
service treats each failed RPC differently:
- EstablishSession: An error is returned in LoadMission.
- Tick: The RPC is retried.
- Stop: The error is ignored, and the RPC is not retried.
Omit for a default of 60 seconds.
lease_resources string repeated Resources that we will need leases on.
inputs bosdyn.api.mission.KeyValue repeated Deprecated. The list of variables the remote host should receive.
Variables given can be available at either run-time or compile-time.
The "key" in KeyValue is the name of the variable as used by the remote system.
DEPRECATED as of 3.3. Please use 'parameters' instead.
parameters bosdyn.api.CustomParamCollection All specifications and any values chosen at record time.
record_time_images bosdyn.api.ImageCaptureAndSource repeated Any images taken at action creation time. For RemoteGRPC's, this will only happen
if the RemoteGRPC advertises parameters that require a region of interest for a specific
camera.

This data is meant to allow UI's to give users context about their actions, AND
provide them a canvas to edit region of interests with after the fact. It is
not used at mission playback time.

Action.Sleep

The robot does nothing but wait while also performing its ActionWrapper(s). For example, if the user wants the robot to pose for some amount of time (while doing nothing else), they would populate an ActionWrapper with Pose and set the desired duration here accordingly.

Field Type Label Description
duration google.protobuf.Duration

ActionWrapper

An ActionWrapper is what the robot should do prior to and during an action. For example, the user may desire that the robot stand in such a way that its z-axis is aligned with the gravity vector, even though it is standing on an incline.

Field Type Label Description
robot_body_sit ActionWrapper.RobotBodySit
robot_body_pose ActionWrapper.RobotBodyPose
spot_cam_led ActionWrapper.SpotCamLed
spot_cam_ptz ActionWrapper.SpotCamPtz
arm_sensor_pointing ActionWrapper.ArmSensorPointing
spot_cam_alignment ActionWrapper.SpotCamAlignment
gripper_camera_params ActionWrapper.GripperCameraParams
gripper_command ActionWrapper.GripperCommand

ActionWrapper.ArmSensorPointing

Position the body and perform a joint move and cartesian command in target frame

Field Type Label Description
joint_trajectory bosdyn.api.ArmJointTrajectory Arm Joint Move Command
The joint trajectory to execute in the initial rough pointing joint move.
wrist_tform_tool bosdyn.api.SE3Pose Arm Cartesian Command
The tool pose relative to the parent link (wrist).
Defaults to a frame with it's origin slightly in front of the gripper's palm plate
aligned with the wrist's orientation.
pose_trajectory_rt_target bosdyn.api.SE3Trajectory A 3D pose trajectory for the tool expressed in target frame,
target_tform_measured_offset bosdyn.api.SE2Pose Robot desired stance relative to waypoint
This is taken by measuring the average of the footprints
in body frame at the time of waypoint creation.
This is used to generate the stance command.
Target == waypoint.
This assumes the waypoint is gravity aligned.
body_assist_params bosdyn.api.spot.BodyControlParams.BodyAssistForManipulation Body mobility params during cartesian move
force_stow_override bool If true, the arm will stow after this action no matter what.
If false, the arm will only stow if the next action is far away.

ActionWrapper.GripperCameraParams

Set the camera params of the gripper camera

Field Type Label Description
params bosdyn.api.GripperCameraParams

ActionWrapper.GripperCommand

Field Type Label Description
request bosdyn.api.GripperCommand.Request
disable_post_action_close bool By default, any action that includes a GripperCommand action wrapper will run
the specified command BEFORE the action is run. By default, after the action
is run the gripper will be closed. This behavior can be turned off by setting
this flag to true.

ActionWrapper.RobotBodyPose

Pose the robot prior to performing the action

Field Type Label Description
target_tform_body bosdyn.api.SE3Pose If your Target is a graph_nav waypoint, this pose will be relative
to the waypoint you are navigating to. If no target was specified,
this parameter will be ignored and the robot will stand in a generic
pose.

ActionWrapper.RobotBodySit

Sit the robot prior to performing the action

ActionWrapper.SpotCamAlignment

Align SpotCam to a waypoint. Cannot be used with SpotCamPtz or RobotBodyPose

Field Type Label Description
alignments ActionWrapper.SpotCamAlignment.Alignment repeated List of alignments to perform
target_tform_sensor bosdyn.api.SE3Pose Desired transform from the sensor to the target
final_zoom float Final zoom the camera should be after all alignments have finished
target_sensor_ids string repeated Optional list of sensor names which should be unobstructed after alignment

ActionWrapper.SpotCamAlignment.Alignment

Field Type Label Description
zoom float Camera zoom parameter
sensor_id string Sensor to use for alignment
scene_object_id string
is_skipped bool If true, this alignment will be skipped during playback
focus_state bosdyn.api.spot_cam.PtzFocusState Focus state used during alignment. Defaults to auto-focus.

ActionWrapper.SpotCamLed

Set the brightness of the LEDs on the SpotCam.

Field Type Label Description
brightnesses ActionWrapper.SpotCamLed.BrightnessesEntry repeated There are four LEDs at indices [0, 3]. The brightness for each LED
may be set between [0.0, 1.0], where 0 is off and 1 is full
brightness.

ActionWrapper.SpotCamLed.BrightnessesEntry

Field Type Label Description
key int32
value float

ActionWrapper.SpotCamPtz

Set the pan, tilt, and zoom of the SpotCam.

Field Type Label Description
ptz_position bosdyn.api.spot_cam.PtzPosition See bosdyn/api/spot_cam

BatteryMonitor

If your mission has docks, autowalk can pause the mission to return to the dock if the battery gets too low. Use this message to control when this behavior happens.

Field Type Label Description
battery_start_threshold float Once charging, the robot will continue to charge until the battery
level is greater than or equal to this threshold, at which point in
time, the mission will start.
battery_stop_threshold float If the battery level is less than or equal to this threshold, the
robot will stop what it is currently doing and return to the dock.
Once the battery level is greater than or equal to the battery start
threshold, the mission will resume.

ChoreographyItems

Choreography elements required for the mission.

Field Type Label Description
choreography_sequences bosdyn.api.spot.ChoreographySequence repeated Any sequences we need to play the mission.
animated_moves bosdyn.api.spot.Animation repeated Any animations we need if we want to play the sequence.

Dock

The dock itself and the target associated with it

Field Type Label Description
dock_id uint32 The docking station ID of the dock corresponds to the number printed on the
fiducial, below the part of the fiducial that looks like a QR code.
Only fiducial IDs greater than or equal to 500 should be
used here because they are reserved for docks.
docked_waypoint_id string To maximize reliability, at record time, the client should dock the robot
while graph_nav is still recording. When the robot is finished docking,
the client should create a waypoint on top of the dock, while the robot is
docked, and then stop recording. The waypoint created while the
robot is sitting on the dock should be specified here.
target_prep_pose Target When it is time for the robot to dock, it will approach this target
before issuing docking commands. If the user is using graph_nav, the
final waypoint in the NavigateRoute OR the waypoint ID in the
NavigateTo MUST be at the docking prep pose. To do this, send a docking
command to move the robot to the docking prep pose. Then, create a
waypoint at the docking prep pose location. Graph_nav is responsible for
navigating the robot to the docking prep pose. Once the robot is in the
docking prep pose, the docking service does the rest.
prompt_duration google.protobuf.Duration At mission playback, if the robot is unable to reach the dock OR successfully
dock, the mission will let the operator know with a user question. If the operator
does not answer, the robot will safely power off. This parameter controls
how long the operator has to answer.
This parameter also controls how long robot will wait to retry to undock on
a failed undock.

Element

An Element is the basic building block of the autowalk.

Field Type Label Description
name string The name of an element may be anything, but it is good practice to choose
something that describes the physical location and action that is occurring
(e.g., boiler room laser scan).
target Target Location the robot should navigate to.
target_failure_behavior FailureBehavior Describes what to do if the robot fails to navigate to target.
action Action Action performed at target destination
action_wrapper ActionWrapper Actions performed by the robot and/or payloads prior to and during an action.
action_failure_behavior FailureBehavior Describes what to do if the robot fails to execute the action.
is_skipped bool Set to true to skip element.
battery_monitor BatteryMonitor If the mission requires more than one battery, the robot needs to return
to the dock and charge before it can complete the mission.
This field defines the battery percentage thresholds that at which the robot
should pause and resume mission execution.
Considering using various thresholds depending on the target's distance from the dock
action_duration google.protobuf.Duration Maximum duration of action execution time, including all wrappers.
If they take longer than this duration, the action will be considered a failure.
Not including, or including a zero duration will set the action to NOT have a
timeout.
id string Unique identifier for this element. This will be embedded in various Data Acquisition
captures and various logging bundles. This should be globally unique across all elements.

FailureBehavior

Field Type Label Description
retry_count int32 The mission can automatically retry navigating to a waypoint or
performing an action. Automatic retries can increase the probability of
successfully navigating to a waypoint, but may cause the robot to take
an unexpected path. Similarly, they can increase the probability of
successfully collecting data for an action, but also increase the amount
of time a mission takes. If the client does not want the robot to
automatically retry navigating to a waypoint or performing an action,
set this to 0. If the client wants the robot to automatically retry
navigating to a waypoint or performing an action, set this to the
desired number of retries. For example, if the client would like the
action to be retried once, set this equal to 1. If this is unset or set
to 0, no retry will occur.
prompt_duration google.protobuf.Duration At mission playback, if something fails (e.g., the robot gets stuck,
an action fails), the user will get all possible actions as options
in a question to choose from. If the user does not answer, the mission
will fall back to the default behavior after this timeout. The default
behaviors are defined by the default_behavior one_of. A minimum
duration of 10 seconds is enforced.
safe_power_off FailureBehavior.SafePowerOff
proceed_if_able FailureBehavior.ProceedIfAble
return_to_start_and_try_again_later FailureBehavior.ReturnToStartAndTryAgainLater
return_to_start_and_terminate FailureBehavior.ReturnToStartAndTerminate

FailureBehavior.ProceedIfAble

If a failure occurs and the prompt has not been answered, the robot will proceed to the next action if able to do so. This may lead to different behavior at mission playback than at mission recording (e.g., the robot may take a different route, the robot may fail to collect the data for an action).

FailureBehavior.ReturnToStartAndTerminate

Only available in missions with a dock! If robot can get back to the dock, it will, and if it does, the mission will end.

FailureBehavior.ReturnToStartAndTryAgainLater

Only available in missions with a dock! If a failure occurs and the prompt has not been answered, the robot will return to the start of the mission. Once at the start of the mission, the robot will attempt to dock. If successfully, robot will try again later after the specified delay.

Field Type Label Description
try_again_delay google.protobuf.Duration How long to wait at start of mission (or on dock) before trying again.
A minimum duration of 60 seconds is enforced.

FailureBehavior.SafePowerOff

If a failure occurs and the prompt has not been answered, the robot will sit down and power off. This is the safest option.

Field Type Label Description
request bosdyn.api.SafePowerOffCommand.Request

GlobalParameters

These parameters apply to the entire autowalk.

Field Type Label Description
group_name string If the mission contains data acquisitions, this will be their group name.
The actual group name used will include the specified group name, and additional
qualifiers to ensure its unique for each start of this mission.
should_autofocus_ptz bool If the mission contains SpotCAM PTZ actions, set this to true. At the start of the
mission (or if the robot falls), the SpotCAM PTZ autofocus will be reset, thereby
improving the quality of the subsequent PTZ captures.
self_right_attempts int32 The mission can automatically self-right the robot. Autonomous self-rights
can damage the robot, its payloads, and its surroundings. If the user
does not want the robot to self-right on its own, set this number to 0.
If the user does want the robot to self-right itself, the user may set a
maximum number of attempts so that the robot does not destroy itself by
repeatedly falling and getting up and falling again.
post_mission_callbacks Action.RemoteGrpc repeated The callbacks that will be executed at the end of the mission. Functionality that
is often found in post-mission callbacks includes uploading data to the cloud or
sending an email. The callbacks will be executed serially (first in, first executed).
skip_actions bool It can be useful to have the robot run a walk without collecting data.
If this boolean is set to true, the compiled mission will still navigate to the
target of each element, however it will not actually perform the associated
action & action wrappers.

PlaybackMode

The playback mode governs how many times the mission is played back (once or more), at what interval the playbacks should occur (e.g., every 2 hours), and if docking is involved, the battery level thresholds at which the robot should either (1) stop and charge or (2) start the playback process again.

Field Type Label Description
once PlaybackMode.Once
periodic PlaybackMode.Periodic
continuous PlaybackMode.Continuous

PlaybackMode.Continuous

The mission should be played continuously only stopping if a battery monitor stop threshold is crossed.

PlaybackMode.Once

The mission should be played back once.

Field Type Label Description
skip_docking_after_completion bool Boolean to allow the robot to not dock after completing a mission.

PlaybackMode.Periodic

The mission should be played back periodically.

Field Type Label Description
interval google.protobuf.Duration The interval is the time that will elapse between the mission
finishing and starting again. It is applied relative to the time at
which the mission finishes. For example, if the user sets the
interval to 2 hours, starts the mission at 12:00, and the mission
takes one hour (finishes at 13:00), the next mission would start at
15:00, NOT 14:00.
Next mission start time = current mission end time + interval
repetitions int32 The number of times the mission should be played back. If set to 1,
the interval no longer applies and the mission will be played back
once. If set to two or more, the mission will run that number of
times, with the amount of time between playbacks equal to the
interval. If set to zero, the mission will run "forever".

Target

A Target is the location the robot should navigate to.

Field Type Label Description
navigate_to Target.NavigateTo
navigate_route Target.NavigateRoute
relocalize Target.Relocalize If set, upon reaching the target the robot will perform an explicit relocalization.
This should increase the accuracy of the robots belief of it's position on the map.
After relocalizing, the robot will re-navigate to the target.
target_stow_behavior Target.TargetStowBehavior

Target.NavigateRoute

Tell the robot to follow a route to a waypoint. If the robot is off the route (i.e., “far” from the route) when NavigateRoute is sent, the robot may navigate in unexpected ways.

Field Type Label Description
route bosdyn.api.graph_nav.Route A route for the robot to follow.
travel_params bosdyn.api.graph_nav.TravelParams Parameters that define how to traverse and end the route. For
example, the user may decide how close to the destination waypoint
the robot needs to be in order to declare success.

Target.NavigateTo

Tell the robot to navigate to a waypoint. It will choose its route.

Field Type Label Description
destination_waypoint_id string A unique string corresponding to the waypoint ID that the robot
should go to.
travel_params bosdyn.api.graph_nav.TravelParams Parameters that define how to traverse and end the route. For
example, the user may decide how close to the destination waypoint
the robot needs to be in order to declare success.

Target.Relocalize

Field Type Label Description
set_localization_request bosdyn.api.graph_nav.SetLocalizationRequest Some SetLocalizationRequests require that waypoint snapshots contain full images.
Make sure your client is downloading / storing / uploading full snapshots if you
plan on using this feature in your client.

Walk

Field Type Label Description
global_parameters GlobalParameters Parameters that apply to the entire mission.
playback_mode PlaybackMode Governs the mode and frequency at which playbacks occur.
map_name string The name of the map this mission corresponds to.
mission_name string The name of the mission.
elements Element repeated The list of actions and their associated locations.
docks Dock repeated The docks the mission can dock at.
AT THE MOMENT AUTOWALK ONLY SUPPORTS A SINGLE DOCK.
However, this is subject to change.
id string Unique identifier for this walk. This will be embedded in various Data Acquisition captures
and various logging bundles. This should be globally unique across all walks.
choreography_items ChoreographyItems Choreography related dependencies (any sequences and animations a robot needs to play this walk).

Target.TargetStowBehavior

Name Number Description
TARGET_STOW_BEHAVIOR_UNKNOWN 0 Will default to TARGET_STOW_BEHAVIOR_AUTO
TARGET_STOW_BEHAVIOR_AUTO 1 Compiler will do some heuristics to figure out if we should stow.
Headed back to dock = stow
Headed to another action that doesn't use arm sensor pointing = stow
Headed to another action that uses arm sensor pointing and is far away = stow
Headed to another action that uses arm sensor pointing and is close = don't stow
TARGET_STOW_BEHAVIOR_NEVER 2 Never ever stow the arm on the way to this action.
TARGET_STOW_BEHAVIOR_ALWAYS 3 Always stow the arm on the way to this action.

Top

bosdyn/api/basic_command.proto

ArmDragCommand

ArmDragCommand.Feedback

Field Type Label Description
status ArmDragCommand.Feedback.Status

ArmDragCommand.Request

BatteryChangePoseCommand

Get the robot into a convenient pose for changing the battery

BatteryChangePoseCommand.Feedback

Field Type Label Description
status BatteryChangePoseCommand.Feedback.Status

BatteryChangePoseCommand.Request

Field Type Label Description
direction_hint BatteryChangePoseCommand.Request.DirectionHint

ConstrainedManipulationCommand

ConstrainedManipulationCommand.Feedback

Field Type Label Description
status ConstrainedManipulationCommand.Feedback.Status
desired_wrench_odom_frame Wrench Desired wrench in odom world frame, applied at hand frame origin
estimation_activated google.protobuf.BoolValue A boolean signal indicating constrained manipulation has seen
enough motion to estimate the constraint and that the wrench
is being applied along the estimated directions.

ConstrainedManipulationCommand.Request

Field Type Label Description
frame_name string Frame that the initial wrench will be expressed in
init_wrench_direction_in_frame_name Wrench Direction of the initial wrench to be applied
Depending on the task, either the force vector or the
torque vector are required to be specified. The required
vector should not have a magnitude of zero and will be
normalized to 1. For tasks that require the force vector,
the torque vector can still be specified as a non-zero vector
if it is a good guess of the axis of rotation of the task.
(for e.g. TASK_TYPE_SE3_ROTATIONAL_TORQUE task types.)
Note that if both vectors are non-zero, they have to be perpendicular.
Once the constrained manipulation system estimates the
constraint, the init_wrench_direction and frame_name
will no longer be used.
tangential_speed double Recommended values are in the range of [-4, 4] m/s
rotational_speed double Recommended values are in the range of [-4, 4] rad/s
force_limit google.protobuf.DoubleValue The limit on the force that is applied on any translation direction
Value must be positive
If unspecified, a default value of 40 N will be used.
torque_limit google.protobuf.DoubleValue The limit on the torque that is applied on any rotational direction
Value must be positive
If unspecified, a default value of 4 Nm will be used.
task_type ConstrainedManipulationCommand.Request.TaskType
end_time google.protobuf.Timestamp The timestamp (in robot time) by which a command must finish executing.
This is a required field and used to prevent runaway commands.
enable_robot_locomotion google.protobuf.BoolValue Whether to enable the robot to take steps during constrained manip to keep the hand in
the workspace.
control_mode ConstrainedManipulationCommand.Request.ControlMode
target_linear_position double Desired linear position to travel for task type
TASK_TYPE_R3_LINEAR_FORCE
target_angle double Desired rotation in task space for all tasks other than
TASK_TYPE_R3_LINEAR_FORCE
This angle is about the estimated axis of rotation.
accel_limit google.protobuf.DoubleValue Acceleration limit for the planned trajectory in the free task DOF.
Note that the units of this variable will be m/(s^2) or rad/(s^2) depending
on the choice of target_linear_position vs. target_angle above.
reset_estimator google.protobuf.BoolValue Constrained manipulation estimates the task frame given the observed initial motion.
Setting this to false saves and uses the estimation state from the previous
constrained manipulation move. This is true by default.

FollowArmCommand

The base will move in response to the hand’s location, allow the arm to reach beyond its current workspace. If the hand is moved forward, the body will begin walking forward to keep the base at the desired offset from the hand.

FollowArmCommand.Feedback

FollowArmCommand commands provide no feedback.

FollowArmCommand.Request

Field Type Label Description
body_offset_from_hand Vec3 Optional body offset from the hand.
For example, to have the body 0.75 meters behind the hand, use (0.75, 0, 0)
disable_walking bool Deprecated. DEPRECATED as of 3.1.
To reproduce the robot's behavior of disable_walking == true,
issue a StandCommand setting the enable_body_yaw_assist_for_manipulation and
enable_hip_height_assist_for_manipulation MobilityParams to true. Any combination
of the enable_*_for_manipulation are accepted in stand giving finer control of
the robot's behavior.

FreezeCommand

Freeze all joints at their current positions (no balancing control).

FreezeCommand.Feedback

Freeze command provides no feedback.

FreezeCommand.Request

Freeze command request takes no additional arguments.

JointCommand

JointCommand.Feedback

Field Type Label Description
status JointCommand.Feedback.Status
num_messages_received uint64 Number of UpdateRequest messages received through the stream

JointCommand.Request

Empty message, no paramaters required to activate.

JointCommand.UpdateRequest

Field Type Label Description
end_time google.protobuf.Timestamp The timestamp (in robot time) when the command will stop executing. This is a
required field and used to prevent runaway commands.
reference_time google.protobuf.Timestamp (Optional) joint trajectory reference time. See extrapolation_time for detailed
explanation. If unspecified, this will default to the time the command is received.
If the time is in the future, no extrapolation will be performed until that time
(extrapolation never goes backwards in time)
extrapolation_duration google.protobuf.Duration (Optional) joint trajectory extrapolation time. If specified, the robot will extrapolate
desired position based on desired velocity, starting at reference_time for at most
extrapolation_duration (or until end_time, whichever is sooner)
position float repeated Commanded joint details
velocity float repeated
load float repeated
gains JointCommand.UpdateRequest.Gains Gains are required to be specified on the first message. After that can be optionally
updated by filling out the gains message again. Partial updates of gains are not
supported, a full gain set must be specified each time.
user_command_key uint32 user_command_key is optional, but it can be used for tracking when commands take effect
on the robot and calculating latencies. Avoid using 0
velocity_safety_limit google.protobuf.FloatValue (Optional) Joint velocity safety limit. Possibly useful during initial development or
gain tuning. If the magnitude of any joint velocity passes the threshold the robot will
trigger a behavior fault and go into a safety state. Client must power down the robot or
clear the behavior fault via the Robot Command Service. Values less than or equal to 0
will be considered invalid and must be sent in every UpdateRequest for use.

JointCommand.UpdateRequest.Gains

Field Type Label Description
k_q_p float repeated position error proportional coefficient
k_qd_p float repeated velocity error proportional coefficient

RobotCommandFeedbackStatus

SE2TrajectoryCommand

Move along a trajectory in 2D space.

SE2TrajectoryCommand.Feedback

The SE2TrajectoryCommand will provide feedback on whether or not the robot has reached the final point of the trajectory.

Field Type Label Description
status SE2TrajectoryCommand.Feedback.Status Current status of the command.
body_movement_status SE2TrajectoryCommand.Feedback.BodyMovementStatus Current status of how the body is moving
final_goal_status SE2TrajectoryCommand.Feedback.FinalGoalStatus Flag indicating if the final requested position was achievable.

SE2TrajectoryCommand.Request

Field Type Label Description
end_time google.protobuf.Timestamp The timestamp (in robot time) by which a command must finish executing.
This is a required field and used to prevent runaway commands.
se2_frame_name string The name of the frame that trajectory is relative to. The trajectory
must be expressed in a gravity aligned frame, so either "vision",
"odom", or "body". Any other provided se2_frame_name will be rejected
and the trajectory command will not be exectuted.
trajectory SE2Trajectory The trajectory that the robot should follow, expressed in the frame
identified by se2_frame_name.

SE2VelocityCommand

Move the robot at a specific SE2 velocity for a fixed amount of time.

SE2VelocityCommand.Feedback

Planar velocity commands provide no feedback.

SE2VelocityCommand.Request

Field Type Label Description
end_time google.protobuf.Timestamp The timestamp (in robot time) by which a command must finish executing. This is a
required field and used to prevent runaway commands.
se2_frame_name string The name of the frame that velocity and slew_rate_limit are relative to.
The trajectory must be expressed in a gravity aligned frame, so either
"vision", "odom", or "flat_body". Any other provided
se2_frame_name will be rejected and the velocity command will not be executed.
velocity SE2Velocity Desired planar velocity of the robot body relative to se2_frame_name.
slew_rate_limit SE2Velocity If set, limits how quickly velocity can change relative to se2_frame_name.
Otherwise, robot may decide to limit velocities using default settings.
These values should be non-negative.

SafePowerOffCommand

Get robot into a position where it is safe to power down, then power down. If the robot has fallen, it will power down directly. If the robot is standing, it will first sit then power down. With appropriate request parameters and under limited scenarios, the robot may take additional steps to move to a safe position. The robot will not power down until it is in a sitting state.

SafePowerOffCommand.Feedback

The SafePowerOff will provide feedback on whether or not it has succeeded in powering off the robot yet.

Field Type Label Description
status SafePowerOffCommand.Feedback.Status Current status of the command.

SafePowerOffCommand.Request

Field Type Label Description
unsafe_action SafePowerOffCommand.Request.UnsafeAction

SelfRightCommand

Move the robot into a “ready” position from which it can sit or stand up.

SelfRightCommand.Feedback

Field Type Label Description
status SelfRightCommand.Feedback.Status

SelfRightCommand.Request

SelfRight command request takes no additional arguments.

SitCommand

Sit the robot down in its current position.

SitCommand.Feedback

Field Type Label Description
status SitCommand.Feedback.Status Current status of the command.

SitCommand.Request

Sit command request takes no additional arguments.

Stance

Field Type Label Description
se2_frame_name string The frame name which the desired foot_positions are described in.
foot_positions Stance.FootPositionsEntry repeated Map of foot name to its x,y location in specified frame.
Required positions for spot: "fl", "fr", "hl", "hr".
accuracy float Required foot positional accuracy in meters
Advised = 0.05 ( 5cm)
Minimum = 0.02 ( 2cm)
Maximum = 0.10 (10cm)

Stance.FootPositionsEntry

Field Type Label Description
key string
value Vec2

StanceCommand

Precise foot placement This can be used to reposition the robots feet in place.

StanceCommand.Feedback

Field Type Label Description
status StanceCommand.Feedback.Status

StanceCommand.Request

Field Type Label Description
end_time google.protobuf.Timestamp The timestamp (in robot time) by which a command must finish executing.
/ This is a required field and used to prevent runaway commands.
stance Stance

StandCommand

The stand the robot up in its current position.

StandCommand.Feedback

The StandCommand will provide two feedback fields: status, and standing_state. Status reflects if the robot has four legs on the ground and is near a final pose. StandingState reflects if the robot has converged to a final pose and does not expect future movement.

Field Type Label Description
status StandCommand.Feedback.Status Current status of the command.
standing_state StandCommand.Feedback.StandingState What type of standing the robot is doing currently.

StandCommand.Request

Stand command request takes no additional arguments.

StopCommand

Stop the robot in place with minimal motion.

StopCommand.Feedback

Stop command provides no feedback.

StopCommand.Request

Stop command request takes no additional arguments.

ArmDragCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_DRAGGING 1 Robot is dragging.
STATUS_GRASP_FAILED 2 Robot is not dragging because grasp failed.
This could be due to a lost grasp during a drag, or because the gripper isn't in a
good position at the time of request. You'll have to reposition or regrasp and then
send a new drag request to overcome this type of error. Note: When requesting drag,
make sure the gripper is positioned in front of the robot (not to the side of or
above the robot body).
STATUS_OTHER_FAILURE 3 Robot is not dragging for another reason.
This might be because the gripper isn't holding an item.
You can continue dragging once you resolve this type of error (i.e. by sending an
ApiGraspOverride request). Note: When requesting drag, be sure to that the robot
knows it's holding something (or use APIGraspOverride to OVERRIDE_HOLDING).

BatteryChangePoseCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_COMPLETED 1 Robot is finished rolling
STATUS_IN_PROGRESS 2 Robot still in process of rolling over
STATUS_FAILED 3 Robot has failed to roll onto its side

BatteryChangePoseCommand.Request.DirectionHint

Name Number Description
HINT_UNKNOWN 0 Unknown direction, just hold still
HINT_RIGHT 1 Roll over right (right feet end up under the robot)
HINT_LEFT 2 Roll over left (left feet end up under the robot)

ConstrainedManipulationCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_RUNNING 1 Constrained manipulation is working as expected
STATUS_ARM_IS_STUCK 2 Arm is stuck, either force is being applied in a direction
where the affordance can't move or not enough force is applied
STATUS_GRASP_IS_LOST 3 The grasp was lost. In this situation, constrained manipulation
will stop applying force, and will hold the last position.

ConstrainedManipulationCommand.Request.ControlMode

Name Number Description
CONTROL_MODE_UNKNOWN 0
CONTROL_MODE_POSITION 1 Position control mode, either a linear or angular position is specified
and constrained manipulation moves to that position with a trapezoidal
trajectory that has the max velocity specified in task_speed
CONTROL_MODE_VELOCITY 2 Velocity control mode where constrained manipulation applies forces to
maintain the velocity specified in task_speed

ConstrainedManipulationCommand.Request.TaskType

Geometrical category of a task. See the constrained_manipulation_helper function for examples of each of these categories. For e.g. SE3_CIRCLE_FORCE_TORQUE corresponds to lever type objects.

Name Number Description
TASK_TYPE_UNKNOWN 0
TASK_TYPE_SE3_CIRCLE_FORCE_TORQUE 1 This task type corresponds to circular tasks where
both the end-effector position and orientation rotate about a circle to manipulate.
The constrained manipulation logic will generate forces and torques in this case.
Example tasks are: A lever or a ball valve with a solid grasp
This task type will require an initial force vector specified
in init_wrench_direction_in_frame_name. A torque vector can be specified
as well if a good initial guess of the axis of rotation of the task is available.
TASK_TYPE_R3_CIRCLE_EXTRADOF_FORCE 2 This task type corresponds to circular tasks that have an extra degree of freedom.
In these tasks the end-effector position rotates about a circle
but the orientation does not need to follow a circle (can remain fixed).
The constrained manipulation logic will generate translational forces in this case.
Example tasks are: A crank that has a loose handle and moves in a circle
and the end-effector is free to rotate about the handle in one direction.
This task type will require an initial force vector specified
in init_wrench_direction_in_frame_name.
TASK_TYPE_SE3_ROTATIONAL_TORQUE 3 This task type corresponds to purely rotational tasks.
In these tasks the orientation of the end-effector follows a circle,
and the position remains fixed. The robot will apply a torque at the
end-effector in these tasks.
Example tasks are: rotating a knob or valve that does not have a lever arm.
This task type will require an initial torque vector specified
in init_wrench_direction_in_frame_name.
TASK_TYPE_R3_CIRCLE_FORCE 4 This task type corresponds to circular tasks where
the end-effector position and orientation rotate about a circle
but the orientation does always strictly follow the circle due to slips.
The constrained manipulation logic will generate translational forces in this case.
Example tasks are: manipulating a cabinet where the grasp on handle is not very rigid
or can often slip.
This task type will require an initial force vector specified
in init_wrench_direction_in_frame_name.
TASK_TYPE_R3_LINEAR_FORCE 5 This task type corresponds to linear tasks where
the end-effector position moves in a line
but the orientation does not need to change.
The constrained manipulation logic will generate a force in this case.
Example tasks are: A crank that has a loose handle, or manipulating
a cabinet where the grasp of the handle is loose and the end-effector is free
to rotate about the handle in one direction.
This task type will require an initial force vector specified
in init_wrench_direction_in_frame_name.
TASK_TYPE_HOLD_POSE 6 This option simply holds the hand in place with stiff impedance control.
You can use this mode at the beginning of a constrained manipulation task or to
hold position while transitioning between two different constrained manipulation
tasks. The target pose to hold will be the measured hand pose upon transitioning to
constrained manipulation or upon switching to this task type. This mode should only
be used during constrained manipulation tasks, since it uses impedance control to
hold the hand in place. This is not intended to stop the arm during position control
moves.

JointCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_ACTIVE 1 Command is still active and processing incoming joint requests
STATUS_ERROR 2 An error has occurred and joint requests are no longer being processed

RobotCommandFeedbackStatus.Status

Name Number Description
STATUS_UNKNOWN 0 Behavior execution is in an unknown / unexpected state.
STATUS_PROCESSING 1 The robot is actively working on the command
STATUS_COMMAND_OVERRIDDEN 2 The command was replaced by a new command
STATUS_COMMAND_TIMED_OUT 3 The command expired
STATUS_ROBOT_FROZEN 4 The robot is in an unsafe state, and will only respond to known safe commands.
STATUS_INCOMPATIBLE_HARDWARE 5 The request cannot be executed because the required hardware is missing.
/ For example, an armless robot receiving a synchronized command with an arm_command
/ request will return this value in the arm_command_feedback status.

SE2TrajectoryCommand.Feedback.BodyMovementStatus

Name Number Description
BODY_STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
BODY_STATUS_MOVING 1 The robot body is not settled at the goal.
BODY_STATUS_SETTLED 2 The robot is at the goal and the body has stopped moving.

SE2TrajectoryCommand.Feedback.FinalGoalStatus

Name Number Description
FINAL_GOAL_STATUS_UNKNOWN 0 FINAL_GOAL_STATUS_UNKNOWN should never be used. If used, an internal error has
happened.
FINAL_GOAL_STATUS_IN_PROGRESS 1 Robot is not stopped or stopping.
FINAL_GOAL_STATUS_ACHIEVABLE 2 Final position was achievable.
FINAL_GOAL_STATUS_BLOCKED 3 Final position was not achievable.

SE2TrajectoryCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_STOPPED 1 The robot has stopped. Either the robot has reached the end of the trajectory or it
believes that it cannot reach the desired position. Robot may start to move again if
a blocked path clears.
STATUS_STOPPING 3 The robot is nearing the end of the requested trajectory and is doing final
positioning.
STATUS_IN_PROGRESS 2 The robot is actively following the requested trajectory.
STATUS_AT_GOAL 1 The following enum values were possibly confusing in situations where the robot
cannot achieve the requested trajectory and are now deprecated.
STATUS_NEAR_GOAL 3
STATUS_GOING_TO_GOAL 2

SafePowerOffCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_POWERED_OFF 1 Robot has powered off.
STATUS_IN_PROGRESS 2 Robot is trying to safely power off.

SafePowerOffCommand.Request.UnsafeAction

Robot action in response to a command received while in an unsafe position. If not specified, UNSAFE_MOVE_TO_SAFE_POSITION will be used

Name Number Description
UNSAFE_UNKNOWN 0
UNSAFE_MOVE_TO_SAFE_POSITION 1 Robot may attempt to move to a safe position (i.e. descends stairs) before sitting
and powering off.
UNSAFE_FORCE_COMMAND 2 Force sit and power off regardless of positioning. Robot will not take additional
steps

SelfRightCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_COMPLETED 1 Self-right has completed
STATUS_IN_PROGRESS 2 Robot is in progress of attempting to self-right

SitCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_IS_SITTING 1 Robot is currently sitting.
STATUS_IN_PROGRESS 2 Robot is trying to sit.

StanceCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_STANCED 1 Robot has finished moving feet and they are at the specified position
STATUS_GOING_TO_STANCE 2 Robot is in the process of moving feet to specified position
STATUS_TOO_FAR_AWAY 3 Robot is not moving, the specified stance was too far away.
Hint: Try using SE2TrajectoryCommand to safely put the robot at the
correct location first.

StandCommand.Feedback.StandingState

Name Number Description
STANDING_UNKNOWN 0 STANDING_UNKNOWN should never be used. If used, an internal error has happened.
STANDING_CONTROLLED 1 Robot is standing up and actively controlling its body so it may occasionally make
small body adjustments.
STANDING_FROZEN 2 Robot is standing still with its body frozen in place so it should not move unless
commanded to. Motion sensitive tasks like laser scanning should be performed in this
state.

StandCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_IS_STANDING 1 Robot has finished standing up and has completed desired body trajectory.
STATUS_IN_PROGRESS 2 Robot is trying to come to a steady stand.

Top

bosdyn/api/bddf.proto

DataDescriptor

A DataDescriptor describes a data block which immediately follows it in the file. A corresponding SeriesDescriptor with a matching series_index must precede this in the file.

Field Type Label Description
series_index uint32 The series_index references the SeriesDescriptor to which the data following is associated.
timestamp google.protobuf.Timestamp The time at which the data is considered to be captured/sampled.
E.g., the shutter-close time of a captured image.
additional_indexes int64 repeated Sometimes a visualizer will want to organize message by data timestamp, sometimes by
the time messages were published or logged.
The additional_indexes field allows extra indexes or timestamps to be associated with
each data block for this purpose.
Other identifying information may also be used here, such as the PID of the process which
originated the data (e.g., for detecting if and when that process restarted).
The values in this field should correspond to the labels defined in "additional_index_names"
in the corresponding SeriesDescriptor.

DescriptorBlock

A Descriptor block typically describes a series of messages, but the descriptor at the start of the file describes the contents of the file as a whole, and the descriptor at the end of the file is an index structure to allow efficient access to the contents of the file.

Field Type Label Description
file_descriptor FileFormatDescriptor
series_descriptor SeriesDescriptor
series_block_index SeriesBlockIndex
file_index FileIndex

FileFormatDescriptor

The first block in the file should be a DescriptorBlock containing a FileFormatDescriptor. FileFormatDescriptor indicates the file format version and annotations. Annotations describe things like the robot from which the log was taken and the release id. The format of annotation keys should be {project-or-organization}/{annotation-name} For example, ‘bosdyn/robot-serial-number’.

Field Type Label Description
version FileFormatVersion The version number of the BDDF file.
annotations FileFormatDescriptor.AnnotationsEntry repeated File/stream-wide annotations to describe the content of the file.
checksum_type FileFormatDescriptor.CheckSumType The type of checksum supported by this stream.
For BDDF version 1.0.0 this should be SHA1.
checksum_num_bytes uint32 The number of bytes used for the BDDF checksum.
For BDDF version 1.0.0 this should always be 20, even if CHECKSUM_NONE is used.

FileFormatDescriptor.AnnotationsEntry

Field Type Label Description
key string
value string

FileFormatVersion

The current data file format is 1.0.0.

Field Type Label Description
major_version uint32
minor_version uint32
patch_level uint32

FileIndex

As a file is closed, a DescriptorBlock containing a FileIndex should be written. The FileIndex summarizes the data series stored in the file and the location of the block-indexes for each type in the file. Each series is assigned a “series_index” within the file, and this index may be used to index into the repeated fields in this message. E.g., for the series with series_index N, you can access its SeriesIdentifier by accessing element N the of the series_identifiers repeated field.

Field Type Label Description
series_identifiers SeriesIdentifier repeated SeriesIdentifier for each series in this file.
series_block_index_offsets uint64 repeated The offset from the start of the file of the SeriesBlockIndex block for each series.
series_identifier_hashes uint64 repeated The hash of the series_identifier for each series.

MessageTypeDescriptor

If a data series contains a sequence of binary messages, the encoding and format of these messages is described by a MessageTypeDescriptor.

Field Type Label Description
content_type string Description of the content type.
E.g., "application/protobuf", "image/jpeg", "text/csv", ...
type_name string If content_type is "application/protobuf", this is the full-name of the protobuf type.
is_metadata bool If true, message contents are necessary for interpreting other messages.
If the content of this file is split into multiple output files, these messages should be
copied into each.

PodTypeDescriptor

If a data series contains signals-style data of time-sampled “plain old datatypes”, this describes the content of the series. All POD data stored in data blocks is stored in little-endian byte order. Any number of samples may be stored within a given data block.

Field Type Label Description
pod_type PodTypeEnum The type of machine-readable values stored.
dimension uint32 repeated If empty, indicates a single POD per sample.
If one-element, indicates a vector of the given size per sample.
If two-elements, indicates a matrix of the given size, and so on.
An M x N x .. x P array of data is traversed from innermost (P) to outermost (M) dimension.

SeriesBlockIndex

This describes the location of the SeriesDescriptor DescriptorBlock for the series, and the timestamp and location in the file of every data block in the series.

Field Type Label Description
series_index uint32 The series_index for the series described by this index block.
descriptor_file_offset uint64 Offset of type descriptor block from start of file.
block_entries SeriesBlockIndex.BlockEntry repeated The timestamp and location of each data block for this series.
total_bytes uint64 The total size of the data stored in the data blocks of this series.

SeriesBlockIndex.BlockEntry

Field Type Label Description
timestamp google.protobuf.Timestamp The timestamp of data in this block.
file_offset uint64 The offset of the data block from the start of the file.
additional_indexes int64 repeated Values of the additional indexes for describing this block.

SeriesDescriptor

A description of a series of data blocks. These data blocks may either represent binary messages of a variable size, or they may represent a sequence of samples of POD data samples: single/vector/matrix/… of integer or floating-point values.

Field Type Label Description
series_index uint32 This index for the series is unique within the data file.
series_identifier SeriesIdentifier This is the globally unique {key -> value} mapping to identify the series.
identifier_hash uint64 This is a hash of the series_identifier.
The hash is the first 64 bits (read as a big-endian encoded uint64_t) of
SHA1(S K1 V1 K2 V2 ...) where,
- S is series identifier text,
- K1 and V1 are the key and value of the first key and value of the spec,
- K2 and V2 are the second key and value of the spec, etc...
Here, all strings are encoded as utf-8, and keys are sorted lexicographically using this
encoding (K1 < K2 < ...).
message_type MessageTypeDescriptor
pod_type PodTypeDescriptor
struct_type StructTypeDescriptor
annotations SeriesDescriptor.AnnotationsEntry repeated Annotations are a {key -> value} mapping for associating additional information with
the series.
The format of annotation keys should be
{project-or-organization}/{annotation-name}
For example, 'bosdyn/channel-name', 'bosdyn/protobuf-type'.
Annotation keys without a '/' are reserved.
The only current key in the reserved namespace is 'units': e.g., {'units': 'm/s2'}.
additional_index_names string repeated Labels for additional index values which should be attached to each DataDescriptor
in the series.
See the description of "additional_indexes" in DataDescriptor.
description string

SeriesDescriptor.AnnotationsEntry

Field Type Label Description
key string
value string

SeriesIdentifier

A key or description for selecting a message series. Because there may be multiple ways of describing a message series, we identify them by a unique mapping of {key -> value}. A series_type corresponds to a set of keys which are expected in the mapping. A ‘bosdyn:grpc:requests’ series_type, containing GRPC robot-id request messages, might thus be specified as: {’service’: ‘robot_id’, ‘message’: ‘bosdyn.api.RobotIdRequest’} A ‘bosdyn:logtick’ series_type, containing a signals data variable from LogTick annotations might be specified as: {’varname’: ‘tablet.wifi.rssi’, ‘schema’: ‘tablet-comms’, ‘client’: ‘bd-tablet’}

Field Type Label Description
series_type string This is the kind of spec, which should correspond to a set of keys which are expected
in the spec.
spec SeriesIdentifier.SpecEntry repeated This is the "key" for naming the series within the file.
A key->value description which should be unique for this series within the file
with this series_type.

SeriesIdentifier.SpecEntry

Field Type Label Description
key string
value string

StructTypeDescriptor

A struct series is a composite formed by a set of other series whose messages or signals-ticks are sampled at the same time. For example, all there may be a struct series for a set of signals variables, all from a process with an ‘update()’ function within which all all variables are sampled with the same timestamp. DataBlocks will not directly reference this series, but only child series of this series. Struct series may reference other struct series, but the series structure must be a directed acyclic graph (DAG): no circular reference structures.

Field Type Label Description
key_to_series_identifier_hash StructTypeDescriptor.KeyToSeriesIdentifierHashEntry repeated A map of a name-reference to a series, identified by its series_identifier_hash.

StructTypeDescriptor.KeyToSeriesIdentifierHashEntry

Field Type Label Description
key string
value uint64

FileFormatDescriptor.CheckSumType

Name Number Description
CHECKSUM_TYPE_UNKNOWN 0 Checksum type is unspecified. Should not be used.
CHECKSUM_TYPE_NONE 1 The writer of this stream is not computing a checksum.
The stream checksum at the end of the file will be 160 bits all set to 0.
CHECKSUM_TYPE_SHA1 2 A 160 bit SHA1 checksum will be included at the end of the stream.
This checksum will be computed over all data before digest itself at the
end of the stream, and can be used to verify the stream was received uncorrupted.

PodTypeEnum

“Plain old data” types which may be stored within POD data blocks.

Name Number Description
TYPE_UNSPECIFIED 0
TYPE_INT8 1
TYPE_INT16 2
TYPE_INT32 3
TYPE_INT64 4
TYPE_UINT8 5
TYPE_UINT16 6
TYPE_UINT32 7
TYPE_UINT64 8
TYPE_FLOAT32 9
TYPE_FLOAT64 10

Top

bosdyn/api/data_acquisition.proto

AcquireDataRequest

Field Type Label Description
header RequestHeader Common request header.
action_id CaptureActionId Define the unique action that all data should be saved with.
metadata Metadata Metadata to store with the data capture. The main Data Acquisition service saves it in the
DataBuffer.
acquisition_requests AcquisitionRequestList List of capability requests that should be collected as part of this capture action.
min_timeout google.protobuf.Duration Optional duration used to extend the amount of time that the data request may take, in
the event that a plugin is incorrectly specifying its timeout.
The amount of time allowed will be the maximum of this duration and any requests
made to plugins or other capture sources.

AcquireDataResponse

Field Type Label Description
header ResponseHeader Common response header
status AcquireDataResponse.Status Result of the AcquirePluginData RPC call. Further monitoring on the success of the
acquisition request can be done using the GetStatus RPC.
request_id uint32 Identifier which can be used to check the status of or cancel the acquisition action.

AcquirePluginDataRequest

Message sent by main Data Acquisition service to all data acquisition plugin services.

Field Type Label Description
header RequestHeader Common request header
data_id DataIdentifier repeated Metadata acquirers use these DataIdentifier objects to associate them with the acquired
metadata when storing them in the DataBuffer.
Data acquirers simply get the timestamp from these DataIdentifier objects to use when
storing the data in the DataBuffer.
metadata Metadata Metadata specified by the requestor.
action_id CaptureActionId Id to be associated with all the data buffered for this request. It will be stored
in the DataIdentifier field of each piece of data buffered from this request.
acquisition_requests AcquisitionRequestList List of capability requests specific for this Data Acquisition plugin.

AcquirePluginDataResponse

Field Type Label Description
header ResponseHeader Common response header
status AcquirePluginDataResponse.Status Result of the AcquirePluginData RPC call. Further monitoring on the success of the
acquisition request can be done using the GetStatus RPC.
request_id uint32 Identifier which can be used to check the status of or cancel the acquisition action..
timeout_deadline google.protobuf.Timestamp Time (in the robot's clock) by which this capture should definitely be complete.
If it is not complete by this time, something has gone wrong.
custom_param_error CustomParamError Filled out if status is STATUS_CUSTOM_PARAMS_ERROR.

AcquisitionCapabilityList

A list of all capabilities (data and images) that a specific data acquisition plugin service can successfully acquire and save the data specified in each capability.

Field Type Label Description
data_sources DataAcquisitionCapability repeated List of non-image data acquisition capabilities.
image_sources ImageAcquisitionCapability repeated List of image data acquisition capabilities.
network_compute_sources NetworkComputeCapability repeated List of network compute capabilities.

AcquisitionRequestList

The grouping of all individual image and data captures for a given capture action.

Field Type Label Description
image_captures ImageSourceCapture repeated List of image requests.
data_captures DataCapture repeated List of non-image data and metadata requests.
network_compute_captures NetworkComputeCapture repeated List of Network Compute Bridge requests

AssociatedAlertData

This message can be stored as a DataBlob in the data buffer in order to be recognized as AlertData that is associated with previously stored data.

Field Type Label Description
reference_id DataIdentifier The data that this AlertData refers to.
The timestamp field is ignored.
If only the action_id is filled out, this AlertData is associated with the entire capture
action.
alert_data AlertData AlertData message to be stored.

AssociatedMetadata

This message can be stored as a DataBlob in the data buffer in order to be recognized as metadata that is associated with previously stored data.

Field Type Label Description
reference_id DataIdentifier The data that this metadata refers to.
The timestamp field is ignored.
If only the action_id is filled out, this metadata is associated with the entire capture
action.
metadata Metadata Metadata message to be stored.

CancelAcquisitionRequest

Field Type Label Description
header RequestHeader Common request header
request_id uint32 Which acquisition request to cancel.

CancelAcquisitionResponse

Field Type Label Description
header ResponseHeader Common response header
status CancelAcquisitionResponse.Status The status of the Cancellation RPC. Further monitoring on the success of the cancellation
request can be done using the GetStatus RPC.

CaptureActionId

The CaptureActionId describes the entire capture action for an AcquireData request and will be used to uniquely identify that full request’s set of stored data.

Field Type Label Description
action_name string The action name is used to group all pieces of data associated with a single AcquireData
request. The action name must be unique for the given group name, meaning no two actions
with the same group name can have the same action name.
group_name string The group name is used to group a "session" of data, such as a mission or a teleop capture
session, which includes multiple capture actions (from multiple AcquireData RPCs).
timestamp google.protobuf.Timestamp Time (in the robot's clock) at which this capture was triggered. If the timestamp is not
specified in the AcquireData RPC, the main data acquisition service on robot will populate
the timestamp field with the timestamp of when the RPC was received.

DataAcquisitionCapability

Description of a data acquisition capability. A data acquisition plugin service will have a set of capabilities for which it can acquire and save the appropriate data.

Field Type Label Description
name string Unique identifier for the data acquisition capability. Used for identification purposes
when making acquire data requests.
description string A human readable name of the data acquisition capability that will be shown on the tablet.
channel_name string Channel name that will be associated with all data stored in the data buffer through
each data acquisition plugin. Metadata acquirers do not specify this field.
service_name string The data acquisition plugin service's service name used in directory registration.
custom_params DictParam.Spec Custom parameters supported by this instance of the service.
has_live_data bool Capability has live data available via GetLiveData RPC.

DataCapture

An individual capture which can be specified in the AcquireData or LiveData request to identify a piece of non-image data to be collected.

Field Type Label Description
name string Name of the data to be captured. This should match the uniquely identifying name from
the DataAcquisitionCapability.
custom_params DictParam Values passed to the service at capture time.
See the DictParam.Spec in DataAcquisitionCapability.

DataError

An error associated with a particular capture action and piece of data.

Field Type Label Description
data_id DataIdentifier Identifier for the data to be saved.
error_message string Human-readable message describing the error.
If a capability was misconfigured, e.g. by an invalid CustomParam in one of the requests,
it should show up here.
error_data google.protobuf.Any Custom plugin-specific data about the problem.

DataIdentifier

A way to identify an individual piece of data stored in the data buffer.

Field Type Label Description
action_id CaptureActionId The action where the data was acquired.
channel string Data buffer channel associated with the DataBlob. The channel is used to group data across
actions by a specific source, and it can be used in queries to retrieve some subset of data.
For example, the channel could be "ptz" and queries can be made for all PTZ images.
data_name string Data-specific identifier that can optionally be used to disambiguate cases where the
action_id and channel are insufficient. For example, you save cropped SpotCAM pano image that
are detected as gauges to a "detected_gauges" channel, but want a way to further individually
identify them as each specific gauge, so you give each detection a unique data_name.
id uint64 Unique identifier specified by the Data Acquisition Store service for this individual piece
of data. It is a monotonically-increasing value that is incremented for each stored capture.
This value is intended to be unique to a robot and not globally unique. We do not guarantee
uniqueness pre and post software upgrades or factory resets. This id does not necessarily
start at 0.

GetServiceInfoRequest

Field Type Label Description
header RequestHeader Common request header

GetServiceInfoResponse

Field Type Label Description
header ResponseHeader Common response header.
capabilities AcquisitionCapabilityList List of capabilities that the data acquisition (plugin) service can
collect and save data for.

GetStatusRequest

Field Type Label Description
header RequestHeader Common request header
request_id uint32 Which acquisition to check the status of.

GetStatusResponse

Field Type Label Description
header ResponseHeader Common response header
status GetStatusResponse.Status
data_saved DataIdentifier repeated Data that has been successfully saved into the data buffer for the capture action.
data_errors DataError repeated A list of data captures which have failed in some way during the action.
For example, the data acquisition plugin is unable to communicate to a sensor and responds
with a data error for that specific data capture.
service_errors PluginServiceError repeated Services which failed independent of a particular data id.
For example, if a plugin times out or crashes, it could be reported here.
network_compute_errors NetworkComputeError repeated Network compute services which failed independent of a particular data id.
For example, if a worker times out or crashes, it could be reported here.

ImageAcquisitionCapability

Description of an image acquisition capability. The image acquisition capabilities will be available through the main data acquisition service on robot and are populated based on all bosdyn.api.ImageService services registered to the robot’s directory.

Field Type Label Description
service_name string The image service's service name used in directory registration.
image_source_names string repeated Deprecated. DEPRECATED as of 3.1.0. Please use "image_sources" below for information regarding the image
source associated with the service.
image_sources ImageSource repeated List of image sources reported by the image service (through the ListImageSources RPC).

ImageSourceCapture

An individual capture which can be specified in the AcquireData request to identify a piece of image data to be collected.

Field Type Label Description
image_service string Name of the image service that the data should be requested from.
image_request ImageRequest Options for requesting this particular image.
image_source string Deprecated. DEPRECATED as of 3.2.0. Use image_request instead.
Specific image source to use from the list reported by the image service within the
ImageAcquisitionCapability message.
pixel_format Image.PixelFormat Deprecated. DEPRECATED as of 3.2.0. Use image_request instead.
Specific pixel format to capture reported by the ImageAcquisitionCapability message.

LiveDataRequest

Request live data from a DAQ plugin service by DataCapture capability name.

Field Type Label Description
header RequestHeader Common request header.
data_captures DataCapture repeated Include capability name and parameter values.

LiveDataResponse

Live data response of a DAQ plugin service for a single capability.

Field Type Label Description
header ResponseHeader Common response header.
live_data LiveDataResponse.CapabilityLiveData repeated One entry for each data capture in the request. Order matches LiveDataRequest order.

LiveDataResponse.CapabilityLiveData

Field Type Label Description
signals LiveDataResponse.CapabilityLiveData.SignalsEntry repeated Map of signal id to signal specification and data.
name string Unique name of the data that is captured.
status LiveDataResponse.CapabilityLiveData.Status
custom_param_error CustomParamError Filled out if status is STATUS_CUSTOM_PARAMS_ERROR.

LiveDataResponse.CapabilityLiveData.SignalsEntry

Field Type Label Description
key string
value Signal

Metadata

Structured data that can be included within a AcquireData RPC and saved in association with that capture action.

Field Type Label Description
data google.protobuf.Struct JSON representation of metadata.

NetworkComputeCapability

Field Type Label Description
server_config NetworkComputeServerConfiguration Service information.
available_models string repeated Deprecated. Provide list of available models.
DEPRECATED as of 3.3. Replaced by AvailableModels.
labels ModelLabels repeated Deprecated. Information about available classes for each model.
DEPRECATED as of 3.3. Replaced by AvailableModels.
models AvailableModels Envelope message for repeated ModelData.

NetworkComputeCapture

Field Type Label Description
input_data NetworkComputeInputData Deprecated. DEPRECATED as of 3.3. Please use input_data_bridge instead.
input_data_bridge NetworkComputeInputDataBridge
server_config NetworkComputeServerConfiguration Which service to use.

NetworkComputeError

Field Type Label Description
service_name string Name of the service with the error
error NetworkComputeError.ErrorCode General type of error that occurred.
network_compute_status NetworkComputeStatus Any particular failure mode reported.
message string Description of the error.

PluginServiceError

An error associated with a particular data acquisition plugin service that was

Field Type Label Description
service_name string Name of the service with the error
error PluginServiceError.ErrorCode Failure mode.
message string Description of the error.

AcquireDataResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1 The capture action has successfully started acquiring the data.
STATUS_UNKNOWN_CAPTURE_TYPE 2 One of the capability requests in the AcquisitionRequestList is unknown.

AcquirePluginDataResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1 The capture action has successfully started acquiring the data.
STATUS_UNKNOWN_CAPTURE_TYPE 2 One of the capability requests in the AcquisitionRequestList is unknown.
STATUS_CUSTOM_PARAMS_ERROR 3 See custom_param_error field for details.

CancelAcquisitionResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1 Successfully cancelled the data acquisition request.
STATUS_FAILED_TO_CANCEL 2 Unable to stop the data acquisition request.
STATUS_REQUEST_ID_DOES_NOT_EXIST 3 [Error] The request_id does not exist.

GetStatusResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_ACQUIRING 1 [Status]

Data acquisition is still in progress.
STATUS_SAVING 2 Data has been acquired, processing and storage is now in progress.
STATUS_COMPLETE 3 Data acquisition is complete.
STATUS_CANCEL_IN_PROGRESS 4 The data acquisition service is cancelling the request.
STATUS_ACQUISITION_CANCELLED 5 The data acquisition request was cancelled manually.
STATUS_DATA_ERROR 10 [Error - AcquireData]

An error occurred while acquiring, processing, or saving data.
STATUS_TIMEDOUT 11 The data collection has passed the deadline for completion.
STATUS_INTERNAL_ERROR 12 An error occurred such that we don't even know our status.
STATUS_CANCEL_ACQUISITION_FAILED 30 [Error - CancelAcquisition]

The cancellation request failed to complete.
STATUS_REQUEST_ID_DOES_NOT_EXIST 20 [Error - GetStatus]

The request_id does not exist.

LiveDataResponse.CapabilityLiveData.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_UNKNOWN_CAPTURE_TYPE 2 The capability name is unknown.
STATUS_CUSTOM_PARAMS_ERROR 3 See custom_param_error field for details.
STATUS_INTERNAL_ERROR 4 Some other problem occurred.

NetworkComputeError.ErrorCode

Name Number Description
STATUS_UNKNOWN 0
STATUS_REQUEST_ERROR 1 The request was rejected.
STATUS_NETWORK_ERROR 2 The request had an error reaching the worker.
STATUS_INTERNAL_ERROR 3 Some other problem prevented the request from succeeding.

PluginServiceError.ErrorCode

Possible ways a plugin can fail.

Name Number Description
STATUS_UNKNOWN 0
STATUS_REQUEST_ERROR 1 The initial RPC to the plugin failed
STATUS_GETSTATUS_ERROR 2 The GetStatus request to the plugin failed with a data error or timeout.
STATUS_INTERNAL_ERROR 3 The plugin reported an internal error.

Top

bosdyn/api/data_acquisition_plugin_service.proto

DataAcquisitionPluginService

The DataAcquisitionPluginService is a gRPC service that a payload developer implements to retrieve data from a sensor (or more generally perform some payload action) and optionally store that data on the robot via the DataAcquisitionStore service.

Method Name Request Type Response Type Description
AcquirePluginData AcquirePluginDataRequest AcquirePluginDataResponse Trigger a data acquisition to save metadata and non-image data to the data buffer.
Sent by the main Data Acquisition service as a result of a data acquisition request from the
tablet or a client.
GetStatus GetStatusRequest GetStatusResponse Query the status of a data acquisition.
GetServiceInfo GetServiceInfoRequest GetServiceInfoResponse Get information from a Data Acquisition service; lists acquisition capabilities.
CancelAcquisition CancelAcquisitionRequest CancelAcquisitionResponse Cancel an in-progress data acquisition.
GetLiveData LiveDataRequest LiveDataResponse Request live data available from this plugin during teleoperation.
Please use the other RPCs for typical data acquisition.

Top

bosdyn/api/data_acquisition_service.proto

DataAcquisitionService

The DataAcquisitionService is the main data acquisition service run on robot, which receives incoming requests and sends queries to all directory-registered DataAcquisitionPluginServices.

Method Name Request Type Response Type Description
AcquireData AcquireDataRequest AcquireDataResponse Trigger a data acquisition to save data and metadata to the data buffer.
Sent by the tablet or a client to initiate a data acquisition and buffering process.
GetStatus GetStatusRequest GetStatusResponse Query the status of a data acquisition.
GetServiceInfo GetServiceInfoRequest GetServiceInfoResponse Get information from a Data Acquisition service; lists acquisition capabilities.
CancelAcquisition CancelAcquisitionRequest CancelAcquisitionResponse Cancel an in-progress data acquisition.
GetLiveData LiveDataRequest LiveDataResponse Request live data available from DAQ plugins during teleoperation.
Please use the other RPCs for typical data acquisition.

Top

bosdyn/api/data_acquisition_store.proto

ActionIdQuery

A query parameter which filters the possible set of data identifiers to those which contain the same action/group names matching any of the names in the set of CaptureActionIds.

Field Type Label Description
action_ids CaptureActionId repeated The action ids to filter with.

DataQueryParams

The message containing the different query parameters which can be applied to the ListData requests.

Field Type Label Description
time_range TimeRangeQuery Time range to query.
action_ids ActionIdQuery List of action ids to query.

ListCaptureActionsRequest

Field Type Label Description
header RequestHeader Common request header.
query DataQueryParams Query parameters for finding action ids.

ListCaptureActionsResponse

Field Type Label Description
header ResponseHeader Common response header.
action_ids CaptureActionId repeated List of action ids that satisfied the query parameters.

ListStoredAlertDataRequest

Field Type Label Description
header RequestHeader Common request header.
query DataQueryParams Query parameters for finding AlertData.

ListStoredAlertDataResponse

Field Type Label Description
header ResponseHeader Common response header.
data_ids DataIdentifier repeated List of AlertData data identifiers that satisfied the query parameters.

ListStoredDataRequest

Field Type Label Description
header RequestHeader Common request header.
query DataQueryParams Query parameters for finding data.

ListStoredDataResponse

Field Type Label Description
header ResponseHeader Common response header.
data_ids DataIdentifier repeated List of data identifiers that satisfied the query parameters.

ListStoredImagesRequest

Field Type Label Description
header RequestHeader Common request header.
query DataQueryParams Query parameters for finding images.

ListStoredImagesResponse

Field Type Label Description
header ResponseHeader Common response header.
data_ids DataIdentifier repeated List of image data identifiers that satisfied the query parameters.

ListStoredMetadataRequest

Field Type Label Description
header RequestHeader Common request header.
query DataQueryParams Query parameters for finding metadata.

ListStoredMetadataResponse

Field Type Label Description
header ResponseHeader Common response header.
data_ids DataIdentifier repeated List of metadata data identifiers that satisfied the query parameters.

QueryMaxCaptureIdRequest

Field Type Label Description
header RequestHeader Common request header.
query QueryParameters Query parameters for finding data.

QueryMaxCaptureIdResponse

Field Type Label Description
header ResponseHeader
max_capture_id uint64

QueryParameters

Field Type Label Description
time_range TimeRangeQuery Time range to query.
action_ids CaptureActionId repeated List of action ids to query. The constructed query statement will have an OR relation
between the action_ids specified in this list, with an AND relation for the fields inside
each action_id. For example, specifying
[{action_name="action1", group_name="group1"}, {action_name="action2", group_name="group2"}]
will insert the following in the WHERE part of the query:
(action_name="action1" AND group_name="group1") OR (action_name="action2" AND
group_name="group2").
channels string repeated Channels to include in the query results. The constructed query statement will have an OR
relation for all the channel values listed in this field.
captures_from_id uint64 Query for captures with id higher or equal to this value. Specifying 0 means that the
Data Acquisition Store will return all captured data it has. Otherwise, it will return new
captures stored with an id greater than the value specified in this field.
only_include_identifiers bool Setting this field to true only returns the DataIdentifiers in the response and not the
actual captures.
include_images bool The following fields specify which capture types to include in the results. If none of the
following fields is specified, then all capture types will be included in the results.
include_data bool
include_metadata bool
include_alerts bool

QueryStoredCaptureResult

Field Type Label Description
data_id DataIdentifier
image ImageCapture
metadata AssociatedMetadata
alert_data AssociatedAlertData
data StoredCapturedData

QueryStoredCapturesRequest

Field Type Label Description
header RequestHeader Common request header.
query QueryParameters Query parameters for finding data.

QueryStoredCapturesResponse

Field Type Label Description
header ResponseHeader Common response header.
action_ids CaptureActionId repeated CaptureActionIds that match the query parameters and are included in the results.
results QueryStoredCaptureResult repeated Results that match the query parameters.
max_capture_id uint64 Max capture_id in the database matching the query parameters.

StoreAlertDataRequest

Field Type Label Description
header RequestHeader Common request header.
alert_data AssociatedAlertData AlertData to store.
data_id DataIdentifier Data identifier of the alert.

StoreAlertDataResponse

Field Type Label Description
header ResponseHeader Common response header.
id uint64

StoreDataRequest

Field Type Label Description
header RequestHeader Common request header.
data bytes Data to store.
data_id DataIdentifier Data identifier of the data.
file_extension string File extension to use when writing the data to file.

StoreDataResponse

Field Type Label Description
header ResponseHeader Common response header.
id uint64

StoreImageRequest

Field Type Label Description
header RequestHeader Common request header.
image ImageCapture Image to store.
data_id DataIdentifier Data identifier of the image.

StoreImageResponse

Field Type Label Description
header ResponseHeader Common response header.
id uint64

StoreMetadataRequest

Field Type Label Description
header RequestHeader Common request header.
metadata AssociatedMetadata Metadata to store.
data_id DataIdentifier Data identifier of the metadata.

StoreMetadataResponse

Field Type Label Description
header ResponseHeader Common response header.
id uint64

StoredCapturedData

Field Type Label Description
data bytes
file_extension string File extension to use for writing the data to a file.

TimeRangeQuery

A query parameter which filters the possible set of data identifiers to those with timestamps within the specified range.

Field Type Label Description
from_timestamp google.protobuf.Timestamp Start of the time range to query.
to_timestamp google.protobuf.Timestamp End of the time range to query.

Top

bosdyn/api/data_acquisition_store_service.proto

DataAcquisitionStoreService

The DataAcquisitionStoreService is used to store data (images, data, metadata) on the robot in association with the DataIdentifiers specified by the DataAcquisitionService. Additionally, requests can be made to the DataAcquisitionStoreService to identify different pieces of data or entire capture actions which match query parameters, such as time ranges or action/group names.

Method Name Request Type Response Type Description
ListCaptureActions ListCaptureActionsRequest ListCaptureActionsResponse List all CaptureActionIds (which identify an entire AcquireData RPC's data captures)
that match the query parameters provided in the request.
ListStoredData ListStoredDataRequest ListStoredDataResponse List data identifiers (which identify specific pieces of data from
an action) for stored data that satisfy the query parameters in the request.
StoreData StoreDataRequest StoreDataResponse Store arbitrary data associated with a DataIdentifier.
ListStoredImages ListStoredImagesRequest ListStoredImagesResponse Type-safe to images: list data identifiers (which identify specific images
from an action) for stored images that satisfy the
query parameters in the request.
StoreImage StoreImageRequest StoreImageResponse Type-safe to images: store image data associated with a DataIdentifier.
ListStoredMetadata ListStoredMetadataRequest ListStoredMetadataResponse Type-safe to JSON metadata: list data identifiers (which identify specific metadata from
an action) for stored metadata that satisfy the query parameters in the request.
StoreMetadata StoreMetadataRequest StoreMetadataResponse Type-safe to JSON metadata: store metadata associated with a DataIdentifier.
ListStoredAlertData ListStoredAlertDataRequest ListStoredAlertDataResponse List data identifiers (which identify specific AlertData from
an action) for stored AlertData that satisfy the query parameters in the request.
StoreAlertData StoreAlertDataRequest StoreAlertDataResponse Store AlertData associated with a DataIdentifier.
QueryStoredCaptures QueryStoredCapturesRequest DataChunk stream Query the Data Acquisition Store for captured data. This streaming RPC returns a single
QueryStoredCapturesResponse message, encoded as a list of DataChunk messages.

If the first capture matching the query is larger than an internal size limit set in the
service, the QueryStoredCapturesResponse message contains only that first capture matching
the query.

Otherwise, the QueryStoredCapturesResponse message contains as many matching captures as can
fit within the internal size limit, without breaking the results order.

To get all captures that match a query, you must make this RPC until it returns an empty
QueryStoredCapturesResponse with no elements in its "results" field.
QueryMaxCaptureId QueryMaxCaptureIdRequest QueryMaxCaptureIdResponse

Top

bosdyn/api/data_buffer.proto

DataBlob

Message-style data to add to the log.

Field Type Label Description
timestamp google.protobuf.Timestamp Timestamp of data in robot clock time. This is required.
channel string A general label for this blob.
This is distinct from type_id, which identifies how the blob is to be parsed.
In practice, this is often the same as the type_id.
type_id string A description of the data's content and its encoding. This is required.
This should be sufficient for deciding how to deserialize the data.
For example, this could be the full name of a protobuf message type.
data bytes Raw data.
For example, jpeg data or a serialized protobuf.

Event

This message contains event data for logging to the public timeline.

Field Type Label Description
type string Type of event, typically prefixed with a project or organization, e.g. "bosdyn:startup"
description string Event description.
This is optional.
source string A description of the source of this event. May be the client name.
- Not required to be unique.
- Disambiguates the source of similar event types.
id string Unique identifier. Used to link start and end messages for events with a duration.
- Long running events may have separate messages at the start and end, in case the message
for the end of the event is lost.
- For events without a separate start and end message (in which case both start_time and
end time should be specified), the 'id' field will be set by the service during upload,
unless the user has already set it.
- This id is not tracked internally by the service. It is only used to consume the event
timeline.
- To be effective, the id value should be generated randomly by the client.
start_time google.protobuf.Timestamp Start and end times for the event:
- Some events are instantaneous. For these, set start_timestamp and end_timestamp to the
same value and send a single message (without an id).
- Some events take time. At the onset, send a message with a unique id, the start time, and
type. The end message should include all data from the start message, any
additional data, and an end time. If you have the end message, you should not need
the start message since it is a strict subset.
end_time google.protobuf.Timestamp
level Event.Level The relative importance of the event.
parameters Parameter repeated Optional set of event parameters.
log_preserve_hint Event.LogPreserveHint Optionally request that the robot try to preserve data near this time for a service log.

OperatorComment

An operator comment to be added to the log. These are notes especially intended to mark when logs should be preserved and reviewed to ensure that robot hardware and/or software is working as intended.

Field Type Label Description
message string String annotation message to add to the log.
timestamp google.protobuf.Timestamp The timestamp of the annotation. This must be in robot time.
If this is not specified, this will default to the time the server received the message.

RecordDataBlobsRequest

Field Type Label Description
header RequestHeader Common request header.
blob_data DataBlob repeated The data blobs to be logged.
sync bool When set, the data blob is committed to the log synchronously. The RPC does not return until
the data is written.

RecordDataBlobsResponse

Field Type Label Description
header ResponseHeader Common response header.
errors RecordDataBlobsResponse.Error repeated Errors which occurred when logging data blobs.

RecordDataBlobsResponse.Error

DataBlob recording error.

Field Type Label Description
type RecordDataBlobsResponse.Error.Type The type of error: if it was caused by the client or the service.
message string An error message.
index uint32 The index to identify the data being stored.

RecordEventsRequest

Field Type Label Description
header RequestHeader Common request header.
events Event repeated The events to be logged.

RecordEventsResponse

Field Type Label Description
header ResponseHeader Common response header.
errors RecordEventsResponse.Error repeated Errors which occurred when logging events.

RecordEventsResponse.Error

Event recording error.

Field Type Label Description
type RecordEventsResponse.Error.Type The type of error: if it was caused by the client, the service, or something else.
message string An error message.
index uint32 The index to identify the data being stored.

RecordOperatorCommentsRequest

Field Type Label Description
header RequestHeader Common request header.
operator_comments OperatorComment repeated The operator comments to be logged.

RecordOperatorCommentsResponse

Field Type Label Description
header ResponseHeader Common response header.
errors RecordOperatorCommentsResponse.Error repeated Errors which occurred when logging operator comments.

RecordOperatorCommentsResponse.Error

Operator comment recording error.

Field Type Label Description
type RecordOperatorCommentsResponse.Error.Type The type of error: if it was caused by the client or the service.
message string An error message.
index uint32 The index to identify the data being stored.

RecordSignalTicksRequest

Field Type Label Description
header RequestHeader Common request header.
tick_data SignalTick repeated The signals data to be logged.

RecordSignalTicksResponse

Field Type Label Description
header ResponseHeader Common response header.
errors RecordSignalTicksResponse.Error repeated Errors which occurred when logging signal ticks.

RecordSignalTicksResponse.Error

Signal tick recording error.

Field Type Label Description
type RecordSignalTicksResponse.Error.Type The type of error: if it was caused by the client, the service, or something else.
message string An error message.
index uint32 The index to identify the data being stored.

RecordTextMessagesRequest

Field Type Label Description
header RequestHeader Common request header.
text_messages TextMessage repeated The text messages to be logged.

RecordTextMessagesResponse

Field Type Label Description
header ResponseHeader Common response header.
errors RecordTextMessagesResponse.Error repeated Errors which occurred when logging text message data.

RecordTextMessagesResponse.Error

Text message recording error.

Field Type Label Description
type RecordTextMessagesResponse.Error.Type The type of error: if it was caused by the client or the service.
message string An error message.
index uint32 The index to identify the data being stored.

RegisterSignalSchemaRequest

Field Type Label Description
header RequestHeader Common request/response header.
schema SignalSchema Defines a schema for interpreting SignalTick data containing packed signals-type data.

RegisterSignalSchemaResponse

Field Type Label Description
header ResponseHeader Common request/response header.
schema_id uint64 Server returns a unique ID based on the client ID and schema definition.
Always greater than zero.

SignalSchema

A description of a set of signals-style variables to log together as timestamped samples.

Field Type Label Description
vars SignalSchema.Variable repeated A SignalTick using this schema contains the values of this ordered list of variables.
schema_name string The name of the schema.

SignalSchema.Variable

A variable of signals-style data, which will be sampled in time.

Field Type Label Description
name string The name of the variable.
type SignalSchema.Variable.Type The type of the data.
is_time bool Zero or one variable in 'vars' may be specified as a time variable.
A time variable must have type TYPE_FLOAT64.

SignalSchemaId

Field Type Label Description
schema_id uint64 {schema, id} pair
schema SignalSchema

SignalTick

A timestamped set of signals variable values.

Field Type Label Description
sequence_id int64 Successive ticks should have successive sequence_id's.
The robot uses this to determine if a tick was somehow lost.
timestamp google.protobuf.Timestamp Timestamp at which the variable values were sampled.
source string The client name.
This may be used to segregate data for the same variables to different parts of the buffer.
schema_id uint64 This specifies the SignalSchema to be used in interpreting the
encoding SignalTick.Encoding Format describing how the data bytes array is encoded.
data bytes The encoded data representing a tick of multiple values of signal-styles data.

TextMessage

A text message to add to the log. These could be internal text-log messages from a client for use in debugging, for example.

Field Type Label Description
message string String annotation message.
timestamp google.protobuf.Timestamp The timestamp of the annotation. This must be in robot time.
If this is not specified, this will default to the time the server received the message.
source string The client name.
This may be used to segregate data for the same variables to different parts of the buffer.
level TextMessage.Level The relative importance of the message.
tag string Optional tag to identify from what code/module this message originated from.
filename string Optional source file name originating the log message.
line_number int32 Optional source file line number originating the log message.

Event.Level

Level, or similarly “visibility,” “importance,” or “weight” of event.

  • Higher level events will increase the visibility on the event timeline, relative to other events.

  • In general, higher level events should be more consequential with respect to the robot operation on a per-occurrence basis.

  • Lower level events should be less consequential on a per-occurrence basis.

  • Non-critical events may be one of LOW, MEDIUM, or HIGH. UNSET is logically equivalent to LOW level.

  • Critical events may be either mission or system critical.

  • System-critical is quasi-reserved for internal robot use, and is used to identify events that directly affect robot status or capability, such as the onset of a critical fault or start of an enabling capability.

  • Mission-critical is quasi-reserved client use, and is intended for events that directly affect the ability of the robot to “do what the user wants,” such as the onset of a service fault or start of an enabling capability.

Name Number Description
LEVEL_UNSET 0
LEVEL_LOW 1 Non-critical events
LEVEL_MEDIUM 2
LEVEL_HIGH 3
LEVEL_MISSION_CRITICAL 4 Critical events
LEVEL_SYSTEM_CRITICAL 5

Event.LogPreserveHint

LogPreserveHint may encode a hint to the robot’s logging system for whether to preserve internal log data near the time of this event. This could be useful in saving data to be used in a service log to send to Boston Dynamics.

Name Number Description
LOG_PRESERVE_HINT_UNSET 0 If this this is unset, it is equivalent to LOG_PRESERVE_HINT_NORMAL.
LOG_PRESERVE_HINT_NORMAL 1 Do not change the robot's default log data preservation behavior in response to this
event.
LOG_PRESERVE_HINT_PRESERVE 2 Request that the robot try to preserve data near the time of this event.
Log space on the robot is limited, so this does not guarantee that the data will be
preserved.

RecordDataBlobsResponse.Error.Type

Name Number Description
NONE 0
CLIENT_ERROR 1
SERVER_ERROR 2

RecordEventsResponse.Error.Type

Name Number Description
NONE 0
CLIENT_ERROR 1
SERVER_ERROR 2

RecordOperatorCommentsResponse.Error.Type

Name Number Description
NONE 0
CLIENT_ERROR 1
SERVER_ERROR 2

RecordSignalTicksResponse.Error.Type

Name Number Description
NONE 0
CLIENT_ERROR 1
SERVER_ERROR 2
INVALID_SCHEMA_ID 3

RecordTextMessagesResponse.Error.Type

Name Number Description
NONE 0
CLIENT_ERROR 1
SERVER_ERROR 2

SignalSchema.Variable.Type

Name Number Description
TYPE_UNKNOWN 0
TYPE_INT8 1
TYPE_INT16 2
TYPE_INT32 3
TYPE_INT64 4
TYPE_UINT8 5
TYPE_UINT16 6
TYPE_UINT32 7
TYPE_UINT64 8
TYPE_FLOAT32 9
TYPE_FLOAT64 10

SignalTick.Encoding

Name Number Description
ENCODING_UNKNOWN 0
ENCODING_RAW 1 Bytes array is a concatenation of little-endian machine representations of
the variables from the SignalSchema, in order listed in that schema.

TextMessage.Level

Name Number Description
LEVEL_UNKNOWN 0 Invalid, do not use.
LEVEL_DEBUG 1 Events likely of interest only in a debugging context.
LEVEL_INFO 2 Informational message during normal operation.
LEVEL_WARN 3 Information about an unexpected but recoverable condition.
LEVEL_ERROR 4 Information about an operation which did not succeed.

Top

bosdyn/api/data_buffer_service.proto

DataBufferService allows adding information to the robot’s log files.

DataBufferService

This service is a mechanism for adding information to the robot’s log files.

Method Name Request Type Response Type Description
RecordTextMessages RecordTextMessagesRequest RecordTextMessagesResponse Add text messages to the log.
RecordOperatorComments RecordOperatorCommentsRequest RecordOperatorCommentsResponse Add a set of operator messages to the log.
RecordDataBlobs RecordDataBlobsRequest RecordDataBlobsResponse Add message-style data to the log.
RecordEvents RecordEventsRequest RecordEventsResponse Add event data to the log.
RegisterSignalSchema RegisterSignalSchemaRequest RegisterSignalSchemaResponse Register a log tick schema, allowing client to later log tick data.
RecordSignalTicks RecordSignalTicksRequest RecordSignalTicksResponse Add signal data for registered signal schema to the log.

Top

bosdyn/api/data_chunk.proto

DataChunk

Represents a chunk of (possibly serialized) data. Chunks will be concatenated together to produce a datagram. This is to avoid size limit restrictions in grpc implementations.

Field Type Label Description
total_size uint64 The total size in bytes of the datagram that this chunk is a part of.
data bytes Bytes in this data chunk. Bytes are sent sequentially.

Top

bosdyn/api/data_index.proto

BlobPage

A set of blob messages of a given channel/msgtype within a given data page.

Field Type Label Description
spec BlobSpec
page PageInfo

BlobPages

A set of pages of data which contain specified Blob messages from the data-buffer.

Field Type Label Description
time_range TimeRange
pages BlobPage repeated

BlobSpec

Specification for selecting of blob messages.

Field Type Label Description
source string If set, require the message source to match this.
message_type string If set, require the message type to match this value.
channel string If set, require the channel to match this value (or channel_glob, if set).
channel_glob string Optionally require the channel to match a glob (or channel, if set)..
For example, 'gps/*' will match all channels starting with 'gps/'.

DataBufferStatus

Field Type Label Description
num_data_buffer_pages int64
data_buffer_total_bytes int64
num_comments int64
num_events int64
blob_specs BlobSpec repeated

DataIndex

Description of data matching a given DataQuery.

Field Type Label Description
time_range TimeRange
blobs BlobPages repeated
text_messages PagesAndTimestamp
events PagesAndTimestamp
comments PagesAndTimestamp

DataQuery

A query for pages containing the desired data.

Field Type Label Description
time_range TimeRange Timespan for data we want to query
blobs BlobSpec repeated Request for pages containing different kinds of data.
text_messages bool return pages of text-messages during the specified timespan
events bool return pages of events
comments bool return pages of operator comments during the specified timespan

DeleteDataPagesRequest

GRPC request to delete pages. Both time_range and page_ids can be set.

Field Type Label Description
header RequestHeader
time_range TimeRange Delete all pages in this time range
page_ids string repeated Delete all pages with matching ids

DeleteDataPagesResponse

Field Type Label Description
header ResponseHeader
bytes_deleted int64
status DeletePageStatus repeated

DeletePageStatus

Field Type Label Description
page_id string
status DeletePageStatus.Status

EventSpec

Specification for selecting Events.

Field Type Label Description
source string
type string
level google.protobuf.Int32Value
log_preserve_hint Event.LogPreserveHint

EventsComments

Requested Events and/or OperatorComments.

Field Type Label Description
time_range TimeRange Timespan for data
events Event repeated
operator_comments OperatorComment repeated
events_limited bool True if the number of events returned was limited by query maximum.
operator_comments_limited bool True if the number of comments returned was limited by query maximum.

EventsCommentsSpec

A request for Events and/or OperatorComments over a given time range.

Field Type Label Description
time_range TimeRange Timespan for data we want to query
events EventSpec repeated Return events which match the request.
comments bool Return operator comments which match the request.
max_events uint32 Maximum number of events to return (limited to 1024).
max_comments uint32 Maximum number of comments to return (limited to 1024).

GetDataBufferStatusRequest

Field Type Label Description
header RequestHeader
get_blob_specs bool

GetDataBufferStatusResponse

Field Type Label Description
header ResponseHeader
data_buffer_status DataBufferStatus

GetDataIndexRequest

GRPC response with requested data index information.

Field Type Label Description
header RequestHeader
data_query DataQuery

GetDataIndexResponse

GRPC request for data index information.

Field Type Label Description
header ResponseHeader
data_index DataIndex

GetDataPagesRequest

Field Type Label Description
header RequestHeader
time_range TimeRange

GetDataPagesResponse

Field Type Label Description
header ResponseHeader
pages PageInfo repeated

GetEventsCommentsRequest

GRPC request for Events and OperatorComments.

Field Type Label Description
header RequestHeader
event_comment_request EventsCommentsSpec

GetEventsCommentsResponse

GRPC response with requested Events and OperatorComments.

Field Type Label Description
header ResponseHeader
events_comments EventsComments

GrpcPages

A set of pages of data which contain specied GRPC request and response messages.

Field Type Label Description
time_range TimeRange
spec GrpcSpec
pages PageInfo repeated

GrpcSpec

Specification for selecting of GRPC logs.

Field Type Label Description
service_name string

PageInfo

A unit of data storage. This may be a bddf data file. Like a file, this data may be downloaded or deleted all together for example.

Field Type Label Description
id string Identifier unique to robot.
path string Relative path to file, if file storage.
source string Name of service/client which provided the data.
time_range TimeRange Time range of the relevant data in the page.
num_ticks int64 Number of time samples or blobs.
total_bytes int64 Total size of data in the page.
format PageInfo.PageFormat
compression PageInfo.Compression
is_open bool True if data is still being written into this page, false if page is complete.
is_downloaded bool True if data is marked as having been downloaded.
deleted_timestamp google.protobuf.Timestamp If this exists, the page was deleted from the robot at the specified time.
download_started_timestamp google.protobuf.Timestamp If this exists, download from this page was started at the specified time.
request_preserve bool True if data has been requested to be preserved.

PagesAndTimestamp

A set of pages and the associated time range they cover.

Field Type Label Description
time_range TimeRange
pages PageInfo repeated

DeletePageStatus.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_DELETED 1
STATUS_DELETION_FAILED 2
STATUS_NOT_FOUND 3

PageInfo.Compression

Name Number Description
COMPRESSION_UNKNOWN 0 Not set -- do not use.
COMPRESSION_NONE 1 Data is not compressed.
COMPRESSION_GZIP 2 Data uses gzip compression.
COMPRESSION_ZSTD 3 Data uses zstd compression.

PageInfo.PageFormat

Name Number Description
FORMAT_UNKNOWN 0 Unset -- do not use.
FORMAT_BDDF_FILE 1 Data is stored in a .bddf file

Top

bosdyn/api/data_service.proto

DataBufferService allows adding information to the robot’s log files.

DataService

The DataService is a mechanism for querying and managing data stored on robot.

Method Name Request Type Response Type Description
GetDataIndex GetDataIndexRequest GetDataIndexResponse Get index of current data matching a given DataQuery.
GetEventsComments GetEventsCommentsRequest GetEventsCommentsResponse Get events and comments.
GetDataBufferStatus GetDataBufferStatusRequest GetDataBufferStatusResponse Get basic stats on data buffer storage.
GetDataPages GetDataPagesRequest GetDataPagesResponse Get a list pf pages matching a given time range
DeleteDataPages DeleteDataPagesRequest DeleteDataPagesResponse Delete a list of pages matching a given time range or page ids

Top

bosdyn/api/directory.proto

Endpoint

A message containing information that allows a client to identify a given endpoint host using an ip and a port.

Field Type Label Description
host_ip string The IP address of the computer hosting this endpoint.
port int32 The port number on which the endpoint is provided, between 0 and 65535.

GetServiceEntryRequest

The GetServiceEntry request message sends the service name to the robot.

Field Type Label Description
header RequestHeader Common request header.
service_name string The unique user-friendly name of the service.

GetServiceEntryResponse

The GetServiceEntry response message returns a ServiceEntry for the desired service name.

Field Type Label Description
header ResponseHeader Common response Header.
status GetServiceEntryResponse.Status Current status of the request.
service_entry ServiceEntry The record for the discovered service. Only set if 'status' field == STATUS_OK.

ListServiceEntriesRequest

The ListServiceEntries request message will ask the robot for all services.

Field Type Label Description
header RequestHeader Common request header.

ListServiceEntriesResponse

The ListServiceEntries response message returns all known services at the time the request was recieved.

Field Type Label Description
header ResponseHeader Common response header.
service_entries ServiceEntry repeated The resources managed by the LeaseService.

ServiceEntry

A message representing a discoverable service. By definition, all services discoverable by this system are expected to be grpc “services” provided by some server.

Field Type Label Description
name string The unique user-friendly name of this service.
type string The type of this service. Usually identifies the underlying implementation.
Does not have to be unique among all ServiceEntry objects.
authority string Information used to route to the desired Service. Can either be a full address
(aService.spot.robot) or just a DNS label that will be automatically converted to an
address (aService).
last_update google.protobuf.Timestamp Last update time in robot timebase for this service record. This serves as the time of
the last heartbeat to the robot.
user_token_required bool If 'user_token_required' field is true, any requests to this service must contain
a user token for the machine. Requests without a user token will result in a
401. Most services will want to require a user_token, but ones like auth_service
do not.
permission_required string If 'permission_required' field is non-empty, any requests to this service must
have the same string in the "per" claim of the user token.
liveness_timeout_secs double Number of seconds to wait between heartbeats before assuming service in no longer live
If unset (0) liveness checks will be disabled for this service.
host_payload_guid string The GUID of the payload that this service was registered from. An empty string represents a
service that was registered via a client using standard user credentials or internal to the
robot. This value is set automatically based on the user token and cannot be set or updated
via the API, so it should not be populated by the client at registration time.

GetServiceEntryResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal DirectoryService issue has happened if UNKNOWN
is set.
STATUS_OK 1 GetService was successful. The service_entry field is filled out.
STATUS_NONEXISTENT_SERVICE 2 GetService failed because the requested service name does not exist.

Top

bosdyn/api/directory_registration.proto

RegisterServiceRequest

The RegisterService request message sends the service’s entry and endpoint to the robot’s directory. This Request serves as a heartbeat to the Directory.

Field Type Label Description
header RequestHeader Common request header.
endpoint Endpoint The endpoint at which this service may be contacted.
service_entry ServiceEntry The service to create. The name must not match any existing service.

RegisterServiceResponse

The RegisterService response message has information of whether the service was registered correctly.

Field Type Label Description
header ResponseHeader Common response Header.
status RegisterServiceResponse.Status Return status for the request.

UnregisterServiceRequest

The UnregisterService request message will unregister a service based on name.

Field Type Label Description
header RequestHeader Common request header.
service_name string The unique user-friendly name of the service.

UnregisterServiceResponse

The UnregisterService response message has information of whether the service was unregistered.

Field Type Label Description
header ResponseHeader Common response Header.
status UnregisterServiceResponse.Status Return status for the request.

UpdateServiceRequest

The UpdateService request message will update a service based on name to include the new endpoint and service entry. This Request serves as a heartbeat to the Directory.

Field Type Label Description
header RequestHeader Common request header.
endpoint Endpoint The endpoint at which this service may be contacted.
service_entry ServiceEntry New record for service. The name field is used as lookup key.

UpdateServiceResponse

The UpdateService response message has information of whether the service was updated on robot.

Field Type Label Description
header ResponseHeader Common response Header.
status UpdateServiceResponse.Status Return status for the request.

RegisterServiceResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal DirectoryRegistrationService issue has happened if UNKNOWN is set.
STATUS_OK 1 Success. The new service record is available.
STATUS_ALREADY_EXISTS 2 RegisterService failed because a service with this name already exists.

UnregisterServiceResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal DirectoryRegistrationService issue has
happened if UNKNOWN is set.
STATUS_OK 1 Success. The service record was deleted.
STATUS_NONEXISTENT_SERVICE 2 The provided service name was not found.

UpdateServiceResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal DirectoryRegistrationService issue has happened if UNKNOWN is set.
STATUS_OK 1 Success. The new service record is available.
STATUS_NONEXISTENT_SERVICE 2 The provided service name was not found.

Top

bosdyn/api/directory_registration_service.proto

DirectoryRegistrationService

DirectoryRegistrationService is a private class that lets services be discovered by clients by adding them to a discovery database. Services can live on robot, payload, or other accessible cloud-based locations. Each service is responsible for registering itself with this service.

Method Name Request Type Response Type Description
RegisterService RegisterServiceRequest RegisterServiceResponse Called by a producer to register as a provider with the application. Returns the
record for that provider. Requires unique name and correctly filled out service
record in request.
UnregisterService UnregisterServiceRequest UnregisterServiceResponse Called by a producer to remove its registration from the DirectoryManager.
UpdateService UpdateServiceRequest UpdateServiceResponse Update the ServiceEntry for a producer on the server.

Top

bosdyn/api/directory_service.proto

DirectoryService

DirectoryService lets clients discover which API services are available on a robot.

Method Name Request Type Response Type Description
GetServiceEntry GetServiceEntryRequest GetServiceEntryResponse Get information about a specific service.
ListServiceEntries ListServiceEntriesRequest ListServiceEntriesResponse List all known services at time of call.

Top

bosdyn/api/docking/docking.proto

ConfigRange

The configuration of a range of dock ID’s

Field Type Label Description
id_start uint32 Starting ID
id_end uint32 Ending ID
type DockType Type of dock for this range

DockState

Message describing the overall dock state of the robot, including power & comms connections.
Not tied to any particular DockingCommand ID.
Note: [*] indicates fields which are only valid if the status is DOCK_STATUS_DOCKED or DOCK_STATUS_DOCKING
or DOCK_STATUS_UNDOCKING.
Note: [^] indicates fields which are only valid if the status is DOCK_STATUS_DOCKED. \

Field Type Label Description
status DockState.DockedStatus Status of if the robot is on dock
dock_type DockType [*] Type of the dock
dock_id uint32 [*] ID of the dock
power_status DockState.LinkStatus [^] Status of power detection from the dock

DockingCommandFeedbackRequest

Message to get the status of a previously issued DockingCommand

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
docking_command_id uint32 Unique identifier of the command to get feedback for.
update_docking_params UpdateDockingParams [optional] Update parameters relating to the specified command ID

DockingCommandFeedbackResponse

Response to a DockingCommandFeedbackRequest for a particualar docking command ID

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used (unset if unknown).
status DockingCommandFeedbackResponse.Status Current feedback of specified command ID.

DockingCommandRequest

Message to command the robot to dock.
Note: If the robot is docked, you can undock the robot by issuing a command with prep_pose_behavior=PREP_POSE_UNDOCK. If undocking, docking_station_id is not required.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease The Lease to show ownership of the robot.
docking_station_id uint32 ID of docking station to dock at.
This is ignored if undocking the robot, the current dock is used.
clock_identifier string Identifier provided by the time sync service to verify time sync between robot and client.
end_time google.protobuf.Timestamp The timestamp (in robot time) at which a command will stop executing.
This can be updated by other RPCs
This is a required field and used to prevent runaway commands.
prep_pose_behavior PrepPoseBehavior [Optional] Specify the prep pose behavior
require_fiducial bool Require the detection of the dock's fiducial

DockingCommandResponse

Response to a DockingCommandRequest

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.
status DockingCommandResponse.Status Result of issued command.
docking_command_id uint32 Unique identifier for the command (if accepted, status=STATUS_OK).

GetDockingConfigRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetDockingConfigResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
dock_configs ConfigRange repeated A series of ConfigRange specifying details for dock ID numbers.

GetDockingStateRequest

Message to get the overall docking state

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetDockingStateResponse

Response of a GetDockingStateRequest

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
dock_state DockState

UpdateDockingParams

Field Type Label Description
end_time google.protobuf.Timestamp The new timestamp (in robot time) at which a command will stop executing.

DockState.DockedStatus

Name Number Description
DOCK_STATUS_UNKNOWN 0 Unknown
DOCK_STATUS_DOCKED 1 Robot is detected as on a dock
DOCK_STATUS_DOCKING 2 Robot is currently running a docking command
DOCK_STATUS_UNDOCKED 3 Robot is not detected as on dock
DOCK_STATUS_UNDOCKING 4 Robot is currently running an undocking command

DockState.LinkStatus

Name Number Description
LINK_STATUS_UNKNOWN 0 Unknown or Not applicable
LINK_STATUS_DETECTING 3 The link status is being detected
LINK_STATUS_CONNECTED 1 The link is detected as connected
LINK_STATUS_ERROR 2 The link could not be detected

DockType

Type of dock

Name Number Description
DOCK_TYPE_UNKNOWN 0 Unknown type of dock
DOCK_TYPE_CONTACT_PROTOTYPE 2 Prototype version SpotDock
DOCK_TYPE_SPOT_DOCK 3 Production version SpotDock
DOCK_TYPE_SPOT_DOGHOUSE 4 Production version SpotDock located in the dog house.

DockingCommandFeedbackResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status is not specified.
STATUS_IN_PROGRESS 1 Docking command is executing.
STATUS_DOCKED 2 Docking command succeeded, the robot is docked.
STATUS_AT_PREP_POSE 11 Final success state for PREP_POSE_ONLY_POSE or PREP_POSE_UNDOCK.
STATUS_MISALIGNED 10 Misaligned was detected between the robot and the dock.
The docking command was aborted to save an ending up in an unrecoverable state, please try again.
STATUS_OLD_DOCKING_COMMAND 3 This DockingCommand overridden by new docking command.
STATUS_ERROR_DOCK_LOST 4 ERROR: The sensed dock has been lost and is no longer found.
STATUS_ERROR_LEASE 5 ERROR: Lease rejected.
STATUS_ERROR_COMMAND_TIMED_OUT 6 ERROR: End time has been reached.
STATUS_ERROR_NO_TIMESYNC 7 ERROR: No Timesync with system.
STATUS_ERROR_TOO_DISTANT 8 ERROR: Provided end time too far in the future.
STATUS_ERROR_NOT_AVAILABLE 12 ERROR: The dock is not available for docking.
STATUS_ERROR_UNREFINED_PRIOR 13 ERROR: The prior could not be confirmed as a real dock
STATUS_ERROR_STUCK 14 ERROR: The robot could not make progress towards docking.
For example, there may be an obstacle in the way.
STATUS_ERROR_SYSTEM 9 ERROR: Internal system error during execution
This error cannot be resolved by issuing a new DockingCommand
Check the returned message for details

DockingCommandResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status is not specified.
STATUS_OK 1 Docking command accepted
STATUS_ERROR_LEASE 4 ERROR: Lease rejected
STATUS_ERROR_DOCK_NOT_FOUND 5 ERROR: Dock fiducial not found.
STATUS_ERROR_NOT_DOCKED 6 ERROR: Trying to undock while not docked
STATUS_ERROR_GRIPPER_HOLDING_ITEM 8 ERROR: Trying to dock when the arm is holding an object.
STATUS_ERROR_NOT_AVAILABLE 9 ERROR: The dock is not available for docking.
STATUS_ERROR_SYSTEM 7 ERROR: Internal system error during execution
This error cannot be resolved by issuing a new DockingCommand
Check the returned message for details

PrepPoseBehavior

Defines how and whether we use the “pre-docking” pose.

Name Number Description
PREP_POSE_UNKNOWN 0 Default behavior, equivalent to PREP_POSE_USE_POSE.
PREP_POSE_USE_POSE 1 Goes to the pre-docking pose before docking.
PREP_POSE_SKIP_POSE 2 Docks before going to the pre-docking pose.
PREP_POSE_ONLY_POSE 3 Goes to the pre-docking pose, and then returns SUCCESS without docking.
PREP_POSE_UNDOCK 4 Use this enum to undock a currently docked robot.

Top

bosdyn/api/docking/docking_service.proto

DockingService

The DockingService provides an interface to dock and undock the robot from Spot Docks, as well as get feedback on command status, and get the current docked status of the robot.

Method Name Request Type Response Type Description
DockingCommand DockingCommandRequest DockingCommandResponse Starts a docking command on the robot.
DockingCommandFeedback DockingCommandFeedbackRequest DockingCommandFeedbackResponse Check the status of a docking command.
GetDockingConfig GetDockingConfigRequest GetDockingConfigResponse Get the configured dock ID ranges.
GetDockingState GetDockingStateRequest GetDockingStateResponse Get the robot's docking state

Top

bosdyn/api/estop.proto

DeregisterEstopEndpointRequest

Deregister the specified E-Stop endpoint registration.

Field Type Label Description
header RequestHeader Common request header
target_endpoint EstopEndpoint The endpoint to deregister.
target_config_id string ID of the configuration we are registering against.

DeregisterEstopEndpointResponse

Response to E-Stop endpoint deregistration request.

Field Type Label Description
header ResponseHeader Common resonse header.
request DeregisterEstopEndpointRequest Copy of the initial request.
status DeregisterEstopEndpointResponse.Status Status code for the response.

EstopCheckInRequest

Client request for setting/maintaining an E-Stop system level. After the first CheckIn, must include response to previous challenge.

Field Type Label Description
header RequestHeader Common request header.
endpoint EstopEndpoint The endpoint making the request.
challenge uint64 Challenge being responded to.
Don't set if this is the first EstopCheckInRequest.
response uint64 Response to above challenge.
Don't set if this is the first EstopCheckInRequest.
stop_level EstopStopLevel Assert this stop level.

EstopCheckInResponse

Server response to EstopCheckInRequest.

Field Type Label Description
header ResponseHeader Common response header.
request EstopCheckInRequest Copy of initial request.
challenge uint64 Next challenge to answer.
status EstopCheckInResponse.Status Status code for the response.

EstopConfig

Configuration of a root / server.

Field Type Label Description
endpoints EstopEndpoint repeated EstopEndpoints that are part of this configuration.
Unique IDs do not have to be filled out, but can be.
unique_id string Unique ID for this configuration.

EstopEndpoint

An to the robot software-E-Stop system.

Field Type Label Description
role string Role of this endpoint. Should be a user-friendly string, e.g. "OCU".
name string Name of this endpoint. Specifies a thing to fill the given role, e.g. "patrol-ocu01"
unique_id string Unique ID assigned by the server.
timeout google.protobuf.Duration Maximum delay between challenge and response for this endpoint prior to soft power off
handling. After timeout seconds has passed, the robot will try to get to a safe state prior
to disabling motor power. The robot response is equivalent to an ESTOP_LEVEL_SETTLE_THEN_CUT
which may involve the robot sitting down in order to prepare for disabling motor power.
cut_power_timeout google.protobuf.Duration Optional maximum delay between challenge and response for this endpoint prior to disabling
motor power. After cut_power_timeout seconds has passed, motor power will be disconnected
immediately regardless of current robot state. If this value is not set robot will default
to timeout plus a nominal expected duration to reach a safe state. In practice this
is typically 3-4 seconds. The response is equivalent to an ESTOP_LEVEL_CUT.

EstopEndpointWithStatus

EstopEndpoint with some extra status data.

Field Type Label Description
endpoint EstopEndpoint The endpoint.
stop_level EstopStopLevel Stop level most recently requested by the endpoint.
time_since_valid_response google.protobuf.Duration Time since a valid response was provided by the endpoint.

EstopSystemStatus

Status of Estop system.

Field Type Label Description
endpoints EstopEndpointWithStatus repeated Status for all available endpoints.
stop_level EstopStopLevel Current stop level for the system.
Will be the most-restrictive stop level specified by an endpoint, or a stop level
asserted by the system as a whole (e.g. if an endpoint timed out).
stop_level_details string Human-readable information on the stop level.

GetEstopConfigRequest

Get the active EstopConfig.

Field Type Label Description
header RequestHeader Common request header.
target_config_id string The 'unique_id' of EstopConfig to get.

GetEstopConfigResponse

Response to EstopConfigRequest.

Field Type Label Description
header ResponseHeader Common response header.
request GetEstopConfigRequest Copy of the request.
active_config EstopConfig The currently active configuration.

GetEstopSystemStatusRequest

Ask for the current status of the Estop system.

Field Type Label Description
header RequestHeader Common request header.

GetEstopSystemStatusResponse

Respond with the current Estop system status.

Field Type Label Description
header ResponseHeader Common response header.
status EstopSystemStatus Status of the Estop system.

RegisterEstopEndpointRequest

Register an endpoint. EstopEndpoints must be registered before they can send commands or request challenges.

Field Type Label Description
header RequestHeader Common request header
target_endpoint EstopEndpoint The endpoint to replace.
Set the endpoint's unique ID if replacing an active endpoint.
target_config_id string ID of the configuration we are registering against.
new_endpoint EstopEndpoint The description of the new endpoint.
Do not set the unique ID. It will be ignored.

RegisterEstopEndpointResponse

Response to registration request.

Field Type Label Description
header ResponseHeader Common response header
request RegisterEstopEndpointRequest Copy of the initial request.
new_endpoint EstopEndpoint The resulting endpoint on success.
status RegisterEstopEndpointResponse.Status Status code for the response.

SetEstopConfigRequest

Set a new active EstopConfig.

Field Type Label Description
header RequestHeader Common request header.
config EstopConfig New configuration to set.
target_config_id string The 'unique_id' of EstopConfig to replace, if replacing one.

SetEstopConfigResponse

Response to EstopConfigRequest.

Field Type Label Description
header ResponseHeader Common response header.
request SetEstopConfigRequest Copy of the request.
active_config EstopConfig The currently active configuration.
status SetEstopConfigResponse.Status

DeregisterEstopEndpointResponse.Status

Name Number Description
STATUS_UNKNOWN 0 An unknown / unexpected error occurred.
STATUS_SUCCESS 1 Request succeeded.
STATUS_ENDPOINT_MISMATCH 2 Target endpoint did not match.
STATUS_CONFIG_MISMATCH 3 Registered to wrong configuration.
STATUS_MOTORS_ON 4 You cannot deregister an endpoint while the motors are on.

EstopCheckInResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Unknown error occurred.
STATUS_OK 1 Valid challenge has been returned.
STATUS_ENDPOINT_UNKNOWN 2 The endpoint specified in the request is not registered.
STATUS_INCORRECT_CHALLENGE_RESPONSE 5 The challenge and/or response was incorrect.

EstopStopLevel

The state of the E-Stop system.

Name Number Description
ESTOP_LEVEL_UNKNOWN 0 Invalid stop level.
ESTOP_LEVEL_CUT 1 Immediately cut power to the actuators.
ESTOP_LEVEL_SETTLE_THEN_CUT 2 Prepare for loss of actuator power, then cut power.
ESTOP_LEVEL_NONE 4 No-stop level. The endpoint believes the robot is safe to operate.

RegisterEstopEndpointResponse.Status

Name Number Description
STATUS_UNKNOWN 0 An unknown / unexpected error occurred.
STATUS_SUCCESS 1 Request succeeded.
STATUS_ENDPOINT_MISMATCH 2 Target endpoint did not match.
STATUS_CONFIG_MISMATCH 3 Registered to wrong configuration.
STATUS_INVALID_ENDPOINT 4 New endpoint was invalid.

SetEstopConfigResponse.Status

Name Number Description
STATUS_UNKNOWN 0 An unknown / unexpected error occurred.
STATUS_SUCCESS 1 Request succeeded.
STATUS_INVALID_ID 2 Tried to replace a EstopConfig, but provided bad ID.
STATUS_MOTORS_ON 4 You cannot set a configuration while the motors are on.

Top

bosdyn/api/estop_service.proto

EstopService

The software robot E-Stop system:

  1. Uses challenge-style communication to enforce end user (aka “originators”) connection for Authority to Operate (ATO).

  2. Offers the ability to issue a direct denial of ATO. The EstopService provides a service interface for the robot EStop/Authority to operate the system.

Method Name Request Type Response Type Description
RegisterEstopEndpoint RegisterEstopEndpointRequest RegisterEstopEndpointResponse Register an Estop "originator" or "endpoint".
This may be a replacement for another active endpoint.
DeregisterEstopEndpoint DeregisterEstopEndpointRequest DeregisterEstopEndpointResponse Deregister the requested estop endpoint.
EstopCheckIn EstopCheckInRequest EstopCheckInResponse Answer challenge from previous response (unless this is the first call), and request
a stop level.
GetEstopConfig GetEstopConfigRequest GetEstopConfigResponse Request the current EstopConfig, describing the expected set of endpoints.
SetEstopConfig SetEstopConfigRequest SetEstopConfigResponse Set a new active EstopConfig.
GetEstopSystemStatus GetEstopSystemStatusRequest GetEstopSystemStatusResponse Ask for the current status of the estop system.

Top

bosdyn/api/fault_service.proto

FaultService

The service fault service enables modification of the robot state ServiceFaultState.

Method Name Request Type Response Type Description
TriggerServiceFault TriggerServiceFaultRequest TriggerServiceFaultResponse Sends a ServiceFault to be reporting in robot state.
ClearServiceFault ClearServiceFaultRequest ClearServiceFaultResponse Clears an active ServiceFault from robot state.

Top

bosdyn/api/full_body_command.proto

FullBodyCommand

The robot command message to specify a basic command that requires full control of the entire robot to be completed.

FullBodyCommand.Feedback

The feedback for the fully body command that will provide information on the progress of the robot command.

Field Type Label Description
stop_feedback StopCommand.Feedback Feedback for the stop command request.
freeze_feedback FreezeCommand.Feedback Feedback for the freeze command request.
selfright_feedback SelfRightCommand.Feedback Feedback for the self-right command request.
safe_power_off_feedback SafePowerOffCommand.Feedback Feedback for the safe power off command request.
battery_change_pose_feedback BatteryChangePoseCommand.Feedback Feedback for the battery change pose command request.
payload_estimation_feedback PayloadEstimationCommand.Feedback Feedback for the payload estimation command request.
constrained_manipulation_feedback ConstrainedManipulationCommand.Feedback Feedback for the constrained manipulation command request
joint_feedback JointCommand.Feedback Feedback for joint level control
status RobotCommandFeedbackStatus.Status

FullBodyCommand.Request

The full body request must be one of the basic command primitives.

Field Type Label Description
stop_request StopCommand.Request Command to stop the robot.
freeze_request FreezeCommand.Request Command to freeze all joints of the robot.
selfright_request SelfRightCommand.Request Command to self-right the robot to a ready position.
safe_power_off_request SafePowerOffCommand.Request Command to safely power off the robot.
battery_change_pose_request BatteryChangePoseCommand.Request Command to put the robot in a position to easily change the battery.
payload_estimation_request PayloadEstimationCommand.Request Command to perform payload mass property estimation
constrained_manipulation_request ConstrainedManipulationCommand.Request Command to perform full body constrained manipulation moves
joint_request JointCommand.Request Activate joint level control
params google.protobuf.Any Robot specific command parameters.

Top

bosdyn/api/geometry.proto

Area

Represents an area in the XY plane.

Field Type Label Description
polygon Polygon
circle Circle

Bounds

Represents bounds on a value, such that lower < value < upper. If you do not want to specify one side of the bound, set it to an appropriately large (or small) number.

Field Type Label Description
lower double
upper double

Box2

Geometric primitive describing a two-dimensional box.

Field Type Label Description
size Vec2

Box2WithFrame

Geometric primitive to describe a 2D box in a specific frame.

Field Type Label Description
box Box2 The box is specified with width (y) and length (x), and the full box is
fixed at an origin, where it's sides are along the coordinate frame's
axes.
frame_name string The pose of the axis-aligned box is in 'frame_name'.
frame_name_tform_box SE3Pose The transformation of the axis-aligned box into the desired frame
(specified above).

Box3

Geometric primitive describing a three-dimensional box.

Field Type Label Description
size Vec3

Box3WithFrame

Geometric primitive to describe a 3D box in a specific frame.

Field Type Label Description
box Box3 The box width (y), length (x), and height (z) are interpreted in, and the
full box is fixed at an origin, where it's sides are along the coordinate
frame's axes.
frame_name string The pose of the axis-aligned box is in 'frame_name'.
frame_name_tform_box SE3Pose The transformation of the axis-aligned box into the desired frame
(specified above).

Circle

Represents a circular 2D area.

Field Type Label Description
center_pt Vec2
radius double Dimensions in m from center_pt.

CylindricalCoordinate

Cylindrical coordinates are a generalization of polar coordiates, adding a height axis. See (http://mathworld.wolfram.com/CylindricalCoordinates.html) for more details.

Field Type Label Description
r double Radial coordinate
theta double Azimuthal coordinate
z double Vertical coordiante

FrameTreeSnapshot

A frame is a named location in space.
For example, the following frames are defined by the API: \

  • “body”: A frame centered on the robot’s body. \

  • “vision”: A non-moving (inertial) frame that is the robot’s best estimate of a fixed location in the world. It is based on both dead reckoning and visual analysis of the world. \

  • “odom”: A non-moving (inertial) frame that is based on the kinematic odometry of the robot only.
    Additional frames are available for robot joints, sensors, and items detected in the world. \

The FrameTreeSnapshot represents the relationships between the frames that the robot knows about at a particular point in time. For example, with the FrameTreeSnapshot, an API client can determine where the “body” is relative to the “vision”. \

To reduce data bandwidth, the FrameTreeSnapshot will typically contain a small subset of all known frames. By default, all services MUST include “vision”, “body”, and “odom” frames in the FrameTreeSnapshot, but additional frames can also be included. For example, an Image service would likely include the frame located at the base of the camera lens where the picture was taken. \

Frame relationships are expressed as edges between “parent” frames and “child” frames, with an SE3Pose indicating the pose of the “child” frame expressed in the “parent” frame. These edges are included in the edge_map field. For example, if frame “hand” is 1m in front of the frame “shoulder”, then the FrameTreeSnapshot might contain:
edge_map {
key: “hand”
value: {
parent_frame_name: “shoulder”
parent_tform_child: {
position: {
x: 1.0
y: 0.0
z: 0.0
}
}
}
} \

Frame relationships can be inverted. So, to find where the “shoulder” is in relationship the “hand”, the parent_tform_child pose in the edge above can be inverted:
hand_tform_shoulder = shoulder_tform_hand.inverse()
Frame relationships can also be concatenated. If there is an additional edge specifying the pose of the “shoulder” relative to the “body”, then to find where the “hand” is relative to the “body” do:
body_tform_hand = body_tform_shoulder * shoulder_tform_hand \

The two properties above reduce data size. Instead of having to send N^2 edge_map entries to represent all relationships between N frames, only N edge_map entries need to be sent. Clients will need to determine the chain of edges to follow to get from one frame to another frae, and then do inversion and concatentation to generate the appropriate pose. \

Note that all FrameTreeSnapshots are expected to be a single rooted tree. The syntax for FrameTreeSnapshot could also support graphs with cycles, or forests of trees - but clients should treat those as invalid representations. \

Field Type Label Description
child_to_parent_edge_map FrameTreeSnapshot.ChildToParentEdgeMapEntry repeated child_to_parent_edge_map maps the child frame name to the ParentEdge.
In aggregate, this forms the tree structure.

FrameTreeSnapshot.ChildToParentEdgeMapEntry

Field Type Label Description
key string
value FrameTreeSnapshot.ParentEdge

FrameTreeSnapshot.ParentEdge

ParentEdge represents the relationship from a child frame to a parent frame.

Field Type Label Description
parent_frame_name string The name of the parent frame. If a frame has no parent (parent_frame_name is empty),
it is the root of the tree.
parent_tform_child SE3Pose Transform representing the pose of the child frame in the parent's frame.

Matrix

Represents a row-major order matrix of doubles.

Field Type Label Description
rows int32
cols int32
values double repeated

MatrixInt32

Represents a row-major order matrix of int32.

Field Type Label Description
rows int32
cols int32
values int32 repeated

MatrixInt64

Represents a row-major order matrix of int64.

Field Type Label Description
rows int32
cols int32
values int64 repeated

Matrixf

Represents a row-major order matrix of floats.

Field Type Label Description
rows int32
cols int32
values float repeated

Plane

Plane primitive, described with a point and normal.

Field Type Label Description
point Vec3 A point on the plane.
normal Vec3 The direction of the planes normal.

PolyLine

Multi-part, 1D line segments defined by a series of points.

Field Type Label Description
points Vec2 repeated

Polygon

Polygon in the XY plane. May be concave, but should not self-intersect. Vertices can be specified in either clockwise or counterclockwise orders.

Field Type Label Description
vertexes Vec2 repeated

PolygonWithExclusions

Represents a region in the XY plane that consists of a single polygon from which polygons representing exclusion areas may be subtracted.

A point is considered to be inside the region if it is inside the inclusion polygon and not inside any of the exclusion polygons.

Note that while this can be used to represent a polygon with holes, that exclusions are not necessarily holes: An exclusion polygon may not be completely inside the inclusion polygon.

Field Type Label Description
inclusion Polygon
exclusions Polygon repeated

Quad

A square oriented in 3D space.

Field Type Label Description
pose SE3Pose The center of the quad and the orientation of the normal.
The normal axis is [0, 0, 1].
size double The side length of the quad.

Quaternion

Quaternion primitive. A quaternion can be used to describe the rotation.

Field Type Label Description
x double
y double
z double
w double

Ray

A ray in 3D space.

Field Type Label Description
origin Vec3 Base of ray.
direction Vec3 Unit vector defining the direction of the ray.

SE2Pose

Geometric primitive to describe 2D position and rotation.

Field Type Label Description
position Vec2 (m)
angle double (rad)

SE2Velocity

Geometric primitive that describes a 2D velocity through it’s linear and angular components.

Field Type Label Description
linear Vec2 (m/s)
angular double (rad/s)

SE2VelocityLimit

Geometric primitive to couple minimum and maximum SE2Velocities in a single message.

Field Type Label Description
max_vel SE2Velocity If set, limits the maximum velocity.
min_vel SE2Velocity If set, limits the minimum velocity.

SE3Covariance

Represents the translation/rotation covariance of an SE3 Pose. The 6x6 matrix can be viewed as the covariance among 6 variables:
rx ry rz x y z
rx rxrx rxry rxrz rxx rxy rxz
ry ryrx ryry ryrz ryx ryy ryz
rz rzrx rzry rzrz rzx rzy rzz
x xrx xry xrz xx xy xz
y yrx yry yrz yx yy yz
z zrx zry zrz zx zy zz
where x, y, z are translations in meters, and rx, ry, rz are rotations around the x, y and z axes in radians.
The matrix is symmetric, so, for example, xy = yx. \

Field Type Label Description
matrix Matrix Row-major order representation of the covariance matrix.
yaw_variance double Deprecated. Variance of the yaw component of the SE3 Pose.
Warning: DEPRECATED as of 2.1. This should equal cov_rzrz, inside matrix. Will be removed
in a future release.
FIXME(sberard): https://bostondynamics.atlassian.net/browse/SPOT-12523
cov_xx double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.
cov_xy double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.
cov_xz double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.
cov_yx double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.
cov_yy double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.
cov_yz double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.
cov_zx double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.
cov_zy double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.
cov_zz double Deprecated. Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release.

SE3Pose

Geometric primitive to describe 3D position and rotation.

Field Type Label Description
position Vec3 (m)
rotation Quaternion

SE3Velocity

Geometric primitive that describes a 3D velocity through it’s linear and angular components.

Field Type Label Description
linear Vec3 (m/s)
angular Vec3 (rad/s)

Vec2

Two dimensional vector primitive.

Field Type Label Description
x double
y double

Vec2Value

A 2D vector of doubles that uses wrapped values so we can tell which elements are set.

Field Type Label Description
x google.protobuf.DoubleValue
y google.protobuf.DoubleValue

Vec3

Three dimensional vector primitive.

Field Type Label Description
x double
y double
z double

Vec3Value

A 3D vector of doubles that uses wrapped values so we can tell which elements are set.

Field Type Label Description
x google.protobuf.DoubleValue
y google.protobuf.DoubleValue
z google.protobuf.DoubleValue

Vector

Represents a vector of doubles

Field Type Label Description
values double repeated

Volume

Represents a volume of space in an unspecified frame.

Field Type Label Description
box Vec3 Dimensions in m, centered on frame origin.

Wrench

Geometric primitive used to specify forces and torques.

Field Type Label Description
force Vec3 (N)
torque Vec3 (Nm)

Top

bosdyn/api/gps/aggregator.proto

NewGpsDataRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
data_points GpsDataPoint repeated GPS Measurements. GPS units that generate data at a high rate
can bundle multiple measurements together in a single message.
gps_device GpsDevice Describer for what device is generating GPS data.

NewGpsDataResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

Top

bosdyn/api/gps/aggregator_service.proto

AggregatorService

The AggregatorService is an endpoint that clients should send GPS data too. Data dumped into the AggregatorService is used by the RegistrationService. In practice: - A GPS will be connected to a peripheral computer - The peripheral computer should establish timesync with the robot - The peripheral computer should read data from the GPS hardware - The peripheral computer should send timestamped data to the AggregatorService

Method Name Request Type Response Type Description
NewGpsData NewGpsDataRequest NewGpsDataResponse

Top

bosdyn/api/gps/gps.proto

GpsDataPoint

Field Type Label Description
llh LLH The GPS measurement as Latitude, Longitude, Height.
ecef bosdyn.api.Vec3 The GPS measurement with respect to the Earth Centered Earth Fixed frame
yaw google.protobuf.DoubleValue Magnetometer yaw. 0 is north. Processes counter clockwise. We did this to match Spot's
body coordinate system, where Z is up.
heading google.protobuf.DoubleValue Movement heading. 0 is north. Processes counter clockwise. We did this to match Spot's
body coordinate system, where Z is up.
accuracy GpsDataPoint.Accuracy
satellites GpsDataPoint.Satellite repeated Satellites used in the location solution.
mode GpsDataPoint.FixMode The current fix, if any.
timestamp_gps google.protobuf.Timestamp GPS timestamp. This will not match robot time.
filter GpsDataPoint.Filter
timestamp_client google.protobuf.Timestamp Optional field corresponding the timestamp of the computer the GPS is connected
to (if any).
timestamp_robot google.protobuf.Timestamp Robot timestamp.
body_tform_gps bosdyn.api.SE3Pose How the GPS is mounted relative to the robots body.

GpsDataPoint.Accuracy

Estimated accuracy is measured in meters

Field Type Label Description
horizontal double
vertical double

GpsDataPoint.FixMode

Field Type Label Description
value GpsDataPoint.FixMode.Mode The current type of fix.

GpsDataPoint.Satellite

Information about a GNSS satellite measurement.

Field Type Label Description
prn uint32 satellite identifier
elevation float Degrees from -90 to 90
azimuth float Degrees from true north
snr float in dB
constellation GpsDataPoint.Satellite.Constellation

GpsDevice

Field Type Label Description
name string A human readable name for this GPS unit. "Piksi" or "Duro" or "Microstrain"

LLH

Latitude/longitude location representation.

Field Type Label Description
latitude double Latitude value in degrees.
longitude double Longitude value in degrees.
height double Height value in meters. The reference system from where the height is
calculated is controlled by the application generating this structure.

LocationAndGpsDevice

Field Type Label Description
data_point GpsDataPoint
device GpsDevice

GpsDataPoint.Filter

Name Number Description
FILTER_UNKNOWN 0
FILTER_NONE 1
FILTER_DURO_INS 2

GpsDataPoint.FixMode.Mode

Types of fixes possible.

Name Number Description
Invalid 0
SPP 1 Single Point Positioning
DGNSS 2 Differential Global Navigation Satellite System
PPS 3 Precise Positioning System Fix
FIXED_RTK 4 Fixed-Point Real-Time Kinematics
FLOAT_RTK 5 Floating-Point Real-Time Kinematics
DEAD_RECKONING 6
FIXED_POSITION 7
SIMULATED 8
SBAS 9 Satellite Based Augmentation System

GpsDataPoint.Satellite.Constellation

Name Number Description
UNKNOWN 0
GPS_L1CA 1
GPS_L2CM 2
SBAS_L1CA 3
GLONASS_L1CA 4
GLONASS_L2CA 5
GPS_L1P 6
GPS_L2P 7
BDS2_B1 8 BDS stands for the BeiDou Navigation Satellite System
BDS2_B2 9
GALILEO_E1B 10
GALILEO_E7I 11

Top

bosdyn/api/gps/registration.proto

GetLocationRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetLocationResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status GetLocationResponse.Status
registration Registration

GpsState

Field Type Label Description
latest_data GpsDataPoint Latest data from the GPS device.
gps_device GpsDevice What GPS device generated the latest data
ecef_p_body bosdyn.api.Vec3 Estimate of where the robot's body is in the ECEF frame given this measurement. Note this must be a position
and not a pose because of the lack of orientation data.
historical_data GpsDataPoint repeated Collection of all GPS data received by this device within some window.

Registration

Field Type Label Description
status Registration.Status
timestamp google.protobuf.Timestamp Time stamp of latest registration.
transforms_snapshot bosdyn.api.FrameTreeSnapshot Includes all normal robots frames ("body", "odom", etc) AND
"ecef" frame, which you can read about here: https://wikipedia.org/wiki/ECEF
robot_body_location LLH The estimated position of the robot's body frame in LLH form. This position is filtered.
gps_states GpsState repeated Most recent data from each GPS. Note that the LLH the GPS is reporting
won't exactly match robot_body_location, because robot_body_location is
filtered, and the GPS might have some offset relative to the robot's body.

ResetRegistrationRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

ResetRegistrationResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

GetLocationResponse.Status

Quality of registration status.

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_NEED_DEVICE 2

Registration.Status

Quality of registration status.

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_NEED_DATA 2 No data has been reported to perform registration.
STATUS_NEED_MORE_DATA 3 Data has been reported, but not enough to get a fix.
STATUS_STALE 4 We have a registration, but it is based on old data.

Top

bosdyn/api/gps/registration_service.proto

RegistrationService

The RegistrationService consumes data sent to the Gps/AggregatorService. It calculates where the robot is in the world, and the transfroms from the robots internal frames to the world frame.

Method Name Request Type Response Type Description
GetLocation GetLocationRequest GetLocationResponse
ResetRegistration ResetRegistrationRequest ResetRegistrationResponse

Top

bosdyn/api/graph_nav/area_callback.proto

AreaCallbackError

Error reporting for things that can go wrong with calls.

Field Type Label Description
service_name string
error AreaCallbackError.CallError
begin_callback BeginCallbackResponse
begin_control BeginControlResponse
update_callback UpdateCallbackResponse
end_callback EndCallbackResponse

AreaCallbackInformation

Specific information about how a AreaCallback implementation should be called. All fields are optional, and need only be filled out if the desired behavior is different from the default.

Field Type Label Description
required_lease_resources string repeated A area callback can request to be in control of one or more resources at runtime.
custom_params bosdyn.api.DictParam.Spec Parameters this area callback supports that do not match any of the other fields.
blockage AreaCallbackInformation.Blockage
impairment_check AreaCallbackInformation.Impairment
entity_waiting AreaCallbackInformation.EntityWaiting
default_stop StopConfiguration How the robot should stop at waypoints by default.
map_config AreaCallbackMapConfig Configuration to store in the map about how to treat the region edges.

AreaCallbackInformationRequest

Message for requesting information about a area callback implementation.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

AreaCallbackInformationResponse

Message for providing information about a area callback implementation.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
info AreaCallbackInformation Information about how the AreaCallback should be called.

BeginCallbackRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
region_info RegionInformation Description of the region we are going to cross.
end_time google.protobuf.Timestamp The timestamp (in robot time) by which a command must finish executing.
If unset, a AreaCallback implementation may pick a reasonable value.
recorded_data AreaCallbackData Configuration data associated with this area callback region
custom_params bosdyn.api.DictParam Any other custom parameters to the callback.

BeginCallbackResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status BeginCallbackResponse.Status Return status for the request.
command_id uint32 Unique identifier for the AreaCallback, used to update the callback in subsequent calls. If
empty, the request was not accepted.
custom_param_error bosdyn.api.CustomParamError Filled out if status is STATUS_CUSTOM_PARAMS_ERROR.

BeginControlRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
leases bosdyn.api.Lease repeated Leases that a AreaCallback uses once it takes control of the robot. This list should match
AreaCallbackInformation required_lease_resources.
command_id uint32 The command id associated with a single execution of a navigation callback.

BeginControlResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_results bosdyn.api.LeaseUseResult repeated Details about how the lease was used.
status BeginControlResponse.Status Return status for the request.

EndCallbackRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
command_id uint32 The command id associated with a single execution of a navigation callback.

EndCallbackResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status EndCallbackResponse.Status Return status for the request.

RegionInformation

Description of an Area Callback region at the time of crossing

Field Type Label Description
region_id string The unique id of the region we are entering.
description string Human-readable description of the region we are entering.
route Route The planned route through the region.

RouteChangeRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
command_id uint32 The command id for which the route is changing.
route Route The new planned route through the region.
unfinished_route Route The remaining old route that was not completed.

RouteChangeResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status RouteChangeResponse.Status

StopConfiguration

Information about how the robot should behave when stopping at a location.

Field Type Label Description
face_direction StopConfiguration.FaceDirection Which direction the robot should face when lining up at a waypoint.
face_stairs_if_present bool If true, always align to stairs at the start of the callback.
Overrides face_direction if stairs are found.
face_yaw_offset google.protobuf.DoubleValue Offset applied to the above facing direction (radians).
max_distance google.protobuf.DoubleValue How close the robot needs to be to the desired pose (meters).
max_yaw google.protobuf.DoubleValue How close the robot needs to be to the desired pose (radians).

UpdateCallbackRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
command_id uint32 The command id associated with a single execution of a navigation callback.
end_time google.protobuf.Timestamp If set, update the end time (in robot time) by which a command must finish executing.
stage UpdateCallbackRequest.Stage

UpdateCallbackResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status UpdateCallbackResponse.Status Return status for the request.
policy UpdateCallbackResponse.NavPolicy Set the control policy that Graph Nav should use when crossing this region, and
how and when Graph Nav should delegate control to or wait for the callback.
This is the expected way to respond, and changing the policy is how a callback
instructs graph nav to wait or continue on.
error UpdateCallbackResponse.Error An error has occurred. Graph Nav will stop calling UpdateCallback and will call
EndCallback.
complete UpdateCallbackResponse.Complete The area callback is complete. Graph Nav will stop calling UpdateCallback and will call
EndCallback.
localization UpdateCallbackResponse.UpdateLocalization Localization changes inform Graph Nav when the callback has moved the robot,
and are ignored unless callback has control of the robot.

UpdateCallbackResponse.Complete

UpdateCallbackResponse.Error

Field Type Label Description
error UpdateCallbackResponse.Error.ErrorType
lease_use_results bosdyn.api.LeaseUseResult repeated Details about how the lease was used. Only set when error == ERROR_LEASE.

UpdateCallbackResponse.NavPolicy

Field Type Label Description
at_start UpdateCallbackResponse.NavPolicy.Option Policy for what Graph Nav should do at the start of the region.
at_end UpdateCallbackResponse.NavPolicy.Option Policy for what Graph Nav should do at the end of the region.
end_config StopConfiguration Override the default settings for how the robot should behave at the end.
Does not apply for OPTION_CONTINUE.

UpdateCallbackResponse.UpdateLocalization

Field Type Label Description
change UpdateCallbackResponse.UpdateLocalization.LocalizationChange Change the localization within GraphNav.

AreaCallbackError.CallError

Name Number Description
ERROR_UNKNOWN 0
ERROR_TRANSPORT 1 Unable to communicate with the callback.
ERROR_RESPONSE 2 The callback responded with an error.
ERROR_SERVICE 3 The service was not registered.

AreaCallbackInformation.Blockage

Specify what graph nav should expect to detect for blockages in this region. For example, if the callback can open doors, the region may initially look blocked due to a closed door, but Graph Nav should still expect it to be traversable.

Name Number Description
BLOCKAGE_UNKNOWN 0
BLOCKAGE_SKIP 1 (Default) The region may appear blocked to Graph Nav, but the callback will still be able
to traverse it. If the region is blocked, Graph Nav should consider it passable unless
it actually gets stuck trying to navigate it.
BLOCKAGE_CHECK 2 Graph Nav should expect the region to be clear. If the region is blocked, Graph Nav can
treat that as impassable.

AreaCallbackInformation.EntityWaiting

Control whether Graph Nav will stop and wait for nearby entities when crossing the region. Entity waiting is normally on for regular Graph Nav, but is by default turned off inside Area callback regions.

Name Number Description
ENTITY_WAITING_UNKNOWN 0
ENTITY_WAITING_DISABLE 1 (Default) Disable waiting for entities when crossing the region.
ENTITY_WAITING_ENABLE 2 Enable waiting for entities when crossing the region.

AreaCallbackInformation.Impairment

Specify whether graph nav should check for impairment when the callback is in control of the robot. Certain failures may make Graph Nav unable to navigate, but may not affect the callback. If the callback is in control of the robot, it may be preferable to let it finish and return control to Graph Nav before reporting any impaired error instead of interrupting the callback.

Name Number Description
IMPAIRMENT_UNKNOWN 0
IMPAIRMENT_SKIP 1 (Default) Do not check Graph Nav impairment when the callback is in control.
IMPAIRMENT_CHECK 2 Continue to check Graph Nav impairment when the callback is in control. If Graph Nav
detects that it is impaired, it will stop the callback immediately.

BeginCallbackResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
STATUS_OK 1 The area callback successfully began.
STATUS_INVALID_CONFIGURATION 2 The area callback failed to start due to some problem with the supplied
configuration_data.
STATUS_EXPIRED_END_TIME 3 The area callback end time already expired.
STATUS_CUSTOM_PARAMS_ERROR 8 One or more keys or values in custom_params are unsupported by the area callback.
See the custom_param_error for details.

BeginControlResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
STATUS_OK 1 The AreaCallback has successfully taken control of the robot.
STATUS_INVALID_COMMAND_ID 2 The request command id does not exist or is no longer executing.
STATUS_MISSING_LEASE_RESOURCES 3 The supplied lease does not match the leases requested in AreaCallbackInformation.
STATUS_LEASE_ERROR 4 A lease use error occurred.

EndCallbackResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
STATUS_OK 1 The AreaCallback has cleanly ended.
STATUS_INVALID_COMMAND_ID 2 The request command id does not exist or is no longer executing.
STATUS_SHUTDOWN_CALLBACK_FAILED 3 Shutting down the callback failed. The callback worker thread did not respond to shutdown
signal.

RouteChangeResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
STATUS_OK 1 The AreaCallback has acknowledged the route change.
STATUS_INVALID_COMMAND_ID 2 The request command id does not exist or is no longer executing.

StopConfiguration.FaceDirection

What direction robot should face.

Name Number Description
FACE_DIRECTION_UNKNOWN 0
FACE_DIRECTION_ALONG_ROUTE 1 (Default) Face along the direction of the next edges in the route,
regardless of the waypoint orientation.
FACE_DIRECTION_WAYPOINT_EXACT 2 Face in the direction of the recorded waypoint.
FACE_DIRECTION_WAYPOINT_AUTO 3 Face in the direction of the recorded waypoint, but if traversing the region in the
opposite direction to how it was recorded, flip the orientation 180 degrees.
FACE_DIRECTION_REGION_END 4 Face in the direction of the end of the region.

UpdateCallbackRequest.Stage

Name Number Description
STAGE_UNKNOWN 0
STAGE_TO_START 1 Traveling to the start of the region.
STAGE_AT_START 2 Waiting at the start of the region.
STAGE_TO_END 3 Traveling to the end of the region.
STAGE_AT_END 4 Waiting at the end of the region.

UpdateCallbackResponse.Error.ErrorType

Name Number Description
ERROR_UNKNOWN 0 UNKNOWN should never be used.
ERROR_BLOCKED 1 The callback has determined that this way is impassable.
ERROR_CALLBACK_FAILED 2 Something went wrong with the callback.
ERROR_LEASE 3 A lease error occurred while executing commands.
ERROR_TIMED_OUT 4 The callback has exceeded allowed execution time.

UpdateCallbackResponse.NavPolicy.Option

Name Number Description
OPTION_UNKNOWN 0
OPTION_CONTINUE 1 Continue past the waypoint. If not already stopped at it, do not stop.
OPTION_STOP 2 Stop at the waypoint.
OPTION_CONTROL 3 Stop at the waypoint and transfer control to the callback.

UpdateCallbackResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
STATUS_OK 1 The AreaCallback is actively updating. If an execution error does occur, that is reported
via the response oneof.
STATUS_INVALID_COMMAND_ID 2 The request command id does not exist or is no longer executing.
STATUS_EXPIRED_END_TIME 3 The area callback end time already expired.

UpdateCallbackResponse.UpdateLocalization.LocalizationChange

Name Number Description
LOCALIZATION_UNKNOWN 0 When unset, Graph Nav will not change the localization.
LOCALIZATION_AT_END 1 The robot is now at the end of the region.

Top

bosdyn/api/graph_nav/area_callback_data.proto

AreaCallbackData

Data for a AreaCallback to be stored in the map

Field Type Label Description
config_data google.protobuf.Any Custom config data used by the service to do its job.
custom_params bosdyn.api.DictParam Any other custom parameters to the callback. This will be copied into
custom_params inside the BeginCallback RPC if it exists.
map_config AreaCallbackMapConfig Configuration data for how this area callback should be treated in the map.

AreaCallbackMapConfig

Configuration data for how an area callback should be treated in a map.

Top

bosdyn/api/graph_nav/area_callback_service.proto

AreaCallbackService

Method Name Request Type Response Type Description
AreaCallbackInformation AreaCallbackInformationRequest AreaCallbackInformationResponse Retrieve information about how to operate the service, including what lease resources are
required by the navigation callback.
BeginCallback BeginCallbackRequest BeginCallbackResponse BeginCallback is called once as the robot enters a AreaCallback region of a map. This call
initializes the navigation callback for operation.
BeginControl BeginControlRequest BeginControlResponse BeginControl is called once after the area callback implementation requests control. Control
is handed off (via a lease) from the caller to the area callback.
UpdateCallback UpdateCallbackRequest UpdateCallbackResponse UpdateCallback is called periodically while the callback is running. Area callback
implementations use UpdateCallback to dictate how caller should operate while callback is
running (pause, continue, etc.)
RouteChange RouteChangeRequest RouteChangeResponse Called only if the route changes in the middle of the region (for example, if the robot is
blocked by an obstacle and re-routes).
EndCallback EndCallbackRequest EndCallbackResponse EndCallback is called once when the caller decides the navigation callback is over. This
might be because the robot exited the callback region or might be because the callback
reported that it finished doing work.

Top

bosdyn/api/graph_nav/gps.proto

GPSLocalization

Info about GPS localization if the robot has this capability.

Field Type Label Description
live_gps_state GPSLocalization.State State of the live GPS data.
map_gps_state GPSLocalization.State State of GPS data at the current waypoint.
ecef_tform_body bosdyn.api.SE3Pose Estimate of where the robot body is in the Earth-Centered-Earth-Fixed (ECEF) frame at the time
of localization.
latitude_longitude_height bosdyn.api.gps.LLH Estimate of the latitude/longitude/height of the robot at the time of localization.

GPSLocalization.State

Name Number Description
STATE_UNKNOWN 0
STATE_OK 1 Using GPS.
STATE_BAD_FRAMES 2 Error getting frames (ko, etc.)
STATE_NO_GPS_OBJECTS 3 No GPS available.
STATE_REGISTRATION_NOT_OK 4 GPS registration isn't ready.
STATE_NO_GPS_STATES 5 No GPS state measurements.
STATE_NOT_ENOUGH_SATELLITES 6 Too few satellites to localize.
STATE_NO_ECEF_FRAME 7 GPS registration is missing a frame.
STATE_HIGH_ERROR 8 The GPS data exists, but is high error.
STATE_STALE 9 The GPS data exists, and we have not used it yet, but it is too old to use.
STATE_INTERNAL_ERROR 10 Internal error (e.g. missing waypoints).

Top

bosdyn/api/graph_nav/graph_nav.proto

AreaCallbackServiceError

Information about problems Area Callback services specifified in a map or on a route.

Field Type Label Description
missing_services string repeated Area Callback services that were requested but could not be contacted by graph nav.
A service is considered missing if it is either not registered, or if it is registered
but does not respond to a AreaCallbackInformation request.
faulted_services bosdyn.api.ServiceFault repeated Area Callback services that were requested but are reporting critical faults.

ClearGraphRequest

Clears the graph on the server. Also clears GraphNav’s localization to the graph. Note that waypoint and edge snapshots may still be cached on the server after this operation. This RPC may not be used while recording a map.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease The Lease to show ownership of graph-nav service.

ClearGraphResponse

The results of the ClearGraphRequest.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.
status ClearGraphResponse.Status Status of the ClearGraphResponse.

DownloadEdgeSnapshotRequest

The DownloadEdgeSnapshot request asks for a specific edge snapshot id to be downloaded. Edge snapshots contain the large sensor data stored in each edge.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
edge_snapshot_id string ID of the data associated with an edge.

DownloadEdgeSnapshotResponse

The DownloadEdgeSnapshot response streams the data of the edge snapshot id currently being downloaded in data chunks no larger than 4MB in size. It is necessary to stream these data to avoid overwhelming gRPC with large http requests.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status DownloadEdgeSnapshotResponse.Status Return status for the request.
edge_snapshot_id string ID of the snapshot associated with an edge.
chunk bosdyn.api.DataChunk 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
EdgeSnapshot object.

DownloadGraphRequest

The DownloadGraphRequest requests that the server send the graph (waypoints and edges) to the client. Note that the returned Graph message contains only the topological structure of the map, and not any large sensor data. Large sensor data should be downloaded using DownloadWaypointSnapshotRequest and DownloadEdgeSnapshotRequest. Both snapshots and the graph are required to exist on the server for GraphNav to localize and navigate.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

DownloadGraphResponse

The DownloadGraph response message includes the current graph on the robot.

Field Type Label Description
header bosdyn.api.ResponseHeader Common request header.
graph Graph The structure of the graph.

DownloadWaypointSnapshotRequest

The DownloadWaypointSnapshot request asks for a specific waypoint snapshot id to be downloaded and has parameters to decrease the amount of data downloaded. After recording a map, first call the DownloadGraph RPC. Then, for each waypoint snapshot id, request the waypoint snapshot from the server using the DownloadWaypointSnapshot RPC.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
waypoint_snapshot_id string ID of the snapshot associated with a waypoint.
download_images bool If true, download the full images and point clouds from
each camera.
compress_point_cloud bool If true, the point cloud will be compressed using the smallest
available point cloud encoding. If false, three 32-bit floats will
be used per point.
do_not_download_point_cloud bool Skip downloading the point cloud, and only download other data such as images or world
objects.

DownloadWaypointSnapshotResponse

The DownloadWaypointSnapshot response streams the data of the waypoint snapshot id currently being downloaded in data chunks no larger than 4MB in size. It is necessary to stream these data to avoid overwhelming gRPC with large http requests.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status DownloadWaypointSnapshotResponse.Status Return status for the request.
waypoint_snapshot_id string ID of the snapshot associated with a waypoint.
chunk bosdyn.api.DataChunk 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 a
WaypointSnapshot object.

GPSNavigationParams

Parameters controlling how the robot will navigate to a GPS coordinate.

Field Type Label Description
goal_llh bosdyn.api.gps.LLH The goal position as latitude/longitude. Height is ignored.
goal_yaw google.protobuf.DoubleValue Counter-clockwise rotation in radians around the "up" axis that the robot will try to achieve at the goal. This is a bearing
around the "up" axis such that East points to zero yaw, and West is pi radians yaw. If not provided, the robot will try to
achieve any allowable orientation at the goal.
max_distance_from_map google.protobuf.DoubleValue The maximum distance we are willing to accept for the LLH coordinate from the mapped data in meters. This
is a 2 dimensional measurement (height is not considered). If not filled out, Spot will decide based on
internal defaults.

GetLocalizationStateRequest

The GetLocalizationState request message requests the current localization state and any other live data from the robot if desired. The localization consists of a waypoint ID and the relative pose of the robot with respect to that waypoint.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
waypoint_id string Return the localization relative to this waypoint, if specified.
request_live_point_cloud bool If true, request the live edge-segmented point cloud that was used
to generate this localization.
request_live_images bool If true, request the live images from realsense cameras at the time of
localization.
request_live_terrain_maps bool If true, request the live terrain maps at the time of localization.
request_live_world_objects bool If true, reqeuest the live world objects at the time of localization.
request_live_robot_state bool If true, requests the full live robot state at the time of localization.
compress_live_point_cloud bool If true, the smallest available encoding will be used for the live point cloud
data. If false, three 32 bit floats will be used per point in the point cloud.
request_gps_state bool If true, request data about the robot's GPS localization.

GetLocalizationStateResponse

The GetLocalizationState response message returns the current localization and robot state, as well as any requested live data information.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
localization Localization Where the robot currently is. If a waypoint_id was specified in the request, this localization
will be relative to that waypoint.
robot_kinematics bosdyn.api.KinematicState Robot kinematic state at time of localization.
remote_cloud_status RemotePointCloudStatus repeated Status of one or more remote point cloud services (such as velodyne).
live_data WaypointSnapshot Contains live data at the time of localization, with elements only filled out
if requested.
lost_detector_state LostDetectorState If the robot drives around without a good localization for a while, eventually
it becomes "lost." I.E. it has a localization, but it no longer trusts
that the localization it has is accurate. Lost detector state is
available through this message.
gps GPSLocalization If the robot has GPS capability and the map was recorded with GPS, this message will show graph nav's estimate of
the robot location in earth-centered frames. To see the raw GPS data, look at the WorldObject list.

LostDetectorState

Message describing whether or not graph nav is lost, and if it is lost, how lost it is. If robot is lost, this state can be reset by either:

  • Driving to an area where the robot’s localization improves.

  • Calling SetLocalization RPC.

Field Type Label Description
is_lost bool Whether or not the robot is currently lost. If this is true, graph nav will reject
NavigateTo or NavigateRoute RPC's.

ModifyNavigationResponse

Field Type Label Description
header bosdyn.api.ResponseHeader
lease_use_results bosdyn.api.LeaseUseResult repeated Results of using the various leases.
status ModifyNavigationResponse.Status Status code specific to the ModifyNavigationResponse.

RemotePointCloudStatus

Message describing the state of a remote point cloud service (such as a velodyne).

Field Type Label Description
service_name string The name of the point cloud service.
exists_in_directory bool Boolean indicating if the point cloud service was registered in the robot's directory with
the provided name.
has_data bool Boolean indicating if the point cloud service is currently outputting data.

RouteFollowingParams

These parameters are specific to how the robot follows a specified route in NavigateRoute.

For each enum in this message, if UNKNOWN is passed in, we default to one of the values (indicated in the comments). Passing UNKNOWN is not considered a programming error.

Field Type Label Description
new_cmd_behavior RouteFollowingParams.StartRouteBehavior
existing_cmd_behavior RouteFollowingParams.ResumeBehavior
route_blocked_behavior RouteFollowingParams.RouteBlockedBehavior

RouteGenParams

SensorCompatibilityStatus

Info on whether the robot’s current sensor setup is compatible with the recorded data in the map.

Field Type Label Description
map_has_lidar_data bool If true, the loaded map has LIDAR data in it.
robot_configured_for_lidar bool If true, the robot is currently configured to use LIDAR data.

SetLocalizationRequest

The SetLocalization request is used to initialize or reset the localization of GraphNav to a map. A localization consists of a waypoint ID, and a pose of the robot relative to that waypoint. GraphNav uses the localization to decide how to navigate through a map. The SetLocalizationRequest contains parameters to help find a correct localization. For example, AprilTags (fiducials) may be used to set the localization, or the caller can provide an explicit guess of the localization. Once the SetLocalizationRequest completes, the current localization to the map will be modified, and can be retrieved using a GetLocalizationStateRequest.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
initial_guess Localization Operator-supplied guess at localization.
ko_tform_body bosdyn.api.SE3Pose Robot pose when the initial_guess was made.
This overcomes the race that occurs when the client is trying to initialize a moving robot.
GraphNav will use its local ko_tform_body and this ko_tform_body to update the initial
localization guess, if necessary.
max_distance double The max distance [meters] is how far away the robot is allowed to localize from the position supplied
in the initial guess. If not specified, the offset is used directly. Otherwise it searches a neighborhood
of the given size.
max_yaw double The max yaw [radians] is how different the localized yaw is allowed to be from the supplied yaw
in the initial guess. If not specified, the offset is used directly. Otherwise it searches a neighborhood
of the given size.
fiducial_init SetLocalizationRequest.FiducialInit Tells the initializer whether to use fiducials, and how to use them.
use_fiducial_id int32 If using FIDUCIAL_INIT_SPECIFIC, this is the specific fiducial ID to use for initialization.
If no detection of this fiducial exists, the service will return STATUS_NO_MATCHING_FIDUCIAL.
If detections exist, but are low quality, STATUS_FIDUCIAL_TOO_FAR_AWAY, FIDUCIAL_TOO_OLD, or FIDUCIAL_POSE_UNCERTAIN will be returned.
do_ambiguity_check bool If true, consider how nearby localizations appear (like turned 180).
restrict_fiducial_detections_to_target_waypoint bool If using FIDUCIAL_INIT_SPECIFIC and this is true, the initializer will only consider
fiducial detections from the target waypoint (from initial_guess). Otherwise, if the
target waypoint does not contain a good measurement of the desired fiducial, nearby waypoints
may be used to infer the robot's location.
refine_fiducial_result_with_icp bool If true, and we are using fiducials during initialization, will run ICP after the fiducial
was used for an initial guess.
refine_with_visual_features VisualRefinementOptions Improve localization based on images from body cameras

SetLocalizationResponse

The SetLocalization response message contains the resulting localization to the map.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Result of using the lease.
status SetLocalizationResponse.Status Return status for the request.
error_report string If set, describes the reason the status is not OK.
localization Localization Result of localization.
suspected_ambiguity SetLocalizationResponse.SuspectedAmbiguity Alternative information if the localization is ambiguous.
impaired_state bosdyn.api.RobotImpairedState If the status is ROBOT_IMPAIRED, this is why the robot is impaired.
sensor_status SensorCompatibilityStatus This status determines whether the robot has compatible sensors for the
map that was recorded. Note that if sensors aren't working, STATUS_IMPAIRED
will be returned, rather than STATUS_INCOMPATIBLE_SENSORS.
quality_check_result SetLocalizationResponse.QualityCheckResult Graph Nav will check the quality of the resulting localization and report the status
here. Note that to preserve backwards compatability with 3.2 and earlier, a poor quality check
does not result in this RPC failing.

SetLocalizationResponse.SuspectedAmbiguity

Field Type Label Description
alternate_robot_tform_waypoint bosdyn.api.SE3Pose Example of a potentially ambiguous localization near the
result of the initialization.

TravelParams

Parameters describing how to travel along a route.

Field Type Label Description
max_distance double Threshold for the maximum distance [meters] that defines when we have reached
the final waypoint.
max_yaw double Threshold for the maximum yaw [radians] that defines when we have reached
the final waypoint (ignored if ignore_final_yaw is set to true).
velocity_limit bosdyn.api.SE2VelocityLimit Speed the robot should use.
Omit to let the robot choose.
ignore_final_yaw bool If true, the robot will only try to achieve
the final translation of the route. Otherwise,
it will attempt to achieve the yaw as well.
feature_quality_tolerance TravelParams.FeatureQualityTolerance
disable_directed_exploration bool Disable directed exploration to skip blocked portions of route
disable_alternate_route_finding bool Disable alternate-route-finding; overrides the per-edge setting in the map.
path_following_mode Edge.Annotations.PathFollowingMode Path following mode
blocked_path_wait_time google.protobuf.Duration Time to wait for blocked path to clear (seconds)
ground_clutter_mode Edge.Annotations.GroundClutterAvoidanceMode Ground clutter avoidance mode.

UploadEdgeSnapshotRequest

Used to upload edge data in chunks for a specific edge snapshot. Edge snapshots contain large sensor data associated with each edge. Chunks will be streamed one at a time to the server. Chunk streaming is required to prevent overwhelming gRPC with large http requests.

Field Type Label Description
header bosdyn.api.RequestHeader Common response header.
chunk bosdyn.api.DataChunk Serialized bytes of a EdgeSnapshot message, restricted to a chunk no larger than 4MB in size.
To break the data into chunks, first serialize it to bytes. Then, send the bytes in order as DataChunk objects.
The chunks will be concatenated together on the server, and deserialized
lease bosdyn.api.Lease The Leases to show ownership of the graph-nav service.

UploadEdgeSnapshotResponse

One response for the entire EdgeSnapshot after all chunks have been concatenated and deserialized.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.
map_stats MapStats General map statistics after upload.

UploadGraphRequest

Uploads a graph to the server. This graph will be appended to the graph that currently exists on the server.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
graph Graph Structure of the graph containing waypoints and edges without
underlying sensor data.
lease bosdyn.api.Lease The Lease to show ownership of graph-nav service.
generate_new_anchoring bool If this is true, generate an (overwrite the) anchoring on upload.
treat_validation_warnings_as_errors bool If true, validation warnings will be treated as errors, and STATUS_INVALID_GRAPH will be returned. This is false by
default.

UploadGraphResponse

Response to the UploadGraphRequest. After uploading a graph, the user is expected to upload large data at waypoints and edges (called snapshots). The response provides a list of snapshot IDs which are not yet cached on the server. Snapshots with these IDs should be uploaded by the client.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status UploadGraphResponse.Status Status for an upload request.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.
loaded_waypoint_snapshot_ids string repeated The waypoint snapshot ids for which there was cached data.
unknown_waypoint_snapshot_ids string repeated The waypoint snapshot ids for which there is no cached data.
loaded_edge_snapshot_ids string repeated The edge snapshot ids for which there was cached data.
unknown_edge_snapshot_ids string repeated The edge snapshot ids for which there was no cached data.
license_status bosdyn.api.LicenseInfo.Status Large graphs can only be uploaded if the license permits them.
sensor_status SensorCompatibilityStatus
area_callback_error AreaCallbackServiceError Errors about Area Callbacks in the map.
map_stats MapStats General map statistics.
validation_status UploadGraphResponse.ValidationStatus If the returned status is STATUS_INVALID_GRAPH, this contains the detailed information about why the
graph was invalid. Note that some graph validation errors are warnings and the robot will be able to navigate
on the graph even when they are present.

UploadGraphResponse.ValidationStatus

Detailed information about why STATUS_INVALID_GRAPH was returned. This will only contain information if the UploadGraph request could not be validated.

Field Type Label Description
missing_waypoint_ids_in_edges string repeated One or more edges references a waypoint that doesn't exist. There are the waypoint IDs
referenced by edges that do not exist. This is an error. Fix the graph and re-upload.
missing_waypoint_ids_in_anchors string repeated The anchoring uploaded referenced waypoint IDs that do not exist. These
are the missing IDs. This is a warning. The anchorings will be ignored.
edge_ids_invalid_transform Edge.Id repeated One or more edges had an invalid from_tform_to transform. These are the edge IDs uploaded
that have an invalid transform. Valid transforms have quaternion rotations that are normalized.
This is a warning. Edges with invalid transforms will be fixed on upload.
waypoint_anchors_invalid_transform string repeated One or more waypoint anchors in the anchoring have an invalid transform. These are the waypoint IDs
that have an invalid transform. Valid transforms have quaternion rotations that are normalized.
This is a warning. Anchors with invalid transforms will be fixed on upload.
object_anchors_invalid_transform string repeated One or more of the object achors in the anchoring have an invalid transform. These are the object IDs
that have an invalid transform. Valid transforms have quaternion rotations that are normalized.
This is a warning. Anchors with invalid transforms will be fixed on upload.
duplicate_waypoint_ids string repeated The Graph in the UploadGraph request contained more than one waypoint with the same ID. These are the
waypoint IDs which occur in the UploadGraph request more than once. Note that IDs are duplicated in this list
the same number of times they are duplicated in the request.
This is an error. Fix the graph and re-upload.
duplicate_waypoint_anchor_ids string repeated The anchoring contains one or more anchor IDs that are duplicated. Note that IDs are duplicated in this list
the same number of times they are duplicated in the request. This is a warning. Only the first anchor will be used.
duplicate_object_anchor_ids string repeated The anchoring contains one or more object anchor IDs that are duplicated. Note that IDs are duplicated in this list
the same number of times they are duplicated in the request. This is a warning. Only the first anchor will be used.
duplicate_edge_ids Edge.Id repeated The Graph in the UploadGraph request contained more than one edge with the equivalent ID. These are the edge IDs
which occur in the UploadGraph request more than once. Note that IDs are duplicated in this list the same number
of times that they are duplicated in the request. Note that edges are not directional, and it is impossible
to have both a->b and b->a in the same map. This is an error. Fix the graph and re-upload.
invalid_waypoint_ids_self_edges string repeated Edges are not allowed to have the same "from" and "to" waypoint. These are the waypoint IDs which have self
edges in the UploadGraph request. This is an error. Fix the graph and re-upload.
has_empty_waypoint_ids bool At least one waypoint in the graph has an empty ID. This is an error. Fix the graph and re-upload.
has_empty_edge_ids bool At least one edge in the graph references a waypoint with an empty ID.
This is an error. Fix the graph and re-upload.
has_empty_waypoint_anchor_ids bool At least one waypoint anchor in the anchoring has an empty ID. This is a warning. Empty anchors will be ignored.
has_empty_object_anchor_ids bool At least one object anchor in the anchoring has an empty ID. This is a warning. Empty anchors will be ignored.
malformed_staircase_edge_ids Edge.Id repeated One or more edges had a malformed staircase annotation. This is an error. Remove, rerecord, or fix the annotation.

UploadWaypointSnapshotRequest

Used to upload waypoint snapshot in chunks for a specific waypoint snapshot. Waypoint snapshots consist of the large sensor data at each waypoint. Chunks will be streamed one at a time to the server. Chunk streaming is required to prevent overwhelming gRPC with large http requests.

Field Type Label Description
header bosdyn.api.RequestHeader Common response header.
chunk bosdyn.api.DataChunk Serialized bytes of a WaypointSnapshot message, restricted to a chunk no larger than 4MB in size.
To break the data into chunks, first serialize it to bytes. Then, send the bytes in order as DataChunk objects.
The chunks will be concatenated together on the server, and deserialized.
lease bosdyn.api.Lease The Leases to show ownership of the graph-nav service.

UploadWaypointSnapshotResponse

One response for the entire WaypointSnapshot after all chunks have been concatenated and deserialized.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.
status UploadWaypointSnapshotResponse.Status
sensor_status SensorCompatibilityStatus
map_stats MapStats General map statistics after upload.

ValidateGraphRequest

Run a check on the currently loaded map.

Field Type Label Description
header bosdyn.api.RequestHeader

ValidateGraphResponse

Report possible errors with the loaded map.

Field Type Label Description
header bosdyn.api.ResponseHeader
status ValidateGraphResponse.Status Status of the currently loaded map.
sensor_status SensorCompatibilityStatus
area_callback_error AreaCallbackServiceError Errors about Area Callbacks in the map.

VisualRefinementOptions

Field Type Label Description
verify_refinement_quality bool Whether to return a STATUS_VISUAL_ALIGNMENT_FAILED if refine_with_visual_features fails.

ClearGraphResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_RECORDING 2 Graph Nav is currently recording a map. You must call
StopRecording from the recording service to continue.

DownloadEdgeSnapshotResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_SNAPSHOT_DOES_NOT_EXIST 2 Error where the given snapshot ID does not exist.

DownloadWaypointSnapshotResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_SNAPSHOT_DOES_NOT_EXIST 2 Error where the given snapshot ID does not exist.

ModifyNavigationResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1 Modify request was accepted.
STATUS_UNRECOGNIZED_COMMAND 2 The command ID wasn't the ID of the last command.

RouteFollowingParams.ResumeBehavior

This setting applies when a NavigateRoute command is issued with the same route and final-waypoint-offset. It is not necessary that command_id indicate the same command. The expected waypoint is the last waypoint that GraphNav was autonomously navigating to.

Name Number Description
RESUME_UNKNOWN 0 The mode is unset.
RESUME_RETURN_TO_UNFINISHED_ROUTE 1 The robot will find the shortest path to any point on the route after the
furthest-along traversed edge, and go to the point that gives that shortest path.
Then, the robot will follow the rest of the route from that point.
This is the default.
RESUME_FAIL_WHEN_NOT_ON_ROUTE 2 The robot will fail the command with status STATUS_NOT_LOCALIZED_TO_ROUTE.

RouteFollowingParams.RouteBlockedBehavior

This setting applies when the robot discovers that the route is blocked.

Name Number Description
ROUTE_BLOCKED_UNKNOWN 0 The mode is unset.
ROUTE_BLOCKED_REROUTE 1 For NavigateToRequests, the robot will find the shortest path to the desination
that avoids the blockage.
For NavigateRouteRequests, the robot will find the shortest path to any point
after the furthest-along blockage, and after the furthest-along traversed edge,
and go to the point that gives that shortest path. Then, the robot will follow
the rest of the route from that point. If multiple points on the route are
similarly close to the robot, the robot will prefer the earliest on the route.
This is the default.
ROUTE_BLOCKED_FAIL 2 The robot will fail the command with status STATUS_STUCK;

RouteFollowingParams.StartRouteBehavior

This setting applies when a new NavigateRoute command is issued (different route or final-waypoint-offset), and command_id indicates a new command.

Name Number Description
START_UNKNOWN 0 The mode is unset.
START_GOTO_START 1 The robot will find the shortest path to the start of the route, possibly using
edges that are not in the route. After going to the start, the robot will follow the
route.
START_GOTO_ROUTE 2 The robot will find the shortest path to any point on the route, and go to the point
that gives that shortest path. Then, the robot will follow the rest of the route from
that point.
If multiple points on the route are similarly close to the robot, the robot will
prefer the earliest on the route.
This is the default.
START_FAIL_WHEN_NOT_ON_ROUTE 3 The robot will fail the command with status STATUS_NOT_LOCALIZED_TO_ROUTE.

SetLocalizationRequest.FiducialInit

Name Number Description
FIDUCIAL_INIT_UNKNOWN 0 It is a programming error to use this one.
FIDUCIAL_INIT_NO_FIDUCIAL 1 Ignore fiducials during initialization.
FIDUCIAL_INIT_NEAREST 2 Localize to the nearest fiducial in any waypoint.
FIDUCIAL_INIT_NEAREST_AT_TARGET 3 Localize to nearest fiducial at the target waypoint (from initial_guess).
FIDUCIAL_INIT_SPECIFIC 4 Localize to the given fiducial at the target waypoint (from initial_guess) if it exists, or any waypoint otherwise.

SetLocalizationResponse.QualityCheckResult

Name Number Description
QUALITY_CHECK_UNKNOWN 0 Unset. Note that the quality check is only performed if the overall Status
enum returns STATUS_SUCCESS, and will be unset otherwise.
QUALITY_CHECK_SUCCESS 1 The quality check passed.
QUALITY_CHECK_POOR_POINT_CLOUD_MATCH 2 After applying the localization, a poor point cloud match to the map was detected.
This can happen if, for example, the map has changed, or the starting location
of the robot is now very different than it was at recording time.
QUALITY_CHECK_POOR_GRAVITY_ALIGNMENT 3 After applying the localization, Graph Nav checked the localization, and found that
the robot's gravity vector does not align with the map's. This can happen if a fiducial
being used to align to the map was detected wrongly during recording, or if the robot's
IMU is miscalibrated. It can also occur when the inital guess passed in to the SetLocalization
RPC is in the incorrect reference frame.
QUALITY_CHECK_SKIPPED 4 There wasn't enough data to make a determination about quality.
QUALITY_CHECK_BAD_HEIGHT 5 The prior passed in is too different from the expected height of the robot e.w.r.t the waypoint.

SetLocalizationResponse.Status

Name Number Description
STATUS_UNKNOWN 0 The status is unknown/unset.
STATUS_OK 1 Localization success.
STATUS_ROBOT_IMPAIRED 2 Robot is experiencing a condition that prevents localization.
STATUS_UNKNOWN_WAYPOINT 3 The given waypoint is unknown by the system.
This could be due to a client error, or because the graph was changed out from under the
client.
STATUS_ABORTED 4 Localization was aborted, likely because of a new request.
STATUS_FAILED 5 Failed to localize for some other reason; see the error_report for details.
This is often because the initial guess was incorrect.
STATUS_FIDUCIAL_TOO_FAR_AWAY 6 Failed to localize because the fiducial requested by 'use_fiducial_id' was too far away from
the robot.
STATUS_FIDUCIAL_TOO_OLD 7 Failed to localize because the fiducial requested by 'use_fiducial_id' had a detection time that was too
far in the past.
STATUS_NO_MATCHING_FIDUCIAL 8 Failed to localize because the fiducial requested by 'use_fiducial_id' did not exist in the map at
the required location.
STATUS_FIDUCIAL_POSE_UNCERTAIN 9 Failed to localize because the fiducial requested by 'use_fiducial_id' had an unreliable
pose estimation, either in the current detection of that fiducial, or in detections that
were saved in the map. Note that when using FIDUCIAL_INIT_SPECIFIC, fiducial detections at
the target waypoint will be used so long as they are not uncertain -- otherwise, detections
at adjacent waypoints may be used. If there exists no uncertain detection of the fiducial
near the target waypoint in the map, the service returns this status.
STATUS_INCOMPATIBLE_SENSORS 10 The localization could not be set, because the map was recorded using a different sensor
setup than the robot currently has onboard. See SensorStatus for more details.
STATUS_VISUAL_ALIGNMENT_FAILED 11 Visual feature based alignment failed or the pose solution was considered unreliable.

TravelParams.FeatureQualityTolerance

Indicates whether robot will navigate through areas with poor quality features

Name Number Description
TOLERANCE_UNKNOWN 0 Unknown value
TOLERANCE_DEFAULT 1 Navigate through default number of waypoints with poor quality features
TOLERANCE_IGNORE_POOR_FEATURE_QUALITY 2 Navigate through unlimited number of waypoints with poor quality features

UploadGraphResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_MAP_TOO_LARGE_LICENSE 3 Can't upload the graph because it was too large for the license.
STATUS_INVALID_GRAPH 4 The graph or its anchoring are invalid. See the ValidationStatus for more details.
STATUS_INCOMPATIBLE_SENSORS 5 The sensor data associated with this graph is incompatible with the current robot. A common example
would be trying to upload a map recorded on a robot that had LIDAR to a robot that did not, or vice
versa.
STATUS_AREA_CALLBACK_ERROR 6 There is an error associated with one of the area callbacks in this graph.

UploadWaypointSnapshotResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Unset.
STATUS_OK 1 Success.
STATUS_INCOMPATIBLE_SENSORS 2 The data in this waypoint snapshot is not compatible with the
current configuration of the robot. Check sensor_status for
more details.

ValidateGraphResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_INCOMPATIBLE_SENSORS 5
STATUS_AREA_CALLBACK_ERROR 6

Top

bosdyn/api/graph_nav/graph_nav_service.proto

GraphNavService

The GraphNav service service is a place-based localization and locomotion service. The service can be used to get/set the localization, upload and download the current graph nav maps, and send navigation requests to move around the map.

Method Name Request Type Response Type Description
SetLocalization SetLocalizationRequest SetLocalizationResponse Trigger a manual localization. Typically done to provide the initial localization.
NavigateRoute NavigateRouteRequest NavigateRouteResponse Tell GraphNav to navigate/traverse a given route.
NavigateTo NavigateToRequest NavigateToResponse Tell GraphNav to navigate to a waypoint along a route it chooses.
NavigateToAnchor NavigateToAnchorRequest NavigateToAnchorResponse Tell GraphNav to navigate to a goal with respect to the current anchoring.
NavigationFeedback NavigationFeedbackRequest NavigationFeedbackResponse Get feedback on active navigation command.
GetLocalizationState GetLocalizationStateRequest GetLocalizationStateResponse Get the localization status and data.
ClearGraph ClearGraphRequest ClearGraphResponse Clears the local graph structure. Also erases any snapshots currently in RAM.
DownloadGraph DownloadGraphRequest DownloadGraphResponse Download the graph structure.
UploadGraph UploadGraphRequest UploadGraphResponse Upload the full list of waypoint IDs, graph topology and other small info.
UploadWaypointSnapshot UploadWaypointSnapshotRequest stream UploadWaypointSnapshotResponse Uploads large waypoint snapshot as a stream for a particular waypoint.
UploadEdgeSnapshot UploadEdgeSnapshotRequest stream UploadEdgeSnapshotResponse Uploads large edge snapshot as a stream for a particular edge.
DownloadWaypointSnapshot DownloadWaypointSnapshotRequest DownloadWaypointSnapshotResponse stream Download waypoint data from the server. If the snapshot exists in disk cache, it will be loaded.
DownloadEdgeSnapshot DownloadEdgeSnapshotRequest DownloadEdgeSnapshotResponse stream Download edge data from the server. If the snapshot exists in disk cache, it will be loaded.
ValidateGraph ValidateGraphRequest ValidateGraphResponse Verify that the graph is still valid and all required external services are still available.
A map that was valid at upload time may not still be valid if required services are no longer running.

Top

bosdyn/api/graph_nav/map.proto

Anchor

This associates a waypoint with a common reference frame, which is not necessarily metric.

Field Type Label Description
id string Identifier of the waypoint.
seed_tform_waypoint bosdyn.api.SE3Pose Pose of the waypoint in the seed frame.

AnchoredWorldObject

This associates a world object with a common reference frame, which is not necessarily metric.

Field Type Label Description
id string Identifier of the world object.
seed_tform_object bosdyn.api.SE3Pose Pose of the object in the seed frame.

Anchoring

Field Type Label Description
anchors Anchor repeated The waypoint ids for the graph, expressed in a common reference frame, which is not
necessarily metric. If there is no anchoring, this is empty.
objects AnchoredWorldObject repeated World objects, located in the common reference frame.

AreaCallbackRegion

Data for a AreaCallback in the annotation.

Field Type Label Description
service_name string This service must be used in a given region to safely traverse it.
description string Human-readable description of this region.
recorded_data AreaCallbackData Configuration data associated with this area callback.

ClientMetadata

Optional metadata to attach to waypoints that are being recorded.

Field Type Label Description
session_name string User-provided name for this recording "session". For example, the user
may start and stop recording at various times and assign a name to a region
that is being recorded. Usually, this will just be the map name.
client_username string If the application recording the map has a special user name,
this is the name of that user.
client_software_version string Version string of any client software that generated this object.
client_id string Identifier of any client software that generated this object.
client_type string Special tag for the client software which created this object.
For example, "Tablet", "Scout", "Python SDK", etc.

Edge

A base element of the graph nav map. Edges consist of a directed edge from one waypoint to another and a transform that estimates the relationship in 3D space between the two waypoints.

Field Type Label Description
id Edge.Id Identifier of this Edge.
Edges are mutable -- the identifier does not have to be updated when other fields change.
snapshot_id string Identifier of this edge's Snapshot data.
from_tform_to bosdyn.api.SE3Pose Describes the transform between the "from" waypoint and the "to" waypoint.
annotations Edge.Annotations Annotations specific to the current edge.

Edge.Annotations

Annotations understood by BostonDynamics systems.

Field Type Label Description
stairs Edge.Annotations.StairData Stairs information/parameters specific to the edge.
direction_constraint Edge.Annotations.DirectionConstraint Direction constraints for how the robot must move and the directions it can face
when traversing the edge.
require_alignment google.protobuf.BoolValue If true, the robot must be aligned with the edge in yaw before traversing it.
flat_ground google.protobuf.BoolValue Deprecated. If true, the edge crosses flat ground and the robot shouldn't try to climb over
obstacles.
DEPRECATED as of 3.3. Replaced by ground_clutter_mode.
override_mobility_params google.protobuf.FieldMask Overrides the following fields of the mobility parameters to whatever is
stored in the map. For example, if this FieldMask contains "stairs_mode" and
"terrain_params.enable_grated_floor", then the map will be
annotated with "stairs_mode" and "enable_grated_floor" settings. An empty FieldMask means
all fields are active annotations. Note that the more conservative of the velocity limit
stored in the mobility parameters and the TravelParams of the entire route will be used
for this edge (regardless of what override_mobility_params says).
mobility_params bosdyn.api.spot.MobilityParams Contains terrain parameters, swing height, obstacle avoidance parameters, etc.
When the robot crosses this edge, it will use the mobility parameters here.
cost google.protobuf.DoubleValue Assign edges a cost; used when finding the "shortest" (lowest cost) path.
edge_source Edge.EdgeSource How this edge was made.
disable_alternate_route_finding bool If true, disables alternate-route-finding for this edge.
path_following_mode Edge.Annotations.PathFollowingMode Path following mode for this edge.
disable_directed_exploration bool Disable directed exploration for this edge.
area_callbacks Edge.Annotations.AreaCallbacksEntry repeated Reference to area callback regions needed to cross this edge.
The string is a unique id for this region, which may be shared
across multiple edges.
ground_clutter_mode Edge.Annotations.GroundClutterAvoidanceMode

Edge.Annotations.AreaCallbacksEntry

Field Type Label Description
key string
value AreaCallbackRegion

Edge.Annotations.StairData

Defines any parameters of the stairs

Field Type Label Description
state AnnotationState Check this before reading other fields.
straight_staircase bosdyn.api.StraightStaircase Deprecated. Parameters describing a straight staircase.
DEPRECATED as of 3.3. Please use staircase_with_landings.
staircase_with_landings bosdyn.api.StaircaseWithLandings Parameters describing an arbitrary staircase.
descent_preference Edge.Annotations.StairData.DescentPreference

Edge.Id

An edge is uniquely identified by the waypoints it connects. Two waypoints will only ever be connected by a single edge. That edge is traversable in either direction.

Field Type Label Description
from_waypoint string Identifier of the "from" waypoint.
to_waypoint string Identifier of the "to" waypoint.

EdgeSnapshot

Relevant data collected along the edge. May be used for automatically generating annotations, for example.

Field Type Label Description
id string Identifier of this snapshot.
Snapshots are immutable -- if any of the other fields change, this ID must also change.
stances EdgeSnapshot.Stance repeated Sampling of stances as robot traversed this edge.
area_callbacks EdgeSnapshot.AreaCallbacksEntry repeated Data used by area callback services to perform their action.

EdgeSnapshot.AreaCallbacksEntry

Field Type Label Description
key string
value AreaCallbackData

EdgeSnapshot.Stance

Field Type Label Description
timestamp google.protobuf.Timestamp Timestamp of the stance.
foot_states bosdyn.api.FootState repeated List of all the foot positions for a single stance.
ko_tform_body bosdyn.api.SE3Pose KO Body position corresponding to this stance.
vision_tform_body bosdyn.api.SE3Pose Vision Body position corresponding to this stance.
planar_ground google.protobuf.BoolValue Does this stance correspond to a planar ground region.

Graph

This is an arbitrary collection of waypoints and edges. The edges and waypoints are not required to be connected. A waypoint may belong to multiple graphs. This message is used to pass around information about a graph’s topology, and is used to serialize map topology to and from files. Note that the graph does not contain any of the waypoint/edge data (which is found in snapshots). Snapshots are stored separately.

Field Type Label Description
waypoints Waypoint repeated The waypoints for the graph (containing frames, annotations, and sensor data).
edges Edge repeated The edges connecting the graph's waypoints.
anchoring Anchoring The anchoring (mapping from waypoints to their pose in a shared reference frame).

MapStats

General statistics on the map that is loaded into GraphNav on the robot, including information on the graph topology and snapshot data.

Field Type Label Description
waypoints MapStats.Stat Waypoints (including alternate route finding waypoints).
waypoint_snapshots MapStats.Stat Waypoint snapshots.
alternate_waypoints MapStats.Stat The alternate route finding waypoints (used for alternate path planning).
edges MapStats.Stat Edges (including alternate route finding edges).
edge_snapshots MapStats.Stat Edge snapshots.
alternate_edges MapStats.Stat Alternate edges (used for alternate path planning).
waypoint_anchors MapStats.Stat Anchors for waypoints. (For computing anchorings to fixed reference frames).
object_anchors MapStats.Stat Anchors for world objects (fiducials).
total_path_length double The total distance travelled along recorded edges by the robot in the loaded
map.

MapStats.Stat

Statistics from a particular type of object stored in the GraphNav map.

Field Type Label Description
count int32 The number of elements.
num_bytes int64 Lower bound on the number of bytes allocated for these elements on RAM
inside the GraphNav server.

Waypoint

A base element of the graph nav map. A waypoint consists of a reference frame, a name, a unique ID, annotations, and sensor data.

Field Type Label Description
id string Identifier of the waypoint. Unique across all maps.
This identifier does not have to be updated when its fields change.
snapshot_id string Identifier of this waypoint's Snapshot data.
waypoint_tform_ko bosdyn.api.SE3Pose Transform from the KO frame (at time of recording) to the waypoint.
annotations Waypoint.Annotations Annotations specific to the current waypoint.

Waypoint.Annotations

Annotations understood by BostonDynamics systems.

Field Type Label Description
name string Human-friendly name of the waypoint. For example, "Kitchen Fridge"
creation_time google.protobuf.Timestamp The time that the waypoint was created while recording a map.
icp_variance bosdyn.api.SE3Covariance Estimate of the variance of ICP when performed at this waypoint, collected at record
time.
scan_match_region Waypoint.Annotations.LocalizeRegion Options for how to localize to a waypoint (if at all).
waypoint_source Waypoint.WaypointSource How this waypoint was made.
client_metadata ClientMetadata Information about the state of the client when this waypoint was created.
loop_closure_settings Waypoint.Annotations.LoopClosureSettings This waypoint may have specific settings to help with loop closure. This
Is useful for example when trying to ensure that a loop closure occurs at
a particular intersection or near a dock.
gps_settings Waypoint.Annotations.GPSSettings Optional GPS navigation settings for this waypoint.

Waypoint.Annotations.GPSSettings

Waypoints can optionally define where they are in an Earth-Centered-Earth-Fixed (ECEF) frame, which can aid in localization.

Field Type Label Description
state AnnotationState If the annotation state is set, the GPS settings will be applied. Otherwise, they will be ignored.
If ignored, GPS will only be used at this waypoint if data from a GPS exists in the waypoint snapshot, and the
robot has a GPS payload installed and running. Set the annotation state to override this behavior.
ecef_tform_waypoint bosdyn.api.SE3Pose This defines the pose of the waypoint in the Earth-Centered-Earth-Fixed (ECEF) frame.
disable_gps_localization bool If true, GPS localization will be disabled at this waypoint. If false, the robot will use GPS when available
to localize to this waypoint.

Waypoint.Annotations.LocalizeRegion

Field Type Label Description
state AnnotationState Check this before reading other fields.
default_region Waypoint.Annotations.LocalizeRegion.Default Oneof field that describes the waypoint's location as a default region (no
special features/traits).
empty Waypoint.Annotations.LocalizeRegion.Empty Oneof field that describes the waypoint's location as a empty/featureless region.
circle Waypoint.Annotations.LocalizeRegion.Circle2D Oneof field that describes the waypoint's location as a circular region.

Waypoint.Annotations.LocalizeRegion.Circle2D

Indicates the number of meters away we can be from this waypoint we can be before scan matching.

  • If zero, the default value is used.

  • If less than zero, no scan matching will be performed at this waypoint.

  • If greater than zero, scan matching will only be performed if the robot is at most this far away from the waypoint. Distance calculation is done in the 2d plane with respect to the waypoint.

Field Type Label Description
dist_2d double meters.

Waypoint.Annotations.LocalizeRegion.Default

Use the default region to localize in.

Waypoint.Annotations.LocalizeRegion.Empty

Do not localize to this waypoint.

Waypoint.Annotations.LoopClosureSettings

Field Type Label Description
disable_loop_closure bool If true, loop closure will be fully disabled at this waypoint.
disable_collision_check bool If true, collision checking will be disabled for loop closures
from or to this waypoint.
max_edge_length double If nonzero, edges are allowed to be this long when making loop
closures to this waypoint. If zero, global/default settings will
be used.
max_odometry_path_length double If nonzero, loop closures to this waypoint may shortcut this amount
of path length. If zero, global/default settings will be used.

WaypointSnapshot

Relevant data collected at the waypoint. May be used for localization or automatically generating annotations, for example. Should be indexed by a waypoint’s “snapshot_id” field.

Field Type Label Description
id string Identifier of this snapshot.
Snapshots are immutable -- if any of the other fields change, this ID must also change.
images bosdyn.api.ImageResponse repeated Any images captured at the waypoint.
point_cloud bosdyn.api.PointCloud Aggregated point cloud data.
objects bosdyn.api.WorldObject repeated Perception objects seen at snapshot time.
robot_state bosdyn.api.RobotState Full robot state during snapshot.
robot_local_grids bosdyn.api.LocalGrid repeated Robot grid data.
is_point_cloud_processed bool If true, the point cloud of this snapshot has been processed.
version_id string If this snapshot is a modified version of the raw snapshot with the given ID (for example, it
has been processed), a new unique ID will we assigned to this field. If the field is empty,
this is the raw version of the snapshot.
has_remote_point_cloud_sensor bool If true, the point cloud contains data from a remote point cloud service,
such as LIDAR.
body_tform_remote_point_cloud_sensor bosdyn.api.SE3Pose Transform from the robot body to the remote point cloud sensor's
reference frame.
payloads bosdyn.api.Payload repeated Defines the payloads attached to the robot at this waypoint.
robot_id bosdyn.api.RobotId Identifiers (software, nickname, etc.) of the robot that created this waypoint.
recording_started_on google.protobuf.Timestamp Information about when the recording session started in robot time basis.
This will be filled out by the recording service when StartRecording is called.

AnnotationState

Indicator of whether or not the waypoint and edge annotations are complete and filled out.

Name Number Description
ANNOTATION_STATE_UNKNOWN 0 No assertions made about this annotation.
ANNOTATION_STATE_SET 1 This annotation and all of its fields have been deliberately set.
ANNOTATION_STATE_NONE 2 This annotation has been deliberately set to "no annotation" -- any subfields are unset.

Edge.Annotations.DirectionConstraint

Name Number Description
DIRECTION_CONSTRAINT_UNKNOWN 0 We don't know if there are direction constraints.
DIRECTION_CONSTRAINT_NO_TURN 1 The robot must not turn while walking the edge, but can face either waypoint.
DIRECTION_CONSTRAINT_FORWARD 2 Robot should walk the edge face-first.
DIRECTION_CONSTRAINT_REVERSE 3 Robot should walk the edge rear-first.
DIRECTION_CONSTRAINT_NONE 4 No constraints on which way the robot faces.

Edge.Annotations.GroundClutterAvoidanceMode

Ground clutter avoidance mode. This enables detection and avoidance of low obstacles.

Name Number Description
GROUND_CLUTTER_UNKNOWN 0 The mode is unset.
GROUND_CLUTTER_OFF 1 The mode is explicitly off.
GROUND_CLUTTER_FROM_FOOTFALLS 2 Enable detection of ground clutter using recorded footfalls.
Objects that were not stepped on during map recording are obstacles.

Edge.Annotations.PathFollowingMode

Path following mode

Name Number Description
PATH_MODE_UNKNOWN 0 Unknown value
PATH_MODE_DEFAULT 1 Use default path following parameters
PATH_MODE_STRICT 2 Use strict path following parameters

Edge.Annotations.StairData.DescentPreference

Name Number Description
DESCENT_PREFERENCE_UNKNOWN 0 Unknown value, default to DESCENT_PREFERENCE_ALWAYS_REVERSE.
DESCENT_PREFERENCE_PREFER_REVERSE 1 Robot will prefer to descend in reverse, but may descend forwards if the route
could not otherwise be executed. This could be due to conflicting constraints
created by an annotation or by another staircase.
DESCENT_PREFERENCE_ALWAYS_REVERSE 2 Robot will always attempt to descend stairs in reverse, even if it causes
navigation to fail.
DESCENT_PREFERENCE_NONE 3 Robot may descend in any order. The exact order it chooses will be decided by
the lowest cost path found by the local trajectory optimizer and adjacent
constraints, if they exist.
NOTE: If a staircase which is difficult for the robot to descend in the forward
direction is marked with this option, it may cause the robot to fall.

Edge.EdgeSource

Name Number Description
EDGE_SOURCE_UNKNOWN 0
EDGE_SOURCE_ODOMETRY 1 Edges with transforms from odometry.
EDGE_SOURCE_SMALL_LOOP_CLOSURE 2 Edges with transforms from a short chain of other edges.
EDGE_SOURCE_FIDUCIAL_LOOP_CLOSURE 3 Edges with transforms from multiple fiducial observations.
EDGE_SOURCE_ALTERNATE_ROUTE_FINDING 4 Edges that may help find alternate routes.
EDGE_SOURCE_USER_REQUEST 5 Created via a CreateEdge RPC.
EDGE_SOURCE_LOCALIZATION 6 Created when we start recording after recording has been paused.
For example, an "extension" of a graph will start with an edge
of type EDGE_SOURCE_LOCALIZATION.

Waypoint.WaypointSource

Name Number Description
WAYPOINT_SOURCE_UNKNOWN 0
WAYPOINT_SOURCE_ROBOT_PATH 1 Waypoints from the robot's location during recording.
WAYPOINT_SOURCE_USER_REQUEST 2 Waypoints with user-requested placement.
WAYPOINT_SOURCE_ALTERNATE_ROUTE_FINDING 3 Waypoints that may help find alternate routes.

Top

bosdyn/api/graph_nav/map_processing.proto

AnchorHintUncertainty

Controls how certain the user is of an anchor’s pose. If left empty, a reasonable default will be chosen.

Field Type Label Description
se3_covariance bosdyn.api.SE3Covariance A full 6x6 Gaussian covariance matrix representing uncertainty of an anchoring.
confidence_bounds PoseBounds Represents the 95 percent confidence interval on individual axes. This
will be converted to a SE3Covariance internally by creating a diagonal
matrix whose elements are informed by the confidence bounds.

AnchoringHint

The user may assign a number of world objects and waypoints a guess at where they are in the seed frame. These hints will be respected by the ProcessAnchoringRequest.

Field Type Label Description
waypoint_anchors WaypointAnchorHint repeated List of waypoints and hints as to where they are in the seed frame.
world_objects WorldObjectAnchorHint repeated List of world objects and hints as to where they are in the seed frame.

PoseBounds

Represents an interval in x, y, z and yaw around some center. Some value x will be within the bounds if center - x_bounds <= x >= center + x_bounds. If the values are left at zero, the bounds are considered to be unconstrained. The center of the bounds is left implicit, and should be whatever this message is packaged with.

Field Type Label Description
x_bounds double Bounds on the x position in meters.
y_bounds double Bounds on the y position in meters.
z_bounds double Bounds on the z position in meters.
yaw_bounds double Bounds on the yaw (rotation around z axis) in radians.

ProcessAnchoringRequest

Causes the server to optimize an existing anchoring, or generate a new anchoring for the map using the given parameters. In general, if parameters are not provided, reasonable defaults will be used. The new anchoring will be streamed back to the client, or modified on the server if desired.

Field Type Label Description
header bosdyn.api.RequestHeader Standard request header.
params ProcessAnchoringRequest.Params
initial_hint AnchoringHint Initial guess at some number of waypoints and world objects and their anchorings.
modify_anchoring_on_server bool If true, the map currently uploaded to the server will have its anchoring modified.
Otherwise, the user is expected to re-upload the anchoring.
stream_intermediate_results bool If true, the anchoring will be streamed back to the user after every iteration.
This is useful for debug visualization.
apply_gps_result_to_waypoints_on_server bool If true, the GPSSettings inside waypoint annotations will be modified based on the optimization.
Every waypoint will have waypoint.gps_settings set, with ecef_tform_waypoint applied form this
optimization. To get these results, call the DownloadGraph RPC. Alternatively, the ecef_tform_waypoint
can be found using: response.gps_result.ecef_tform_seed * seed_tform_waypoint[waypoint_id].
Note that after this operation completes successfully, all waypoints in the graph can be used to navigate
using GPS, even if they didn't have GPS data in their waypoint snapshots.

ProcessAnchoringRequest.Params

Parameters for procesing an anchoring.

Field Type Label Description
optimizer_params ProcessAnchoringRequest.Params.OptimizerParams
measurement_params ProcessAnchoringRequest.Params.MeasurementParams
weights ProcessAnchoringRequest.Params.Weights
optimize_existing_anchoring google.protobuf.BoolValue If true, the anchoring which already exists on the server will be used as the initial
guess for the optimizer. Otherwise, a new anchoring will be generated for every waypoint
which doesn't have a value passed in through initial_hint. If no hint is provided,
and this value is false, every waypoint will be given a starting anchoring based on
the oldest waypoint in the map.
gravity_ewrt_seed bosdyn.api.Vec3 The optimizer will try to keep the orientation of waypoints consistent with gravity.
If provided, this is the gravity direction expressed with respect to the seed. This
will be interpreted as a unit vector. If not filled out, a default of (0, 0, -1) will be
used.

ProcessAnchoringRequest.Params.MeasurementParams

Parameters which affect the measurements the optimzier uses to process the anchoring.

Field Type Label Description
use_kinematic_odometry google.protobuf.BoolValue If true, waypoints which share the same kinematic odometry
frame will be constrained to one another using it.
use_visual_odometry google.protobuf.BoolValue If true, waypoints which share the same visual odometry frame
will be constrained to one another using it.
use_gyroscope_measurements google.protobuf.BoolValue If true, waypoints will be constrained so that the apparent pose of the
robot w.r.t the waypoint at the time of recording is consistent with gravity.
use_loop_closures google.protobuf.BoolValue If true, edges which were created by topology processing via loop closures will
be used as constraints.
use_world_objects google.protobuf.BoolValue If true, world object measurements will be used to constrain waypoints to one another
when those waypoints co-observe the same world object.
use_gps google.protobuf.BoolValue If true, GPS measurements stored in waypoint snapshots will be used to
help constrain the anchoring.

ProcessAnchoringRequest.Params.OptimizerParams

Parameters affecting the underlying optimizer.

Field Type Label Description
max_iters google.protobuf.Int32Value Maximum iterations of the optimizer to run.
max_time_seconds google.protobuf.DoubleValue Maximum time the optimizer is allowed to run before giving up.

ProcessAnchoringRequest.Params.Weights

Relative weights to use for each of the optimizer’s terms. These can be any positive value. If set to zero, a reasonable default will be used. In general, the higher the weight, the more the optimizer will care about that particular measurement.

Field Type Label Description
kinematic_odometry_weight double
visual_odometry_weight double
world_object_weight double
hint_weight double
gyroscope_weight double
loop_closure_weight double
gps_weight double

ProcessAnchoringResponse

Streamed response from the ProcessAnchoringRequest. These will be streamed until optimization is complete. New anchorings will be streamed as they become available.

Field Type Label Description
header bosdyn.api.ResponseHeader
status ProcessAnchoringResponse.Status
waypoint_results Anchor repeated Contains new anchorings for waypoint(s) processed by the server.
These will be streamed back to the user as they become available.
world_object_results AnchoredWorldObject repeated Contains new anchorings for object(s) (e.g april tags) processed by the server.
These will be streamed back to the user as they become available
anchoring_on_server_was_modified bool If modify_anchoring_on_server was set to true in the request, then the anchoring currently on the server
was modified using map processing. If this is set to false, then either an error occurred during
processing, or modify_anchoring_on_server was set to false in the request.
When anchoring_on_server_was_modified is set to false, the client is expected to upload the results
back to the server to commit the changes.
iteration int32 The current optimizer iteration that produced these data.
cost double The current nonlinear optimization cost.
final_iteration bool If true, this is the result of the final iteration of optimization.
This will always be true when stream_intermediate_results in the request is false.
violated_waypoint_constraints WaypointAnchorHint repeated On failure due to constraint violation, these hints were violated by the optimization.
Try increasing the pose bounds on the constraints of these hints.
violated_object_constraints WorldObjectAnchorHint repeated On failure due to constraint violation, these hints were violated by the optimization.
Try increasing the pose bounds on the constraints of these hints.
missing_snapshot_ids string repeated When there are missing waypoint snapshots, these are the IDs of the missing snapshots.
Upload them to continue.
missing_waypoint_ids string repeated When there are missing waypoints, these are the IDs of the missing waypoints. Upload them
to continue.
invalid_hints string repeated Unorganized list of waypoints and object IDs which were invalid (missing from the map).
inconsistent_edges Edge.Id repeated List of edges that are inconsistent with the optimized result. This can happen when incorrect
loop closures have been made before optimization, when inconsistent anchoring hints were passed in,
or because the optmizer ended up in a local minimum.
gps_result ProcessAnchoringResponse.GPSResult If GPS embedding optimzation was enabled, this is the result of that process.

ProcessAnchoringResponse.GPSResult

Field Type Label Description
status ProcessAnchoringResponse.GPSResult.GPSStatus Overall status of the GPS embedding optimization.
ecef_tform_seed bosdyn.api.SE3Pose Pose of the "seed" frame of this optimization in the Earth-Centered-Earth-Fixed (ECEF) frame.
This can be used to estimate the pose of every waypoint in the ECEF frame via:
ecef_tform_waypoint = ecef_tform_seed * anchoring.waypoints[waypoint_id].seed_tform_waypoint
num_measurements_used int32 This is the number of GPS measurements actually used to compute the GPS embedding.

ProcessTopologyRequest

Processes a GraphNav map by creating additional edges. After processing, a new subgraph is created containing additional edges to add to the map. Edges are created between waypoints that are near each other. These waypoint pairs are called “loop closures”, and are found by different means. In general, if parameters are not provided, reasonable defaults will be used. Note that this can be used to merge disconnected subgraphs from multiple recording sessions so long as they share fiducial observations.

Field Type Label Description
header bosdyn.api.RequestHeader Standard message header.
params ProcessTopologyRequest.Params Parameters. If not filled out, reasonable defaults will be used.
modify_map_on_server bool If true, any processing should directly modify the map on the server.
Otherwise, the client is expected to upload the processing results (newly created edges)
back to the server. The processing service shares memory with a map container service
(e.g the GraphNav service).

ProcessTopologyRequest.CollisionCheckingParams

Parameters for how to check for collisions when creating loop closures. The system will avoid creating edges in the map that the robot cannot actually traverse due to the presence of nearby obstacles.

Field Type Label Description
check_edges_for_collision google.protobuf.BoolValue By default, this is true.
collision_check_robot_radius google.protobuf.DoubleValue Assume that the robot is a sphere with this radius. Only accept a
loop closure if this spherical robot can travel in a straight line
from one waypoint to the other without hitting obstacles.
collision_check_height_variation google.protobuf.DoubleValue Consider significant height variations along the edge (like stairs or ramps)
to be obstacles. The edge will not be created if there is a height change along
it of more than this value according to the nearby sensor data.

ProcessTopologyRequest.FiducialLoopClosureParams

Parameters for how to close a loop using fiducials (AprilTags). This infers which waypoints should be connected to one another based on shared observations of AprilTags. Note that multiple disconnected subgraphs (for example from multiple recording sessions) can be merged this way.

Field Type Label Description
min_loop_closure_path_length google.protobuf.DoubleValue The minimum distance between waypoints found by walking a path from
one waypoint to the other using only the existing edges in the map.
Set this higher to avoid creating small shortcuts along the existing path.
Note that this is a 2d path length.
max_loop_closure_edge_length google.protobuf.DoubleValue Once a loop closure candidate is found, the system creates an edge between the
candidate waypoints. Only create the edge if it is shorter than this value.
Note that this is a 3d edge length.
max_fiducial_distance google.protobuf.DoubleValue Maximum distance to accept between a waypoint and a fiducial detection to
use that fiducial detection for generating loop closure candidates.
max_loop_closure_height_change google.protobuf.DoubleValue The maximum apparent height change of the created edge that we are
willing to accept between waypoints. This avoids closing loops up ramps,
stairs, etc. or closing loops where there is significant odometry drift.
prune_edges google.protobuf.BoolValue If true, redundant edges will be ignored, and only the "best" in a small area
will be selected (true by default).

ProcessTopologyRequest.ICPParams

Parameters for how to refine loop closure edges using iterative closest point matching.

Field Type Label Description
icp_iters google.protobuf.Int32Value The maximum number of iterations to run. Set to zero to skip ICP processing.
max_point_match_distance google.protobuf.DoubleValue The maximum distance between points in the point cloud we are willing to
accept for matches.

ProcessTopologyRequest.OdometryLoopClosureParams

Parameters for how to close loops using odometry. This infers which waypoints should be connected to one another based on the odometry measurements in the map.

Field Type Label Description
max_loop_closure_path_length google.protobuf.DoubleValue The maximum distance between waypoints found by walking a path from one
waypoint to the other using only the existing edges in the map. Beyond
this distance, we are unwilling to trust odometry.
min_loop_closure_path_length google.protobuf.DoubleValue The minimum distance between waypoints found by walking a path from
one waypoint to the other using only the existing edges in the map.
Set this higher to avoid creating small shortcuts along the existing path.
Note that this is a 2d path length.
max_loop_closure_height_change google.protobuf.DoubleValue The maximum apparent height change of the created edge that we are
willing to accept between waypoints. This avoids closing loops up ramps,
stairs, etc. or closing loops where there is significant odometry drift.
max_loop_closure_edge_length google.protobuf.DoubleValue Once a loop closure candidate is found, the system creates an edge between the
candidate waypoints. Only create the edge if it is shorter than this value.
Note that this is a 3d edge length.
num_extra_loop_closure_iterations google.protobuf.Int32Value Use prior loop closures to infer new odometry based loop closures. This is
useful when other sources of loop closures (like fiducials) are being used.
The existence of those loop closures allows the system to infer other nearby
loop closures using odometry. Alternatively, the user may call the ProcessTopology
RPC multiple times to achieve the same effect.
prune_edges google.protobuf.BoolValue If true, redundant edges will be ignored, and only the "best" in a small area
will be selected (true by default).

ProcessTopologyRequest.Params

Parameters which control topology processing. In general, anything which isn’t filled out will be replaced by reasonable defaults.

Field Type Label Description
do_odometry_loop_closure google.protobuf.BoolValue True by default -- generate loop closure candidates using odometry.
odometry_loop_closure_params ProcessTopologyRequest.OdometryLoopClosureParams Parameters for generating loop closure candidates using odometry.
icp_params ProcessTopologyRequest.ICPParams Parameters for refining loop closure candidates using iterative closest point
cloud matching.
do_fiducial_loop_closure google.protobuf.BoolValue True by default -- generate loop closure candidates using fiducials.
fiducial_loop_closure_params ProcessTopologyRequest.FiducialLoopClosureParams Parameters for generating loop closure candidates using fiducials.
collision_check_params ProcessTopologyRequest.CollisionCheckingParams Parameters which control rejecting loop closure candidates which
collide with obstacles.
timeout_seconds double Causes the processing to time out after this many seconds. If not set, a default of 45 seconds
will be used. If this timeout occurs before the overall RPC timeout, a partial result will be
returned with ProcessTopologyResponse.timed_out set to true. Processing can be continued by
calling ProcessTopology again.

ProcessTopologyResponse

Result of the topology processing RPC. If successful, contains a subgraph of new waypoints or edges created by this process.

Field Type Label Description
header bosdyn.api.ResponseHeader Standard message header.
status ProcessTopologyResponse.Status Result of the processing.
new_subgraph Graph This graph contains the new edge(s) created by map processing. Note that these edges will be
annotated with their creation method. Note that several subgraphs may be returned via
streaming as the map is processed.
map_on_server_was_modified bool If modify_map_on_server was set to true in the request, then the map currently on the server
was modified using map processing. If this is set to false, then either an error occurred during
processing, or modify_map_on_server was set to false in the request.
When map_on_server_was_modified is set to false, the client is expected to upload the results
back to the server to commit the changes.
missing_snapshot_ids string repeated When there are missing waypoint snapshots, these are the IDs of the missing snapshots.
Upload them to continue.
missing_waypoint_ids string repeated When there are missing waypoints, these are the IDs of the missing waypoints. Upload them
to continue.
timed_out bool If true, the processing timed out. Note that this is not considered an error. Run topology processing again
to continue adding edges.

WaypointAnchorHint

Waypoints may be anchored to a particular seed frame. The user may request that a waypoint be anchored in a particular place with some Gaussian uncertainty. Note on gravity alignment: optimization is sensitive to bad alignment with respect to gravity. By default, the orientation of the seed frame assumes gravity is pointing in the negative z direction. Take care to ensure that the orientation of the waypoint is correct with respect to gravity. By convention, waypoints’ orientation is defined as: Z up, X forward, Y left. So, if the robot is flat on the ground, the waypoint’s z axis should align with the seed frame’s z axis. z z ^ ^ | | | | | | +——>x | Waypoint Seed

Field Type Label Description
waypoint_anchor Anchor This is to be interpreted as the mean of a Gaussian distribution, representing
the pose of the waypoint in the seed frame.
seed_tform_waypoint_uncertainty AnchorHintUncertainty This is the uncertainty of the anchor's pose in the seed frame.
If left empty, a reasonable default uncertainty will be generated.
seed_tform_waypoint_constraint PoseBounds Normally, the optimizer will move the anchorings of waypoints based on context, to minimize the
overall cost of the optimization problem. By providing a constraint on pose, the user can ensure
that the anchors stay within a certain region in the seed frame.
Leaving this empty will allow the optimizer to move the anchoring from the hint as far as it likes.

WorldObjectAnchorHint

World objects (such as fiducials) may be anchored to a particular seed frame. The user may request that an object be anchored in a particular place with some Gaussian uncertainty. Note on gravity alignment: optimization is sensitive to bad alignment with respect to gravity. By default, the orientation of the seed frame assumes gravity is pointing in the negative z direction. Take care to ensure that the orientation of the world object is correct with respect to gravity. By convention, fiducials’ orientation is defined as: Z out of the page, X up and Y left (when looking at the fiducial). So, if a fiducial is mounted perfectly flat against a wall, its orientation w.r.t the seed frame would have the top of the fiducial facing positive Z. +———–+ z | ^x | ^ | | | | | | | | | <—-+ | | | y | Seed | | +———–+ Fiducial (on wall)

Field Type Label Description
object_anchor AnchoredWorldObject This is to be interpreted as the mean of a Gaussian distribution, representing
the pose of the object in the seed frame.
seed_tform_object_uncertainty AnchorHintUncertainty This is the uncertainty of the anchor's pose in the seed frame.
If left empty, a reasonable default uncertainty will be generated.
seed_tform_object_constraint PoseBounds Normally, the optimizer will move the anchorings of object based on context, to minimize the
overall cost of the optimization problem. By providing a constraint on pose, the user can ensure
that the anchors stay within a certain region in the seed frame.
Leaving this empty will allow the optimizer to move the anchoring from the hint as far as it likes.

ProcessAnchoringResponse.GPSResult.GPSStatus

Status of the GPS embedding optimization.

Name Number Description
GPS_STATUS_UNKNOWN 0
GPS_STATUS_OK 1 Managed to find an ECEF transform.
GPS_STATUS_NOT_ENOUGH_MEASUREMENTS 2 Not enough high quality GPS measurements in the map.

ProcessAnchoringResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Programming error.
STATUS_OK 1 Success.
STATUS_MISSING_WAYPOINT_SNAPSHOTS 2 Not all of the waypoint snapshots exist on the server. Upload them to continue.
STATUS_INVALID_GRAPH 3 The graph is invalid topologically, for example containing missing waypoints referenced by edges.
STATUS_OPTIMIZATION_FAILURE 4 The optimization failed due to local minima or an ill-conditioned problem definition.
STATUS_INVALID_PARAMS 5 The parameters passed to the optimizer do not make sense (e.g negative weights).
STATUS_CONSTRAINT_VIOLATION 6 One or more anchors were moved outside of the desired constraints.
STATUS_MAX_ITERATIONS 7 The optimizer reached the maximum number of iterations before converging.
STATUS_MAX_TIME 8 The optimizer timed out before converging.
STATUS_INVALID_HINTS 9 One or more of the hints passed in to the optimizer are invalid (do not correspond to real waypoints or objects).
STATUS_MAP_MODIFIED_DURING_PROCESSING 10 Tried to write the anchoring after processing, but another client may have modified the map. Try again.
STATUS_INVALID_GRAVITY_ALIGNMENT 11 An anchor hint (waypoint or fiducial) had an invalid orientation with respect to gravity.

ProcessTopologyResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Programming error.
STATUS_OK 1 Success.
STATUS_MISSING_WAYPOINT_SNAPSHOTS 2 Not all of the waypoint snapshots exist on the server. Upload them to continue.
STATUS_INVALID_GRAPH 3 The graph is invalid topologically, for example containing missing waypoints referenced by edges.
STATUS_MAP_MODIFIED_DURING_PROCESSING 4 Tried to write the anchoring after processing, but another client may have modified the map. Try again

Top

bosdyn/api/graph_nav/map_processing_service.proto

MapProcessingService

Defines services for processing an existing GraphNav map.

Method Name Request Type Response Type Description
ProcessTopology ProcessTopologyRequest ProcessTopologyResponse stream Processes a GraphNav map by creating additional edges or waypoints. After processing,
a new subgraph is created containing additional waypoints or edges to add to the map.
ProcessAnchoring ProcessAnchoringRequest ProcessAnchoringResponse stream Processes a GraphNav map by modifying the anchoring of waypoints and world objects in the map
with respect to a seed frame. After processing, a new anchoring is streamed back.

Top

bosdyn/api/graph_nav/nav.proto

CompletedRoute

Information about the route that a robot has followed during a command.

Field Type Label Description
waypoint_ids string repeated List of waypoints reached in the order they were reached.
edges CompletedRoute.CompletedEdge repeated Information about the completed edges, in the order they were completed.

CompletedRoute.CompletedEdge

Field Type Label Description
edge_id Edge.Id
not_in_map bool If true, this edge was specially constructed to bypass a blockage, and does not exist
in the map.

Localization

The localization state of the robot. This reports the pose of the robot relative to a particular waypoint on the graph nav map.

Field Type Label Description
waypoint_id string Waypoint this localization is relative to.
waypoint_tform_body bosdyn.api.SE3Pose Pose of body in waypoint frame.
seed_tform_body bosdyn.api.SE3Pose Pose of body in a common reference frame. The common reference frame defaults to the starting
fiducial frame, but can be changed. See Anchoring for more info.
timestamp google.protobuf.Timestamp Time (in robot time basis) that this localization was valid.

Route

Route that the robot should follow or is currently following.

Field Type Label Description
waypoint_id string repeated Ordered list of waypoints to traverse, starting from index 0.
edge_id Edge.Id repeated Ordered list of edges to traverse between those waypoints.

Top

bosdyn/api/graph_nav/recording.proto

CreateEdgeRequest

The CreateEdge request message specifies an edge to create between two existing waypoints. The edge must not already exist in the map. This can be used to close a loop or to add any additional edges.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
edge Edge Create an edge between two existing waypoints in the map with
the given parameters.
lease bosdyn.api.Lease The recording service is protected by a lease. The client must have a
lease to the recording service to modify its internal state.

CreateEdgeResponse

The CreateEdge response message contains the status of this request and any useful error information if the request fails.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status CreateEdgeResponse.Status Return status for the request.
error_existing_edge Edge If set, the existing edge that caused the STATUS_EXISTS error.
lease_use_result bosdyn.api.LeaseUseResult The results/status of the lease provided.
map_stats MapStats General statistics of the map loaded in GraphNav.

CreateWaypointRequest

The CreateWaypoint request message specifies a name and environment the robot should use to generate a waypoint in the graph at it’s current location.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
waypoint_name string Name of the waypoint to create. Overrides any naming prefix.
recording_environment RecordingEnvironment This will be merged into a copy of the existing persistent recording
environment and used as the environment for the created waypoint
and the edge from the previous waypoint to the new one.
It will not affect the persistent environment.
lease bosdyn.api.Lease The recording service is protected by a lease. The client must have a
lease to the recording service to modify its internal state.
require_fiducials int32 repeated If filled out, asks that the record service verify that the given fiducial IDs
are presently visible before creating a waypoint. This is useful for verifying
that the robot is where the user thinks it is in an area with known fiducials.
world_objects bosdyn.api.WorldObject repeated Additional world objects to insert into this waypoint.

CreateWaypointResponse

The CreateWaypoint response message contains the complete waypoint, and the associated edge connecting this waypoint to the graph when the request succeeds.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
created_waypoint Waypoint The waypoint that was just created.
created_edge Edge The edge connecting the waypoint just created with the last created waypoint in the map.
status CreateWaypointResponse.Status Return status for the request.
lease_use_result bosdyn.api.LeaseUseResult The results/status of the lease provided.
missing_fiducials int32 repeated If the status is STATUS_MISSING_FIDUCIALS, the following fiducials
were not visible to the robot when trying to create the waypoint.
bad_pose_fiducials int32 repeated If the status is STATUS_FIDUCIAL_POSE_NOT_OK, these are the fiducials that could not be
localized confidently.
license_status bosdyn.api.LicenseInfo.Status Large graphs can only be uploaded if the license permits them. Recording
will stop automatically when the graph gets too large. If CreateWaypointResponse
is requested after the graph gets too large, it will fail, and license
status will be filled out.
map_stats MapStats General statistics of the map loaded in GraphNav.

GetRecordStatusRequest

The GetRecordStatus request message asks for the current state of the recording service.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetRecordStatusResponse

The GetRecordStatus response message returns whether the service is currently recording and what the persistent recording environment is at the time the request was recieved.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
is_recording bool If true, the record service is actively recording
a chain.
recording_environment RecordingEnvironment The current persistent recording environment.
map_state GetRecordStatusResponse.MapState
status GetRecordStatusResponse.Status
impaired_state bosdyn.api.RobotImpairedState If the status is ROBOT_IMPAIRED, this is why the robot is impaired.
session_start_time google.protobuf.Timestamp This is the robot local timestamp that graph_nav began recording on.
If the Start Recording Request's session start time is provided, this should
be the same as the request's session start time.
map_stats MapStats General statistics of the map loaded in GraphNav.

RecordingEnvironment

The RecordingEnvironment is a set of annotation information and a name for the current environment that will persist for all edges and waypoints until it is changed or updated

Field Type Label Description
name_prefix string This will be prepended to the start of every waypoint name.
waypoint_environment Waypoint.Annotations Persistent waypoint annotation that will be merged in
to all waypoints in this recording.
edge_environment Edge.Annotations Persistent edge annotation that will be merged in to all
edges in this recording.

SetRecordingEnvironmentRequest

The SetRecordingEnvironment request message sets a persistent recording environment until changed with another SetRecordingEnvironment rpc.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
environment RecordingEnvironment Persistent environment to use while recording. This allows the
user to specify annotations and naming prefixes for new waypoints
and edges.
lease bosdyn.api.Lease The recording service is protected by a lease. The client must have a
lease to the recording service to modify its internal state.

SetRecordingEnvironmentResponse

The SetRecordingEnvironment response message includes the result and status of the request.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult The results/status of the lease provided.

StartRecordingRequest

The StartRecording request tells the recording service to begin creating waypoints with the specified recording_environment.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease The recording service is protected by a lease. The client must have a
lease to the recording service to modify its internal state.
recording_environment RecordingEnvironment This will be merged into a copy of the existing persistent recording
environment and used as the environment for the created waypoint
and the edge from the previous waypoint to the new one.
It will not affect the persistent environment.
require_fiducials int32 repeated If filled out, asks that the record service verify that the given fiducial IDs
are presently visible before starting to record. This is useful for verifying
that the robot is where the user thinks it is in an area with known fiducials.
session_start_time google.protobuf.Timestamp If provided, this timestamp will be used in every waypoint snapshot as the
"started_recording_on" timestamp. Otherwise, a new timestmap will be generated
after "StartRecording" is called. This is to allow association between waypoint
snapshots based on recording session time.

StartRecordingResponse

The StartRecording response messge returns the first created waypoint, which is made at the location the robot was standing when the request was made, in addition to any status information.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
created_waypoint Waypoint The waypoint that was just created.
lease_use_result bosdyn.api.LeaseUseResult The results/status of the lease provided.
status StartRecordingResponse.Status Return status for the request.
missing_fiducials int32 repeated If the status is STATUS_MISSING_FIDUCIALS, these are the fiducials that are not currently
visible.
bad_pose_fiducials int32 repeated If the status is STATUS_FIDUCIAL_POSE_NOT_OK, these are the fiducials that could not be
localized confidently.
license_status bosdyn.api.LicenseInfo.Status Large graphs can only be uploaded if the license permits them. Recording
will stop automatically when the graph gets too large. If StartRecording
is requested again after the graph gets too large, it will fail, and license
status will be filled out.
impaired_state bosdyn.api.RobotImpairedState If the status is ROBOT_IMPAIRED, this is why the robot is impaired.
session_start_time google.protobuf.Timestamp This is the robot local timestamp that graph_nav began recording on. If the Start Recording
Request's session start time is provided, this should be the same as the request's session
start time.
map_stats MapStats General statistics of the map loaded in GraphNav.

StopRecordingRequest

The StopRecording request message tells the robot to no longer continue adding waypoints and edges to the graph.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease The recording service is protected by a lease. The client must have a
lease to the recording service to modify its internal state.

StopRecordingResponse

The StopRecording response message contains the status of this request and any useful error information if the request fails.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status StopRecordingResponse.Status The return status for the request.
error_waypoint_localized_id string If not localized to end, specifies which waypoint we are localized to.
lease_use_result bosdyn.api.LeaseUseResult The results/status of the lease provided.
session_start_time google.protobuf.Timestamp This is the robot local timestamp that graph_nav began recording on. If the
StartRecordingRequest's session start time is provided, this should be the same as the
request's session start time.
map_stats MapStats General statistics of the map loaded in GraphNav.

CreateEdgeResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status is unknown/unset.
STATUS_OK 1 The edge was successfully created.
STATUS_EXISTS 2 Edge already exists with the given ID.
STATUS_NOT_RECORDING 3 Clients can only create edges when recording.
STATUS_UNKNOWN_WAYPOINT 4 One or more of the specified waypoints aren't in the map.
STATUS_MISSING_TRANSFORM 5 Specified edge did not include a transform.

CreateWaypointResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status is unknown/unset.
STATUS_OK 1 The waypoint was successfully created.
STATUS_NOT_RECORDING 2 Clients can only create waypoints when recording.
STATUS_COULD_NOT_CREATE_WAYPOINT 3 An internal server error prevented the creation of the waypoint.
STATUS_MISSING_FIDUCIALS 4 Could not see the required fiducials.
STATUS_MAP_TOO_LARGE_LICENSE 5 The map was too big to create a waypoint based on the license.
STATUS_REMOTE_CLOUD_FAILURE_NOT_IN_DIRECTORY 6 A required remote cloud did not exist in the service directory.
STATUS_REMOTE_CLOUD_FAILURE_NO_DATA 7 A required remote cloud did not have data.
STATUS_FIDUCIAL_POSE_NOT_OK 8 All fiducials are visible but their pose could not be determined accurately.

GetRecordStatusResponse.MapState

Name Number Description
MAP_STATE_UNKNOWN 0
MAP_STATE_OK 1 Successfully started recording.
MAP_STATE_TOO_LARGE_FOR_LICENSE 2 Unable to continue recording because a larger map requires an upgraded license.

GetRecordStatusResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_ROBOT_IMPAIRED 2 Unable to record waypoints because the robot is impaired. When this happens,
the system will not create new waypoints until the robot is no longer impaired.
See impaired_state for more details.

StartRecordingResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status is unknown/unset.
STATUS_OK 1 Recording has been started.
STATUS_COULD_NOT_CREATE_WAYPOINT 2 In this case we tried to start recording, but GraphNav was internally still waiting for
some data from the robot.
STATUS_FOLLOWING_ROUTE 3 Can't start recording because the robot is following a route.
STATUS_NOT_LOCALIZED_TO_EXISTING_MAP 4 When recording branches, the robot is not localized to the existing map before starting
to record a new branch.
STATUS_MISSING_FIDUCIALS 5 Can't start recording because the robot doesn't see the required fiducials.
STATUS_MAP_TOO_LARGE_LICENSE 6 Can't start recording because the map was too large for the license.
STATUS_REMOTE_CLOUD_FAILURE_NOT_IN_DIRECTORY 7 A required remote cloud did not exist in the service directory.
STATUS_REMOTE_CLOUD_FAILURE_NO_DATA 8 A required remote cloud did not have data.
STATUS_FIDUCIAL_POSE_NOT_OK 9 All fiducials are visible but at least one pose could not be determined accurately.
STATUS_TOO_FAR_FROM_EXISTING_MAP 10 When recording branches, the robot is too far from the existing map when starting
to record a new branch.
STATUS_ROBOT_IMPAIRED 11 Unable to start recording because the robot is impaired.
See impaired_state for more details.

StopRecordingResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status is unknown/unset.
STATUS_OK 1 Recording is stopped.
STATUS_NOT_LOCALIZED_TO_END 2 In this case we tried to stop recording, but had an incorrect localization.
graph_nav is expected to be localized to the final waypoint in the chain before
we stop recording.
STATUS_NOT_READY_YET 3 The robot is still processing the map it created to where the robot is currently located.
You can't stop recording until that processing is finished. You should not move
the robot, then try to stop recording again after 1-2 seconds.

Top

bosdyn/api/graph_nav/recording_service.proto

GraphNavRecordingService

The recording service can be used to record a Graph Nav map (containing waypoints and edges). The recorded map can consist of the following:

  • Chain: a topological arrangement of waypoints/edges where every waypoint has at least 1 but at most 2 edges attached to it.

  • Branch: separate Chains can be joined together into a Branch at exactly one waypoint. When recording a map using the recording service, a common pattern is:

  • Call StartRecording to begin recording a chain of waypoints.

  • Call SetRecordingEnvironment to define persistent annotations for the edges and waypoints.

  • While recording, call GetRecordStatus to get feedback on the state of the recording service.

  • While recording, call GetMapStatus to determine what waypoints have been created.

  • Optionally call CreateWaypoint to create waypoints in specific locations.

  • Call StopRecording to pause the recording service and create branches.

  • While recording (or after completing recording), call DownloadWaypoint/Edge Snapshot rpc’s from the GraphNavService to download the large sensor data with the map.

Method Name Request Type Response Type Description
StartRecording StartRecordingRequest StartRecordingResponse Start recording the map from the current localization.
Creates a waypoint if you are starting to record. Otherwise, waits until you are
sufficiently far away from the previous waypoint.
StopRecording StopRecordingRequest StopRecordingResponse Stop recording the map from the current localization.
CreateWaypoint CreateWaypointRequest CreateWaypointResponse Create a new waypoint at the current localization.
SetRecordingEnvironment SetRecordingEnvironmentRequest SetRecordingEnvironmentResponse Set the environmnent and name prefix to use for the recording.
CreateEdge CreateEdgeRequest CreateEdgeResponse Create an arbitrary edge between two waypoints.
GetRecordStatus GetRecordStatusRequest GetRecordStatusResponse Tells the client the internal state of the record service, and the structure of the map that has been recorded
so far.

Top

bosdyn/api/gripper_camera_param.proto

GripperCameraGetParamRequest

The GripperCameraGetParam request message queries the robot for the current gripper sensor parameters.

Field Type Label Description
header RequestHeader Common request header.

GripperCameraGetParamResponse

The GripperCameraGetParam response message contains the current gripper sensor parameters. Gripper sensor parameters do not persist across reboots.

Field Type Label Description
header ResponseHeader Common request header.
params GripperCameraParams

GripperCameraParamRequest

The GripperCameraParam request message sets new gripper sensor parameters. Gripper sensor parameters do not persist across reboots.

Field Type Label Description
header RequestHeader Common request header.
params GripperCameraParams

GripperCameraParamResponse

Field Type Label Description
header ResponseHeader Common response header.

GripperCameraParams

Field Type Label Description
camera_mode GripperCameraParams.CameraMode CameraMode sets the resolution, frame rate and image format.
brightness google.protobuf.FloatValue Set the image brightness level.
Min 0, max 1
contrast google.protobuf.FloatValue Set the image contrast level.
Min 0, max 1
saturation google.protobuf.FloatValue Set the image saturation level.
Min 0, max 1
gain google.protobuf.FloatValue Set the image gain level.
This paramater is only effective when manual exposure is used.
Min 0, max 1
exposure_auto google.protobuf.BoolValue Whether the camera should use auto exposure.
Unset is equivalent to setting exposure_auto = true
exposure_absolute google.protobuf.FloatValue Manually set the image exposure level. This value is only used if exposure_auto is false.
Min 0, max 1
exposure_roi RoiParameters Region of interest for exposure. Specify a spot exposure on a
certain part of the image. Only used in auto-exposure mode.
focus_auto google.protobuf.BoolValue Whether the camera should automatically focus the image.
Unset is equivalent to setting focus_auto = true
focus_absolute google.protobuf.FloatValue Manually set the image focus. This value is only used if focus_auto is false.
If focus_auto is true, this value will be populated with the current focus value.
Min 0, max 1
0 corresponds to focus at infinity, 1 corresponds to a focal point close to the camera.
focus_roi RoiParameters Region of interest for focus. Only used when in auto-focus mode.
draw_focus_roi_rectangle google.protobuf.BoolValue Set to true to draw a rectangle in the image where the focus ROI is.
Unset is equivalent to setting draw_focus_roi_rectangle = false
hdr HdrParameters High dynamic range (HDR) mode sets the camera to take multiple frames to get exposure
in a large range. HDR will reduce framerate in high-framerate modes.
led_mode GripperCameraParams.LedMode Set the LED mode.
led_torch_brightness google.protobuf.FloatValue Brightness of the LED in torch mode. Min = 0, max = 1.
Note: A brightness value of 0 is not off, but is the minimum brightness.
To turn off the LED, set the led_mode to LED_MODE_OFF
white_balance_temperature_auto google.protobuf.BoolValue Whether the camera should use auto white balance
Unset is equivalent to setting white_balance_temperature_auto = true
gamma google.protobuf.FloatValue Set the image gamma level.
Min 0, max 1
white_balance_temperature google.protobuf.FloatValue Manually set the white balance focus. This value is only used if white_balance_temperature_auto is false.
Min 0, max 1
0 corresponds to focus at infinity, 1 corresponds to a focal point close to the camera.
sharpness google.protobuf.FloatValue Set the image sharpness level.
Min 0, max 1

RoiParameters

Region of interest (ROI) indicates the region within the image that should be used for determination of automatic focus or exposure.

Field Type Label Description
roi_percentage_in_image Vec2 Center point of the ROI in the image. The upper lefthand corner of the image is (0, 0) and
the lower righthand corner is (1, 1). The middle of the image is (0.5, 0.5).
window_size RoiParameters.RoiWindowSize Size of the region of interest.

GripperCameraParams.CameraMode

Name Number Description
MODE_UNKNOWN 0 MODE_UNKNOWN should not be used.
MODE_640_480 11 640x480 pixels.
MODE_640_480_120FPS_UYVY 11
MODE_1280_720 1 1280x720 pixels.
MODE_1280_720_60FPS_UYVY 1
MODE_1920_1080 14 1920x1080 pixels.
MODE_1920_1080_60FPS_MJPG 14
MODE_3840_2160 15 3840x2160 pixels.
MODE_3840_2160_30FPS_MJPG 15
MODE_4096_2160 17 4096x2160 pixels.
MODE_4096_2160_30FPS_MJPG 17
MODE_4208_3120 16 4208x3120 pixels.
MODE_4208_3120_20FPS_MJPG 16

GripperCameraParams.LedMode

Name Number Description
LED_MODE_UNKNOWN 0 LED_MODE_UNKNOWN should not be used.
LED_MODE_OFF 1 Off
LED_MODE_TORCH 2 Constantly on. Brightness level can be set in the led_torch_brightness field.

HdrParameters

High dynamic range (HDR) modes available. HDR sets the camera to take multiple frames to get exposure in a large range. HDR will reduce framerate in high-framerate modes.

Name Number Description
HDR_UNKNOWN 0 (or not set): will not change HDR settings.
HDR_OFF 1 HDR disabled
HDR_AUTO 2 Camera's on-board processor determines how much HDR is needed
HDR_MANUAL_1 3 Manual HDR enabled (minimum)
HDR_MANUAL_2 4
HDR_MANUAL_3 5
HDR_MANUAL_4 6 Manual HDR enabled (maximum)

RoiParameters.RoiWindowSize

Name Number Description
ROI_WINDOW_SIZE_UNKNOWN 0 ROI window size, 1 is the smallest, 8 is the largest.
ROI_WINDOW_SIZE_1 1
ROI_WINDOW_SIZE_2 2
ROI_WINDOW_SIZE_3 3
ROI_WINDOW_SIZE_4 4
ROI_WINDOW_SIZE_5 5
ROI_WINDOW_SIZE_6 6
ROI_WINDOW_SIZE_7 7
ROI_WINDOW_SIZE_8 8

Top

bosdyn/api/gripper_camera_param_service.proto

GripperCameraParamService

Method Name Request Type Response Type Description
SetParams GripperCameraParamRequest GripperCameraParamResponse
GetParams GripperCameraGetParamRequest GripperCameraGetParamResponse

Top

bosdyn/api/gripper_command.proto

ClawGripperCommand

Command to open and close the gripper.

ClawGripperCommand.Feedback

Field Type Label Description
status ClawGripperCommand.Feedback.Status Current status of the command.

ClawGripperCommand.Request

Field Type Label Description
trajectory ScalarTrajectory Scalar trajectory for opening/closing the gripper. If 1 point is specified
with no end time, we will execute a minimum time trajectory that observes
velocity and acceleration constraints. Otherwise, we will use piecewise
cubic interpolation, meaning there will be a cubic polynomial between each
trajectory point, with continuous position and velocity at each trajectory
point. If the requested trajectory violates the velocity or acceleration
constraints below, a trajectory that is as close as possible but still
obeys the constraints will be executed instead.
position is radians: 0 is fully closed -1.5708 (-90 degrees) is fully open
velocity is radians / sec.
maximum_open_close_velocity google.protobuf.DoubleValue If unspecified, a default value of 10 (rad/s) will be used.
maximum_open_close_acceleration google.protobuf.DoubleValue If unspecified, a default value of 40 (rad/s/s) will be used.
maximum_torque google.protobuf.DoubleValue Maximum torque applied. If unspecified, a default value of 5.5 (Nm) will be used.
disable_force_on_contact bool By default the gripper transitions to force control when it detects an object closing.
Setting this field to true disables the transition to force control on contact detection
and always keeps the gripper in position control.

GripperCommand

The synchronized command message for commanding the gripper to move. A synchronized commands is one of the possible robot command messages for controlling the robot.

GripperCommand.Feedback

The feedback for the gripper command that will provide information on the progress of the command.

Field Type Label Description
claw_gripper_feedback ClawGripperCommand.Feedback Feedback for the claw gripper command.
status RobotCommandFeedbackStatus.Status

GripperCommand.Request

The gripper request must be one of the basic command primitives.

Field Type Label Description
claw_gripper_command ClawGripperCommand.Request Control opening and closing the gripper.

ClawGripperCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_IN_PROGRESS 1 The gripper is opening or closing.
STATUS_AT_GOAL 2 The gripper is at the final point of the trajectory.
STATUS_APPLYING_FORCE 3 During a close, detected contact and transitioned to force control.

Top

bosdyn/api/header.proto

CommonError

General error code are returned in the header to facilitate error-handling which is not message-specific. This can be used for generic error handlers, aggregation, and trend analysis.

Field Type Label Description
code CommonError.Code The different error codes that can be returned on a grpc response message.
message string Human-readable error description. Not for programmatic analysis.
data google.protobuf.Any Extra information that can optionally be provided for generic error handling/analysis.

RequestHeader

Standard header attached to all GRPC requests to services.

Field Type Label Description
request_timestamp google.protobuf.Timestamp Time that the request was sent, as measured by the client's local system clock.
client_name string Name of the client to identify itself. The name will typically include a
symbolic string to identify the program, and a unique integer to identify
the specific instance of the process running.
disable_rpc_logging bool If Set to true, request that request and response messages for this call are not recorded
in the GRPC log.

ResponseHeader

Standard header attached to all GRPC responses from services.

Field Type Label Description
request_header RequestHeader Echo-back the RequestHeader for timing information, etc....
request_received_timestamp google.protobuf.Timestamp Time that the request was received. The server clock is the time basis.
response_timestamp google.protobuf.Timestamp Time that the response was received. The server clock is the time basis.
error CommonError Common errors, such as invalid input or internal server problems.
If there is a common error, the rest of the response message outside of the
ResponseHeader will be invalid.
request google.protobuf.Any Echoed request message. In some cases it may not be present, or it may be a stripped
down representation of the request.

CommonError.Code

Name Number Description
CODE_UNSPECIFIED 0 Code is not specified.
CODE_OK 1 Not an error. Request was successful.
CODE_INTERNAL_SERVER_ERROR 2 Service experienced an unexpected error state.
CODE_INVALID_REQUEST 3 Ill-formed request. Request arguments were not valid.

Top

bosdyn/api/image.proto

CaptureParameters

Sensor parameters associated with an image capture.

Field Type Label Description
exposure_duration google.protobuf.Duration The duration of exposure in microseconds.
gain double Sensor gain in dB.
custom_params DictParam Any other custom parameters used in the image capture.

GetImageRequest

The GetImage request message which can send multiple different image source requests at once.

Field Type Label Description
header RequestHeader Common request header.
image_requests ImageRequest repeated The different image requests for this rpc call.

GetImageResponse

The GetImage response message which includes image data for all requested sources.

Field Type Label Description
header ResponseHeader Common response header.
image_responses ImageResponse repeated The ordering of these image responses is defined by the order of the ImageRequests.

Image

Rectangular color/greyscale/depth images.

Field Type Label Description
cols int32 Number of columns in the image (in pixels).
rows int32 Number of rows in the image (in pixels).
data bytes Raw image data.
format Image.Format How the image is encoded.
pixel_format Image.PixelFormat Pixel format of the image; this will be set even when the Format implies
the pixel format.

ImageCapture

Rectangular color/greyscale images.

Field Type Label Description
acquisition_time google.protobuf.Timestamp The time at which the image data was acquired in the robot's time basis.
transforms_snapshot FrameTreeSnapshot A tree-based collection of transformations, which will include the transformations to each image's
sensor in addition to transformations to the common frames ("vision", "body", "odom").
All transforms within the snapshot are at the acquistion time of the image.
frame_name_image_sensor string The frame name for the image's sensor source. This will be included in the transform snapshot.
image Image Image data.
capture_params CaptureParameters Sensor parameters associated with this image capture.

ImageCaptureAndSource

This message is a subset of the ImageResponse message with only the information needed to pass captured images to other services.

Field Type Label Description
shot ImageCapture The image capture contains the image data and information about the state of the camera and
robot at the time the image was collected.
source ImageSource The source describes general information about the camera source the image data was collected
from.
image_service string Image service. If blank, it is assumed to be the robot's default image service.

ImageRequest

The image request specifying the image source and data format desired.

Field Type Label Description
image_source_name string The string name of the image source to get image data from.
quality_percent double Image quality: a number from 0 (worst) to 100 (highest).
Note that jpeg quality 100 is still lossy.
image_format Image.Format Specify the desired image encoding (e.g. JPEG, RAW). If no format is specified (e.g. FORMAT_UNKNOWN), the image
service will choose the best format for the data.
resize_ratio double Optional specification of the desired image dimensions.
If the original image is 1920x1080, a resize_ratio of (2/3) will return an image with size 1280x720
The range is clipped to [0.01, 1] while maintaining the original aspect ratio.
For backwards compatibliity, a value of 0 means no resizing.
Note: this field is not supported by the robot body cameras image service (image).
pixel_format Image.PixelFormat Specify the desired pixel format (e.g. GREYSCALE_U8, RGB_U8). If no format is specified
(e.g. PIXEL_FORMAT_UNKNOWN), the image service will choose the best format for the data.
custom_params DictParam Parameters unique to the servicer that do not match any of the above fields.
Whether or not these are valid may depend on the values of the above fields.

ImageResponse

The image response for each request, that includes image data and image source information.

Field Type Label Description
shot ImageCapture The image capture contains the image data and information about the state of the camera and robot
at the time the image was collected.
source ImageSource The source describes general information about the camera source the image data was collected from.
status ImageResponse.Status Return status of the request.
custom_param_error CustomParamError Filled out if status is STATUS_CUSTOM_PARAMS_ERROR.

ImageSource

Proto for a description of an image source on the robot.

Field Type Label Description
name string The name of this image source used to get images.
cols int32 Number of columns in the image (in pixels).
rows int32 Number of rows in the image (in pixels).
depth_scale double For depth images, the pixel value that represents a depth of one meter.
Depth in meters can be computed by dividing the raw pixel value by this scale factor.
pinhole ImageSource.PinholeModel Rectilinear camera model.
image_type ImageSource.ImageType The kind of images returned by this image source.
pixel_formats Image.PixelFormat repeated The pixel formats a specific image source supports.
image_formats Image.Format repeated The image formats a specific image source supports.
custom_params DictParam.Spec ImageRequest parameters unique to this source that do not match any of the above fields.

ImageSource.PinholeModel

The camera can be modeled as a pinhole camera described with a matrix. Camera Matrix can be constructed by the camera intrinsics: [[focal_length.x, skew.x, principal_point.x], [[ skew.y, focal_length.y, principal_point.y], [[ 0, 0, 1]]

Field Type Label Description
intrinsics ImageSource.PinholeModel.CameraIntrinsics The camera intrinsics are necessary for descrbing the pinhole camera matrix.

ImageSource.PinholeModel.CameraIntrinsics

Intrinsic parameters are in pixel space.

Field Type Label Description
focal_length Vec2 The focal length of the camera.
principal_point Vec2 The optical center in sensor coordinates.
skew Vec2 The skew for the intrinsic matrix.

ListImageSourcesRequest

The ListImageSources request message for the robot image service.

Field Type Label Description
header RequestHeader Common request header.

ListImageSourcesResponse

The ListImageSources response message which contains all known image sources for the robot.

Field Type Label Description
header ResponseHeader Common response Header.
image_sources ImageSource repeated The set of ImageSources available from this service.
May be empty if the service serves no cameras (e.g., if no cameras were found on startup).

Image.Format

Name Number Description
FORMAT_UNKNOWN 0 Unknown image format.
FORMAT_JPEG 1 Color/greyscale formats.
JPEG format.
FORMAT_RAW 2 Uncompressed. Requires pixel_format.
FORMAT_RLE 3 1 byte run-length before each pixel value.

Image.PixelFormat

Name Number Description
PIXEL_FORMAT_UNKNOWN 0 Unspecified value -- should not be used.
PIXEL_FORMAT_GREYSCALE_U8 1 One byte per pixel.
PIXEL_FORMAT_RGB_U8 3 Three bytes per pixel.
PIXEL_FORMAT_RGBA_U8 4 Four bytes per pixel.
PIXEL_FORMAT_DEPTH_U16 5 Little-endian uint16 z-distance from camera (mm).
PIXEL_FORMAT_GREYSCALE_U16 6 Big-endian uint16

ImageResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
An internal ImageService issue has happened if UNKNOWN is set.
None of the other fields are filled out.
STATUS_OK 1 Call succeeded at filling out all the fields.
STATUS_UNKNOWN_CAMERA 2 Image source name in request is unknown. Other fields are not filled out.
STATUS_SOURCE_DATA_ERROR 3 Failed to fill out ImageSource. All the other fields are not filled out.
STATUS_IMAGE_DATA_ERROR 4 There was a problem with the image data. Only the ImageSource is filled out.
STATUS_UNSUPPORTED_IMAGE_FORMAT_REQUESTED 5 The requested image format is unsupported for the image-source named. The image data will
not be filled out. Note, if an image request has "FORMAT_UNKNOWN", the service should choose the
best format to provide the data in.
STATUS_UNSUPPORTED_PIXEL_FORMAT_REQUESTED 6 The requested pixel format is unsupported for the image-source named. The image data will
not be filled out. Note, if an image request has "PIXEL_FORMAT_UNKNOWN", the service
should choose the best format to provide the data in.
STATUS_UNSUPPORTED_RESIZE_RATIO_REQUESTED 7 The requested ratio is out of bounds [0,1] or unsupported by the image service
STATUS_CUSTOM_PARAMS_ERROR 8 One or more keys or values in custom_params are unsupported by the image service.
See the custom_param_error for details.

ImageSource.ImageType

Name Number Description
IMAGE_TYPE_UNKNOWN 0 Unspecified image type.
IMAGE_TYPE_VISUAL 1 Color or greyscale intensity image.
IMAGE_TYPE_DEPTH 2 Pixel values represent distances to objects/surfaces.

Top

bosdyn/api/image_geometry.proto

AreaI

Represents an area in the XY plane, with integer indices

Field Type Label Description
rectangle RectangleI

RectangleI

Represents a rectangle, with integer indices.

Field Type Label Description
x int32 Distance from the left
y int32 Distance from the top
cols int32 Width of the rectangle in pixels
rows int32 Height of the rectangle in pixels

Top

bosdyn/api/image_service.proto

ImageService

An Image service provides access to one or more images, for example from cameras. It supports querying for the list of available images provided by the service and then supports requesting a latest given image by source name.

Method Name Request Type Response Type Description
ListImageSources ListImageSourcesRequest ListImageSourcesResponse Obtain the list of ImageSources for this given service.
Note that there may be multiple ImageServices running, each with their own set of sources
The name field keys access to individual images when calling GetImage.
GetImage GetImageRequest GetImageResponse Request an image by name, with optional parameters for requesting image quality level.

Top

bosdyn/api/ir_enable_disable.proto

IREnableDisableRequest

Field Type Label Description
header RequestHeader < Common request header.
request IREnableDisableRequest.Request

IREnableDisableResponse

Field Type Label Description
header ResponseHeader < Common response header.

IREnableDisableRequest.Request

Name Number Description
REQUEST_UNKNOWN 0 Unspecified value -- should not be used.
REQUEST_OFF 1 Disable emissions.
REQUEST_ON 2 Enable emissions.

Top

bosdyn/api/ir_enable_disable_service.proto

IREnableDisableService

Method Name Request Type Response Type Description
IREnableDisable IREnableDisableRequest IREnableDisableResponse

Top

bosdyn/api/keepalive/keepalive.proto

ActionAfter

Field Type Label Description
record_event ActionAfter.RecordEvent
auto_return ActionAfter.AutoReturn
controlled_motors_off ActionAfter.ControlledMotorsOff
immediate_robot_off ActionAfter.ImmediateRobotOff
lease_stale ActionAfter.LeaseStale
after google.protobuf.Duration Take the specified action after not hearing from the associated policy_id in this long.

ActionAfter.AutoReturn

Robot triggers AutoReturn.

Field Type Label Description
leases bosdyn.api.Lease repeated Leases that AutoReturn may use to accomplish its goals when it triggers.
This field is required.
This should be a newer lease than the last one used to control the robot.
For example, if you have acquired lease [6] from the robot, you should begin controlling
the robot with [6, 0, 1] and pass [6, 1] here.
If you have added an associated lease, it should be the [6] lease.
params bosdyn.api.auto_return.Params Parameters to AutoReturn. See that message's documentation for details.

ActionAfter.ControlledMotorsOff

After coming to a halt, robot sits and powers off its motors. Takes priority over AutoReturn and HaltRobot actions.

ActionAfter.ImmediateRobotOff

Robot powers off its computer immediately. WARNING: This will cause loss of recent data, and may damage the robot or its payloads if done while the robot is not sitting.

ActionAfter.LeaseStale

The leases are marked as stale, making the resource available for other clients. See the LeaseResource message for details.

Field Type Label Description
leases bosdyn.api.Lease repeated

ActionAfter.RecordEvent

Record an event.

Field Type Label Description
events bosdyn.api.Event repeated The events to be logged.

CheckInRequest

Field Type Label Description
header bosdyn.api.RequestHeader
policy_id uint64 Specify the policy whose timer should be refreshed.

CheckInResponse

Field Type Label Description
header bosdyn.api.ResponseHeader
last_checkin google.protobuf.Timestamp Time the robot recorded the check in. Specified in robot's clock.
status CheckInResponse.Status

GetStatusRequest

Field Type Label Description
header bosdyn.api.RequestHeader

GetStatusResponse

Field Type Label Description
header bosdyn.api.ResponseHeader
status LivePolicy repeated Per-policy status.
active_control_actions GetStatusResponse.PolicyControlAction repeated Is a Policy controlling the robot?
An empty field means that no Policy is actively controlling the robot, though other actions
may have triggered. For details, clients must parse the "status" field above.

LivePolicy

Field Type Label Description
policy_id uint64
policy Policy
last_checkin google.protobuf.Timestamp What time the policy was last refreshed with a check-in. Specified in robot's clock.
client_name string client_name from the RequestHeader of the most recent CheckInRequest for this policy.

ModifyPolicyRequest

Field Type Label Description
header bosdyn.api.RequestHeader
to_add Policy
policy_ids_to_remove uint64 repeated

ModifyPolicyResponse

Field Type Label Description
header bosdyn.api.ResponseHeader If the Policy in the request was invalid, CODE_INVALID_REQUEST will be set in this header.
In that case, no policies will have been removed.
CODE_INVALID_REQUEST can also happen if the Policy contains unknown fields. This may happen
if there is a version mismatch between client and server.
status ModifyPolicyResponse.Status
added_policy LivePolicy The policy added to the session, if any.
removed_policies LivePolicy repeated The policies removed from the session, if any.

Policy

Field Type Label Description
name string Human-friendly name of this policy.
actions ActionAfter repeated What to do, when.
associated_leases bosdyn.api.Lease repeated If provided, this field ties this policy to lease ownership.
When any one associated lease is no longer an owner, this policy is automatically removed.
user_id string Optionally provide a unique identifier for this policy.
Uniqueness is not enforced by the service; this is entirely for client use.

CheckInResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_INVALID_POLICY_ID 2 Set if the given policy ID was not valid on the system.

GetStatusResponse.PolicyControlAction

Name Number Description
POLICY_CONTROL_ACTION_UNKNOWN 0
POLICY_CONTROL_ACTION_AUTO_RETURN 1
POLICY_CONTROL_ACTION_MOTORS_OFF 2
POLICY_CONTROL_ACTION_ROBOT_OFF 3

ModifyPolicyResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1 Policy was added successfully, and/or policies were removed successfully.
STATUS_INVALID_POLICY_ID 2 Set if any given policy ID was not valid on the system.
No policy will have been added.
STATUS_INVALID_LEASE 3 Set if given policy's associated_lease was not the same, super, or sub lease of the
active lease.
No policy will have been removed.

Top

bosdyn/api/keepalive/keepalive_service.proto

KeepaliveService

The Keepalive service allows users to specify what the system should do when one or more clients stop communicating with the robot. The actions, and when those actions happen, are specified in a Policy. Clients will periodically check in with the Keepalive service to prevent the actions from happening.

This service is in BETA and may undergo changes in future releases.

Method Name Request Type Response Type Description
ModifyPolicy ModifyPolicyRequest ModifyPolicyResponse Add and/or remove policies of the session.
Adding or removing only happens if all parts of the request are valid. For example, if the
policy to be added is valid, but policies to be removed are not valid, no policy is added.
CheckIn CheckInRequest CheckInResponse Refresh the timer on a specific policy.
GetStatus GetStatusRequest GetStatusResponse Get the status of the current session.

Top

bosdyn/api/lease.proto

AcquireLeaseRequest

The AcquireLease request message which sends which resource the lease should be for.

Field Type Label Description
header RequestHeader Common request header.
resource string The resource to obtain a Lease for.

AcquireLeaseResponse

The AcquireLease response returns the lease for the desired resource if it could be obtained. If a client is returned a new lease, the client should initiate a RetainLease bidirectional streaming request immediately after completion of AcquireLease.

Field Type Label Description
header ResponseHeader Common response Header.
status AcquireLeaseResponse.Status Return status for the request.
lease Lease The lease for the resource. Only set if status field == STATUS_OK.
lease_owner LeaseOwner The owner for the lease. Set if status field == OK or status field ==
RESOURCE_ALREADY_CLAIMED.

Lease

Leases are used to verify that a client has exclusive access to a shared resources. Examples of shared resources are the motors for a robot, or indicator lights on a robot. Leases are initially obtained by clients from the LeaseService. Clients then attach Leases to Commands which require them. Clients may also generate sub-Leases to delegate out control of the resource to other services.

Field Type Label Description
resource string The resource that the Lease is for.
epoch string The epoch for the Lease. The sequences field are scoped to a particular epoch.
One example of where this can be used is to generate a random epoch
at LeaseService startup.
sequence uint32 repeated Logical vector clock indicating when the Lease was generated.
client_names string repeated The set of different clients which have sent/receieved the lease.

LeaseOwner

Details about who currently owns the Lease for a resource.

Field Type Label Description
client_name string The name of the client application.
user_name string The name of the user.

LeaseResource

Describes all information about a sepcific lease: including the resource it covers, the active lease, and which application is the owner of a lease.

Field Type Label Description
resource string The resource name.
lease Lease The active lease, if any.
lease_owner LeaseOwner The Lease Owner, if there is a Lease.
stale_time google.protobuf.Timestamp Deprecated. The robot time when this lease will become stale. A stale lease can be
acquired with an AcquireLeaseRequest OR a TakeLeaseRequest, while a lease
that is not stale can only be acquired with a TakeLeaseRequest.

Leases get marked stale when they haven't been used in a while. If you want
to prevent your lease from being marked stale, you need to either:
- Periodically send RetainLeaseRequests.
- Periodically send valid commands to the robot using the lease. Note
that only some types of commands will actually cause explicit lease
retention.

Commands & RetainLeaseRequests issued with a stale lease will still be accepted.
Stale leases, when used, will cause the used lease to no longer be stale.

DEPRECATED as of 3.3. Lease staleness is now set by the Keepalive service.
This value is only an estimate, and may not be correct if a Keepalive client has changed it.
Please use the is_stale flag for an instantaneous report on staleness, or check the
GetStatusResponse in the Keepalive service to get a time.
is_stale bool This lease has been marked stale, and may be acquired by another client.

LeaseUseResult

Result for when a Lease is used - for example, in a LeaseRetainer, or associated with a command.

Field Type Label Description
status LeaseUseResult.Status
owner LeaseOwner The current lease owner.
attempted_lease Lease The lease which was attempted for use.
previous_lease Lease The previous lease, if any, which was used.
latest_known_lease Lease The "latest"/"most recent" lease known to the system.
latest_resources Lease repeated Represents the latest "leaf" resources of the hierarchy.

ListLeasesRequest

The ListLease request message asks for information about any known lease resources.

Field Type Label Description
header RequestHeader Common request header.
include_full_lease_info bool Include the full data of leases in use, if available.
Defaults to false to receive basic information.

ListLeasesResponse

The ListLease response message returns all known lease resources from the LeaseService.

Field Type Label Description
header ResponseHeader Common response header.
resources LeaseResource repeated The resources managed by the LeaseService.
resource_tree ResourceTree Provide the hierarchical lease structure.
A resource can encapsulate multiple sub-resources.
For example, the "body" lease may include control of the legs, arm, and gripper.

ResourceTree

Lease resources can be divided into a hierarchy of sub-resources that can be commanded together. This message describes the hierarchy of a resource.

Field Type Label Description
resource string The name of this resource.
sub_resources ResourceTree repeated Sub-resources that make up this resource.

RetainLeaseRequest

The RetainLease request will inform the LeaseService that the application contains to hold ownership of this lease. Lease holders are expected to be reachable and alive. If enough time has passed since the last RetainLeaseRequest, the LeaseService will revoke the lease.

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to retain ownership over. May also be a "super" lease of the lease to retain
ownership over.

RetainLeaseResponse

The RetainLease response message sends the result of the attempted RetainLease request, which contains whether or not the lease is still owned by the application sending the request.

Field Type Label Description
header ResponseHeader Common response header.
lease_use_result LeaseUseResult Result of using the lease.

ReturnLeaseRequest

The ReturnLease request message will be sent to the LeaseService. If the lease is currently active for the resource, the LeaseService will invalidate the lease. Future calls to AcquireLease by any client will now succeed.

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to return back to the LeaseService.

ReturnLeaseResponse

The ReturnLease response message

Field Type Label Description
header ResponseHeader Common response header.
status ReturnLeaseResponse.Status Return status for the request.

TakeLeaseRequest

The TakeLease request message which sends which resource the lease should be for.

Field Type Label Description
header RequestHeader Common request header.
resource string The resource to obtain a Lease for.

TakeLeaseResponse

The TakeLease response returns the lease for the desired resource if it could be obtained. In most cases if the resource is managed by the LeaseService, TakeLease will succeed. However, in the future policies may be introduced which will prevent TakeLease from succeeding and clients should be prepared to handle that case. If a client obtains a new lease, the client should initiate a RetainLease bidirectional streaming request immediately after completion of TakeLease.

Field Type Label Description
header ResponseHeader Common response header.
status TakeLeaseResponse.Status Return status for the request.
lease Lease The lease for the resource. Only set if status field == STATUS_OK.
lease_owner LeaseOwner The owner for the lease. Set if status field == STATUS_OK.

AcquireLeaseResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal LeaseService issue has happened
if UNKNOWN is set.
STATUS_OK 1 AcquireLease was successful.The lease field will be populated with the new
lease for the resource. The client is expected to call the RetainLease method
immediately after.
STATUS_RESOURCE_ALREADY_CLAIMED 2 AcquireLease failed since the resource has already been claimed.
The TakeLease method may be used to forcefully grab the lease.
STATUS_INVALID_RESOURCE 3 AcquireLease failed since the resource is not known to LeaseService.
The ListLeaseResources method may be used to list all known
resources.
STATUS_NOT_AUTHORITATIVE_SERVICE 4 The LeaseService is not authoritative - so Acquire should not work.

LeaseUseResult.Status

Name Number Description
STATUS_UNKNOWN 0 An internal issue occurred.
STATUS_OK 1 The Lease was accepted.
STATUS_INVALID_LEASE 2 The Lease is invalid.
STATUS_OLDER 3 The Lease is older than the current lease, and rejected.
STATUS_REVOKED 4 The Lease holder did not check in regularly enough, and the Lease is stale.
STATUS_UNMANAGED 5 The Lease was for an unmanaged resource.
STATUS_WRONG_EPOCH 6 The Lease was for the wrong epoch.

ReturnLeaseResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal LeaseService issue has happened if UNKNOWN is
set.
STATUS_OK 1 ReturnLease was successful.
STATUS_INVALID_RESOURCE 2 ReturnLease failed because the resource covered by the lease
is not being managed by the LeaseService.
STATUS_NOT_ACTIVE_LEASE 3 ReturnLease failed because the lease was not the active lease.
STATUS_NOT_AUTHORITATIVE_SERVICE 4 The LeaseService is not authoritative - so Acquire should not work.

TakeLeaseResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal LeaseService issue has happened if UNKNOWN is
set.
STATUS_OK 1 TakeLease was successful. The lease field will be populated with the
new lease for the resource. The client is expected to call the RetainLease
method immediately after.
STATUS_INVALID_RESOURCE 2 TakeLease failed since the resource is not known to LeaseService.
The ListLeaseResources method may be used to list all known
resources.
STATUS_NOT_AUTHORITATIVE_SERVICE 3 The LeaseService is not authoritative - so Acquire should not work.

Top

bosdyn/api/lease_service.proto

LeaseService

LeaseService provides Leases of shared resources to clients. An example of a shared resource is the set of leg motors on Spot, which has the resource name of “body”. Clients can delegate out the Leases they receive from the LeaseService to additional clients or services by generating sub-leases. Leases obtained from the LeaseService may be revoked if the Lease holder does not check in frequently to the LeaseService, or if another client force-acquires a Lease.

Method Name Request Type Response Type Description
AcquireLease AcquireLeaseRequest AcquireLeaseResponse Acquire a lease to a specific resource if the resource is available.
TakeLease TakeLeaseRequest TakeLeaseResponse Take a lease for a specific resource even if another client has a lease.
ReturnLease ReturnLeaseRequest ReturnLeaseResponse Return a lease to the LeaseService.
ListLeases ListLeasesRequest ListLeasesResponse List state of all leases managed by the LeaseService.
RetainLease RetainLeaseRequest RetainLeaseResponse Retain possession of a lease.

Top

bosdyn/api/license.proto

GetFeatureEnabledRequest

Field Type Label Description
header RequestHeader Common request header.
feature_codes string repeated Check if specific named features are enabled on the robot under the currently
loaded license.

GetFeatureEnabledResponse

Field Type Label Description
header ResponseHeader Common response header.
feature_enabled GetFeatureEnabledResponse.FeatureEnabledEntry repeated The resulting map showing the feature name (as the map key) and a boolean indicating
if the feature is enabled with this license (as the map value).

GetFeatureEnabledResponse.FeatureEnabledEntry

Field Type Label Description
key string
value bool

GetLicenseInfoRequest

Field Type Label Description
header RequestHeader Common request header.

GetLicenseInfoResponse

Field Type Label Description
header ResponseHeader Common response header
license LicenseInfo The details about the current license that is uploaded to the robot.

LicenseInfo

Field Type Label Description
status LicenseInfo.Status The status of the uploaded license for this robot.
id string Unique license number.
robot_serial string Serial number of the robot this license covers.
not_valid_before google.protobuf.Timestamp The license is not valid for use for any dates before this timestamp.
not_valid_after google.protobuf.Timestamp The license is not valid for use for any dates after this timestamp.
licensed_features string repeated Human readable list of licensed features included for this license.

LicenseInfo.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_VALID 1
STATUS_EXPIRED 2
STATUS_NOT_YET_VALID 3
STATUS_MALFORMED 4
STATUS_SERIAL_MISMATCH 5
STATUS_NO_LICENSE 6

Top

bosdyn/api/license_service.proto

LicenseService

The LicenseService allows clients to query the currently installed license on robot.

Method Name Request Type Response Type Description
GetLicenseInfo GetLicenseInfoRequest GetLicenseInfoResponse Get information, such as the license number, dates of validity, and features for the license
currently uploaded on the robot.
GetFeatureEnabled GetFeatureEnabledRequest GetFeatureEnabledResponse Check if specific features (identified by string names) are enabled under the currently loaded
license for this robot.

Top

bosdyn/api/local_grid.proto

GetLocalGridTypesRequest

The GetLocalGridTypes request message asks to the local grid types.

Field Type Label Description
header RequestHeader Common request header.

GetLocalGridTypesResponse

The GetLocalGridTypes response message returns to get all known string names for local grid types.

Field Type Label Description
header ResponseHeader Common response header.
local_grid_type LocalGridType repeated The list of available local grid types.

GetLocalGridsRequest

The GetLocalGrid request message can request for multiple different types of local grids at one time.

Field Type Label Description
header RequestHeader Common request header.
local_grid_requests LocalGridRequest repeated Specifications of the requested local grids.

GetLocalGridsResponse

The GetLocalGrid response message replies with all of the local grid data for the requested types, and a numerical count representing the amount of status errors that occurred when getting this data.

Field Type Label Description
header ResponseHeader Common response header.
local_grid_responses LocalGridResponse repeated Response of local grid or error status for each requested local grid.
num_local_grid_errors int32 The number of individual local grids requests which could not be satisfied.

LocalGrid

A grid-based local grid structure, which can represent different kinds of data, such as terrain or obstacle data.

Field Type Label Description
local_grid_type_name string The human readable string name that is used to identify the type of local grid data.
acquisition_time google.protobuf.Timestamp The time at which the local grid data was computed and last valid at.
transforms_snapshot FrameTreeSnapshot A tree-based collection of transformations, which will include the transformations to each of
the returned local grids in addition to transformations to the common frames ("vision", "body", "odom").
All transforms within the snapshot are at the acquistion time of the local grid.
frame_name_local_grid_data string The frame name for the local grid data. This frame refers to the corner of cell (0, 0), such that
the map data is in the +x, +y quadrant.
The cell data is packed in x-y order, so the cell at:
data[xi + extent.num_cells_x * yj]
has its center at position:
{(xi + 0.5) * extent.cell_size, (yj + 0.5) * extent.cell_size}.
extent LocalGridExtent Location, size and resolution of the local grid.
cell_format LocalGrid.CellFormat The data type of all individual cells in the local grid.
encoding LocalGrid.Encoding The encoding for the 'data' field of the local grid message.
data bytes The encoded local grid representation.
Cells are encoded according to the encoding enum, and are stored in in row-major order (x-major).
This means that the data field has data entered row by row. The grid cell located at (i, j) will be
at the (index = i * num_cells_x + j) within the data array.
rle_counts int32 repeated RLE pixel repetition counts: use data[i] repeated rle_counts[i] times when decoding the
bytes data field.
cell_value_scale double The scale for the cell value data; only valid if it is a non-zero number.
cell_value_offset double A fixed value offset that is applied to each value of the cell data.
Actual values in local grid are: (({value from data} * cell_value_scale) + cell_value_offset).

LocalGridExtent

Information about the dimensions of the local grid, including the number of grid cells and the size of each cell.

Field Type Label Description
cell_size double Size of each side of the individual cells in the local grid (in meters).
The area of a grid cell will be (cell_size x cell_size).
num_cells_x int32 Number of cells along x extent of local grid (number of columns in local grid/ the local
grid width). Note, that the (num_cells_x)x(num_cells_y) represents the total number of grid
cells in the local grid.
num_cells_y int32 Number of cells along y extent of local grid (number of rows in local grid).
Note, that the (num_cells_x)x(num_cells_y) represents the totla number of grid
cells in the local grid.

LocalGridRequest

LocalGrids are requested by LocalGridType string name.

Field Type Label Description
local_grid_type_name string

LocalGridResponse

The local grid response message will contain either the local grid or an error status.

Field Type Label Description
local_grid_type_name string The type name of the local grid included in this response.
status LocalGridResponse.Status Status of the request for the individual local grid.
local_grid LocalGrid The requested local grid data.

LocalGridType

Representation of an available type of local grid.

Field Type Label Description
name string

LocalGrid.CellFormat

Describes the data type of a cell.

Name Number Description
CELL_FORMAT_UNKNOWN 0 Not specified -- not a valid value.
CELL_FORMAT_FLOAT32 1 Each cell of the local grid is encoded as a little-endian 32-bit floating point number.
CELL_FORMAT_FLOAT64 2 Each cell of the local grid is encoded as a little-endian 64-bit floating point number.
CELL_FORMAT_INT8 3 Each cell of the local grid is encoded as a signed 8-bit integer.
CELL_FORMAT_UINT8 4 Each cell of the local grid is encoded as an unsigned 8-bit integer.
CELL_FORMAT_INT16 5 Each cell of the local grid is encoded as a little-endian signed 16-bit integer.
CELL_FORMAT_UINT16 6 Each cell of the local grid is encoded as a little-endian unsigned 16-bit integer.

LocalGrid.Encoding

Encoding used for storing the local grid.

Name Number Description
ENCODING_UNKNOWN 0 Not specified -- not a valid value.
ENCODING_RAW 1 Cells are stored packed uncompressed.
ENCODING_RLE 2 Run-length encoding: repeat counts stored in rle_counts.

LocalGridResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Not specified -- not a valid value.
STATUS_OK 1 LocalGrid was returned successfully.
STATUS_NO_SUCH_GRID 2 The requested local grid-type is unknown.
STATUS_DATA_UNAVAILABLE 3 The request local grid data is not available at this time.
STATUS_DATA_INVALID 4 The local grid data was not valid for some reason.

Top

bosdyn/api/local_grid_service.proto

LocalGridService

The map service provides access multiple kinds of cell-based map data. It supports querying for the list of available types of local grids provided by the service, and supports requesting a set of the latest local grids by map type name.

Method Name Request Type Response Type Description
GetLocalGridTypes GetLocalGridTypesRequest GetLocalGridTypesResponse Obtain the list of available map types.
The name field keys access to individual local grids when calling GetLocalGrids.
GetLocalGrids GetLocalGridsRequest GetLocalGridsResponse Request a set of local grids by type name.

Top

bosdyn/api/log_status/log_status.proto

GetActiveLogStatusesRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetActiveLogStatusesResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status GetActiveLogStatusesResponse.Status Response status.
log_statuses LogStatus repeated A collection of the statuses of logs that are not in a terminal state (logStatus < 100)

GetLogStatusRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
id string Id of the log to retrieve.

GetLogStatusResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status GetLogStatusResponse.Status Response status.
log_status LogStatus Status of the retrieved log.

LogStatus

Field Type Label Description
id string Id of the response log.
status LogStatus.Status Status of the response log.
type LogStatus.Type Type of log.

StartExperimentLogRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
keep_alive google.protobuf.Duration How long into the future should this log end?

StartExperimentLogResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status StartExperimentLogResponse.Status Response status.
log_status LogStatus Status of the created log.
end_time google.protobuf.Timestamp Timestamp of the end of the log, in robot time.

StartRetroLogRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
past_duration google.protobuf.Duration How long into the past should this log start?

StartRetroLogResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status StartRetroLogResponse.Status Response status.
log_status LogStatus Status of the created log.
end_time google.protobuf.Timestamp Timestamp of the end of the log, in robot time.

TerminateLogRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
id string Id of log to terminate.

TerminateLogResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status TerminateLogResponse.Status Response status.
log_status LogStatus Status of terminated log.

UpdateExperimentLogRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
keep_alive google.protobuf.Duration How long into the future should this log continue?
id string Id of log to be extended.

UpdateExperimentLogResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status UpdateExperimentLogResponse.Status Response status.
log_status LogStatus Status of the updated log.
end_time google.protobuf.Timestamp Timestamp of the end of the log, in robot time.

GetActiveLogStatusesResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1

GetLogStatusResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_ID_NOT_FOUND 2 This log is not available on the robot.

LogStatus.Status

Status of a previous request for log bundler generation. Terminal statuses start at 100, such that if a status >= DONE, it can be concluded that the request is no longer active.

Name Number Description
STATUS_UNKNOWN 0 The status was not set, so something went wrong.
STATUS_RECEIVED 1 Request received, thread is not created for bundling the logs.
STATUS_IN_PROGRESS 2 Request in progress, thread is actively creating the bundle.
STATUS_SYNCING 3 Log end_time has passed, server post processing taking place.
STATUS_DONE 100 Bundling process is complete with no failures and was terminated by API.
STATUS_FAILED 101 Failure encountered while generating bundle.
STATUS_TERMINATED 102 Bundle creation was terminated by API prior to completion.

LogStatus.Type

Types of logs

Name Number Description
TYPE_UNKNOWN 0
TYPE_EXPERIMENT 1 A log into the future.
TYPE_RETRO 2 A retroactive log.

StartExperimentLogResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_EXPERIMENT_LOG_RUNNING 2 Cannot start another experiment log, one is already running.

StartRetroLogResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_EXPERIMENT_LOG_RUNNING 2 An experiment log is already running.
STATUS_CONCURRENCY_LIMIT_REACHED 3 Maximum retro logs running concurrently.

TerminateLogResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_ID_NOT_FOUND 2 This log is not available on the robot.

UpdateExperimentLogResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_ID_NOT_FOUND 2 This log is not available on the robot
STATUS_LOG_TERMINATED 3 Log has already terminated

Top

bosdyn/api/log_status/log_status_service.proto

LogStatusService

The LogStatusService provides clients the ability to

  • Retrieve log status by id

  • Access a collection of active logs

  • Start and stop retro logs

  • Start, extend and stop experiment logs

  • Terminate logs before their expiration time

Method Name Request Type Response Type Description
GetLogStatus GetLogStatusRequest GetLogStatusResponse Retrieve log status by id.
GetActiveLogStatuses GetActiveLogStatusesRequest GetActiveLogStatusesResponse View statuses of active logs.
StartRetroLog StartRetroLogRequest StartRetroLogResponse Given a duration T, StartRetroLog(T) triggers a log covering the timespan [logStartTime, t_rpc],
where logStartTime = max(t_rpc - T, t_buffer), t_rpc = time of RPC reception,
and t_buffer = time of first log on the buffer.
StartExperimentLog StartExperimentLogRequest StartExperimentLogResponse Given a duration T, StartExperimentLog(T) starts logging all data to
disk with a keepalive/watchdog timer of T. The duration of the log will be [t_rpc, t_rpc + T]
where t_rpc = time of RPC reception. The duration of this log can be extended by calling
UpdateExperimentLog before the log's status reaches a terminal state.
If any retro logs are running, they will be terminated by starting an experiment log.
Only one experiment log can be run at a time.
UpdateExperimentLog UpdateExperimentLogRequest UpdateExperimentLogResponse UpdateExperimentLog(id, T) will update the keepalive/watchdog timer of
the log with the provided id if the log is active. The updated duration
of the log will be [t_rpc, t_rpc + T] where t_rpc = time of RPC reception.
TerminateLog TerminateLogRequest TerminateLogResponse Terminate Log before it is complete.

Top

bosdyn/api/manipulation_api.proto

AllowableOrientation

Allowable orientation allow you to specify vectors that the different axes of the robot’s gripper will be aligned with in the final grasp pose. \

Frame:
In stow position, +X is to the front of the gripper, pointing forward.
+Y is out of the side of the gripper going to the robot’s left
+Z is straight up towards the sky \

Here, you can supply vectors that you want the gripper to be aligned with at the final grasp position. For example, if you wanted to grasp a cup, you’d wouldn’t want a top-down grasp. So you might specify:
frame_name = “vision” (so that Z is gravity aligned)
VectorAlignmentWithTolerance:
axis_to_on_gripper_ewrt_gripper = Vec3(0, 0, 1) <— we want to control the gripper’s z-axis. \

     axis_to_align_with_ewrt_frame = Vec3(0, 0, 1)  <--- ...and we want that axis to be
                                                            straight up \
     tolerance_z = 0.52  <--- 30 degrees \

This will ensure that the z-axis of the gripper is pointed within 30 degrees of vertical so that your grasp won’t be top-down (which would need the z-axis of the gripper to be pointed at the horizon). \

You can also specify more than one AllowableOrientation to give the system multiple options. For example, you could specify that you’re OK with either a z-up or z-down version of the cup grasp, allowing the gripper roll 180 from the stow position to grasp the cup.

Field Type Label Description
rotation_with_tolerance RotationWithTolerance
vector_alignment_with_tolerance VectorAlignmentWithTolerance
squeeze_grasp SqueezeGrasp

ApiGraspOverride

Use this message to assert the ground truth about grasping. Grasping is usually detected automatically by the robot. If the client wishes to override the robot’s determination of grasp status, send an ApiGraspOverride message with either: OVERRIDE_HOLDING, indicating the gripper is holding something, or OVERRIDE_NOT_HOLDING, indicating the gripper is not holding anything.

Field Type Label Description
override_request ApiGraspOverride.Override

ApiGraspOverrideRequest

Field Type Label Description
header RequestHeader Common request header.
api_grasp_override ApiGraspOverride
carry_state_override ApiGraspedCarryStateOverride If the grasp override is set to NOT_HOLDING, setting a carry_state_override
message will cause the request to be rejected as malformed.

ApiGraspOverrideResponse

Field Type Label Description
header ResponseHeader Common response header.

ApiGraspedCarryStateOverride

Use this message to assert properties about the grasped item. By default, the robot will assume all grasped items are not carriable.

Field Type Label Description
override_request ManipulatorState.CarryState

GraspParams

Field Type Label Description
grasp_palm_to_fingertip float Where the grasp is on the hand. Set to 0 to be a (default) palm grasp, where the object will
be pressed against the gripper's palm plate. Set to 1.0 to be a fingertip grasp, where the
robot will try to pick up the target with just the tip of its fingers. \
Intermediate values move the grasp location between the two extremes.
grasp_params_frame_name string Frame name for the frame that the constraints in allowable_orientation are expressed in.
allowable_orientation AllowableOrientation repeated Optional constraints about the orientation of the grasp. This field lets you specify things
like "only do a top down grasp," "grasp only from this direction," or "grasp with the gripper
upside-down." If you don't pass anything, the robot will automatically search for a good
grasp orientation.
position_constraint GraspPositionConstraint Optional parameter on how much the robot is allowed to move the grasp from where the user
requested. Set this to be GRASP_POSITION_CONSTRAINT_FIXED_AT_USER_POSITION to get a grasp
that is at the exact position you requested, but has less or no automatic grasp selection
help in position.
manipulation_camera_source ManipulationCameraSource Optional hint about which camera was used to generate the target points. The robot will
attempt to correct for calibration error between the arm and the body cameras.

ManipulationApiFeedbackRequest

Field Type Label Description
header RequestHeader Common request header.
manipulation_cmd_id int32 Unique identifier for the command, provided by ManipulationApiResponse.

ManipulationApiFeedbackResponse

Field Type Label Description
header ResponseHeader Common response header.
manipulation_cmd_id int32 The unique identifier for the ManipulationApiFeedbackRequest.
current_state ManipulationFeedbackState
transforms_snapshot_manipulation_data FrameTreeSnapshot Data from the manipulation system: \
"walkto_raycast_intersection": \
If you sent a WalkToObject request, we raycast in the world to intersect your pixel/ray
with the world. The point of intersection is included in this transform snapshot
with the name "walkto_raycast_intersection". \
"grasp_planning_solution": \
If you requested a grasp plan, this frame will contain the planning solution if
available. This will be the pose of the "hand" frame at the completion of the grasp. \
"gripper_nearest_object": \
If the range camera in the hand senses an object, this frame will have the position of
the nearest object. This is useful for getting a ballpark range measurement.

ManipulationApiRequest

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to show ownership of the robot.
walk_to_object_ray_in_world WalkToObjectRayInWorld Walk to an object with a raycast in to the world
walk_to_object_in_image WalkToObjectInImage Walk to an object at a pixel location in an image.
pick_object PickObject Pick up an object.
pick_object_in_image PickObjectInImage Pick up an object at a pixel location in an image.
pick_object_ray_in_world PickObjectRayInWorld Pick up an object based on a ray in 3D space. This is the lowest-level, most
configurable object picking command.
pick_object_execute_plan PickObjectExecutePlan Execute a previously planned pick.

ManipulationApiResponse

Field Type Label Description
header ResponseHeader Common response header.
manipulation_cmd_id int32 ID of the manipulation command either just issued or that we are providing feedback for.
lease_use_result LeaseUseResult Details about how the lease was used.

PickObject

Field Type Label Description
frame_name string Name of the frame you want to give your input in.
object_rt_frame Vec3 Pickup an object at the location, given in the frame named above.
grasp_params GraspParams Optional parameters for the grasp.

PickObjectExecutePlan

No data

PickObjectInImage

Field Type Label Description
pixel_xy Vec2 Pickup an object that is at a pixel location in an image.
transforms_snapshot_for_camera FrameTreeSnapshot A tree-based collection of transformations, which will include the transformations to each
image's sensor in addition to transformations to the common frames ("vision", "body",
"odom"). All transforms within the snapshot are at the acquistion time of the image.
frame_name_image_sensor string The frame name for the image's sensor source. This must be included in the transform
snapshot.
camera_model ImageSource.PinholeModel Camera model.
grasp_params GraspParams Optional parameters for the grasp.
walk_gaze_mode WalkGazeMode Automatic walking / gazing configuration.
See detailed comment in the PickObjectRayInWorld message.

PickObjectRayInWorld

Field Type Label Description
ray_start_rt_frame Vec3 Cast a ray in the world and pick the first object found along the ray. \
This is the lowest-level grasping message; all other grasp options internally use this
message to trigger a grasp. \
Example:
You see the object you are interested in with the gripper's camera. To grasp it, you
cast a ray from the camera out to 4 meters (well past the object). \
To do this you'd set: \
ray_start_rt_frame: camera's position \
ray_end_rt_frame: camera's position + unit vector along ray of interest * 4 meters
ray_end_rt_frame Vec3
frame_name string Name of the frame the above parameters are represented in.
grasp_params GraspParams Optional parameters for the grasp.
walk_gaze_mode WalkGazeMode Configure if the robot should automatically walk and/or gaze at the target object before
performing the grasp. \
1. If you haven't moved the robot or deployed the arm, use PICK_AUTO_WALK_AND_GAZE \
2. If you have moved to the location you want to pick from, but haven't yet deployed the arm,
use PICK_AUTO_GAZE. \
3. If you have already moved the robot and have the hand looking at your target object, use
PICK_NO_AUTO_WALK_OR_GAZE. \
If you are seeing issues with "MANIP_STATE_GRASP_FAILED_TO_RAYCAST_INTO_MAP," that means that
the automatic system cannot find your object when trying to automatically walk to it, so
consider using PICK_AUTO_GAZE or PICK_NO_AUTO_WALK_OR_GAZE.

RotationWithTolerance

Field Type Label Description
rotation_ewrt_frame Quaternion
threshold_radians float

SqueezeGrasp

A “squeeze grasp” is a top-down grasp where we try to keep both jaws of the gripper in contact with the ground and bring the jaws together. This can allow the robot to pick up small objects on the ground.

If you specify a SqueezeGrasp as: allowed: - with no other allowable orientations: then the robot will perform a squeeze grasp. - with at least one other allowable orientation: the robot will attempt to find a normal grasp with that orientation and if it fails, will perform a squeeze grasp. disallowed: - with no other allowable orientations: the robot will perform an unconstrained grasp search and a grasp if a good grasp is found. If no grasp is found, the robot will report MANIP_STATE_GRASP_PLANNING_NO_SOLUTION - with other allowable orientations: the robot will attempt to find a valid grasp. If it cannot it will report MANIP_STATE_GRASP_PLANNING_NO_SOLUTION

Field Type Label Description
squeeze_grasp_disallowed bool

VectorAlignmentWithTolerance

Field Type Label Description
axis_on_gripper_ewrt_gripper Vec3 Axis on the gripper that you want to align. For example, to align the front of the gripper
to be straight down, you'd use:
axis_on_gripper_ewrt_gripper = Vec3(1, 0, 0) \
axis_to_align_with_ewrt_frame = Vec3(0, 0, -1) (in the "vision" frame) \
axis_to_align_with_ewrt_frame Vec3
threshold_radians float

WalkToObjectInImage

Field Type Label Description
pixel_xy Vec2 Walk to an object that is at a pixel location in an image.
transforms_snapshot_for_camera FrameTreeSnapshot A tree-based collection of transformations, which will include the transformations to each
image's sensor in addition to transformations to the common frames ("vision", "body",
"odom"). All transforms within the snapshot are at the acquisition time of the image.
frame_name_image_sensor string The frame name for the image's sensor source. This will be included in the transform
snapshot.
camera_model ImageSource.PinholeModel Camera model.
offset_distance google.protobuf.FloatValue Optional offset distance for the robot to stand from the object's location. The robot will
walk forwards or backwards from where it is so that its center of mass is this distance from
the object. \
If unset, we use a reasonable default value.

WalkToObjectRayInWorld

Walks the robot up to an object. Useful to prepare to grasp or manipulate something.

Field Type Label Description
ray_start_rt_frame Vec3 Position of the start of the ray (see PickObjectRayInWorld for detailed comments.)
ray_end_rt_frame Vec3 Position of the end of the ray.
frame_name string Name of the frame that the above parameters are expressed in.
offset_distance google.protobuf.FloatValue Optional offset distance for the robot to stand from the object's location. The robot will
walk forwards or backwards from where it is so that its center of mass is this distance from
the object. \
If unset, we use a reasonable default value.

ApiGraspOverride.Override

Name Number Description
OVERRIDE_UNKNOWN 0
OVERRIDE_HOLDING 1
OVERRIDE_NOT_HOLDING 2

GraspPositionConstraint

Name Number Description
GRASP_POSITION_CONSTRAINT_UNKNOWN 0
GRASP_POSITION_CONSTRAINT_NORMAL 1
GRASP_POSITION_CONSTRAINT_FIXED_AT_USER_POSITION 2

ManipulationCameraSource

Name Number Description
MANIPULATION_CAMERA_SOURCE_UNKNOWN 0
MANIPULATION_CAMERA_SOURCE_STEREO 1
MANIPULATION_CAMERA_SOURCE_HAND 2

ManipulationFeedbackState

Name Number Description
MANIP_STATE_UNKNOWN 0
MANIP_STATE_DONE 1
MANIP_STATE_SEARCHING_FOR_GRASP 2
MANIP_STATE_MOVING_TO_GRASP 3
MANIP_STATE_GRASPING_OBJECT 4
MANIP_STATE_PLACING_OBJECT 5
MANIP_STATE_GRASP_SUCCEEDED 6
MANIP_STATE_GRASP_FAILED 7
MANIP_STATE_GRASP_PLANNING_SUCCEEDED 11
MANIP_STATE_GRASP_PLANNING_NO_SOLUTION 8
MANIP_STATE_GRASP_FAILED_TO_RAYCAST_INTO_MAP 9 Note: if you are experiencing raycast failures during grasping, consider using a different
grasping call that does not require the robot to automatically walk up to the grasp.
MANIP_STATE_GRASP_PLANNING_WAITING_DATA_AT_EDGE 13 The grasp planner is waiting for the gaze to have the target object not on the edge of the
camera view. If you are seeing this in an automatic mode, the robot will soon retarget the
grasp for you. If you are seeing this in a non-auto mode, you'll need to change your gaze
to have the target object more in the center of the hand-camera's view.
MANIP_STATE_WALKING_TO_OBJECT 10
MANIP_STATE_ATTEMPTING_RAYCASTING 12
MANIP_STATE_MOVING_TO_PLACE 14
MANIP_STATE_PLACE_FAILED_TO_RAYCAST_INTO_MAP 15
MANIP_STATE_PLACE_SUCCEEDED 16
MANIP_STATE_PLACE_FAILED 17

WalkGazeMode

Configure automatic walking and gazing at the target.

Name Number Description
PICK_WALK_GAZE_UNKNOWN 0
PICK_AUTO_WALK_AND_GAZE 1 Default, walk to the target and gaze at it automatically
PICK_AUTO_GAZE 2 Don't move the robot base, but automatically look at the grasp target.
PICK_NO_AUTO_WALK_OR_GAZE 3 No automatic gazing or walking. Note: if you choose this option, the target location
must not be near the edges or off the screen on the hand camera's view.
PICK_PLAN_ONLY 4 Only plan for the grasp, don't move the robot. Since we won't move
the robot, the target location must not be near the edges or out of
the hand camera's view. The robot must be located near the object.
(Equivalent conditions as for success with PICK_NO_AUTO_WALK_OR_GAZE)

Top

bosdyn/api/manipulation_api_service.proto

ManipulationApiService

Method Name Request Type Response Type Description
ManipulationApi ManipulationApiRequest ManipulationApiResponse
ManipulationApiFeedback ManipulationApiFeedbackRequest ManipulationApiFeedbackResponse
OverrideGrasp ApiGraspOverrideRequest ApiGraspOverrideResponse

Top

bosdyn/api/metrics_logging/absolute_metrics.proto

AbsoluteMetricsSnapshot

Stores a collection of AbsoluteMetrics. The scalar values stored in this structure are meant to be cumulative.

Field Type Label Description
timestamp_start google.protobuf.Timestamp Assume two snapshots. One at time=t, and one at time=t-1. If we subtract the metrics
of snapshot t-1 from the metrics of snapshot t, we'll get change in metrics. That change
in metrics corresponds to the bounding time given by the following two timestamps.
Note, when the user transitions from opt out to opt in, or the robot starts up for the first
time, timestamp_start will be empty!
timestamp_end google.protobuf.Timestamp
sequence_number int32 Monotonic number. Every time the robot creates a snapshot, this number will increment. It
will be how the robot reports what snapshots are available, and how the client & proxy track
what snapshots they have & still need.
robot_serial_number string
robot_species string
parameters bosdyn.api.Parameter repeated
events bosdyn.api.Event repeated Robot events

Top

bosdyn/api/metrics_logging/metrics_logging_robot.proto

GetAbsoluteMetricSnapshotRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
sequence_numbers int32 repeated The robot will respond with the corresponding Snapshot for these
sequence_numbers, if it has them.

GetAbsoluteMetricSnapshotResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
snapshots SignedProto repeated Signed AbsoluteMetricsSnapshot messages corresponding to the request timestamps.
The robot will exclude snapshots if:
* They don't exist on the robot
* If included, the snapshot would push the total response message size over the GRPC limit.

GetMetricsRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
keys string repeated If keys are specified, the GetMetricsResponse will only include parameters
which match the keys. If no keys are specified, all parameters will be returned.
include_events bool Include events in the GetMetricsResponse. By default events will not be included.

GetMetricsResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
parameters bosdyn.api.Parameter repeated Current parameters for metrics.
missing_keys string repeated If any keys specified in the GetMetricsRequest are not present in the database,
they'll be reported here.
events bosdyn.api.Event repeated Events included in the metrics.

GetStoreSequenceRangeRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetStoreSequenceRangeResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
first_sequence_number int32 The inclusive sequence_number of the first entry in the store.
last_sequence_number int32 The inclusive sequence_number of the last entry in the store.

Top

bosdyn/api/metrics_logging/metrics_logging_robot_service.proto

MetricsLoggingRobotService

Method Name Request Type Response Type Description
GetStoreSequenceRange GetStoreSequenceRangeRequest GetStoreSequenceRangeResponse
GetAbsoluteMetricSnapshot GetAbsoluteMetricSnapshotRequest GetAbsoluteMetricSnapshotResponse
GetMetrics GetMetricsRequest GetMetricsResponse

Top

bosdyn/api/metrics_logging/signed_proto.proto

SignedProto

A custom signed format. Sequentially laid out:

4 bytes header 20 bytes fingerprint 512 bytes signature X bytes data.

header -> When this format changes, we’ll use the header to delminate which format was used to generate this data.

fingerprint -> The fingerprint of public key corresponding to the private key that was used to generate the signature. As keys rotate, this will allow the signature verifier to know what key to use to verify the signature.

signature -> singnature of the data field.

data -> Contents specified by parent container. Usually contains a serialized protobuf.

Field Type Label Description
data bytes

Top

bosdyn/api/mission/mission.proto

AnswerQuestionRequest

Answer one of the outstanding questions.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
question_id int64 Identifier of the question being answered.
code int64 The answer_code from the Question corresponding to the user's choice.
custom_params bosdyn.api.DictParam The answers for the Question corresponding to custom_params specification from the Question.

AnswerQuestionResponse

Response from the server after a client has answered one of its questions.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status AnswerQuestionResponse.Status The result of the AnswerQuestionRequest.
custom_param_error bosdyn.api.CustomParamError Filled out if status is STATUS_CUSTOM_PARAMS_ERROR.

FailedNode

General message describing a node that has failed, for example as part of a PlayMission or LoadMission RPC.

Field Type Label Description
name string Human-readable name of this node, e.g. "Goto waypoint 1", or "Power On".
error string The reason why this node failed. May not be provided by all nodes.
impl_typename string The type of node, e.g. "bosdyn.api.mission.Sequence". May not be provided by all nodes.

GetInfoRequest

Request mission information. This covers information that stays static until a new mission is loaded.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetInfoResponse

Provides the currently loaded mission’s information.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
mission_info MissionInfo Description of the loaded mission's structure.
Unset if no mission has been successfully loaded.

GetMissionRequest

For requesting the mission as it was loaded in LoadMission.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetMissionResponse

Responding with the mission as it was loaded in LoadMission.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
root Node Root node of the mission loaded.
Unset if no mission has been loaded.
id int64 Mission ID as reported in MissionInfo. -1 if no mission has been loaded.

GetStateRequest

Get the state of the mission.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
history_upper_tick_bound google.protobuf.Int64Value Upper bound on the node state to retrieve, inclusive. Leave unset for the latest data.
history_lower_tick_bound int64 Tick counter for the lower bound of per-node state to retrieve.
history_past_ticks int64 Number of ticks to look into the past from the upper bound.

GetStateResponse

Response to a GetStateRequest.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
state State The requested mission state.

LoadMissionRequest

The LoadMission request specifies a root node for the mission that should be used.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
root Node Root node of the mission to load.
leases bosdyn.api.Lease repeated Leases that will be needed to validate the mission.

LoadMissionResponse

The LoadMission response returns the mission info generated by the service if successfully loaded, and a status and other inforamtion if the request fails.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status LoadMissionResponse.Status Result of loading the mission.
lease_use_results bosdyn.api.LeaseUseResult repeated Results from any leases that may have been used.
As part of mission validation, some of the non-mission leases may have been used.
mission_info MissionInfo Provides the structure of the mission. Set when loading succeeds.
failed_nodes FailedNode repeated If certain nodes failed compilation or validation, they will be reported back in this field.

MissionInfo

Static information about the mission. Used to interpret the mission state.

Field Type Label Description
id int64 Mission ID assigned by the server.
root NodeInfo The root node of the mission.

NodeInfo

Provides children and metadata of a single node within the mission.

Field Type Label Description
id int64 Unique to each node within the LOADED mission.
Not guaranteed to be consistent between loads of the same mission.
Used to identify the nodes in the State message.
name string Human-readable name of this node, e.g. "Goto waypoint 1", or "Power On".
user_data UserData Any UserData that was associated with this node.
children NodeInfo repeated Info on all children of this node, if any are present.

PauseMissionRequest

The PauseMission request message will pause the mission that is currently executing, if there is one.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease Lease on the mission service.

PauseMissionResponse

The PauseMission response message will return the status of the request.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status PauseMissionResponse.Status Result of the pause request.
lease_use_result bosdyn.api.LeaseUseResult Result of the lease in the pause request.

PlayMissionRequest

A request to play the currently loaded mission for a fixed amount of time.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
pause_time google.protobuf.Timestamp Run the mission until this time.
Pause the mission at that time if we have not received a new PlayMissionRequest.
This ensures the mission stops relatively quickly if there is an unexpected client drop-out.
Clients should regularly send PlayMissionRequests with a pause_time that reflects how often
they expect to check in with the mission service.
leases bosdyn.api.Lease repeated Leases that the mission will need, plus the lease on the mission service.
settings PlaySettings Settings active until the next PlayMission or RestartMission request.

PlayMissionResponse

The PlayMission response message will return the status of the play mission request.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status PlayMissionResponse.Status The result of the play request.
lease_use_results bosdyn.api.LeaseUseResult repeated Results from any leases that may have been provided with the play request.

PlaySettings

“Global” settings to use while a mission is running. Some of these settings are not globally applicable. For example, the velocity_limit does not change the speed at which the robot poses the body.

Field Type Label Description
velocity_limit bosdyn.api.SE2VelocityLimit Velocity limits on the robot motion. Example use: limit velocity in "navigate to" nodes.
disable_directed_exploration bool Disable directed exploration to bypass blocked path sections
disable_alternate_route_finding bool Disable alternate-route-finding; overrides the per-edge setting in the map.
path_following_mode bosdyn.api.graph_nav.Edge.Annotations.PathFollowingMode Specifies whether to use default or strict path following mode.
ground_clutter_mode bosdyn.api.graph_nav.Edge.Annotations.GroundClutterAvoidanceMode Specify whether or not to enable ground clutter avoidance, and which type.

Question

A question posed by a Prompt node, or by the internal operation of another node.

Field Type Label Description
id int64 Identifier of this question, unique across all missions executing on a single host.
source string What's asking the question. Should be unique in the active mission.
text string The text of the question itself.
options Prompt.Option repeated Options to choose from.
Uses the submessage from the "prompt" node message.
custom_params bosdyn.api.DictParam.Spec Custom parameter specification for the answer expected for this question.
for_autonomous_processing bool Set to true if this question was meant to be answered by some automated system, not a
human. Clients should usually avoid generating a UI element to ask such a question.
severity bosdyn.api.AlertData.SeverityLevel Severity for this question. See comment in Prompt message in nodes.proto for a better understanding
of what levels mean.

RestartMissionRequest

A request to restart the currently loaded mission.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
pause_time google.protobuf.Timestamp Run the mission until this time.
Pause the mission at that time if we have not received a new PlayMissionRequest.
This ensures the mission stops relatively quickly if there is an unexpected client drop-out.
Clients should regularly send PlayMissionRequests with a pause_time that reflects how often
they expect to check in with the mission service.
leases bosdyn.api.Lease repeated Leases that the mission will need, plus the lease on the mission service.
settings PlaySettings Settings active until the next PlayMission or RestartMission request.

RestartMissionResponse

The RestartMission response includes the status and any failed nodes for the request.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status RestartMissionResponse.Status The result of the restart request.
lease_use_results bosdyn.api.LeaseUseResult repeated Results from any leases that may have been used.
As part of mission validation, some of the non-mission leases may have been used.
failed_nodes FailedNode repeated If certain nodes failed validation, they will be reported back in this field.

State

State of the mission service.

Field Type Label Description
questions Question repeated What questions are outstanding?
answered_questions State.AnsweredQuestion repeated History of questions that have been answered.
The server will set some limit on the available history.
history State.NodeStatesAtTick repeated Node states ordered from newest to oldest.
history[0] will always be the data from this tick.
status State.Status Current status of the mission.
error string Describes the unexpected error encountered by the mission service.
Only filled out if STATUS_ERROR is set.
tick_counter int64 The mission's tick counter when this state was generated.
-1 indicates no mission has been started.
mission_id int64 The mission's ID.
-1 indicates no mission has been loaded.

State.AnsweredQuestion

A question that has been answered already.

Field Type Label Description
question Question The question that this state information is related to.
accepted_answer_code int64 The code corresponding to the option answered for this prompt.
custom_params bosdyn.api.DictParam Custom parameter values answered for this prompt.

State.NodeStatesAtTick

Field Type Label Description
tick_counter int64 The tick counter when this state was produced.
tick_start_timestamp google.protobuf.Timestamp Time at which this tick started, in host time basis.
node_states State.NodeStatesAtTick.NodeState repeated At this tick, the state of every node that was ticked, in the order they were ticked.

State.NodeStatesAtTick.NodeState

Field Type Label Description
result Result The result of this node's tick.
error string May be set when the 'result' is RESULT_FAILURE or RESULT_ERROR, this describes why
the node failed. Not all nodes will have an error explaining why they failed.
id int64 ID from NodeInfo.
blackboard State.NodeStatesAtTick.NodeState.BlackboardState Nodes can write and read from the blackboard. Every node has a scoped blackboard.

State.NodeStatesAtTick.NodeState.BlackboardState

Field Type Label Description
variables KeyValue repeated

StopMissionRequest

The StopMission request message will fully stop the mission.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease Lease on the mission service.

StopMissionResponse

The StopMission response message will return the status of the request.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status StopMissionResponse.Status Result of the stop request.
lease_use_result bosdyn.api.LeaseUseResult Result of the lease in the stop request.

AnswerQuestionResponse.Status

Possible results for answering a question.

Name Number Description
STATUS_UNKNOWN 0 Invalid; do not use.
STATUS_OK 1 Answer accepted.
STATUS_INVALID_QUESTION_ID 2 Question ID is not valid / unknown by the mission service.
STATUS_INVALID_CODE 3 Answer code is not applicable for the question indicated.
STATUS_ALREADY_ANSWERED 4 Question was already answered.
STATUS_CUSTOM_PARAMS_ERROR 5 One or more keys or values in custom_params are unsupported by the question.
See the custom_param_error for details.
STATUS_INCOMPATIBLE_ANSWER 6 Answer format is not applicable for the question indicated.

LoadMissionResponse.Status

Possible results of loading a mission.

Name Number Description
STATUS_UNKNOWN 0 Invalid status, do not use.
STATUS_OK 1 The mission was loaded successfully.
STATUS_COMPILE_ERROR 2 Load-time compilation failed. The mission was malformed.
STATUS_VALIDATE_ERROR 3 Load-time validation failed. Some part of the mission was unable to initialize.

PauseMissionResponse.Status

Possible results of a pause request.

Name Number Description
STATUS_UNKNOWN 0 Invalid status, do not use.
STATUS_OK 1 Mission is paused or finished running.
STATUS_NO_MISSION_PLAYING 2 No mission has started playing.
NOT returned when two PauseMissionRequests are received back-to-back. In that case,
you will get STATUS_OK.

PlayMissionResponse.Status

Possible results for a play request.

Name Number Description
STATUS_UNKNOWN 0 Invalid status, do not use.
STATUS_OK 1 Mission is playing, or the mission has already completed.
Use GetStateResponse to tell the difference.
STATUS_NO_MISSION 2 Call LoadMission first.

RestartMissionResponse.Status

Possible results of requesting a restart.

Name Number Description
STATUS_UNKNOWN 0 Invalid status, do not use.
STATUS_OK 1 Mission has restarted.
STATUS_NO_MISSION 2 Call LoadMission first.
STATUS_VALIDATE_ERROR 3 Validation failed.

State.Status

Possible overall status states of the mission.

Name Number Description
STATUS_UNKNOWN 0 Invalid status, do not use.
STATUS_FAILURE 1 The mission has failed due to a node failure.
STATUS_RUNNING 2 The mission is still running.
STATUS_SUCCESS 3 The mission succeeded!
STATUS_PAUSED 4 Execution has been paused.
STATUS_ERROR 5 The mission service itself or the behavior tree encountered an unexpected error, outside
of a node failing.
STATUS_NONE 6 No mission has been loaded.
STATUS_STOPPED 7 The mission was stopped before completion.

StopMissionResponse.Status

Possible results of a stop request.

Name Number Description
STATUS_UNKNOWN 0 Invalid status, do not use.
STATUS_OK 1 Mission is stopped/complete.
The mission state may be in any of the "complete states", e.g. if the mission completed
successfully before this RPC took effect, the mission will report STATUS_SUCCESS and not
STATUS_STOPPED.
STATUS_NO_MISSION_PLAYING 2 No mission has started playing.
NOT returned if the mission is already stopped. In that case, you will get STATUS_OK.

Top

bosdyn/api/mission/mission_service.proto

MissionService

The MissionService can be used to specify high level autonomous behaviors for Spot using behavior trees.

Method Name Request Type Response Type Description
LoadMission LoadMissionRequest LoadMissionResponse RPCs for loading missions to the robot. NOTE: LoadMission and LoadMissionAsChunks may fail
for large missions because the request and response may exceed the maximum message size. Use
LoadMissionAsChunks2 instead.
LoadMissionAsChunks .bosdyn.api.DataChunk stream LoadMissionResponse This RPC may be deprecated in the future, please use LoadMissionAsChunks2 instead. Non-preferred
method for loading large missions to the robot because only the request is a streaming RPC. The data
chunks are deserialized into a LoadMissionRequest. NOTE: LoadMissionAsChunks may fail for large missions
because the response may exceed the maximum message size.
LoadMissionAsChunks2 .bosdyn.api.DataChunk stream .bosdyn.api.DataChunk stream Preferred RPC for loading large missions to the robot because both the request and response
are streaming RPCs, allowing you to break the message up into multiple streamed messages. The
data chunks are deserialized into a LoadMissionRequest and LoadMissionResponse.
PlayMission PlayMissionRequest PlayMissionResponse Start executing a loaded mission.
Will not restart a mission that has run to completion. Use RestartMission to do that.
PauseMission PauseMissionRequest PauseMissionResponse Pause mission execution.
StopMission StopMissionRequest StopMissionResponse Stop a running mission.
Must use RestartMission, not PlayMission, to begin from the beginning.
RestartMission RestartMissionRequest RestartMissionResponse Start executing a loaded mission from the beginning.
Does not need to be called after LoadMission.
GetState GetStateRequest GetStateResponse Get the state of the mission.
GetInfo GetInfoRequest GetInfoResponse RPCs for getting static information regarding the mission. Used to interpret mission state.
NOTE: GetInfo may fail for large missions because the response may exceed the maximum message size.
Use GetInfoAsChunks instead.
GetInfoAsChunks GetInfoRequest .bosdyn.api.DataChunk stream Preferred RPC for getting the status of large missions from the robot because the response is a streaming
streaming RPC, allowing you to break the message up into multiple streamed messages. THe data chunks are
deserialized into a GetInfoResponse.
GetMission GetMissionRequest GetMissionResponse Download the mission as it was uploaded to the service.
GetMissionAsChunks GetMissionRequest .bosdyn.api.DataChunk stream Alternative method to download large missions that allows you to break
the mission up into multiple streamed requests. Each data chunk message should be
deserialized as a GetMissionResponse protobuf message.
AnswerQuestion AnswerQuestionRequest AnswerQuestionResponse Specify an answer to the question asked by the mission.

Top

bosdyn/api/mission/nodes.proto

BosdynDockState

Get the state of the docking service from the robot.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
child Node Child node. Children will have access to the state gathered by this node.
state_name string Name of the bosdyn.api.DockState object in the blackboard. For example, if this is set to
"power_status", children can look up "power_status" in the blackboard.

BosdynGraphNavLocalize

Tell GraphNav to re-localize the robot using a SetLocalizationRequest. This overrides whatever the current localization is. This can be useful to reinitialize the system at a known state.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
localization_request bosdyn.api.graph_nav.SetLocalizationRequest If no localization_request is provided, the default options used
are FIDUCIAL_INIT_NEAREST (the system will initialize to the nearest fiducial).
Otherwise, the options inside the set_localization_request will be used.
Note that ko_tform_body in the request will be ignored (it will be recalculated at runtime).
allow_bad_quality bool If true, a poor quality check will not result in the node returning FAILURE.
If false, the localization will be checked for quality by comparing agains the map data, and
if the localization is poor quality, the node returns FAILURE.
response_bb_key string If non-empty, the blackboard variable with this name will contain the response of the
graph nav SetLocalization request after this node receives it.

BosdynGraphNavState

Get GraphNav state from the robot and save it to the blackboard.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
child Node Child node. Children will have access to the state gathered by this node.
state_name string Name of the bosdyn.api.GetLocalizationStateResponse object in the blackboard. For example,
if this is set to "nav", children can look up "nav.localization.waypoint_id" in the
blackboard to get the waypoint the robot is localized to.
waypoint_id string Id of the waypoint that we want the localization to be relative to.
If this is empty, the localization will be relative to the waypoint that the
robot is currently localized to.

BosdynGripperCameraParamsState

Get the state of the gripper camera params from the robot.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
child Node Child node. Children will have access to the state gathered by this node.
state_name string Name of the bosdyn.api.GripperCameraParams object in the blackboard. For example, if this is
set to "gripper_params", children can look up "gripper_params.camera_mode" in the blackboard.

BosdynNavigateRoute

Tell the robot to navigate a route.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
route bosdyn.api.graph_nav.Route A route for the robot to follow.
route_follow_params bosdyn.api.graph_nav.RouteFollowingParams What should the robot do if it is not at the expected point in the route, or the route is
blocked.
travel_params bosdyn.api.graph_nav.TravelParams Parameters that define how to traverse and end the route.
navigation_feedback_response_blackboard_key string If provided, this will write the last NavigationFeedbackResponse message
to a blackboard variable with this name.
navigate_route_response_blackboard_key string If provided, this will write the last NavigateRouteResponse message to
a blackboard variable with this name.

BosdynNavigateTo

Tell the robot to navigate to a waypoint.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
destination_waypoint_id string ID of the waypoint to go to.
route_gen_params bosdyn.api.graph_nav.RouteGenParams Preferences on how to pick the route.
travel_params bosdyn.api.graph_nav.TravelParams Parameters that define how to traverse and end the route.
navigation_feedback_response_blackboard_key string If provided, this will write the last NavigationFeedbackResponse message
to a blackboard variable with this name.
navigate_to_response_blackboard_key string If provided, this will write the last NavigateToResponse message to
a blackboard variable with this name.
route_blocked_behavior bosdyn.api.graph_nav.RouteFollowingParams.RouteBlockedBehavior Defines robot behavior when route is blocked. Defaults to reroute when route is blocked.

BosdynPowerRequest

Make a robot power request

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
request bosdyn.api.PowerCommandRequest.Request The request to make. See the PowerCommandRequest documentation for details.

BosdynRecordEvent

Record an APIEvent

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
event bosdyn.api.Event The event to be logged. Note that everything should be populated except the id, start_time
and end_time. The start and end time will be populated by the mission, using the node's start
time. The id field shouldn't be set when the start and end times are the same.
succeed_early bool If set to false, this node will wait for the RecordEvents rpc to complete. If set to true,
this node will send the RecordEventsRequest, and then return SUCCESS without waiting for
the RecordEventsResponse.
additional_parameters BosdynRecordEvent.AdditionalParametersEntry repeated In addition to the parameters specified in the event field, this field can be used
to specify events only known at runtime. Map key will be parameter label, map value will be
evaluated then packed into parameter value.

BosdynRecordEvent.AdditionalParametersEntry

Field Type Label Description
key string
value Value

BosdynRobotCommand

Execute a RobotCommand. These nodes will “succeed” once a feedback response is received indicating success. Any commands that require an “end time” will have that information set based on the end time of the mission.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the directory is running on.
command bosdyn.api.RobotCommand The command to execute. See the RobotCommand documentation for details.

BosdynRobotState

Get state from the robot.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
child Node Child node. Children will have access to the state gathered by this node.
state_name string Name of the bosdyn.api.RobotState object in the blackboard. For example, if this is set to
"robot", children can look up "robot.power_state.motor_power_state" in the blackboard.

ClearBehaviorFaults

This node will:

  1. Check if there are behavior faults. If there are none, it will return success.

  2. Check if all behavior faults are clearable. If not, it will return failure.

  3. Try to clear the clearable behavior faults. If it cannot, it will return failure.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
robot_state_blackboard_name string Name of a robot state message defined in the blackboard.
Usually provided by embedding this node in a [BosdynRobotState] node.
cleared_cause_fall_blackboard_name string Optional blackboard variable name. If specified, this node will write the number of
cleared behavior faults that had CAUSE_FALL.
cleared_cause_hardware_blackboard_name string Optional blackboard variable name. If specified, this node will write the number of
cleared behavior faults that had CAUSE_HARDWARE.
cleared_cause_lease_timeout_blackboard_name string Optional blackboard variable name. If specified, this node will write the number of
cleared behavior faults that had CAUSE_LEASE_TIMEOUT.

Condition

Checks a simple comparison statement.

Field Type Label Description
lhs Condition.Operand Left-hand side of the comparison.
rhs Condition.Operand Right-hand side of the comparison.
operation Condition.Compare Comparison operator to compare lhs and rhs.
handle_staleness Condition.HandleStaleness

Condition.Operand

Options for where to retrieve values from.

Field Type Label Description
var VariableDeclaration Reference an existing variable.
const ConstantValue Use a constant value.

ConstantResult

Just returns a constant when calling tick().

Field Type Label Description
result Result This result is always returned when calling tick().

DataAcquisition

Trigger the acquisition and storage of data.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the data acquisition service is registered with.
request bosdyn.api.AcquireDataRequest Specification of the data and metadata to store.
completion_behavior DataAcquisition.CompletionBehavior
group_name_format string Define a format string that will be used together with the blackboard to generate
a group_name. If a value is specified in this field, it will override the group_name value
specified in the CaptureActionId of the AcquireDataRequest. Values from the blackboard will
replace the keys in braces {}.
Example: "telop-{date}", where "date" is a blackboard variable.
Example: "{date}loop{loop_counter}", where "loop_counter" is a blackboard variable from a
Repeat node.
request_name_in_blackboard string If populated, name of the variable in the blackboard in which to store the AcquireDataRequest
after it's created, and sent to the Data Acquisition service.
metadata_name_in_blackboard string The name of the metadata object in the blackboard to be stored.
The metadata object can be any protobuf message.
The metadata will be merged with the AcquireDataRequest's metadata field.
action_name_format string Define a format string that will be used together with the blackboard to generate
an action_name. If a value is specified in this field, it will override the action_name
value specified in the CaptureActionId of the AcquireDataRequest. Values from the blackboard
will replace the keys in braces {}.
Example: "element 0 attempt {loop_counter}", where "loop_counter" is a blackboard variable
from a Retry.
disable_cancel_on_pause_or_stop bool If set to false (default), this node will cancel an outgoing AcquireDataRequest when the node
is paused / stopped. When the node is resumed, it will restart the AcquireDataRequest.

If set to true, this node will NOT cancel outgoing AcquireDataRequest's when the node is
paused / stopped. When the node is resumed, it will check feedback on the original outgoing
AcquireDataReqeust.
format_metadata bool If true, metadata string values may contain formatted blackboard variables.
Please see the documentation in FormatBlackboard for more information about supported string
formats.

DataAcquisitionOnInterruption

Send an AcquireDataRequest to the data acquisition service when the mission is interrupted. Interuptions are anything that causes the mission to stop ticking automatically.

Field Type Label Description
child Node Child to run when node starts. If mission is interrupted while the child is still running,
the mission service will send an AcquireDataRequest to the data acquisition service. The
child will resume when the mission resumes. The DataAcquisitionOnInterruption node will
always return the status of this child node.
request_when_interrupted DataAcquisition Data acquisition request that will be sent if the mission is interrupted.
This is not an actual node. It will only be used for the data acquisition request details.
The completion_behavior, request_name_in_blackboard, metadata_name_in_blackboard, and
format_metadata fields will not be used.
pause_mission_metadata bosdyn.api.Metadata Interruption reason: PauseMission RPC called.
restart_mission_metadata bosdyn.api.Metadata Interruption reason: RestartMission RPC called.
load_mission_metadata bosdyn.api.Metadata Interruption reason: LoadMission RPC called.
stop_mission_metadata bosdyn.api.Metadata Interruption reason: StopMission RPC called.
lease_use_error_metadata bosdyn.api.Metadata Interruption reason: Lease use error occured.
play_mission_timeout_metadata bosdyn.api.Metadata Interruption reason: Play mission timeout exceeded.
child_node_error_metadata bosdyn.api.Metadata Interruption reason: Child node returned an error result.
child_node_exception_metadata bosdyn.api.Metadata Interruption reason: Child node threw an exception.
default_metadata bosdyn.api.Metadata This is used if any of the above are empty or if an unexpected interruption occurs.
keys_for_lease_use_error_message string repeated If key(s) are specified, the additional information about the lease use error will be stored
in the AcquireDataRequest metadata. All given key(s) must be used in order to access the
error message reason from the JSON metadata. The last key holds error message.

DateToBlackboard

Record a datetime string into the blackboard. Writes the date according to ISO8601 format.

Field Type Label Description
key string The key of the variable that will be written.

DefineBlackboard

Defines new blackboard variables within the scope of the child. Shadows blackboard variables in the parent scope.

Field Type Label Description
blackboard_variables KeyValue repeated The list of variables that should be defined for this subtree,
with initial values.
child Node The blackboard variables will only persist in the subtree defined by this
child node. The child's tick() will be called on the child until it
returns either SUCCESS or FAILURE.

Dock

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the docking service is registered with.
docking_station_id uint32 ID of docking station to dock at.
child Node Deprecated. Optional child node. Children will have access to the status variables gathered by this node.
If specified, child node will determine success/failure of this node.

DEPRECATED as of 3.0.0. Use docking_command_response_blackboard_key and
docking_command_feedback_response_blackboard_key instead.
command_status_name string Deprecated. Name of the command status variable in the blackboard. This is the status of the docking
command request made to the robot. Please refer to
bosdyn.api.docking.DockingCommandResponse.Status for more details. Children can use this
name to look up docking command status in the blackboard. If no name is provided, status will
not be available.

DEPRECATED as of 3.0.0. Use docking_command_response_blackboard_key and
docking_command_feedback_response_blackboard_key instead.
feedback_status_name string Deprecated. Name of the feedback status variable in the blackboard. This is the feedback provided while
docking is in progress. Please refer to
bosdyn.api.docking.DockingCommandFeedbackResponse.Status for a list of possible status
values. Children can use this name to look up docking status in the blackboard. If no name
is provided, status will not be available.

DEPRECATED as of 3.0.0. Use docking_command_response_blackboard_key and
docking_command_feedback_response_blackboard_key instead.
prep_pose_behavior bosdyn.api.docking.PrepPoseBehavior Defines how we use the "pre-docking" behavior.
docking_command_feedback_response_blackboard_key string If provided, this will write the last DockingCommandFeedbackResponse message
to a blackboard variable with this name.
docking_command_response_blackboard_key string If provided, this will write the last DockingCommandResponse message to
a blackboard variable with this name.
require_fiducial bool Require the detection of the dock's fiducial

ExecuteChoreography

Sends a request to play a choreography sequence with the given name, and then monitors the state of the dancing robot.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
sequence_name string The name of the sequence to play.

ForDuration

Run this child for a maximum amount of mission execution time. Will exit with child’s status if the child finishes early, FAILURE if the child remains in RUNNING state for too long and no timeout_child is specified, or the status of the timeout_child.

Field Type Label Description
duration google.protobuf.Duration Maximum duration of mission execution time.
child Node Child to execute for the duration.
time_remaining_name string Optional blackboard variable name. If specified, this node will define a blackboard
variable that its child has access to, and write the number of seconds remaining as
a double to the blackboard under this name.
timeout_child Node Optional node that will run if the child times out. If not specified, this node
will return FAILURE when the child times out. If specified, and the
child times out, this node will return the status of the timeout_child.
The timeout_child does not respect the original timeout.

FormatBlackboard

Sets a blackboard variable to a formatted string, reading from other blackboard vars.

Field Type Label Description
key string The key of the variable that will be written.
format string Define a format string that will be used together with the blackboard to generate
string value. Values from the blackboard will replace the keys in braces {}, i.e.
{blackboard_variable_name}. We also allow some string formatting options, namely:

1) Floating point decimal places: {float_variable:.2f}
2) TBD

Select examples:

Format String: "telop-{date}"
Blackboard: "date" is a blackboard variable with string value: "2021-05-13"
Output: "teleop-2021-05-13"

Format String: "{date}loop{loop_counter}"
Blackboard: "date" is a blackboard variable with string value: "2021-05-13"
Blackboard: "loop_counter" is a blackboard variable with integer value: "3"
Output: "2021-05-13_loop_3"

Format String: "battery charge is: {state.power_state.locomotion_charge_percentage.value}"
Blackboard: "state" is a protobuf message in the blackboard from a BosdynRobotState, and
the power_state submessage has a charge percentage of 30.2148320923085
Output: "battery charge is: 30.2158320923085"

Format String: "battery charge is:
{state.power_state.locomotion_charge_percentage.value:.2f}"
Blackboard: "state" is a protobuf message in the blackboard from a BosdynRobotState, and
the power_state submessage has a charge percentage of 30.2148320923085
Output: "battery charge is: 30.21"

Format String: "the value is {x:.0f}"
Blackboard: "x" is a blackboard variable with float value: "2.71828"
Output: "the value is 3"

MissionUploadChoreography

Uploads the given set of animations and choreography sequences to the robot.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine the service is running on.
choreography_sequences bosdyn.api.spot.ChoreographySequence repeated Choreography sequences to be loaded (required by the mission).
animated_moves bosdyn.api.spot.Animation repeated Any animations we need to load if we want to play the sequences.

Node

Wrapper for a mission node. Contains the basics common to all mission nodes. Specifics of what the node does are contained in the “impl” field.

Field Type Label Description
name string Human-readable name of this node, e.g. "Goto waypoint 1", or "Power On".
user_data UserData Collection of user data associated with this node.
reference_id string Reference identifier of this node.
Set iff another node references this one.
impl google.protobuf.Any Deprecated. DEPRECATED as of 4.0.
Implementation of this node. For example, this may be a Sequence.
node_reference string Unique identifier of another node. If this is filled out, rather than the "impl", then
the referenced node will be used in place of this one.
condition Condition
sequence Sequence
selector Selector
repeat Repeat
retain_lease RetainLease
retry Retry
for_duration ForDuration
bosdyn_dock_state BosdynDockState
bosdyn_power_request BosdynPowerRequest
bosdyn_robot_state BosdynRobotState
bosdyn_robot_command BosdynRobotCommand
remote_grpc RemoteGrpc
sleep Sleep
prompt Prompt
set_blackboard SetBlackboard
date_to_blackboard DateToBlackboard
define_blackboard DefineBlackboard
format_blackboard FormatBlackboard
constant_result ConstantResult
bosdyn_navigate_route BosdynNavigateRoute
bosdyn_navigate_to BosdynNavigateTo
bosdyn_graph_nav_state BosdynGraphNavState
bosdyn_graph_nav_localize BosdynGraphNavLocalize
bosdyn_record_event BosdynRecordEvent
simple_parallel SimpleParallel
spot_cam_ptz SpotCamPtz
spot_cam_store_media SpotCamStoreMedia
spot_cam_led SpotCamLed
spot_cam_focus_state SpotCamFocusState
spot_cam_reset_autofocus SpotCamResetAutofocus
store_metadata StoreMetadata
switch Switch
data_acquisition DataAcquisition
data_acquisition_on_interruption DataAcquisitionOnInterruption
dock Dock
restart_when_paused RestartWhenPaused
clear_behavior_faults ClearBehaviorFaults
bosdyn_gripper_camera_params_state BosdynGripperCameraParamsState
set_gripper_camera_params SetGripperCameraParams
parallel_and ParallelAnd
set_grasp_override SetGraspOverride
execute_choreography ExecuteChoreography
mission_upload_choreography MissionUploadChoreography
parameter_values KeyValue repeated Defines parameters, used by this node or its children.
The "key" in KeyValue is the name of the parameter being defined.
The value can be a constant or another parameter value.
overrides KeyValue repeated Overwrites a protobuf field in this node's implementation.
The "key" in KeyValue is the name of the field to override.
The value to write can be sourced from a constant, or a parameter value.
parameters VariableDeclaration repeated Declares parameters needed at compile time by this node, or children of this node.
This is a way for a node to communicate what parameters its implementation and/or children
require, without unpacking the entire subtree.

ParallelAnd

Run many child nodes together, returning only after they have all completed or an early exit is triggered.

Field Type Label Description
children Node repeated
finish_every_node bool Boolean to finish every child node. If this is false, if one of the nodes fails, the whole
ParallelAnd will stop & return the failure immediately.
If this is true, if one of the nodes fails, the ParallelAnd will continue to run until all
the children have exited, then report the failure.
If a node raises an error, the error will always be reported immediately.
Default false.

Prompt

Prompt the world at large to answer a question. This node represents a request for information from ANY listeners that may be out there.

Field Type Label Description
always_reprompt bool Should we always re-prompt when this node is started?
If false, this node will only ever prompt if it is started and its question is unanswered.
This may be used, for example, to ask the user to check the robot after any self-right.
If true, this node will prompt whenever it is started.
This may be used, for example, to tell the user to perform some one-time action, like open a
door for the robot.
text string The text of the question itself. The question text may contain formatted blackboard
variables. Please see the documentation in FormatBlackboard for more information
about supported string formats.
source string Metadata describing the source of the question.
The answer will be written into the state blackboard with this as the variable name.
options Prompt.Option repeated Deprecated. The set of options that can be chosen for this prompt.
options_list Prompt.OptionsList The set of options that can be chosen for this prompt.
custom_params bosdyn.api.DictParam.Spec Custom parameter specification for the answer expected for this prompt.
child Node Child node, run after the prompt has been responded to.
Children will have access to the answer code provided by the response.
for_autonomous_processing bool Hint that Question posed by this Prompt is meant to be answered by some automated system.
See the Question message for details.
severity bosdyn.api.AlertData.SeverityLevel Severity for this prompt. Used to determine what sort of alerting
this prompt will trigger.
Here are guidelines for severity as it pertains to missions:
INFO: Normal operation. For example, waiting for charge; waiting on the dock for logs to
download. WARN: Something went wrong, but the mission will try to recover autonomously.
ERROR: Something went wrong, and the mission can't recover without human intervention.
Intervention is not time sensitive and can be resolved when convenient.
CRITICAL: Something went wrong, and the mission can't recover without human intervention.
Human needs to rescue the robot before battery runs out because it's not charging.
question_name_in_blackboard string If specified, this node will write its current question (bosdyn.api.mission.Question proto)
to the blackboard while it is being ticked.

Prompt.Option

Data about the options to choose from.

Field Type Label Description
text string Text associated with this option. Should be displayed to the user.
answer_code int64 Numeric code corresponding to this option. Passed as part of the answer.

Prompt.OptionsList

Field Type Label Description
options Prompt.Option repeated

RemoteGrpc

Call out to another system using the RemoteMission service.

Field Type Label Description
host string Host that is running the directory server. Usually, this is just the robot.
service_name string Name of the service in the directory.
timeout float Timeout of any single RPC. If the timeout is exceeded, the RPC will fail. The mission service
treats each failed RPC differently:
- EstablishSession: An error is returned in LoadMission.
- Tick: The RPC is retried.
- Stop: The error is ignored, and the RPC is not retried.
Omit for a default of 60 seconds.
lease_resources string repeated Resources that we will need leases on.
inputs KeyValue repeated The list of variables the remote host should receive.
Variables given can be available at either run-time or compile-time.
The "key" in KeyValue is the name of the variable as used by the remote system.
group_name_format string Define a format string that will be used together with the blackboard to generate
a group_name. If a value is specified in this field, it will override the group_name value
specified in the group_name of the TickRequest. Values from the blackboard will
replace the keys in braces {}.
Example: "telop-{date}", where "date" is a blackboard variable.
Example: "{date}loop{loop_counter}", where "loop_counter" is a blackboard variable from a
Repeat node.
params bosdyn.api.DictParam Should match the advertised spec for the RemoteMissionService in question.

Repeat

Repeat a child node.

Field Type Label Description
max_starts int32 Start the child node exactly this many times.
Note that a value of 1 makes the Repeat node a no-op.
child Node Child to repeat max_starts times.
start_counter_state_name string If set, the node will write the start index to the blackboard.
respect_child_failure bool If set to false, this repeat node will keep running its child regardless of whether
or not the child succeeds or fails.
If set to true, this repeat node will only keep running its child when the child
succeeds. If the child fails, the repeat node will fail.

RestartWhenPaused

This node will run and return the status of the child node. If the mission is paused while this node is executing, the child will be restarted when the mission is resumed.

Field Type Label Description
child Node

RetainLease

Send RetainLease for every Lease the mission service is given via PlayMissionRequest. Returns RUNNING while there are more leases to retain, SUCCESS once a lease for each resource has been retained, and FAILURE if any one lease cannot be retained.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the lease service is registered with.

Retry

Retry a child node until it succeeds, or exceeds a number of attempts.

Field Type Label Description
max_attempts int32 Only allow this many attempts. Note that a value of 1 makes this Retry node a no-op.
child Node Child to retry up to max_attempts.
attempt_counter_state_name string If set, the node will write the attempt index to the blackboard.

Selector

Run all children in order until a child succeeds.

Field Type Label Description
always_restart bool Forces the execution to always begin with the first child. If false, and
the Selector ran last tick, it will continue with the node it was ticking.
children Node repeated List of all children to iterate through.

Sequence

Run all children in order until a child fails.

Field Type Label Description
always_restart bool Forces the execution to always begin with the first child. If false, and
the Sequence ran last tick, it will continue with the node it was ticking.
children Node repeated List of all children to iterate through.

SetBlackboard

Sets existing blackboard variables within this scope to specific values, returning SUCCESS.

Field Type Label Description
blackboard_variables KeyValue repeated The key of the KeyValue is the name of the blackboard variable.
The value will be dereferenced and converted into a value type at runtime
inside this node's tick function. For example, if the value is a runtime
variable, that variable will be evaluated at tick time, and then stored into
the blackboard. If the value is another blackboard variable, that blackboard
variable's value will be copied into the variable specified by the key.

SetGraspOverride

Set grasp override and carry state override requests

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the gripper camera param service is registered
with.
grasp_override_request bosdyn.api.ApiGraspOverrideRequest

SetGripperCameraParams

Set gripper camera params

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the gripper camera param service is registered
with.
params_in_blackboard_key string
new_params bosdyn.api.GripperCameraParams

SimpleParallel

Run two child nodes together, returning the primary child’s result when it completes.

Field Type Label Description
primary Node Primary node, whose completion will end the execution of SimpleParallel.
The secondary node will be ticked at least once.
secondary Node Secondary node, which will be ticked as long as the primary is still running.
run_secondary_node_once bool By default, if the secondary node finishes before the primary node, the secondary node
will be restarted. If this flag is set to true, and the secondary node completes before
the primary node, it will never be restarted.

Sleep

When started, begins a sleep timer for X seconds. Returns “success” after the timer elapses, “running” otherwise.

Field Type Label Description
seconds float Number of seconds to sleep for.
restart_after_stop bool If this node is stopped, should it restart the timer?

SpotCamFocusState

Set the focus on the Spot CAM PTZ

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the Spot CAM registered with.
focus_state bosdyn.api.spot_cam.PtzFocusState Focus State to set the Spot CAM PTZ to, from SetPtzFocusStateRequest

SpotCamLed

Set the LEDs to a specified brightness

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the Spot CAM registered with.
brightnesses SpotCamLed.BrightnessesEntry repeated Brightnesses of the LEDs, from SetLEDBrightnessRequest

SpotCamLed.BrightnessesEntry

Field Type Label Description
key int32
value float

SpotCamPtz

Point the PTZ to a specified orientation

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the Spot CAM registered with.
ptz_position bosdyn.api.spot_cam.PtzPosition The rest of the fields are from bosdyn.api.spot_cam.ptz.SetPtzPositionRequest, see that
message for details.
adjust_parameters SpotCamPtz.AdjustParameters Setting adjust_parameters will enable auto-adjusting the PTZ pan and tilt at playback time,
based on where the robot is, relative to the waypoint. Leave empty to disable auto-adjust
features.

SpotCamPtz.AdjustParameters

Field Type Label Description
localization_varname string Variable name to retrieve the graph nav state from.
waypoint_id string Waypoint ID where this PTZ configuration was originally set up.
waypoint_tform_body bosdyn.api.SE3Pose Pose of body in waypoint frame at the time this PTZ configuration was originally set up.

SpotCamResetAutofocus

Reset the autofocus on the Spot CAM PTZ

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the Spot CAM registered with.

SpotCamStoreMedia

Store media using the Spot CAM.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the Spot CAM registered with.
camera bosdyn.api.spot_cam.Camera The rest of the fields are from bosdyn.api.spot_cam.logging.StoreRequest, see that message
for details.
type bosdyn.api.spot_cam.Logpoint.RecordType What type of media should be stored from this action.
tag string Extra metadata to store alongside the captured media.

StoreMetadata

Triggers a StoreMetadataRequest to the data acquisition store.

Field Type Label Description
service_name string Name of the service to use.
host string Host machine of the directory server that the data acquisition service is registered with.
acquire_data_request_name string The name of the blackboard variable that holds the associated AcquireDataRequest. The
reference ID that this metadata is associated with will be copied from the request.
metadata_name string The name of the metadata object in the blackboard to be stored.
The metadata object can be any protobuf message.
metadata_json google.protobuf.Struct JSON representation of metadata
metadata_channel string The data buffer channel on which to store the metadata.

Switch

Run a specific child based on a specified pivot_value.

This node exists because of a subtle implmentation detail in Selector(always_restart = true). The astute reader might believe that they can construct a switch node by using a selector with sequences & conditions as children. This is ALMOST true, EXCEPT that a selector (with always_restart = true) can leave multiple children in the running state IF:

  • A later selector child was RUNNING last tick

  • An eariler selector child returns RUNNING this tick

Even though the later selector child won’t be ticked, it will still be left in the running state and not restart when the selector advances to it again later. Sometimes this is desireable, sometimes it isn’t. Switch is constrained to only have one child running, and if the switch ever switches children and return to a previously running child, that child will be restarted.

Field Type Label Description
pivot_value Value Expresses an integer value that decides which child to run.
always_restart bool If false, this node will read the pivot_value once when its starts, and execute
the specified child until it finishes even if the pivot_value changes.

If true, this node will read from the pivot_value every tick, and change
which child it's ticking when an underlying blackboard variable changes.
int_children Switch.IntChildrenEntry repeated List of all children to possibly run.
default_child Node If none of the above cases match, use this child

Switch.IntChildrenEntry

Field Type Label Description
key int32
value Node

Condition.Compare

Comparison operator.

Name Number Description
COMPARE_UNKNOWN 0 Invalid, do not use.
COMPARE_EQ 1 Equal.
COMPARE_NE 2 Not equal.
COMPARE_LT 3 Less than.
COMPARE_GT 4 Greater than.
COMPARE_LE 5 Less than or equal.
COMPARE_GE 6 Greater than or equal.

Condition.HandleStaleness

When comparing runtime values in the blackboard, some values might be “stale” (i.e too old). This defines how the comparator should behave when a read value is stale.

Name Number Description
HANDLE_STALE_UNKNOWN 0 acts like READ_ANYWAY for backwards compatibility.
HANDLE_STALE_READ_ANYWAY 1 ignore how stale this data is.
HANDLE_STALE_RUN_UNTIL_FRESH 2 return the RUNNING status until the data being read is not stale.
HANDLE_STALE_FAIL 3 return FAILURE status if stale data is read.

DataAcquisition.CompletionBehavior

Name Number Description
COMPLETE_UNKNOWN 0
COMPLETE_AFTER_SAVED 1 Node is complete after all data has been saved.
COMPLETE_AFTER_ACQUIRED 2 Node is complete after all data is acquired, but before processing and storage.
This allows the robot to continue on with the mission sooner, but
it will be unaware of failures in processing or storage.

Top

bosdyn/api/mission/remote.proto

EstablishSessionRequest

Information to initialize a session to the remote service for a particular mission node.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
leases bosdyn.api.Lease repeated All leases that the remote service may need.
inputs VariableDeclaration repeated Deprecated. Use this to provide other data (e.g. from the blackboard).
The RemoteGrpc node will provide the name of the node automatically.
DEPRECATED as of 3.3. Please use 'params' in [TickRequest] instead.

EstablishSessionResponse

Provide the id to use for the particular mission node to tick this remote service.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status EstablishSessionResponse.Status Result of this establish session request.
session_id string On success, contains an ID for this session.
missing_lease_resources string repeated Need to provide leases on these resources.
lease_use_results bosdyn.api.LeaseUseResult repeated Details about how any leases were used.
Allowed to be empty, if leases were not actually used.
missing_inputs VariableDeclaration repeated Deprecated. The inputs required by the contacted node that were not mentioned in the request.
DEPRECATED as of 3.3. Please use 'params_error' instead.

GetRemoteMissionServiceInfoRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetRemoteMissionServiceInfoResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
custom_params bosdyn.api.DictParam.Spec The parameters the service expects to be called at runtime with.

StopRequest

Used to stop a node that was previously ticked, so that it knows that the next Tick represents a restart rather than a continuation.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
session_id string Session ID as returned by the EstablishSessionResponse.
Used to guarantee coherence between a single client and a servicer.

StopResponse

Results of attempting to stop a remote node.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status StopResponse.Status Result of the stop request.

TeardownSessionRequest

End the session originally established by an EstablishSessionRequest.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
session_id string Session ID as returned by the EstablishSessionResponse.
Used to guarantee coherence between a single client and a servicer.

TeardownSessionResponse

Results of ending a session.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status TeardownSessionResponse.Status The result of a TeardownSessionRequest.

TickRequest

Request that the remote tick itself for a particular node in the mission.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
session_id string Session ID as returned by the EstablishSessionResponse.
Used to guarantee coherence between a single client and a servicer.
leases bosdyn.api.Lease repeated All leases that the remote service may need.
inputs KeyValue repeated Inputs provided to the servicer.
DEPRECATED as of 3.3. Please use 'params' instead.
params bosdyn.api.DictParam Parameters set by the client. Depending on the structure of the mission,
the value may change during ticking.
group_name string Callbacks can be used to record data using Data Acquisition. The mission
can provide a hint to the callback with the current group, so that the
data the callback saves is correctly grouped with other data generated
by the mission. The value may change during ticking.

TickResponse

Response with the results of the tick. Remote services should strive to return quickly, even if only returning RUNNING.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status TickResponse.Status Result of the current tick.
missing_lease_resources string repeated Need to provide leases on these resources.
lease_use_results bosdyn.api.LeaseUseResult repeated Details about how any leases were used.
Allowed to be empty, if leases were not actually used.
missing_inputs VariableDeclaration repeated Filled out when status is STATUS_MISSING_INPUTS, indicating what inputs were not in the
request.
error_message string If you need to report other error details, you can use this field.
custom_param_error bosdyn.api.CustomParamError Filled out if status is STATUS_CUSTOM_PARAMS_ERROR.

EstablishSessionResponse.Status

Possible results of establishing a session.

Name Number Description
STATUS_UNKNOWN 0 Status unknown/unset.
STATUS_OK 1 Provided inputs / outputs are compatible.
STATUS_MISSING_LEASES 2 Remote service needs leases on additional resources.
If set, the missing_lease_resources field should contain the resources needed but not
provided.
STATUS_MISSING_INPUTS 3 Remote service needs additional inputs.

StopResponse.Status

Possible results for a StopRequest.

Name Number Description
STATUS_UNKNOWN 0 Status unknown/unset.
STATUS_OK 1 Service stopped.
STATUS_INVALID_SESSION_ID 2 The request provided an invalid session ID.

TeardownSessionResponse.Status

Possible results of ending a session.

Name Number Description
STATUS_UNKNOWN 0 Status unknown/unset.
STATUS_OK 1 Session was torn down -- servicer has probably wiped all associated data / state.
STATUS_INVALID_SESSION_ID 2 The request provided an invalid session ID.
This may mean the session was already torn down.

TickResponse.Status

Possible results from the node. The FAILURE, RUNNING, and SUCCESS statuses map to the behavior tree terms, all others indicate an error in the TickRequest.

Name Number Description
STATUS_UNKNOWN 0 Invalid; do not use.
STATUS_FAILURE 1 Node completed but failed.
STATUS_RUNNING 2 Node is processing and may finish in a future tick.
STATUS_SUCCESS 3 Node completed and succeeded.
STATUS_INVALID_SESSION_ID 4 The request provided an invalid session ID.
STATUS_MISSING_LEASES 5 The request was missing required leases.
STATUS_MISSING_INPUTS 6 The request was missing required inputs.
STATUS_CUSTOM_PARAMS_ERROR 7 There was another error with the input parameters.
See the params_error field for details.

Top

bosdyn/api/mission/remote_service.proto

RemoteMissionService

Interface for mission callbacks. Mission RemoteGrpc nodes will act as clients to this service type, calling out to this service when loaded, ticked, or unloaded.

Method Name Request Type Response Type Description
EstablishSession EstablishSessionRequest EstablishSessionResponse Call this once at mission load time, once for each node that references this remote service.
Tick TickRequest TickResponse Call this every time the RemoteGrpc node is ticked.
Stop StopRequest StopResponse Call this every time the RemoteGrpc node WAS ticked in the previous cycle, but was NOT ticked
in this cycle. Signals that the next tick will be a restart, rather than a continuation.
TeardownSession TeardownSessionRequest TeardownSessionResponse Tells the service it can forget any data associated with the given session ID.
Should be called once for every EstablishSession call.
GetRemoteMissionServiceInfo GetRemoteMissionServiceInfoRequest GetRemoteMissionServiceInfoResponse Asks the service what to describe itself Can be called by clients at mission
record time to parameterize a RemoteGrpc node.

Top

bosdyn/api/mission/util.proto

ConstantValue

A constant value. Corresponds to the VariableDeclaration Type enum.

Field Type Label Description
float_value double
string_value string
int_value int64
bool_value bool
msg_value google.protobuf.Any

KeyValue

Key/Value pair, used in other messages.

Field Type Label Description
key string
value Value

UserData

Data a user can associate with a node.

Field Type Label Description
id string Identifier. Enables matching the Node uploaded to the MissionService with the NodeInfo
downloaded from the MissionService.
bytestring bytes Arbitrary data. We recommend keeping it small, to avoid bloating the size of the mission.
source_representation google.protobuf.Any The source representation is a high level representation of this mission.
By analogy, it is the "source code" to this "compiled" mission.
At this time this field can either contain:
- Nothing
- A [bosdyn.api.autowalk.Walk] if the mission was compiled using the Autowalk service.

Value

A value of a run-time or compile-time variable.

Field Type Label Description
constant ConstantValue A constant value.
runtime_var VariableDeclaration Look up a variable provided at run-time.
parameter VariableDeclaration Look up a Node Parameter.

VariableDeclaration

Declaration of a run-time or compile-time variable.

Field Type Label Description
name string Name of the variable, to be used as the key in KeyValue pairs.
type VariableDeclaration.Type Type that this variable is expected to have. Used to verify assignments and comparisons.

Result

Results from executing / ticking / running a single node.

Name Number Description
RESULT_UNKNOWN 0 Invalid, should not be used.
RESULT_FAILURE 1 The node completed running, but failed.
RESULT_RUNNING 2 The node is still in process and has not completed.
RESULT_SUCCESS 3 The node completed, and succeeded.
RESULT_ERROR 4 The node encountered an operational error while trying to execute.

VariableDeclaration.Type

Supported types for blackboard or parameter values.

Name Number Description
TYPE_UNKNOWN 0
TYPE_FLOAT 1
TYPE_STRING 2
TYPE_INT 3
TYPE_BOOL 4
TYPE_MESSAGE 5

Top

bosdyn/api/mobility_command.proto

MobilityCommand

The robot command message to specify a basic command that moves the robot.

MobilityCommand.Feedback

The feedback for the mobility command that will provide information on the progress of the robot command.

Field Type Label Description
se2_trajectory_feedback SE2TrajectoryCommand.Feedback Feedback for the trajectory command.
se2_velocity_feedback SE2VelocityCommand.Feedback Feedback for the velocity command.
sit_feedback SitCommand.Feedback Feedback for the sit command.
stand_feedback StandCommand.Feedback Feedback for the stand command.
stance_feedback StanceCommand.Feedback
stop_feedback StopCommand.Feedback
follow_arm_feedback FollowArmCommand.Feedback
status RobotCommandFeedbackStatus.Status

MobilityCommand.Request

The mobility request must be one of the basic command primitives.

Field Type Label Description
se2_trajectory_request SE2TrajectoryCommand.Request Command to move the robot along a trajectory.
se2_velocity_request SE2VelocityCommand.Request Command to move the robot at a fixed velocity.
sit_request SitCommand.Request Command to sit the robot down.
stand_request StandCommand.Request Command to stand up the robot.
stance_request StanceCommand.Request
stop_request StopCommand.Request
follow_arm_request FollowArmCommand.Request
params google.protobuf.Any Robot specific command parameters.

Top

bosdyn/api/network_compute_bridge.proto

AvailableModels

Field Type Label Description
data ModelData repeated Contains model name, class labels, and per-model parameters.

ComputeParameters

Field Type Label Description
other_data google.protobuf.Any Other data that isn't an image. NetworkComputeBridge service will pass it through
to the remote server so you can do computation on arbitrary data.
model_name string Name of the model to be run on the input data.
reference_images ImageCaptureAndSource repeated For some computer vision operations a number of reference images are required along with the
input image. These images might have been taken months ago, not neccessarilly taken right
now.
custom_params DictParam Input parameters unique to this worker that do not match any of the above fields.

ImageSourceAndService

Field Type Label Description
image_source string When only an image source is specified, network compute bridge will choose default values
for other request options.
image_request ImageRequest A full image request with the image source name as well as other options.
image_service string Image service. If blank, it is assumed to be the robot's default image service.

ListAvailableModelsRequest

Field Type Label Description
header RequestHeader Common request header
server_config NetworkComputeServerConfiguration Configuration about which server to use.

ListAvailableModelsResponse

Field Type Label Description
header ResponseHeader Common response header.
available_models string repeated Deprecated. Provide list of available models.
DEPRECATED as of 3.3. Replaced by AvailableModels.
labels ModelLabels repeated Deprecated. Optional information about available classes for each model
DEPRECATED as of 3.3. Replaced by AvailableModels.
models AvailableModels Envelope message for repeated ModelData.
status ListAvailableModelsStatus Command status

ModelData

Field Type Label Description
model_name string The model name used should match a name specified here.
available_labels string repeated List of class labels returned by this model (optional).
output_image_spec OutputImageSpec repeated An ordered list of what types of outputs this NCB model generates.
This can be used by clients to determine which NCB images to display first
at action configuration time.

It's ok for the NCB worker to return a different set of outputs (more / fewer)
than specified here.
custom_params DictParam.Spec Per-model parameters.

ModelLabels

Field Type Label Description
model_name string Model name.
available_labels string repeated List of class labels returned by this model.

NetworkComputeInputData

Field Type Label Description
image_source_and_service ImageSourceAndService Image source to collect an image from.
image Image Image to process, if you are not using an image source.
other_data google.protobuf.Any Other data that isn't an image. NetworkComputeBridge service will pass it through
to the remote server so you can do computation on arbitrary data.
model_name string Name of the model to be run on the input data.
min_confidence float Minimum confidence [0.0 - 1.0] an object must have to be returned. Detections below this
confidence threshold will be suppressed in the response.
rotate_image NetworkComputeInputData.RotateImage Options for rotating the image before processing. When unset, no rotation is applied.
Rotation is supported for data from image services that provide a FrameTreeSnapshot
defining the sensor's frame with respect to Spot's body and vision frames.
Field is ignored for non-image input.
DEPRECATED as of 3.3. Please rotate the image client-side before passing it to NCB worker.

NetworkComputeInputDataBridge

The network compute bridge will receive this input data, and convert it to a [NetworkComputeInputDataWorker] before sending an RPC to the network compute bridge worker.

Field Type Label Description
image_sources_and_services ImageSourceAndService repeated Image sources to collect a number of images from. The ImageResponses
will populate the [images] field in [NetworkComputeInputDataWorker].
parameters ComputeParameters

NetworkComputeInputDataWorker

The network compute bridge worker will receive this input data.

Field Type Label Description
images ImageCaptureAndSource repeated Live images (usually) filled out by NetworkComputeBridge right before NCB worker
is called.
parameters ComputeParameters Input data.

NetworkComputeRequest

Field Type Label Description
header RequestHeader Common request header.
input_data NetworkComputeInputData Deprecated. Input data.
DEPRECATED as of 3.3, use input_data_bridge instead.
input_data_bridge NetworkComputeInputDataBridge
server_config NetworkComputeServerConfiguration Configuration about which server to use.

NetworkComputeResponse

Field Type Label Description
header ResponseHeader Common response header.
object_in_image WorldObject repeated Deprecated. Detection information. May include bounding boxes, image coordinates, 3D pose information,
etc.
DEPRECATED as of 4.0. Use object_in_image field in OutputImage instead.
image_response ImageResponse Deprecated. The image we computed the data on. If the input image itself was provided in the request,
this field is not populated. This field is not set for non-image input.
DEPRECATED as of 3.3. Use image_responses instead.
image_responses ImageCaptureAndSource repeated The image we computed the data on. This field is not set for non-image input.
image_rotation_angle double Deprecated. If the image was rotated for processing, this field will contain the amount it was rotated by
(counter-clockwise, in radians).

Note that the image returned is not rotated, regardless of if it was rotated
for processing. This ensures that all other calibration and metadata remains valid.
DEPRECATED as of 3.3. Please rotate the image client-side before passing it to NCB worker.
other_data google.protobuf.Any Non image-type data that can optionally be returned by a remote server.
status NetworkComputeStatus Command status
custom_param_error CustomParamError Filled out if status is NETWORK_COMPUTE_STATUS_CUSTOM_PARAMS_ERROR.
alert_data AlertData Deprecated. Optional field to indicate an alert detected by this model.

Note that this alert will be reported for this entire response (including all output images).
If you have multiple output images and only want to alert on a specific image,
use the alert_data field in the associated OutputImage message.
DEPRECATED as of 3.3. Use alert_data in OutputImage instead.
output_images NetworkComputeResponse.OutputImagesEntry repeated Optional field to output images generated by this model.
Maps name to OutputImage.
roi_output_data NetworkComputeResponse.RoiOutputDataEntry repeated Deprecated. Information computed about the regions of interest by the worker.
DEPRECATED as of 3.3. Support for non-image products will be added in the future.

NetworkComputeResponse.OutputImagesEntry

Field Type Label Description
key string
value OutputImage

NetworkComputeResponse.RoiOutputDataEntry

Field Type Label Description
key string
value OutputData

NetworkComputeServerConfiguration

Field Type Label Description
service_name string Service name in the robot's Directory for the worker that will process the request.

OutputData

Field Type Label Description
metadata google.protobuf.Struct Optional metadata related to this image/region.
object_in_image WorldObject repeated Optional detection information. May include bounding boxes, image coordinates,
3D pose information, etc.
alert_data AlertData Optional alert related to this image/region.
other_data google.protobuf.Any Optional data of a custom type.

OutputImage

Field Type Label Description
image_response ImageResponse Annotated image showing process/end results.
metadata google.protobuf.Struct Optional metadata related to this image.
object_in_image WorldObject repeated Optional detection information. May include bounding boxes, image coordinates,
3D pose information, etc.
alert_data AlertData Optional alert related to this image.

OutputImageSpec

Information about the output of an NCB worker.

Field Type Label Description
key string This string corresponds to the key in output_images
name string A human readable name for this output_image.

WorkerComputeRequest

Field Type Label Description
header RequestHeader Common request header.
input_data NetworkComputeInputDataWorker

WorkerComputeResponse

Field Type Label Description
header ResponseHeader Common response header.
other_data google.protobuf.Any Non image-type data that can optionally be returned by a remote server.
status NetworkComputeStatus Command status
custom_param_error CustomParamError Filled out if status is NETWORK_COMPUTE_STATUS_CUSTOM_PARAMS_ERROR.
output_images WorkerComputeResponse.OutputImagesEntry repeated Output images generated by this model.

WorkerComputeResponse.OutputImagesEntry

Field Type Label Description
key string
value OutputImage

ListAvailableModelsStatus

Name Number Description
LIST_AVAILABLE_MODELS_STATUS_UNKNOWN 0 Status is not specified.
LIST_AVAILABLE_MODELS_STATUS_SUCCESS 1 Succeeded.
LIST_AVAILABLE_MODELS_STATUS_EXTERNAL_SERVICE_NOT_FOUND 2 External service not found in the robot's directory.
LIST_AVAILABLE_MODELS_STATUS_EXTERNAL_SERVER_ERROR 3 The call to the external server did not succeed.

NetworkComputeInputData.RotateImage

Name Number Description
ROTATE_IMAGE_UNKNOWN 0 Unspecified rotation method. Do not use.
ROTATE_IMAGE_NO_ROTATION 3 No rotation applied.
ROTATE_IMAGE_ALIGN_HORIZONTAL 1 Rotate the images so the horizon is not rolled with respect to gravity.
ROTATE_IMAGE_ALIGN_WITH_BODY 2 Rotate the images so that the horizon in the image is aligned with the inclination of
the body. For example, when applied to the left body camera this option rotates the image
so that the world does not appear upside down when the robot is standing upright, but if
the body is pitched up, the image will appear rotated.

NetworkComputeStatus

Name Number Description
NETWORK_COMPUTE_STATUS_UNKNOWN 0 Status is not specified.
NETWORK_COMPUTE_STATUS_SUCCESS 1 Succeeded.
NETWORK_COMPUTE_STATUS_EXTERNAL_SERVICE_NOT_FOUND 2 External service not found in the robot's directory.
NETWORK_COMPUTE_STATUS_EXTERNAL_SERVER_ERROR 3 The call to the external server did not succeed.
NETWORK_COMPUTE_STATUS_ROTATION_ERROR 4 The robot failed to rotate the image as requested.
NETWORK_COMPUTE_STATUS_CUSTOM_PARAMS_ERROR 5 One or more keys or values in the input custom_params are unsupported by the service.
See the custom_param_error for details.
NETWORK_COMPUTE_STATUS_ANALYSIS_FAILED 6 Transient error to indicate that the model failed to analyze the set of input images, but a
retry might work.

Top

bosdyn/api/network_compute_bridge_service.proto

NetworkComputeBridge

RPCs for sending images or other data to networked server for computation.

Method Name Request Type Response Type Description
NetworkCompute NetworkComputeRequest NetworkComputeResponse
ListAvailableModels ListAvailableModelsRequest ListAvailableModelsResponse

NetworkComputeBridgeWorker

Set of RPCs for workers of the network compute bridge. This is seperate from the RPCs for the on-robot network compute bridge so that if they need to diverge in the future it is possible to do so.

Method Name Request Type Response Type Description
NetworkCompute NetworkComputeRequest NetworkComputeResponse
WorkerCompute WorkerComputeRequest WorkerComputeResponse
ListAvailableModels ListAvailableModelsRequest ListAvailableModelsResponse

Top

bosdyn/api/network_stats.proto

Association

Field Type Label Description
mac_address string MAC address of the associated station
connected_time google.protobuf.Duration Time duration since the station last connected.
rx_signal_dbm int32 Signal strength of last received packet
rx_signal_avg_dbm int32 Signal strength average
rx_beacon_signal_avg_dbm int32 Signal strength average for beacons only.
expected_bits_per_second int64 Expected throughput
rx_bytes int64 Total received bytes
rx_packets int64 Total received packets from the associated station
rx_bits_per_second int64 Last unicast receive rate
tx_bytes int64 Total transmitted bytes
tx_packets int64 Total transmitted packets to the associated station
tx_bits_per_second int64 Current unicast transmit rate
tx_retries int64 Cumulative retry count to this station, within connected time
tx_failed int64 Cumulative failed tx packet count to this station, within connected time
beacons_received int64 Number of beacons received from this peer
beacon_loss_count int64 Number of times beacon loss was detected

WifiDevice

Field Type Label Description
type WifiDevice.Type
name string
mac_address string
ssid string
tx_power_dbm int32
associations Association repeated

WifiStats

Field Type Label Description
hostname string
devices WifiDevice repeated

WifiDevice.Type

Name Number Description
UNKNOWN 0
AP 1
CLIENT 2

Top

bosdyn/api/parameter.proto

Parameter

A generic parameter message used by the robot state service to describe different, parameterized aspects of the robot.

Field Type Label Description
label string Name of parameter.
units string Units of parameter value.
int_value int64 Value of a countable measure.
float_value double Value of a continuous measure.
timestamp google.protobuf.Timestamp A point in time.
duration google.protobuf.Duration A time duration.
string_value string Value as a string.
bool_value bool Value as true/false.
uint_value uint64 Unsigned integer
notes string Description of the parameter or its value.

Top

bosdyn/api/payload.proto

JointLimits

JointLimits contain hip joint angles where limb to payload collisions occur.

Field Type Label Description
label string Label identifying the respective limb to which these apply [fr,fl,hr,hl]
hy float repeated (hy, hx) coordinates outlining the hip joint limits where collisions occur
between robot hip and payload. Paired vectors must be of equal length.
Angles are measured with actual contact. Appropriate margin will be provided
in software. Radians.
Left legs must have hx > 0. Right legs must have hx < 0.
hx float repeated All legs must have hy > 1.3.

ListPayloadsRequest

The ListPayloads request message sent to the robot to get all known payloads.

Field Type Label Description
header RequestHeader Common request header.

ListPayloadsResponse

The ListPayloads response message returns all payloads registered in the robot’s directory.

Field Type Label Description
header ResponseHeader Common response header.
payloads Payload repeated The returned list of payloads registered in the directory.

MomentOfIntertia

Structure describing the moment of intertia of a body. The xx, yy, zz fields are the diagonal of the MOI tensor, and the xy, xz, and yz fields are the off diagonal terms.

Field Type Label Description
xx float
yy float
zz float
xy float
xz float
yz float

Payload

A Payload describes a single payload installed on the Spot platform. It includes all external information necessary to represent the payload to the user as a single record.

Field Type Label Description
GUID string A unique id provided by the payload or auto-generated by the website.
name string A human readable name describing this payload. It is provided by the
payload as part of the payload announcement system.
description string A human-readable description string providing more context as to the
function of this payload. It is displayed in UIs.
label_prefix string repeated A list of labels used to indicate what type of payload this is.
is_authorized bool Set true once the payload is authorized by the administrator in the payload webpage.
Must be set to false at registration time.
is_enabled bool Set true if the payload is attached to the robot.
Must be set to false at registration time.
is_noncompute_payload bool Set true for payloads registered without their own computers. These records
are all manually entered.
version SoftwareVersion Payload version details.
body_tform_payload SE3Pose The pose of the payload relative to the body frame.
mount_tform_payload SE3Pose The pose of the payload relative to the mount frame.
mount_frame_name MountFrameName Optional - mount frame_name (if not included, payload is assumed to be in the body mount
frame)
liveness_timeout_secs double Number of seconds to wait between heartbeats before assuming payload is no longer live
If unset (0) liveness checks will be disabled for this service.
ipv4_address string IP address of the payload for the robot to ping
If left empty, assume that the payload will send heartbeats
link_speed int32 In mbps (10, 100, 1000, etc)
mass_volume_properties PayloadMassVolumeProperties The mass and volume properties of the payload.
preset_configurations PayloadPreset repeated A list of possible physical configurations for the payload.

PayloadMassVolumeProperties

PayloadMassVolumeProperties contain mass and volume information for the payload in the format that the user interacts with it. It is transmitted to the control and perception systems and processed there to inform those systems.

Field Type Label Description
total_mass float Total mass of payload in kg.
com_pos_rt_payload Vec3 Position of the center of mass of the payload in the payload frame. Meters.
moi_tensor MomentOfIntertia The moment of inertia of the payload, represented about the payload
center of mass, in the payload frame. Units in [kg*m^2].
bounding_box Box3WithFrame repeated Zero or more bounding boxes indicating the occupied volume of the payload.
These boxes must be represented in the payload frame by specifying
Must have Box3WithFrame.frame_name == "payload".
joint_limits JointLimits repeated Joint limits defining limits to range of motion of the hips of the robot,
in order to prevent collisions with the payload.
This field is optional and is only recommended for advanced development
purposes.

PayloadPreset

The physical configurations for the payload.

Field Type Label Description
preset_name string A human readable name describing this configuration. It is displayed in
the admin console, but will not overwrite the top level payload name.
description string A human-readable description providing context on this configuration. It is
displayed in the admin console.
mount_tform_payload SE3Pose The pose of the payload relative to the body frame.
mount_frame_name MountFrameName Optional - mount frame_name (if not included, payload is assumed to be in the body mount
frame)
mass_volume_properties PayloadMassVolumeProperties The mass and volume properties of the payload.
label_prefix string repeated A list of labels used to indicate what type of payload this is.

MountFrameName

Payloads are defined relative to a frame on the robot. These are the possible frames.

Name Number Description
MOUNT_FRAME_UNKNOWN 0 This is the default. For backwards compatibility, we assume unknown means body mount frame.
MOUNT_FRAME_BODY_PAYLOAD 1 The body payload mount frame, as defined in documentation.
MOUNT_FRAME_GRIPPER_PAYLOAD 2 The gripper payload mount frame, as defined in documentation.
MOUNT_FRAME_WR1 3 The wrist link frame, as defined in the gripper CAD and documentation.

Top

bosdyn/api/payload_estimation.proto

PayloadEstimationCommand

Command the robot to stand and execute a routine to estimate the mass properties of an unregistered payload attached to the robot.

PayloadEstimationCommand.Feedback

The PayloadEstimationCommand provides several pieces of feedback:

  • If the routine is finished running (and its current progress).

  • If the routine encountered any errors while running.

  • The resulting payload estimated by the routine.

Field Type Label Description
status PayloadEstimationCommand.Feedback.Status Status of the estimation routine.
progress float The approximate progress of the routine, range [0-1].
error PayloadEstimationCommand.Feedback.Error Error status of the estimation routine.
estimated_payload Payload The resulting payload estimated by the estimation routine.

PayloadEstimationCommand.Request

PayloadEstimation command request takes no additional arguments. The estimation routine takes about ~1min to run. Subsequent PayloadEstimationCommand requests issued while the routine is in progress are ignored until the routine is completed.

PayloadEstimationCommand.Feedback.Error

Name Number Description
ERROR_UNKNOWN 0
ERROR_NONE 1 No error has occurred.
ERROR_FAILED_STAND 2 Robot failed to stand/change stance.
ERROR_NO_RESULTS 3 Failed to calculate results.

PayloadEstimationCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_COMPLETED 1 Completed estimation routine successfully; estimated_payload is populated.
STATUS_SMALL_MASS 2 Completed estimation routine successfully, but estimated mass is small enough to
not significantly impact mobility; estimated_payload is empty.
STATUS_IN_PROGRESS 3 Estimation routine is currently running; estimated_payload is empty.
STATUS_ERROR 4 Error occurred during the routine; estaimted_payload is empty.

Top

bosdyn/api/payload_registration.proto

GetPayloadAuthTokenRequest

Request a user token from the robot A token will only be provided after the registered payload has been enabled by an admin. The returned user token will have limited access to the services necessary for a simple payload.

Field Type Label Description
header RequestHeader Common request header.
payload_credentials PayloadCredentials Payload credentials.
payload_guid string Deprecated. The GUID to identify which payload to get the auth token for.
DEPRECATED as of 3.0.0. Please use payload_credentials instead.
payload_secret string Deprecated. The payload secret for the specified payload.
DEPRECATED as of 3.0.0. Please use payload_credentials instead.

GetPayloadAuthTokenResponse

The GetPayloadAuthToken response message that returns the token for the payload.

Field Type Label Description
header ResponseHeader Common response header.
status GetPayloadAuthTokenResponse.Status Return status for the request.
token string A limited-access user token provided on successful payload registration

PayloadCredentials

PayloadCredentials are used to authorize a payload.

Field Type Label Description
guid string The GUID of the payload.
secret string The secret of the payload.

RegisterPayloadRequest

The RegisterPayload request message contains the payload information and secret to be able to register it to the directory.

Field Type Label Description
header RequestHeader Common request header.
payload Payload The payload to register, which must have, at minimum, GUID specified correctly.
The admin console can be used to verify that the payload definition is valid
after registration.
payload_secret string A private string provided by the payload to verify identity for auth.

RegisterPayloadResponse

The RegisterPayload response message contains the status of whether the payload was successfully registered to the directory.

Field Type Label Description
header ResponseHeader Common response header.
status RegisterPayloadResponse.Status Return status for the request.

UpdatePayloadAttachedRequest

Attach/detach the payload with the matching GUID. The existing payload must have a secret set and the request must provide the secret for access. GUID is immutable and cannot be updated.

Field Type Label Description
header RequestHeader Common request header.
payload_credentials PayloadCredentials Payload credentials, used to identify the payload and authorize the changes.
request UpdatePayloadAttachedRequest.Request Attach or detach the payload.

UpdatePayloadAttachedResponse

The UpdatePayloadAttached response message contains the status of whether the update was successful.

Field Type Label Description
header ResponseHeader Common response header.
status UpdatePayloadAttachedResponse.Status Return status for the request.

UpdatePayloadVersionRequest

Update the payload definition of the payload with matching GUID. The existing payload must have a secret set and the request must provide the secret for access. GUID and is_authorized fields are immutable and cannot be updated.

Field Type Label Description
header RequestHeader Common request header.
payload_credentials PayloadCredentials Payload credentials.
payload_guid string Deprecated. The GUID of the payload to be updated.
DEPRECATED as of 3.0.0. Please use payload_credentials instead.
payload_secret string Deprecated. The payload secret for the specified payload.
DEPRECATED as of 3.0.0. Please use payload_credentials instead.
updated_version SoftwareVersion The new software version that the payload is being updated to.

UpdatePayloadVersionResponse

The UpdatePayloadVersion response message contains the status of whether the update was successful.

Field Type Label Description
header ResponseHeader Common response header.
status UpdatePayloadVersionResponse.Status Return status for the request.

GetPayloadAuthTokenResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal PayloadRegistrationService issue has happened
if UNKNOWN is set.
STATUS_OK 1 Success. The token is available.
STATUS_INVALID_CREDENTIALS 2 GetPayloadAuthToken failed because the paylod guid & secret do not match any registered
payloads.
STATUS_PAYLOAD_NOT_AUTHORIZED 3 GetPayloadAuthToken failed because the paylod has not been authorized by an admin.

RegisterPayloadResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal PayloadRegistrationService issue has happened
if UNKNOWN is set.
STATUS_OK 1 Success. The new service record is available.
STATUS_ALREADY_EXISTS 2 RegisterPayload failed because a payload with this GUID already exists.

UpdatePayloadAttachedRequest.Request

Name Number Description
REQUEST_UNKNOWN 0
REQUEST_ATTACH 1
REQUEST_DETACH 2

UpdatePayloadAttachedResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal PayloadRegistrationService issue has happened
if UNKNOWN is set.
STATUS_OK 1 Success. The payload version has been updated.
STATUS_DOES_NOT_EXIST 2 UpdatePayloadAttached failed because a payload with this GUID does not yet exist.
STATUS_INVALID_CREDENTIALS 3 UpdatePayloadAttached failed because the paylod guid & secret do not match any registered
payloads.
STATUS_PAYLOAD_NOT_AUTHORIZED 4 UpdatePayloadAttached failed because the requested payload has not yet been authorized.
Authorize the payload in the webserver first, then try again.

UpdatePayloadVersionResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used. An internal PayloadRegistrationService issue has happened
if UNKNOWN is set.
STATUS_OK 1 Success. The payload version has been updated.
STATUS_DOES_NOT_EXIST 2 UpdatePayload failed because a payload with this GUID does not yet exist.
STATUS_INVALID_CREDENTIALS 3 UpdatePayload failed because the paylod guid & secret do not match any registered
payloads.

Top

bosdyn/api/payload_registration_service.proto

PayloadRegistrationService

This service provides a way to register new payloads.

Method Name Request Type Response Type Description
RegisterPayload RegisterPayloadRequest RegisterPayloadResponse Register a payload with the directory.
UpdatePayloadVersion UpdatePayloadVersionRequest UpdatePayloadVersionResponse Update the version for the registered payload.
GetPayloadAuthToken GetPayloadAuthTokenRequest GetPayloadAuthTokenResponse Get the authentication token information associated with a given payload.
UpdatePayloadAttached UpdatePayloadAttachedRequest UpdatePayloadAttachedResponse Tell the robot whether the specified payload is attached..

Top

bosdyn/api/payload_service.proto

PayloadService

This service provides a way to query for the currently-registered payloads.

Method Name Request Type Response Type Description
ListPayloads ListPayloadsRequest ListPayloadsResponse List all payloads the robot knows about.

Top

bosdyn/api/point_cloud.proto

GetPointCloudRequest

The GetPointCloud request message to ask a specific point cloud service for data.

Field Type Label Description
header RequestHeader Common request header.
point_cloud_requests PointCloudRequest repeated Sources to retrieve from. The service will return a response for each PointCloudRequest.

GetPointCloudResponse

Field Type Label Description
header ResponseHeader Common response header.
point_cloud_responses PointCloudResponse repeated The resulting point clouds for each requested source.

ListPointCloudSourcesRequest

Field Type Label Description
header RequestHeader Common request header.

ListPointCloudSourcesResponse

The GetPointCloud response message which returns any point cloud data associated with that service.

Field Type Label Description
header ResponseHeader Common response Header.
point_cloud_sources PointCloudSource repeated The set of PointCloudSources available from this service.
May be empty if the service serves no point clouds (e.g., if no sensors were found on startup).

PointCloud

Data from a point-cloud producing sensor or process.

Field Type Label Description
source PointCloudSource The sensor or process that produced the point cloud.
num_points int32 The number of points in the point cloud.
encoding PointCloud.Encoding Representation of the underlying point cloud data.
encoding_parameters PointCloud.EncodingParameters Constants needed to decode the point cloud.
data bytes Raw byte data representing the points.

PointCloud.EncodingParameters

Parameters needed to decode the point cloud.

Field Type Label Description
scale_factor int32 Used in the remapping process from bytes to metric units. (unitless)
max_x double In XYZ_4SC and XYZ_5SC, the point cloud is assumed to lie inside a box
centered in the data frame. max_x, max_y, max_z are half the dimensions
of that box. These dimensions should be assumed to be meters.
max_y double max_y is half the dimensions of the assumed box (for XYZ_4SC and XYZ_5SC). These
dimensions should be assumed to be meters.
max_z double max_z is half the dimensions of the assumed box (for XYZ_4SC and XYZ_5SC). These
dimensions should be assumed to be meters.
remapping_constant double Used in the remapping process from bytes to metric units. (unitless)
For XYZ_4SC and XYZ_5C, this should equal 127.
bytes_per_point int32 Number of bytes in each point in this encoding.

PointCloudRequest

Field Type Label Description
point_cloud_source_name string Name of the point cloud source to request from.

PointCloudResponse

Field Type Label Description
status PointCloudResponse.Status Return status for the request.
point_cloud PointCloud The current point cloud from the service.

PointCloudSource

Information about a sensor or process that produces point clouds.

Field Type Label Description
name string The name of the point cloud source. This is intended to be unique accross all point cloud sources,
and should be human readable.
frame_name_sensor string The frame name of the sensor. The transformation from vision_tform_sensor can be computed
by traversing the tree in the FrameTreeSnapshot.
acquisition_time google.protobuf.Timestamp Time that the data was produced on the sensor in the robot's clock.
transforms_snapshot FrameTreeSnapshot A tree-based collection of transformations, which will include the transformations
to the point cloud data frame and the point cloud sensor frame.

PointCloud.Encoding

Point clouds may be encoded in different ways to preserve bandwidth or disk space.

Name Number Description
ENCODING_UNKNOWN 0 The point cloud has an unknown encoding.
ENCODING_XYZ_32F 1 Each point is x,y,z float32 value (12 bytes, little-endian) stored sequentially. This allows
the point cloud to be expressed in any range and resolution represented by floating point
numbers, but the point cloud will be larger than if one of the other encodings is used.
ENCODING_XYZ_4SC 2 Each point is 3 signed int8s plus an extra shared signed int8s (4 byte).
byte layout: [..., p1_x, p1_y, p1_z, x, ...]
Each coordinate is mapped to a value between -1 and +1 (corresponding to a
minimum and maximum range).
The resulting point is:
P = remap(p1 * f + p2, c * f, m)
Where:
p1 = the highest byte in each dimension of the point.
p2 = a vector of "extra" bytes converted to metric units.
= [mod (x, f), mod(x/f, f), mod(x/(f^2), f)] - f/2
x = the "extra" byte for each point.
f = An integer scale factor.
m = [max_x, max_y, max_z], the point cloud max bounds in meters.
c = a remapping constant.
And:
remap(a, b, c) = (a + b)/(2 * b) - c
Point clouds use 1/3 the memory of XYZ_32F, but have limits on resolution
and range. Points must not lie outside of the box of size [-m, m]. Within that box,
the resolution of the point cloud will depend on the encoding parameters.
For example if m = [10, 10, 10], and f = 5 with c = 127 the resolution is
approximately 1.5 cm per point.
ENCODING_XYZ_5SC 3 Each point is 3 signed int8s plus two extra shared signed int8s (5 byte).
The encoding is the same as XYZ_4SC, except the "extra" value x is a 16 bit integer.
This encoding has roughly double the resolution of XYZ_4SC, but takes up
an additional byte for each point.

PointCloudResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
An internal PointCloudService issue has happened if UNKNOWN is set.
None of the other fields are filled out.
STATUS_OK 1 Call succeeded at filling out all the fields.
STATUS_SOURCE_DATA_ERROR 2 Failed to fill out PointCloudSource. All the other fields are not filled out.
STATUS_POINT_CLOUD_DATA_ERROR 3 There was a problem with the point cloud data. Only the PointCloudSource is filled out.
STATUS_UNKNOWN_SOURCE 4 Provided point cloud source was not found. One

Top

bosdyn/api/point_cloud_service.proto

PointCloudService

The point cloud service provides access to one or more point cloud sources, for example from a lidar. It supports querying the list of available sources provided by the service and it supports requesting the latest point cloud data for each source by name.

Method Name Request Type Response Type Description
ListPointCloudSources ListPointCloudSourcesRequest ListPointCloudSourcesResponse Obtain the list of PointCloudSources for this given service.
Note that there may be multiple PointCloudServices running, each with their own set of sources
The name field keys access to individual point clouds when calling GetPointCloud.
GetPointCloud GetPointCloudRequest GetPointCloudResponse Request point clouds by source name.

Top

bosdyn/api/power.proto

FanPowerCommandFeedbackRequest

The PowerCommandFeedback request message, which can get the feedback for a specific power command id number.

Field Type Label Description
header RequestHeader Common request header.
command_id uint32 Unique identifier for the command of which feedback is desired.

FanPowerCommandFeedbackResponse

The PowerCommandFeedback response message, which contains the progress of the power command.

Field Type Label Description
header ResponseHeader Common response header.
status FanPowerCommandFeedbackResponse.Status Current status of specified command.
desired_end_time google.protobuf.Timestamp Based on duration, the time that this command was intended to stop being in effect. If
stopped/overriden prematurely, early_stop_time will reflect the actual time the command
stopped being in effect
early_stop_time google.protobuf.Timestamp If the command was stopped or overridden before its desired end time, the time at which it
was stopped. If command succeeded, this time is empty.

FanPowerCommandRequest

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to show ownership of the robot.
percent_power int32 What percent power does the user want the fans to run at?
Range is 0 to 100, with 0 being off and 100 being full power
duration google.protobuf.Duration How long the user wants control of the fans
May not be duration the command is actually in effect for if temperature gets too high

FanPowerCommandResponse

Field Type Label Description
header ResponseHeader Common response header.
lease_use_result LeaseUseResult Details about how the lease was used.
status FanPowerCommandResponse.Status Current feedback of specified command.
desired_end_time google.protobuf.Timestamp Based on received duration, the time when this command will stop being in effect
command_id uint32 Unique identifier for the command, If empty, was not accepted.

PowerCommandFeedbackRequest

The PowerCommandFeedback request message, which can get the feedback for a specific power command id number.

Field Type Label Description
header RequestHeader Common request header.
power_command_id uint32 Unique identifier for the command of which feedback is desired.

PowerCommandFeedbackResponse

The PowerCommandFeedback response message, which contains the progress of the power command.

Field Type Label Description
header ResponseHeader Common response header.
status PowerCommandStatus Current status of specified command.
blocking_faults SystemFault repeated Optional list of active faults blocking success of the PowerCommandRequest

PowerCommandRequest

The PowerCommand request which specifies a change in the robot’s motor power.

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to show ownership of the robot.
request PowerCommandRequest.Request

PowerCommandResponse

The PowerCommand response message which contains a unique identifier that can be used to get feedback on the progress of a power command from the power service.

Field Type Label Description
header ResponseHeader Common response header.
lease_use_result LeaseUseResult Details about how the lease was used.
status PowerCommandStatus Current feedback of specified command.
power_command_id uint32 Unique identifier for the command, If empty, was not accepted.
license_status LicenseInfo.Status License check status
blocking_faults SystemFault repeated Optional list of active faults blocking success of the PowerCommandRequest

ResetSafetyStopRequest

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to show ownership of the robot.
safety_stop_type ResetSafetyStopRequest.SafetyStopType

ResetSafetyStopResponse

Field Type Label Description
header ResponseHeader Common response header.
lease_use_result LeaseUseResult Details about how the lease was used.
status ResetSafetyStopResponse.Status Current feedback of specified command.

FanPowerCommandFeedbackResponse.Status

Feedback on the current state of a fan power command on the robot.

Name Number Description
STATUS_UNKNOWN 0 Status is not specified.
STATUS_COMPLETE 1 Fan Power command succeeded for entire requested duration and is now done.
STATUS_RUNNING 2 Fan command is still in effect due to requested duration but has succeeded so far
STATUS_TEMPERATURE_STOP 3 ERROR: Command stopped before finish due to temperature becoming too high
STATUS_OVERRIDDEN_BY_COMMAND 4 ERROR: A newer Fan Power Request took over before the full duration of this request was
up.

FanPowerCommandResponse.Status

Feedback on the current state of a fan power command on the robot.

Name Number Description
STATUS_UNKNOWN 0 Status is not specified.
STATUS_OK 1 Fan Power command succeeded. May still get overriden later in duration
STATUS_TEMPERATURE_TOO_HIGH 2 ERROR: Fan Power command rejected because temperature above safe threshold

PowerCommandRequest.Request

Commands for the robot to execute. Note that not all Spot robots are compatible with all these commands. Check your robot’s HardwareConfiguration in bosdyn.api.robot_state.

Name Number Description
REQUEST_UNKNOWN 0 Invalid request; do not use.
REQUEST_OFF 1 Cut power to motors immediately.
REQUEST_ON 2 Turn on power to the robot motors.
REQUEST_OFF_MOTORS 1 Cut power to motors immediately.
REQUEST_ON_MOTORS 2 Turn on power to the robot motors.
REQUEST_OFF_ROBOT 3 Turn off the robot. Same as physical switch.
REQUEST_CYCLE_ROBOT 4 Power cycle the robot. Same as physical switch.
REQUEST_OFF_PAYLOAD_PORTS 5 Cut power to the payload ports.
REQUEST_ON_PAYLOAD_PORTS 6 Turn on power to the payload ports.
REQUEST_OFF_WIFI_RADIO 7 Cut power to the hardware Wi-Fi radio.
REQUEST_ON_WIFI_RADIO 8 Power on the hardware Wi-Fi radio.

PowerCommandStatus

Feedback on the current state of a power command on the robot.

Name Number Description
STATUS_UNKNOWN 0 Status is not specified.
STATUS_IN_PROGRESS 1 Power command is executing.
STATUS_SUCCESS 2 Power command succeeded.
STATUS_SHORE_POWER_CONNECTED 3 ERROR: Robot cannot be powered on while on wall power.
STATUS_BATTERY_MISSING 4 ERROR: Battery not inserted into robot.
STATUS_COMMAND_IN_PROGRESS 5 ERROR: Power command cant be overwritten.
STATUS_ESTOPPED 6 ERROR: Cannot power on while estopped. A robot may have multiple estops.
Inspect EStopState for additional info.
STATUS_FAULTED 7 ERROR: Cannot power due to a fault. Inspect FaultState for more info.
STATUS_INTERNAL_ERROR 8 ERROR: Internal error occurred, may be clear-able by issuing a power off command.
STATUS_LICENSE_ERROR 9 ERROR: License check failed. Check license_status field for details.
INCOMPATIBLE_HARDWARE_ERROR 10 ERROR: The Spot hardware is not compatible with the request request.
STATUS_OVERRIDDEN 11 ERROR: Robot has overridden the power command and disabled motor power. In the case
of a commanded power OFF, robot will report SUCCESS if power is disabled.
STATUS_KEEPALIVE_MOTORS_OFF 12 ERROR: Cannot power on while a Keepalive policy with a motors-off action is active.
See the Keepalive API service for more details.

ResetSafetyStopRequest.SafetyStopType

Types of safety stop commands the robot can execute.

Name Number Description
SAFETY_STOP_UNKNOWN 0 Invalid request; do not use.
SAFETY_STOP_PRIMARY 1 Primary safety stop.
SAFETY_STOP_REDUNDANT 2 Redundant safety stop.

ResetSafetyStopResponse.Status

Feedback on the reset safety stop command.

Name Number Description
STATUS_UNKNOWN 0 Status is not specified.
STATUS_OK 1 Reset safety stop command succeeded.
STATUS_INCOMPATIBLE_HARDWARE_ERROR 2 ERROR: Reset safety stop command failed due to incompatible hardware.
STATUS_FAILED 3 ERROR: Reset safety stop command was run and failed.
STATUS_UNKNOWN_STOP_TYPE 4 ERROR: Reset safety stop command failed due to unknown stop type.

Top

bosdyn/api/power_service.proto

PowerService

The power service for the robot that can power on/off the robot’s motors.

Method Name Request Type Response Type Description
PowerCommand PowerCommandRequest PowerCommandResponse Starts a power command on the robot. A robot can only accept one power command at once.
Power commands, are not interruptible. Once a command is issued, it must complete before
another command can be issued.
PowerCommandFeedback PowerCommandFeedbackRequest PowerCommandFeedbackResponse Check the status of a power command.
FanPowerCommand FanPowerCommandRequest FanPowerCommandResponse Separate RPC for toggling fan power due to need for time/percent power parameters
FanPowerCommandFeedback FanPowerCommandFeedbackRequest FanPowerCommandFeedbackResponse Check the status of a fan power command.
ResetSafetyStop ResetSafetyStopRequest ResetSafetyStopResponse Reset the safety stop bit on SRSF-configured robots.

Top

bosdyn/api/ray_cast.proto

RayIntersection

Field Type Label Description
type RayIntersection.Type Type of the raycast intersection that was performed.
hit_position_in_hit_frame Vec3 Position of ray cast hit in the RaycastResponse hit_frame.
distance_meters double Distance of hit from ray origin.

RaycastRequest

Field Type Label Description
header RequestHeader Common request header.
ray_frame_name string The ray's coordinate frame. When unset, this will default to vision frame.
ray Ray The ray, containing and origin and an direction.
min_intersection_distance float Ignore intersections closer than this location on the ray.
Defaults to 0 if not provided.
intersection_types RayIntersection.Type repeated Type of the raycast you want to perform. If multiple are set, the result will wait until
all raycasts are complete and return a single result proto.

If this field is left empty, all available sources are used.

RaycastResponse

Field Type Label Description
header ResponseHeader Common response header.
status RaycastResponse.Status Return status for a request.
message string Human-readable error description. Not for programmatic analysis.
hit_frame_name string The frame raycast hits are returned in. Generally this should be the same frame the client
initially requested in.
hits RayIntersection repeated Ray cast hits, sorted with the closest hit first along the ray's extent.
transforms_snapshot FrameTreeSnapshot A tree-based collection of transformations, which will include the
transformations to each of the returned world objects in addition to
transformations to the common frames ("vision", "body", "odom"). All
transforms within the snapshot are taken at the time when the request is received.

Note that each object's frame names are defined within the properties
submessage e.g. "frame_name".

RayIntersection.Type

Name Number Description
TYPE_UNKNOWN 0 TYPE_UNKNOWN should not be used.
TYPE_GROUND_PLANE 1 Intersected against estimated ground plane.
TYPE_TERRAIN_MAP 2 Intersected against the terrain map.
TYPE_VOXEL_MAP 3 Intersected against the full 3D voxel map.
TYPE_HAND_DEPTH 4 Intersected against the hand depth data.

RaycastResponse.Status

Name Number Description
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_INVALID_INTERSECTION_TYPE 3 [Programming Error] Requested source not valid for current robot configuration.
STATUS_UNKNOWN_FRAME 4 [Frame Error] The frame_name for a command was not a known frame.

Top

bosdyn/api/ray_cast_service.proto

RayCastService

Method Name Request Type Response Type Description
Raycast RaycastRequest RaycastResponse Asks robot to cast the desired ray against its map of the
surrounding environment to find the nearest intersection point.

Top

bosdyn/api/robot_command.proto

ClearBehaviorFaultRequest

A ClearBehaviorFault request message has the associated behavior fault id to be cleared.

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to show ownership of the robot.
behavior_fault_id uint32 Unique identifier for the error

ClearBehaviorFaultResponse

A ClearBehaviorFault response message has status indicating whether the service cleared the fault or not.

Field Type Label Description
header ResponseHeader Common response header.
lease_use_result LeaseUseResult Details about how the lease was used.
status ClearBehaviorFaultResponse.Status Return status for a request.
behavior_fault BehaviorFault Echo back the behavior fault if it was active at the time of request.
blocking_system_faults SystemFault repeated Blocking hardware faults for an unclearable behavior fault.

JointControlStreamRequest

Field Type Label Description
header RequestHeader Common request header.
joint_command JointCommand.UpdateRequest Joint command details

JointControlStreamResponse

Field Type Label Description
header ResponseHeader Common response header.
status JointControlStreamResponse.Status Return status for the stream.
message string Human-readable error description. Not for programmatic analysis.

RobotCommand

A command for a robot to execute. The server decides if a set of commands is valid for a given robot and configuration.

Field Type Label Description
full_body_command FullBodyCommand.Request Commands which require control of entire robot.
synchronized_command SynchronizedCommand.Request A synchronized command, for partial or full control of robot.

RobotCommandFeedback

Command specific feedback. Distance to goal, estimated time remaining, probability of success, etc. Note that the feedback should directly mirror the command request.

Field Type Label Description
full_body_feedback FullBodyCommand.Feedback Commands which require control of entire robot.
synchronized_feedback SynchronizedCommand.Feedback A synchronized command, for partial or full control of robot.

RobotCommandFeedbackRequest

The RobotCommandFeedback request message, which can get the feedback for a specific robot command id number.

Field Type Label Description
header RequestHeader Common request header.
robot_command_id uint32 Unique identifier for the command, provided by StartRequest.

RobotCommandFeedbackResponse

The RobotCommandFeedback response message, which contains the progress of the robot command.

Field Type Label Description
header ResponseHeader Common response header.
lease_use_result LeaseUseResult Details about how the lease was used.
feedback RobotCommandFeedback Command specific feedback.

RobotCommandRequest

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.

Field Type Label Description
header RequestHeader Common request header.
lease Lease The Lease to show ownership of the robot.
command RobotCommand A command for a robot to execute. A command can be comprised of several subcommands.
clock_identifier string Identifier provided by the time sync service to verify time sync between robot and client.

RobotCommandResponse

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.

Field Type Label Description
header ResponseHeader Common response header.
lease_use_result LeaseUseResult Details about how the lease was used.
status RobotCommandResponse.Status Return status for a request.
message string Human-readable error description. Not for programmatic analysis.
robot_command_id uint32 Unique identifier for the command, If empty, command was not accepted.

ClearBehaviorFaultResponse.Status

Name Number Description
STATUS_UNKNOWN 0 An unknown / unexpected error occurred.
STATUS_CLEARED 1 The BehaviorFault has been cleared.
STATUS_NOT_CLEARED 2 The BehaviorFault could not be cleared.

JointControlStreamResponse.Status

Name Number Description
STATUS_UNKNOWN 0 An unknown / unexpected error occurred.
STATUS_OK 1 Steam was accepted and ended normally
STATUS_INVALID_REQUEST 2 [Programming Error]

Request was invalid / malformed in some way.
STATUS_INACTIVE 3 The robot is not in joint control mode.
STATUS_EXPIRED 4 [Timesync Error]

The command was received after its end_time had already passed.
STATUS_TOO_DISTANT 5 The command end time was too far in the future.

RobotCommandResponse.Status

Name Number Description
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 The robot does not understand this command.
STATUS_NO_TIMESYNC 4 [Timesync Error]

Client has not done timesync with robot.
STATUS_EXPIRED 5 The command was received after its end_time had already passed.
STATUS_TOO_DISTANT 6 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 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.

Top

bosdyn/api/robot_command_service.proto

RobotCommandService

The robot command service allows a client application to control and move the robot.

Method Name Request Type Response Type Description
RobotCommand RobotCommandRequest RobotCommandResponse Starts a behavior command on the robot. Issuing a new command overrides the active command.
Each command is issued a UID for feedback retrieval.
RobotCommandFeedback RobotCommandFeedbackRequest RobotCommandFeedbackResponse A client queries this RPC to determine a robot's progress towards completion of a command.
This updates the client with metrics like "distance to goal."
The client should use this feedback to determine whether the current command has
succeeded or failed, and thus send the next command.
ClearBehaviorFault ClearBehaviorFaultRequest ClearBehaviorFaultResponse Clear robot behavior fault.

RobotCommandStreamingService

This service is used to stream high rate commands to the robot once they have been activated using RobotCommandService.RobotCommand This service is in BETA and may undergo changes in future releases.

Method Name Request Type Response Type Description
JointControlStream JointControlStreamRequest stream JointControlStreamResponse Command updates for joint control

Top

bosdyn/api/robot_id.proto

RobotId

Robot identity information, which should be static while robot is powered-on.

Field Type Label Description
serial_number string A unique string identifier for the particular robot.
species string Type of robot. E.g., 'spot'.
version string Robot version/platform.
software_release RobotSoftwareRelease Version information about software running on the robot.
nickname string Optional, customer-supplied nickname.
computer_serial_number string Computer Serial Number. Unlike serial_number, which identifies a complete robot,
the computer_serial_number identifies the computer hardware used in the robot.

RobotIdRequest

The RobotId request message sent to a robot to learn it’s basic identification information.

Field Type Label Description
header RequestHeader Common request/response header.

RobotIdResponse

The RobotId response message, including the ID information for a robot.

Field Type Label Description
header ResponseHeader Common request/response header.
robot_id RobotId The requested RobotId information.

RobotSoftwareRelease

Description of the software release currently running on the robot.

Field Type Label Description
version SoftwareVersion The software version, e.g., 2.0.1
name string The name of the robot, e.g., '20190601'
type string Kind of software release.
changeset_date google.protobuf.Timestamp Timestamp of the changeset.
changeset string Changeset hash.
api_version string API version. E.g., 2.14.5.
build_information string Extra information associated with the build.
install_date google.protobuf.Timestamp Date/time when release was installed.
parameters Parameter repeated Other information about the build.

SoftwareVersion

The software versioning number for a release.

Field Type Label Description
major_version int32 Signficant changes to software.
minor_version int32 Normal changes to software.
patch_level int32 Fixes which should not change intended capabilities or affect compatibility.

Top

bosdyn/api/robot_id_service.proto

RobotIdService

RobotIdService provides mostly static identifying information about a robot. User authentication is not required to access RobotIdService to assist with early robot discovery.

Method Name Request Type Response Type Description
GetRobotId RobotIdRequest RobotIdResponse Get the robot id information. The ID contains basic information about a robot
which is made available over the network as part of robot discovery without
requiring user authentication.

Top

bosdyn/api/robot_state.proto

BatteryState

The battery state for the robot. This includes information about the charge or the battery temperature.

Field Type Label Description
timestamp google.protobuf.Timestamp Robot clock timestamp corresponding to these readings.
identifier string An identifier for this battery (could be a serial number or a name. subject to change).
charge_percentage google.protobuf.DoubleValue Number from 0 (empty) to 100 (full) indicating the estimated state of charge of the battery.
estimated_runtime google.protobuf.Duration An estimate of remaining runtime. Note that this field might not be populated.
current google.protobuf.DoubleValue Measured current into (charging, positive) or out of (discharging, negative) the battery in
Amps.
voltage google.protobuf.DoubleValue Measured voltage of the entire battery in Volts.
temperatures double repeated Measured temperature measurements of battery, in Celsius.
Temperatures may be measured in many locations across the battery.
status BatteryState.Status Current state of the battery.

BehaviorFault

The details of what the behavior fault consistents of, and the id for the fault. The unique behavior_fault_id can be used to clear the fault in robot command service ClearBehaviorFault rpc.

Field Type Label Description
behavior_fault_id uint32 Behavior fault unique id
onset_timestamp google.protobuf.Timestamp Time of robot local clock at time of the error
cause BehaviorFault.Cause The potential cause of the fault.
status BehaviorFault.Status Information about the status/what can be done with the fault.

BehaviorFaultState

This describes any current behaviror faults on the robot, which would block any robot commands from going through. These can be cleared using the ClearBehaviorFault rpc in the robot command service.

Field Type Label Description
faults BehaviorFault repeated Current errors potentially blocking commands on robot

CombinedJointStates

Field Type Label Description
acquisition_timestamp google.protobuf.Timestamp Robot clock timestamp corresponding to these readings.
position float repeated The ordering of joints in these repeated fields are the same as (TODO where)
velocity float repeated
load float repeated

CommsState

The current comms information, including what comms the robot is using and the current status of the comms network.

Field Type Label Description
timestamp google.protobuf.Timestamp Robot timestamp corresponding to these readings.
wifi_state WiFiState The communication state is WiFi.

EStopState

The robot’s current E-Stop states and endpoints. A typical robot has several different E-Stops, all which must be “NOT_ESTOPPED” in order to run the robot.

Field Type Label Description
timestamp google.protobuf.Timestamp Robot clock timestamp corresponding to these readings.
name string Name of the E-Stop
type EStopState.Type What kind of E-Stop this message describes.
state EStopState.State The state of the E-Stop (is it E-Stopped or not?)
state_description string Optional description of E-Stop status.

FootState

Information about the foot positions and contact state, on a per-foot basis.

Field Type Label Description
foot_position_rt_body Vec3 The foot position described relative to the body.
contact FootState.Contact Is the foot in contact with the ground?
terrain FootState.TerrainState

FootState.TerrainState

Foot specific terrain data. Data may not be valid if the contact state is not CONTACT_MADE.

Field Type Label Description
ground_mu_est double Estimated ground coefficient of friction for this foot.
frame_name string Reference frame name for vector data.
foot_slip_distance_rt_frame Vec3 Foot slip distance rt named frame
foot_slip_velocity_rt_frame Vec3 Foot slip velocity rt named frame
ground_contact_normal_rt_frame Vec3 Ground contact normal rt named frame
visual_surface_ground_penetration_mean double Mean penetration (meters) of the foot below the ground visual
surface. For penetrable terrains (gravel/sand/grass etc.) these values are
positive. Negative values would indicate potential odometry issues.
visual_surface_ground_penetration_std double Standard deviation of the visual surface ground penetration.

HardwareConfiguration

Robot Hardware Configuration, described with the robot skeleton.

Field Type Label Description
skeleton Skeleton Robot link and joint description.
can_power_command_request_off_robot bool Turn off the robot. Same as physical switch.
can_power_command_request_cycle_robot bool Power cycle the robot. Same as physical switch.
can_power_command_request_payload_ports bool Control power to the payload ports.
can_power_command_request_wifi_radio bool Control power to the hardware Wi-Fi radio.
has_audio_visual_system bool Robot has audio visual system installed.
redundant_safety_stop_enabled bool Robot is configured with redundant safety stop.

ImuState

Field Type Label Description
packet_rate double Frequency at which IMU packets are expected to arrive.
packets ImuState.Packet repeated A set of data packets since the last message.
identifier string Name for this imu.
mounting_link_name string Name of the link the IMU is mounted on.
This name matches a link listed in RobotState.kinematic_state.transforms_snapshot.
position_imu_rt_link Vec3 Position of the IMU in the mounting link frame expressed in the mounting link's frame (m).

ImuState.Packet

Field Type Label Description
acceleration_rt_odom_in_link_frame Vec3 Linear acceleration of the imu relative to the odom frame expressed in the mounting
link's frame (m/s^2).
angular_velocity_rt_odom_in_link_frame Vec3 Angular velocity of the imu relative to the odom frame expressed in the mounting link's
frame (rad/s).
odom_rot_link Quaternion Rotation from mounting link to odom frame as reported by the IMU.
timestamp google.protobuf.Timestamp Packet timestamp. Note that a given state update may contain many imu packets so
this timestamp will be different than the header timestamp for the state message.

JointState

Proto containing the state of a joint on the robot. This can be used with the robot skeleton to update the current view of the robot.

Field Type Label Description
name string This name maps directly to the joints in the URDF.
position google.protobuf.DoubleValue This is typically an angle in radians as joints are typically revolute. However, for
translational joints this could be a distance in meters.
velocity google.protobuf.DoubleValue The joint velocity in [m/s].
acceleration google.protobuf.DoubleValue The joint acceleration in [m/s^2].
load google.protobuf.DoubleValue This is typically a torque in Newton meters as joints are typically revolute. However, for
translational joints this could be a force in Newtons.

KinematicState

The kinematic state of the robot describes the current estimated positions of the robot body and joints throughout the world. It includes a transform snapshot of the robot’s current known frames as well as joint states and the velocity of the body.

Field Type Label Description
joint_states JointState repeated Joint state of all robot joints.
acquisition_timestamp google.protobuf.Timestamp Robot clock timestamp corresponding to these readings.
transforms_snapshot FrameTreeSnapshot A tree-based collection of transformations. See
https://dev.bostondynamics.com/docs/concepts/geometry_and_frames for conceptual
documentation on frames. The snapshop will include the following frames:
“odom”: An inertial frame that estimates the fixed location in the world (relative to where
the robot is booted up) using the kinematics of the robot.

“vision”: An inertial frame that estimates the fixed location in the world (relative to where
the robot is booted up), and is calculated using visual analysis of the world and the robot’s
odometry.

“body”: A frame describing the robot body’s position and orientation. The frame’s origin is
at the geometric center of the hips with the x-axis pointing from the hip center to the
middle of the front hips.

“flat_body”: A gravity-aligned frame describing the robot body’s position and orientation.
The position is at the robot’s center, and the x/y-axes lie flat in the “odom” frame x-y
plane. Specifically, the x-axis is the normalized projection of the robot’s “body” frame
x-axis to the “odom” x-y plane.

"gpe”: A frame that represents the robot’s ground plane estimate. The full SE(3) pose can be
converted into a plane (a point and normal).

For robots with a SpotArm attached, see
https://support.bostondynamics.com/s/article/Spot-Arm-specifications-and-concepts conceptual
documentation on SpotArm specific frames. The snaphot will also include the following frames:
"hand": The hand frame is used by many of the ArmCommand requests available in the API. The
origin is slightly in front of the gripper's palm plate and its oreination is aligned with
'arm0.link_wr1'.

"arm0.link_wr1": A frame describing the robot's distal wrist link's position and orientation.
The origin of the frame is at the end of the link on its rotational axis. It's x-axis is
aligned with the rotational axis.

All transforms within the snapshot are at the acquisition time of kinematic state.
velocity_of_body_in_vision SE3Velocity Velocity of the body frame with respect to vision frame and expressed in vision frame.
The linear velocity is applied at the origin of the body frame.
velocity_of_body_in_odom SE3Velocity Velocity of the body frame with respect to odom frame and expressed in odom frame.
Again, the linear velocity is applied at the origin of the body frame.

ManipulatorState

Additional state published if an arm is attached to the robot.

Field Type Label Description
gripper_open_percentage double How open the gripper is, measured in percent.
0 = fully closed, 100 = fully open.
is_gripper_holding_item bool Will be true if the gripper is holding an item, false otherwise.
estimated_end_effector_force_in_hand Vec3 The estimated force on the end-effector expressed in the hand frame.
stow_state ManipulatorState.StowState Information on if the arm is stowed, or deployed.
velocity_of_hand_in_vision SE3Velocity Velocity of the hand frame with respect to vision frame and expressed in vision frame.
The linear velocity is applied at the origin of the hand frame.
velocity_of_hand_in_odom SE3Velocity Velocity of the hand frame with respect to odom frame and expressed in odom frame.
Again, the linear velocity is applied at the origin of the hand frame.
carry_state ManipulatorState.CarryState

MotorTemperature

Field Type Label Description
name string Name of the affected motor of the robot, specified by the joint name and degree of freedom.
temperature double Measured temperature of the motor, in Celsius.

PowerState

The power state for the robot. If a robot is not in the POWER OFF state, if is not safe to approach. The robot must not be E-Stopped to enter the POWER_ON state.

Field Type Label Description
timestamp google.protobuf.Timestamp Robot clock timestamp corresponding to these readings.
motor_power_state PowerState.MotorPowerState The motor power state of the robot.
shore_power_state PowerState.ShorePowerState The shore power state of the robot.
robot_power_state PowerState.RobotPowerState The payload ports power state of the robot.
payload_ports_power_state PowerState.PayloadPortsPowerState The payload ports power state of the robot.
wifi_radio_power_state PowerState.WifiRadioPowerState The hardware radio power state of the robot.
locomotion_charge_percentage google.protobuf.DoubleValue Number from 0 (empty) to 100 (full) indicating the estimated state of charge.
This field provides a summary of the BatteryStates that provide power for motor and/or
base compute power, both of which are required for locomotion.
locomotion_estimated_runtime google.protobuf.Duration An estimate of remaining runtime. Note that this field might not be populated.
This field provides a summary of the BatteryStates that provide power for motor and/or
base compute power, both of which are required for locomotion.

RobotHardwareConfigurationRequest

The RobotHardwareConfiguration request message to get hardware configuration, described by the robot skeleton and urdf.

Field Type Label Description
header RequestHeader Common request header.

RobotHardwareConfigurationResponse

The RobotHardwareConfiguration response message, which returns the hardware config from the time the request was received.

Field Type Label Description
header ResponseHeader Common response header.
hardware_configuration HardwareConfiguration The requested RobotState.

RobotImpairedState

Keeps track of why the robot is not able to drive autonomously.

Field Type Label Description
impaired_status RobotImpairedState.ImpairedStatus If the status is ROBOT_IMPAIRED, this is specifically why the robot is impaired.
system_faults SystemFault repeated If impaired_status is STATUS_SYSTEM_FAULT, these are the faults which caused the robot to
stop.
service_faults ServiceFault repeated If impaired_status is STATUS_SERVICE_FAULT, these are the service faults which caused
the robot to stop.
behavior_faults BehaviorFault repeated If impaired_status is STATUS_BEHAVIOR_FAULT, these are the behavior faults which caused
the robot to stop.

RobotLinkModelRequest

The RobotLinkModel request message uses a link name returned by the RobotHardwareConfiguration response to get the associated OBJ file.

Field Type Label Description
header RequestHeader Common request header.
link_name string The link name of which the OBJ file shoould represent.

RobotLinkModelResponse

The RobotLinkModel response message returns the OBJ file for a specifc robot link.

Field Type Label Description
header ResponseHeader Common response header.
link_model Skeleton.Link.ObjModel The requested RobotState skeleton obj model.

RobotMetrics

Key robot metrics (e.g., Gait cycles (count), distance walked, time moving, etc…).

Field Type Label Description
timestamp google.protobuf.Timestamp Robot timestamp corresponding to these metrics.
metrics Parameter repeated Key tracked robot metrics, such as distance walked, runtime, etc.

RobotMetricsRequest

The RobotMetrics request message to get metrics and parameters from the robot.

Field Type Label Description
header RequestHeader Common request header.

RobotMetricsResponse

The RobotMetrics response message, which returns the metrics information from the time the request was received.

Field Type Label Description
header ResponseHeader Common response header.
robot_metrics RobotMetrics The requested robot metrics.

RobotState

The current state of the robot.

Field Type Label Description
power_state PowerState Power state (e.g. motor power).
battery_states BatteryState repeated Battery state (e.g. charge, temperature, current).
comms_states CommsState repeated Communication state (e.g. type of comms network).
system_fault_state SystemFaultState Different system faults for the robot.
estop_states EStopState repeated Because there may be multiple E-Stops, and because E-Stops may be supplied with payloads,
this is a repeated field instead of a hardcoded list.
kinematic_state KinematicState Kinematic state of the robot (e.g. positions, velocities, other frame information).
behavior_fault_state BehaviorFaultState Robot behavior fault state.
foot_state FootState repeated The foot states (and contact information).
manipulator_state ManipulatorState State of the manipulator, only populated if an arm is attached to the robot.
service_fault_state ServiceFaultState Service faults for services registered with the robot.
terrain_state TerrainState Relevant terrain data beneath and around the robot
system_state SystemState Temperature data for the motors.

RobotStateRequest

The RobotState request message to get the current state of the robot.

Field Type Label Description
header RequestHeader Common request header.

RobotStateResponse

The RobotState response message, which returns the robot state information from the time the request was received.

Field Type Label Description
header ResponseHeader Common response header.
robot_state RobotState The requested RobotState.

RobotStateStreamRequest

The RobotStateStream request message to get the current state of the robot.

Field Type Label Description
header RequestHeader Common request header.

RobotStateStreamResponse

Field Type Label Description
header ResponseHeader Common response header.
joint_states CombinedJointStates Joint state of all robot joints.
inertial_state ImuState IMU state
last_command RobotStateStreamResponse.CommandState For determining latency information about the last command received is provided.

RobotStateStreamResponse.CommandState

Field Type Label Description
user_command_key uint32
received_timestamp google.protobuf.Timestamp

ServiceFaultState

The current state of each service fault the robot is experiencing. An “active” fault indicates a fault currently in a service. A “historical” fault indicates a, now cleared, service problem.

Field Type Label Description
faults ServiceFault repeated Currently active faults
historical_faults ServiceFault repeated Service faults that have been cleared. Acts as a ring buffer with size of 50.
aggregated ServiceFaultState.AggregatedEntry repeated Aggregated service fault data. Maps attribute string to highest severity level
of any active fault containing that attribute string.
This provides a very quick way of determining if there any "locomotion" or
"vision" faults above a certain severity level.

ServiceFaultState.AggregatedEntry

Field Type Label Description
key string
value ServiceFault.Severity

Skeleton

Kinematic model of the robot skeleton.

Field Type Label Description
links Skeleton.Link repeated The list of links that make up the robot skeleton.
urdf string URDF description of the robot skeleton.

SystemFault

The current system faults for a robot. A fault is an indicator of a hardware or software problem on the robot. An active fault may indicate the robot may fail to comply with a user request. The exact response a fault may vary, but possible responses include: failure to enable motor power, loss of perception enabled behavior, or triggering a fault recovery behavior on robot.

Field Type Label Description
name string Name of the fault.
onset_timestamp google.protobuf.Timestamp Time of robot local clock at fault onset.
duration google.protobuf.Duration Time elapsed since onset of the fault.
code int32 Error code returned by a fault. The exact interpretation of the fault code
is unique to each variety of fault on the robot. The code is useful for
Boston Dynamics support staff to diagnose hardware/software issues on
robot.
uid uint64 Fault UID
error_message string User visible description of the fault (and possibly remedies.)
attributes string repeated Fault attributes
Each fault may be flagged with attribute metadata (strings in this case.)
These attributes are useful to communicate that a particular fault may
have significant effect on robot operations. Some potential attributes
may be "robot", "imu", "vision", or "battery". These attributes would let
us flag a fault as indicating a problem with the base robot hardware,
gyro, perception system, or battery respectively. A fault may have, zero,
one, or more attributes attached to it, i.e. a "battery" fault may also
be considered a "robot" fault.
severity SystemFault.Severity Fault severity, how bad is the fault?
The severity level will have some indication of the potential robot
response to the fault. For example, a fault marked with "battery"
attribute and severity level SEVERITY_WARN may indicate a low battery
state of charge. However a "battery" fault with severity level
SEVERITY_CRITICAL likely means the robot is going to shutdown
immediately.

SystemFaultState

The current state of each system fault the robot is experiencing. An “active” fault indicates a hardware/software currently on the robot. A “historical” fault indicates a, now cleared, hardware/software problem. Historical faults are useful to diagnose robot behavior subject to intermittent failed states.

Field Type Label Description
faults SystemFault repeated Currently active faults
historical_faults SystemFault repeated Inactive faults that cleared within the last 10 minutes
aggregated SystemFaultState.AggregatedEntry repeated Aggregated fault data.
This provides a very quick way of determining if there any
"battery" or "vision" faults above a certain severity level.

SystemFaultState.AggregatedEntry

Field Type Label Description
key string
value SystemFault.Severity

SystemState

Field Type Label Description
motor_temperatures MotorTemperature repeated Temperature of the robot motors.

TerrainState

Relevant terrain data beneath and around the robot

Field Type Label Description
is_unsafe_to_sit bool Is the terrain immediately under the robot such that sitting or powering off
the robot may cause the robot to be in an unstable position?

WiFiState

Field Type Label Description
current_mode WiFiState.Mode Current WiFi mode.
essid string Essid of robot (master mode) or connected network.

BatteryState.Status

Name Number Description
STATUS_UNKNOWN 0 The battery is in an unknown / unexpected state.
STATUS_MISSING 1 The battery is not plugged in or otherwise not talking.
STATUS_CHARGING 2 The battery is plugged in to shore power and charging.
STATUS_DISCHARGING 3 The battery is not plugged into shore power and discharging.
STATUS_BOOTING 4 The battery was just plugged in and is booting up= 3;

BehaviorFault.Cause

Name Number Description
CAUSE_UNKNOWN 0 Unknown cause of error
CAUSE_FALL 1 Error caused by mobility failure or fall
CAUSE_HARDWARE 2 Error caused by robot hardware malfunction
CAUSE_LEASE_TIMEOUT 3 A lease has timed out

BehaviorFault.Status

Name Number Description
STATUS_UNKNOWN 0 Unknown clearable status
STATUS_CLEARABLE 1 Fault is clearable
STATUS_UNCLEARABLE 2 Fault is currently not clearable

EStopState.State

Name Number Description
STATE_UNKNOWN 0 No E-Stop information is present. Only happens in an error case.
STATE_ESTOPPED 1 E-Stop is active -- robot cannot power its actuators.
STATE_NOT_ESTOPPED 2 E-Stop is released -- robot may be able to power its actuators.

EStopState.Type

Name Number Description
TYPE_UNKNOWN 0 Unknown type of E-Stop. Do not use this field.
TYPE_HARDWARE 1 E-Stop is a physical button
TYPE_SOFTWARE 2 E-Stop is a software process

FootState.Contact

Name Number Description
CONTACT_UNKNOWN 0 Unknown contact. Do not use.
CONTACT_MADE 1 The foot is currently in contact with the ground.
CONTACT_LOST 2 The foot is not in contact with the ground.

ManipulatorState.CarryState

The stowing behavior is modified as a function of the Carry State. If holding an item, the stowing behavior will be modified as follows: NOT_CARRIABLE - The arm will not stow, instead entering stop CARRIABLE - The arm will not stow, instead entering stop CARRIABLE_AND_STOWABLE - The arm will stow while continuing to grasp the item The comms loss behavior of the arm is also modified as follows: NOT_CARRIABLE - The arm will release the item and stow CARRIABLE - The arm will not stow, instead entering stop CARRIABLE_AND_STOWABLE - The arm will stow while continuing to grasp the item

Name Number Description
CARRY_STATE_UNKNOWN 0
CARRY_STATE_NOT_CARRIABLE 1
CARRY_STATE_CARRIABLE 2
CARRY_STATE_CARRIABLE_AND_STOWABLE 3

ManipulatorState.StowState

Name Number Description
STOWSTATE_UNKNOWN 0
STOWSTATE_STOWED 1
STOWSTATE_DEPLOYED 2

PowerState.MotorPowerState

Name Number Description
STATE_UNKNOWN 0 Unknown motor power state. Do not use this field.
MOTOR_POWER_STATE_UNKNOWN 0
STATE_OFF 1 Motors are off, the robot is safe to approach.
MOTOR_POWER_STATE_OFF 1
STATE_ON 2 The motors are powered.
MOTOR_POWER_STATE_ON 2
STATE_POWERING_ON 3 The robot has received an ON command, and is turning on.
MOTOR_POWER_STATE_POWERING_ON 3
STATE_POWERING_OFF 4 In the process of powering down, not yet safe to approach.
MOTOR_POWER_STATE_POWERING_OFF 4
STATE_ERROR 5 The robot is in an error state and must be powered off before attempting to re-power.
MOTOR_POWER_STATE_ERROR 5

PowerState.PayloadPortsPowerState

State describing if the payload port has power.

Name Number Description
PAYLOAD_PORTS_POWER_STATE_UNKNOWN 0 Unknown payload port power state. Do not use this field.
PAYLOAD_PORTS_POWER_STATE_ON 1 The payload port is powered on.
PAYLOAD_PORTS_POWER_STATE_OFF 2 The payload port does not have power.

PowerState.RobotPowerState

State describing if the robot has power.

Name Number Description
ROBOT_POWER_STATE_UNKNOWN 0 Unknown robot power state. Do not use this field.
ROBOT_POWER_STATE_ON 1 The robot is powered on.
ROBOT_POWER_STATE_OFF 2 The robot does not have power.
Impossible to get this response, as the robot cannot respond if it is powered off.

PowerState.ShorePowerState

State describing if robot is connected to shore (wall) power. Robot can’t be powered on while on shore power

Name Number Description
STATE_UNKNOWN_SHORE_POWER 0 Unknown shore power state. Do not use.
SHORE_POWER_STATE_UNKNOWN 0
STATE_ON_SHORE_POWER 1 The robot is connected to shore power. The robot will not power on while connected to
shore power.
SHORE_POWER_STATE_ON 1
STATE_OFF_SHORE_POWER 2 The robot is disconnected from shore power and motors can be powered up.
SHORE_POWER_STATE_OFF 2

PowerState.WifiRadioPowerState

State describing if the robot Wi-Fi router has power.

Name Number Description
WIFI_RADIO_POWER_STATE_UNKNOWN 0 Unknown radio power state. Do not use this field.
WIFI_RADIO_POWER_STATE_ON 1 The radio is powered on.
WIFI_RADIO_POWER_STATE_OFF 2 The radio does not have power.

RobotImpairedState.ImpairedStatus

If the robot is stopped due to being impaired, this is the reason why.

Name Number Description
IMPAIRED_STATUS_UNKNOWN 0 Unknown/unexpected error.
IMPAIRED_STATUS_OK 1 The robot is able to drive.
IMPAIRED_STATUS_NO_ROBOT_DATA 2 The autonomous system does not have any data from the robot state service.
IMPAIRED_STATUS_SYSTEM_FAULT 3 There is a system fault which caused the robot to stop. See system_fault for details.
IMPAIRED_STATUS_NO_MOTOR_POWER 4 The robot's motors are not powered on.
IMPAIRED_STATUS_REMOTE_CLOUDS_NOT_WORKING 5 The autonomous system is expected to have a remote point cloud (e.g. a LIDAR), but this
is not working.
IMPAIRED_STATUS_SERVICE_FAULT 6 A remote service the autonomous system depends on is not working.
IMPAIRED_STATUS_BEHAVIOR_FAULT 7 A behavior fault caused the robot to stop. See behavior_faults for details.
IMPAIRED_STATUS_ENTITY_DETECTOR_NOT_WORKING 8 The autonomous system expected to have a payload providing an entity detector.
The detector is either not present, or not working. Note that if the detector
exists but is throwing a system fault, the status will be IMPAIRED_STATUS_SYSTEM_FAULT.

SystemFault.Severity

Name Number Description
SEVERITY_UNKNOWN 0 Unknown severity
SEVERITY_INFO 1 No hardware problem
SEVERITY_WARN 2 Robot performance may be degraded
SEVERITY_CRITICAL 3 Critical fault

WiFiState.Mode

Name Number Description
MODE_UNKNOWN 0 The robot's comms state is unknown, or no user requested mode.
MODE_ACCESS_POINT 1 The robot is acting as an access point.
MODE_CLIENT 2 The robot is connected to a network.

Top

bosdyn/api/robot_state_service.proto

RobotStateService

The robot state service tracks all information about the measured and computed states of the robot at the current time.

Method Name Request Type Response Type Description
GetRobotState RobotStateRequest RobotStateResponse Get robot state information (such as kinematic state, power state, or faults).
GetRobotMetrics RobotMetricsRequest RobotMetricsResponse Get different robot metrics and parameters from the robot.
GetRobotHardwareConfiguration RobotHardwareConfigurationRequest RobotHardwareConfigurationResponse Get the hardware configuration of the robot, which describes the robot skeleton and urdf.
GetRobotLinkModel RobotLinkModelRequest RobotLinkModelResponse Returns the OBJ file for a specifc robot link. Intended to be called after
GetRobotHardwareConfiguration, using the link names returned by that call.

RobotStateStreamingService

This service is in BETA and may undergo changes in future releases.

Method Name Request Type Response Type Description
GetRobotStateStream RobotStateStreamRequest RobotStateStreamResponse stream Lightweight Streaming version of RobotState

Top

bosdyn/api/service_customization.proto

BoolParam

A boolean parameter.

Field Type Label Description
value bool The value sent by a client.

BoolParam.Spec

Field Type Label Description
default_value google.protobuf.BoolValue Default value. If unset, UIs can pick their own default OR force user to make a
selection.

CustomParam

Field Type Label Description
dict_value DictParam
list_value ListParam
int_value Int64Param
double_value DoubleParam
string_value StringParam
roi_value RegionOfInterestParam
bool_value BoolParam
one_of_value OneOfParam

CustomParam.Spec

Field Type Label Description
dict_spec DictParam.Spec This parameter is actually a set of sub-parameters.
Useful for setting up a paramter hierarchy, e.g.
param A
/ \
/ \
param A.B param A.C
list_spec ListParam.Spec This parameter is a list of things.
int_spec Int64Param.Spec
double_spec DoubleParam.Spec
string_spec StringParam.Spec
roi_spec RegionOfInterestParam.Spec
bool_spec BoolParam.Spec
one_of_spec OneOfParam.Spec

CustomParamCollection

Collection of both specifications and values. Meant to be used as a snapshot of specifications offered by a service, and the values chosen by a user.

Field Type Label Description
specs DictParam.Spec
values DictParam

CustomParamError

Errors specific to the use of custom parameters.

Field Type Label Description
status CustomParamError.Status
error_messages string repeated List of error messages from this parameter and its children

DictParam

A dictionary of parameters.

Field Type Label Description
values DictParam.ValuesEntry repeated

DictParam.ChildSpec

Field Type Label Description
spec CustomParam.Spec
ui_info UserInterfaceInfo

DictParam.Spec

Field Type Label Description
specs DictParam.Spec.SpecsEntry repeated Each element can have its own type. Dictionaries can even contain dictionaries!
is_hidden_by_default bool Whether the dict should initially appear hidden/collapsed. For example an "Advanced"
section that users infrequently access.

The client may ignore this value if there is sufficient screen space.

DictParam.Spec.SpecsEntry

Field Type Label Description
key string
value DictParam.ChildSpec

DictParam.ValuesEntry

Field Type Label Description
key string
value CustomParam

DoubleParam

A 64-bit floating point parameter. Wraps specification-related messages, and contains fields for the value sent by a client.

Field Type Label Description
value double Value should be provided in the same units as defined by the spec.

DoubleParam.Spec

Field Type Label Description
default_value google.protobuf.DoubleValue Default value. If unspecified, UIs can pick their own default OR force user to make a
selection.

Units of value, default_value, and min_max.
units Units
min_value google.protobuf.DoubleValue A value sent by the client must be within this minimum and maximum (inclusive).
If unset, only limited by system representation.
ERROR: It is an error to specify a min_value larger than the max_value.
max_value google.protobuf.DoubleValue

Int64Param

A 64-bit integer parameter. Wraps specification-related messages, and contains fields for the value sent by a client.

Field Type Label Description
value int64 Value should be provided in the same units as defined by the spec.

Int64Param.Spec

Field Type Label Description
default_value google.protobuf.Int64Value Default value. If unspecified, UIs can pick their own default OR force user to make a
selection.
units Units Units of value, default_value, min_value, min_value.
min_value google.protobuf.Int64Value A value sent by the client must be within this minimum and maximum (inclusive).
If unset, only limited by system representation.
ERROR: It is an error to specify a min_value larger than the max_value.
max_value google.protobuf.Int64Value

ListParam

A list of elements of given types.

Field Type Label Description
values CustomParam repeated

ListParam.Spec

Field Type Label Description
element_spec CustomParam.Spec Each element in the list must follow the specification of the matching type.
For example, if element_specs.int_spec is filled out, all values should follow
that specification. If element_specs.string_spec is filled out, all values
should follow that specification.
min_number_of_values google.protobuf.Int64Value Minimum and maximum number of values the client may send (inclusive).
If min_number_of_values is 0, the parameter is optional.

0 <= min_number_of_values <= max_number_of_values
max_number_of_values google.protobuf.Int64Value

OneOfParam

A selected param from one of several options. Can be useful to specify parameters that have correlations.

Example 1 - A camera that advertises an “exposure” parameter: OneOf Option 1: Auto exposure [no additional parameters] OneOf Option 2: Manual exposure [additonal exposure double parameter from 0 - 100 ms]

Example 2 - A NCB worker that will alert if temperature outside a specified bound: OneOf Option 1: No alert [no additional parameters] OneOf Option 2: Alert if above max [addional max_temp parameter] OneOf Option 3: Alert if below min [additional min_temp parameter] OneOf Option 4: Alert if above max or below min [additional max_temp and min_temp parameters]

In the above examples, the service advertises a OneOf spec, the UI lets user PICK which child of the OneOf they want, and then the UI lets the user specify any child specific parameters.

Field Type Label Description
key string
values OneOfParam.ValuesEntry repeated The values of the chosen spec will is guaranteed to be at value[key].
The values of the other specs might at value[that_specs_key], but no guarantees.

OneOfParam.ChildSpec

Field Type Label Description
spec DictParam.Spec
ui_info UserInterfaceInfo

OneOfParam.Spec

Field Type Label Description
specs OneOfParam.Spec.SpecsEntry repeated What options are available. Only one will be specified by the user.

If an option has no additional parameters, its spec should be an empty DictParam.Spec.
default_key string Which option to start selected. If left blank, UI will pick one for you.

OneOfParam.Spec.SpecsEntry

Field Type Label Description
key string
value OneOfParam.ChildSpec

OneOfParam.ValuesEntry

Field Type Label Description
key string
value DictParam

RegionOfInterestParam

Region of Interest parameter, region is associated with a specific image.

Field Type Label Description
area AreaI
service_and_source RegionOfInterestParam.ServiceAndSource The name of the image service and source the UI had the user specify the ROI on.
image_cols int32 Width of the image (in pixels) when the ROI was specified.
This should be used to ensure that the ROI is applied to an image with the same
size / aspect ratio.
image_rows int32 Height of the image (in pixels).
This should be used to ensure that the ROI is applied to an image with the same
size / aspect ratio.

RegionOfInterestParam.ServiceAndSource

Field Type Label Description
service string
source string

RegionOfInterestParam.Spec

Field Type Label Description
service_and_source RegionOfInterestParam.ServiceAndSource Sometimes, which image the ROI will reference is obvious:
- Image services
- Network compute bridge workers that accept a single image

Othertimes, it might not be clear which image an ROI is supposed to reference. In those
cases, the Spec for the ROI can advertise which image it wants.
default_area AreaI Default value. If unset, UIs can pick their own default OR force user to make a
selection.
allows_rectangle bool Area may eventually contain many shape primatives. In that case, services can constrain
which primatives they accept. These will be opt in, so that adding new primative types
won't be automatically advertised by older services.

StringParam

A text parameter. Wraps specification-related messages, and contains fields for the value sent by a client.

Field Type Label Description
value string The value sent by a client.

StringParam.Spec

Field Type Label Description
options string repeated A value sent by the client must be equal to one of these.
editable bool Whether or not this parameter accepts a freeform string.
If set to true, clients can pick one of the given options OR type their own value.
If set to false, clients have to pick one of the given options.
If no options are specified, clients should type their own value (ignoring this bool).
default_value string Default value. If empty, UIs can pick their own default OR force user to make a
selection.

UserInterfaceInfo

Field Type Label Description
display_name string This string is an optional display name for the UI. If left unset, UI will use the
DictParam key to label the corresponding UI element. DictParam key is meant to be
machine readable, and shouldn't change accross releases. display_name is meant to be
human readable, and can change from release to release if needed.
description string An optional description that provides additional information about the parameter. Use in
combination with display_name.
display_order int64 This is an optional sorting hint. UI elements will likely be shown in a list, and
Dictionary children will be sorted by [display_order, display_name, dictionary key],
in ascending numerical order and alphabetical string order.

CustomParamError.Status

Name Number Description
STATUS_UNKNOWN 0 Invalid, do not use.
STATUS_OK 1 No problems!
STATUS_INVALID_COMBINATION 2 The combination of parameters was invalid.
STATUS_UNSUPPORTED_PARAMETER 3 One or more of the children parameters is unsupported by the service.
STATUS_INVALID_VALUE 4 One or more of the parameters had an invalid value.
STATUS_INVALID_TYPE 5 One or more of the parameters had an invalid type (e.g. a string when an int was needed).

Top

bosdyn/api/service_fault.proto

ClearServiceFaultRequest

Clear a service fault from the robot’s ServiceFaultState (in robot_state.proto). The active ServiceFault to clear will be determined by matching fault_name and service_name/payload_guid, specified in the ServiceFaultId message.

Field Type Label Description
header RequestHeader Common request header.
fault_id ServiceFaultId Identifying information of the fault to clear.
clear_all_service_faults bool Clear all faults that are associated with the same service_name. Use carefully.
clear_all_payload_faults bool Clear all faults that are associated with the same payload_guid. Use carefully.

ClearServiceFaultResponse

The ClearServiceFault response message contains a header indicating success.

Field Type Label Description
header ResponseHeader Common response header.
status ClearServiceFaultResponse.Status Return status for the request.

ServiceFault

The current service faults for services registered with the robot. A fault is an indicator of a problem with a service or payload registered with the robot. An active fault may indicate a service may fail to comply with a user request. If the name, service_name, and payload_guid of a newly triggered ServiceFault matches an already active ServiceFault the new fault will not be added to the active fault list. The oldest matching fault will be maintained.

Field Type Label Description
fault_id ServiceFaultId Identifying information of the fault.
error_message string User visible description of the fault (and possibly remedies). Will be
displayed on tablet.
attributes string repeated Fault attributes
Each fault may be flagged with attribute metadata (strings in this case.)
These attributes are useful to communicate that a particular fault may
have significant effect on the operations of services. Some potential attributes
may be "autowalk", "Spot CORE", "vision", or "gauge detection". These
attributes enable the caller to flag a fault as indicating a problem with
particular robot abstractions. A fault may have, zero, one, or more
attributes attached to it.
severity ServiceFault.Severity The severity level will have some indication of the potential breakage
resulting from the fault. For example, a fault associated with payload
X and severity level SEVERITY_INFO may indicate the payload is in an
unexpected state but still operational. However, a fault with serverity
level SEVERITY_CRITICAL may indicate the payload is no
longer operational.
onset_timestamp google.protobuf.Timestamp Time of robot local clock at fault onset. Set by robot-state service.
duration google.protobuf.Duration Time elapsed since onset of the fault. Set by robot-state service.

ServiceFaultId

Information necessary to uniquely specify a service fault. A service fault typically is associated with a service running on the robot or a payload. Occassionally, the fault may pertain to a payload but no specific service on the payload. In that situation, no service_name should not be specified and instead a payload_guid should be specified. Otherwise, in the standard case of a service originating fault, only the service_name should be specified and the payload_guid will be populated automatically by the fault service on robot.

Field Type Label Description
fault_name string Name of the fault.
service_name string Name of the registered service associated with the fault.
Optional. Service name does not need to be specified if this is a payload-level
fault with no associated service.
payload_guid string GUID of the payload associated with the faulted service.
Optional. If not set, it will be assigned to the payload associated with the
service_name.

TriggerServiceFaultRequest

Trigger a new service fault that will be reported in the robot ServiceFaultState. These faults will be displayed in the tablet. Developers should be careful to avoid overwhelming operators with dozens of minor messages.

Field Type Label Description
header RequestHeader Common request header.
fault ServiceFault The fault to report in ServiceFaultState.

TriggerServiceFaultResponse

The TriggerServiceFault response message contains a header indicating success.

Field Type Label Description
header ResponseHeader Common response header.
status TriggerServiceFaultResponse.Status Return status for the request.

ClearServiceFaultResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
STATUS_OK 1 Success. The fault has been cleared.
STATUS_FAULT_NOT_ACTIVE 2 ServiceFaultId not found in active faults.

ServiceFault.Severity

Name Number Description
SEVERITY_UNKNOWN 0 Unknown severity
SEVERITY_INFO 1 Service still functional
SEVERITY_WARN 2 Service performance may be degraded
SEVERITY_CRITICAL 3 Critical service fault

TriggerServiceFaultResponse.Status

Name Number Description
STATUS_UNKNOWN 0 UNKNOWN should never be used.
STATUS_OK 1 Success. The fault has been triggerd.
STATUS_FAULT_ALREADY_ACTIVE 2 ServiceFaultId already in active faults.

Top

bosdyn/api/signals.proto

AlertConditionSpec

Ex 3: “Critical Condition” (boolean signal)

  • alert_data.severity: SEVERITY_LEVEL_CRITICAL

  • condition: false If the value is false, then SEVERITY_LEVEL_CRITICAL.

Field Type Label Description
alert_data AlertData Indicate severity if thresholds are met or exceeded.
min double If the signal value is <= the min, the condition is met.
max double If the signal value is >= the max, the condition is met.
bounds Bounds If the signal value is >= the lower bound and <= the upper bound, the condition is met.
condition bool If boolean signal value is false, and the condition is false, the condition is met.

SensorOutputSpec

Sensor output specification.

Field Type Label Description
bounds Bounds Min and max (lower and upper) range of the sensor.

Ex: 0.0 - 100.0 psia
resolution google.protobuf.DoubleValue Ex: 0.02 (+/-)
units Units The units of the sensor data.

Ex: "psia"
sample_rate google.protobuf.DoubleValue The sample rate of the sensor.

Ex: 0.5 Hz

Signal

The signal specification and the recorded data.

Field Type Label Description
signal_spec SignalSpec
signal_data SignalData

SignalData

The recorded signal data.

Field Type Label Description
data SignalData.Data
timestamp google.protobuf.Timestamp Optional timestamp for when the data was collected. If unset, the RPC time will be used.

SignalData.Data

Field Type Label Description
double double
int int64
string string
bool bool

SignalDisplayInfo

Signal display information.

Field Type Label Description
name string Optional display name typically used for signal acronyms or abbreviations.
Ex: "PT1" (short name)
If unset, no name will be displayed.
description string An optional description that provides additional information about the signal.
Ex: "Pressure Transducer 1" (long name)
If unset, no description will be displayed.
order int64 This is an optional sorting hint for how to display a set of signals.
If unset, the list will be sorted alphabetically by name or id.

SignalSpec

The signal specification.

Field Type Label Description
info SignalDisplayInfo
sensor SensorOutputSpec
alerts AlertConditionSpec repeated A signal can have multiple alert conditions.
If multiple conditions are simultaneously met,
the higher severity condition or first in the list will be the accepted alert state.

Top

bosdyn/api/sparse_features.proto

Keypoint

A point of interest in an image expressed as a pixel coordinate with associated metadata.

Field Type Label Description
coordinates Vec2 The image pixel coordinates of the keypoint.
binary_descriptor bytes A binary descriptor representing the keypoint.
score float The score of this keypoint from the underlying keypoint detector, if applicable.
size float The diameter in pixels of the local neighborhood used to construct the descriptor.
angle float The orientation of the keypoint, if applicable.

KeypointMatches

A pair of keypoint sets containing only features in common that have been matched.

Field Type Label Description
reference_keypoints KeypointSet The set of common keypoints in a first ("reference") image.
live_keypoints KeypointSet The set of common keypoints in a second ("live") image.
matches Match repeated Indices of pairs of matches in the two KeypointSets and their distance measure.
type KeypointMatches.MatchType The algorithm used to compute these matches.

KeypointSet

A set of keypoints detected in a single image.

Field Type Label Description
keypoints Keypoint repeated A set of detected keypoints and associated metadata.
type KeypointSet.KeypointType The algorithm used to compute this keypoint and its descriptor.

Match

Field Type Label Description
reference_index int32 The index in the reference KeypointSet of the keypoint in the matching pair.
live_index int32 The index in the live KeypointSet of the keypoint in the matching pair.
distance float The distance in descriptor space between the two keypoints.

KeypointMatches.MatchType

Name Number Description
MATCH_UNKNOWN 0
MATCH_ORB 1 Keypoints matched by the ORB feature matching algorithm (Oriented FAST and Rotated
BRIEF).
MATCH_LIGHTGLUE 2 Keypoints matched by the LightGlue matching algorithm.

KeypointSet.KeypointType

Name Number Description
KEYPOINT_UNKNOWN 0
KEYPOINT_SIMPLE 1 Keypoints that consist only of image coordinates. Simple keypoints do not have
descriptors.
KEYPOINT_ORB 2 Keypoints detected by the ORB feature extraction algorithm (Oriented FAST and Rotated
BRIEF).
KEYPOINT_DISK 3 Keypoints detected by the DISK feature extraction algorithm (Discrete Keypoints).

Top

bosdyn/api/spot/choreography_params.proto

AnimateParams

Field Type Label Description
animation_name string The name of the animated move. There are no default values/bounds associated with this field.
body_entry_slices google.protobuf.DoubleValue How many slices to smoothly transition from previous pose to animation.
body_exit_slices google.protobuf.DoubleValue How many slices to return from animation to nominal pose. Zero indicates to keep final
animated pose.
translation_multiplier bosdyn.api.Vec3Value Multiplier for animated translation by axis to exaggerate or suppress motion along specific
axes.
rotation_multiplier EulerZYXValue Multiplier for the animated orientation by axis to exaggerate or suppress motion along
specific axes.
arm_entry_slices google.protobuf.DoubleValue How many slices to smoothly transition from previous pose to animation.
shoulder_0_offset google.protobuf.DoubleValue Joint angle offsets in radians for the arm joints.
shoulder_1_offset google.protobuf.DoubleValue
elbow_0_offset google.protobuf.DoubleValue
elbow_1_offset google.protobuf.DoubleValue
wrist_0_offset google.protobuf.DoubleValue
wrist_1_offset google.protobuf.DoubleValue
gripper_offset google.protobuf.DoubleValue
speed google.protobuf.DoubleValue How fast to playback. 1.0 is normal speed. larger is faster.
offset_slices google.protobuf.DoubleValue How late into the nominal script to start.
gripper_multiplier google.protobuf.DoubleValue Multiply all gripper angles by this value.
gripper_strength_fraction google.protobuf.DoubleValue How hard the gripper can squeeze. Fraction of full strength.
arm_dance_frame_id google.protobuf.Int32Value Which dance frame to use as a reference for workspace arm moves. Including this parameter
overrides the animation frame.
body_tracking_stiffness google.protobuf.DoubleValue How hard to try to track the animated body motion.
Only applicable to animations that control both the body and the legs.
On a scale of 1 to 10 (11 for a bit extra).
Higher will result in more closely tracking the animated body motion, but possibly at the
expense of balance for more difficult animations.

AnimatedCycleParams

Field Type Label Description
animation_name google.protobuf.StringValue
enable_animation_duration google.protobuf.BoolValue
enable_leg_timing google.protobuf.BoolValue
enable_stance_shape google.protobuf.BoolValue

ArmMoveParams

Parameters specific to ArmMove move.

Field Type Label Description
shoulder_0 google.protobuf.DoubleValue Joint angles in radians for the arm joints.
shoulder_1 google.protobuf.DoubleValue
elbow_0 google.protobuf.DoubleValue
elbow_1 google.protobuf.DoubleValue
wrist_0 google.protobuf.DoubleValue
wrist_1 google.protobuf.DoubleValue
easing Easing How the motion should be paced.
gripper google.protobuf.DoubleValue Movement for the gripper.

BodyHoldParams

Parameters specific to the BodyHold move.

Field Type Label Description
rotation EulerZYXValue The robot will rotate its body to the specified orientation (roll/pitch/yaw) [rad].
translation bosdyn.api.Vec3Value The positional offset to the robot's current location [m].
entry_slices google.protobuf.DoubleValue How many "slices" (beats or sub-beats) are allowed before reaching the desired pose.
exit_slices google.protobuf.DoubleValue How many "slices" (beats or sub-beats) are allowed for the robot to return to the original
pose.

BourreeParams

Parameters for the Bourree move.

Field Type Label Description
velocity bosdyn.api.Vec2Value The speed at which we should bourree [m/s]. X is forward. Y is left.
yaw_rate google.protobuf.DoubleValue How fast the bourree should turn [rad/s].
stance_length google.protobuf.DoubleValue How far apart front and hind feet should be. [m]

ButtCircleParams

Parameters specific to the ButtCircle DanceMove.

Field Type Label Description
radius google.protobuf.DoubleValue How big a circle the robutt will move in. Described in meters.
beats_per_circle google.protobuf.DoubleValue The number of beats that elapse while performing the butt circle.
number_of_circles google.protobuf.DoubleValue The number of circles that will be performed. If non-zero, takes precedence over
beats_per_circle.
pivot Pivot The pivot point the butt circles should be centered around.
clockwise google.protobuf.BoolValue Which way to rotate.
starting_angle google.protobuf.DoubleValue Where to start. Zero is up.

ChickenHeadParams

Parameters specific to the chicken head move.

Field Type Label Description
bob_magnitude bosdyn.api.Vec3Value Bobs the head in this direction in the robot footprint frame.
beats_per_cycle google.protobuf.Int32Value How fast to bob the head.
follow google.protobuf.BoolValue Should we move the frame when the robot steps?

ClapParams

Parameters specific to clapping.

Field Type Label Description
direction bosdyn.api.Vec3Value Direction in a gravity-aligned body frame of clapping motion. A typical value for the
location is (0, 1, 0).
location bosdyn.api.Vec3Value Location in body frame of the clap. A typical value for the location is (0.4, 0, -0.5).
speed google.protobuf.DoubleValue Speed of the clap [m/s].
clap_distance google.protobuf.DoubleValue How far apart the limbs are before clapping [m].

Color

Field Type Label Description
red google.protobuf.DoubleValue
green google.protobuf.DoubleValue
blue google.protobuf.DoubleValue

CrawlParams

Parameters for the robot’s crawling gait.

Field Type Label Description
swing_slices google.protobuf.DoubleValue The number of slices (beats/sub-beats) the duration of a leg swing in the crawl gait should
be.
velocity bosdyn.api.Vec2Value The speed at which we should crawl [m/s]. X is forward. Y is left.
stance_width google.protobuf.DoubleValue The distance between the robot's left and right feet [m].
stance_length google.protobuf.DoubleValue The distance between the robot's front and back feet [m].

CustomGaitCommand

Field Type Label Description
drive_velocity_body bosdyn.api.SE2Velocity Locomotion velocity in the horizontal plane in robot body frame. (m/s, m/s, rad/s)
finished bool When true, robot will transition to a stand, then continue the sequence.
Until then, the sequence will keep looping through this move.
body_translation_offset bosdyn.api.Vec3 How much to offset the body pose. Additive with other offsets.

Meters.
body_orientation_offset EulerZYX Radians.

CustomGaitCommandLimits

Field Type Label Description
maximum_drive_velocity_body bosdyn.api.SE2Velocity Maximum absolute value of locomotion velocity in the horizontal plane in robot body frame.
(m/s, m/s, rad/s)
maximum_body_translation_offset bosdyn.api.Vec3 Maximum absolute value of the body offsets.

Meters.
maximum_body_orientation_offset EulerZYX Radians.

CustomGaitParams

Field Type Label Description
max_velocity bosdyn.api.Vec2Value Maximum steering commands that will be accepted.
max_yaw_rate google.protobuf.DoubleValue
acceleration_scaling google.protobuf.DoubleValue How much to limit steering acceleration. 1 is normal. Smaller is less acceleration.
cycle_duration google.protobuf.DoubleValue Gait pattern. When to liftoff and touchdown each leg.
fl_swing SwingPhases
two_fl_swings google.protobuf.BoolValue
second_fl_swing SwingPhases
fr_swing SwingPhases
two_fr_swings google.protobuf.BoolValue
second_fr_swing SwingPhases
hl_swing SwingPhases
two_hl_swings google.protobuf.BoolValue
second_hl_swing SwingPhases
hr_swing SwingPhases
two_hr_swings google.protobuf.BoolValue
second_hr_swing SwingPhases
show_stance_shape google.protobuf.BoolValue Relative positions of feet.
stance_shape StanceShape
com_height google.protobuf.DoubleValue Constant posture.
For a phase-dependent posture, combine with a Body move.
body_translation_offset bosdyn.api.Vec3Value
body_rotation_offset EulerZYXValue
low_speed_body_fraction google.protobuf.DoubleValue
general_swing_params SwingParams Modify the path the foot takes between liftoff and touchdown.
General swing parameters apply to legs that are not configured to have their own parameter
set.
use_fl_swing_params google.protobuf.BoolValue Individual legs can have their own parameters or use the general swing parameters.
fl_swing_params SwingParams
use_fr_swing_params google.protobuf.BoolValue
fr_swing_params SwingParams
use_hl_swing_params google.protobuf.BoolValue
hl_swing_params SwingParams
use_hr_swing_params google.protobuf.BoolValue
hr_swing_params SwingParams
stand_in_place google.protobuf.BoolValue Stand rather than stepping in place when not moving.
standard_final_stance google.protobuf.BoolValue Go back to a standard rectangular stance when ending the gait.
Otherwise maintains the customized stance shape.
show_stability_params google.protobuf.BoolValue Parameters that impact the stability of the gait rather than its appearance.
mu google.protobuf.DoubleValue Friction coefficient between the feet and the ground.
timing_stiffness google.protobuf.DoubleValue How much the robot is allowed to deviate from the specified timing.
0 means no deviation.
Otherwise: large values mean less deviation and small values mean more is acceptable.
Too much timing adjustment (low, non-zero values) may make the gait unstable.
At least a little timing adjustment is recommended for gaits with flight phases (periods with
0 feet on the ground).
step_position_stiffness google.protobuf.DoubleValue How much the robot is allowed to deviate from the specified stance shape.
0 means no deviation.
Otherwise: large values mean less deviation and small values mean more is acceptable.
Too much position adjustment (low, non-zero values) may make the gait unstable.
enable_perception_obstacle_avoidance google.protobuf.BoolValue Enable/disable various aspects of perception.
obstacle_avoidance_padding google.protobuf.DoubleValue
enable_perception_terrain_height google.protobuf.BoolValue
enable_perception_step_placement google.protobuf.BoolValue
maximum_stumble_distance google.protobuf.DoubleValue How far the robot should stumble before giving up and freezing.
trip_sensitivity google.protobuf.DoubleValue How sensitive we should be to trip detection.
On the range [0, 1], where 1 is normal sensitivity and 0 is ignoring all trips.
Useful for very aggressive gaits or when a costume is restricting leg motion.
animated_cycle_params AnimatedCycleParams Using an animated cycle to define the gait style

EulerRateZYXValue

Euler Angle rates (yaw->pitch->roll) vector that uses wrapped values so we can tell which elements are set.

Field Type Label Description
roll google.protobuf.DoubleValue
pitch google.protobuf.DoubleValue
yaw google.protobuf.DoubleValue

EulerZYX

Euler Angle (yaw->pitch->roll) vector.

Field Type Label Description
roll double
pitch double
yaw double

EulerZYXValue

Euler Angle (yaw->pitch->roll) vector that uses wrapped values so we can tell which elements are set.

Field Type Label Description
roll google.protobuf.DoubleValue
pitch google.protobuf.DoubleValue
yaw google.protobuf.DoubleValue

FadeColorParams

Field Type Label Description
top_color Color
bottom_color Color
fade_in_slices google.protobuf.DoubleValue
fade_out_slices google.protobuf.DoubleValue

FidgetStandParams

Field Type Label Description
preset FidgetStandParams.FidgetPreset
min_gaze_pitch google.protobuf.DoubleValue
max_gaze_pitch google.protobuf.DoubleValue
gaze_mean_period google.protobuf.DoubleValue
gaze_center_cfp bosdyn.api.Vec3Value
shift_mean_period google.protobuf.DoubleValue
shift_max_transition_time google.protobuf.DoubleValue
breath_min_z google.protobuf.DoubleValue
breath_max_z google.protobuf.DoubleValue
breath_max_period google.protobuf.DoubleValue
leg_gesture_mean_period google.protobuf.DoubleValue
gaze_slew_rate google.protobuf.DoubleValue
gaze_position_generation_gain bosdyn.api.Vec3Value
gaze_roll_generation_gain google.protobuf.DoubleValue

Figure8Params

Field Type Label Description
height google.protobuf.DoubleValue
width google.protobuf.DoubleValue
beats_per_cycle google.protobuf.DoubleValue

FrameSnapshotParams

Field Type Label Description
frame_id google.protobuf.Int32Value
fiducial_number google.protobuf.Int32Value
include_front_left_leg FrameSnapshotParams.Inclusion
include_front_right_leg FrameSnapshotParams.Inclusion
include_hind_left_leg FrameSnapshotParams.Inclusion
include_hind_right_leg FrameSnapshotParams.Inclusion
compensated google.protobuf.BoolValue

FrontUpParams

Parameters specific to FrontUp move.

Field Type Label Description
mirror google.protobuf.BoolValue Should we raise the hind feet instead.

GotoParams

Field Type Label Description
absolute_position bosdyn.api.Vec2Value
absolute_yaw google.protobuf.DoubleValue
step_position_stiffness google.protobuf.DoubleValue
duty_cycle google.protobuf.DoubleValue
link_to_next google.protobuf.BoolValue Should we combine with the next move into a smooth trajectory.

GripperParams

Parameters for open/close of gripper.

Field Type Label Description
angle google.protobuf.DoubleValue Angle in radians at which the gripper is open. Note that a 0 radian angle correlates to
completely closed.
speed google.protobuf.DoubleValue Speed in m/s at which the gripper should open/close to achieve the desired angle.

HopParams

Parameters specific to Hop move.

Field Type Label Description
velocity bosdyn.api.Vec2Value The velocity of the hop gait (X is forward; y is left)[m/s].
yaw_rate google.protobuf.DoubleValue How fast the hop gait should turn [rad/s].
stand_time google.protobuf.DoubleValue How long the robot should stand in between each hop.

IndependentColorParams

Field Type Label Description
top_left Color
upper_mid_left Color
lower_mid_left Color
bottom_left Color
top_right Color
upper_mid_right Color
lower_mid_right Color
bottom_right Color
fade_in_slices google.protobuf.DoubleValue
fade_out_slices google.protobuf.DoubleValue

JumpParams

Parameters for the robot making a jump.

Field Type Label Description
yaw google.protobuf.DoubleValue The amount in radians that the robot will turn while in the air.
flight_slices google.protobuf.DoubleValue The amount of time in slices (beats) that the robot will be in the air.
stance_width google.protobuf.DoubleValue The distance between the robot's left and right feet [m].
stance_length google.protobuf.DoubleValue The distance between the robot's front and back feet [m].
translation bosdyn.api.Vec2Value How far the robot should jump [m].
split_fraction google.protobuf.DoubleValue How much it should lo/td the first pair of lets ahead of the other pair. In fraction of
flight time.
lead_leg_pair JumpParams.Lead
yaw_is_absolute google.protobuf.BoolValue Should we turn to a yaw in choreography sequence frame?
translation_is_absolute google.protobuf.BoolValue Should we translate in choreography sequence frame?
absolute_yaw google.protobuf.DoubleValue The direction the robot should face upon landing relative to pose at the start of the dance.
[rad]
absolute_translation bosdyn.api.Vec2Value Where the robot should land relative to the pose at the start of the dance. [m]
swing_height google.protobuf.DoubleValue
absolute google.protobuf.BoolValue Deprecated. Deprecation Warning ***
DEPRECATED as of 3.0.0: The absolute field has been deprecated and split into the
yaw_is_absolute and translation_is_absolute fields. The following field will be deprecated
and moved to 'reserved' in a future release.

KneelCircleParams

Parameters specific to the kneel_circles move.

Field Type Label Description
location bosdyn.api.Vec3Value Location in body frame of the circle center. A typical value for the location is (0.4, 0,
-0.5).
beats_per_circle google.protobuf.Int32Value How beats per circle. One or two are reasonable values.
number_of_circles google.protobuf.DoubleValue How many circles to perform. Mutually exclusive with beats_per_circle.
offset google.protobuf.DoubleValue How far apart the feet are when circling [m].
radius google.protobuf.DoubleValue Size of the circles [m].
reverse google.protobuf.BoolValue Which way to circle.

KneelLegMove2Params

Parameters specific to KneelLegMove2 move.

Field Type Label Description
left_hip_x google.protobuf.DoubleValue Joint angles of the front left leg in radians.
left_hip_y google.protobuf.DoubleValue
left_knee google.protobuf.DoubleValue
right_hip_x google.protobuf.DoubleValue Joint angles of the front right leg in radians.
right_hip_y google.protobuf.DoubleValue
right_knee google.protobuf.DoubleValue
easing Easing How the motion should be paced.
link_to_next google.protobuf.BoolValue Should we combine with the next move into a smooth trajectory.

KneelLegMoveParams

Parameters specific to KneelLegMove move.

Field Type Label Description
hip_x google.protobuf.DoubleValue Joint angles of the left front leg in radians.
If mirrored, the joints will be flipped for the other leg.
hip_y google.protobuf.DoubleValue
knee google.protobuf.DoubleValue
mirror google.protobuf.BoolValue If mirrored is true, the joints will be flipped for the leg on the other side (right vs left)
of the body.
easing Easing How the motion should be paced.

LegJointParams

Field Type Label Description
fl_hx google.protobuf.DoubleValue
fl_hy google.protobuf.DoubleValue
fl_kn google.protobuf.DoubleValue
fr_hx google.protobuf.DoubleValue
fr_hy google.protobuf.DoubleValue
fr_kn google.protobuf.DoubleValue
hl_hx google.protobuf.DoubleValue
hl_hy google.protobuf.DoubleValue
hl_kn google.protobuf.DoubleValue
hr_hx google.protobuf.DoubleValue
hr_hy google.protobuf.DoubleValue
hr_kn google.protobuf.DoubleValue

Pace2StepParams

Parameters specific to pace translation.

Field Type Label Description
motion bosdyn.api.Vec2Value How far to move relative to starting position. [m]
absolute_motion bosdyn.api.Vec2Value Where to move relative to position at start of script. [m]
motion_is_absolute google.protobuf.BoolValue Is motion specified relative to pose at start of dance?
swing_height google.protobuf.DoubleValue Swing parameters to describe the footstep pattern during the pace translation gait. Note, a
zero (or nearly zero) value will be considered as an unspecified parameter.
swing_velocity google.protobuf.DoubleValue
yaw google.protobuf.DoubleValue How far to turn, described in radians with a positive value representing a turn to the left.
absolute_yaw google.protobuf.DoubleValue Orientation to turn to, relative to the orientation at the start of the script. [rad]
yaw_is_absolute google.protobuf.BoolValue Should we turn to a yaw in choreography sequence frame?
absolute google.protobuf.BoolValue Deprecation Warning ***
DEPRECATED as of 3.0.0: The absolute field has been deprecated and split into the
yaw_is_absolute and translation_is_absolute fields. The following field will be deprecated
and moved to 'reserved' in a future release.

RandomRotateParams

Parameters specific to the RandomRotate move.

Field Type Label Description
amplitude EulerZYXValue The amplitude [rad] of the rotation in each axis.
speed EulerRateZYXValue The speed [rad/s] of the motion in each axis.
speed_variation google.protobuf.DoubleValue The amount of variation allowed in the speed of the random rotations [m/s]. Note,
this must be a positive value.
num_speed_tiers google.protobuf.Int32Value The specified speed values will be split into this many number of tiers between
the bounds of [speed - speed_variation, speed + speed variation]. Then a tier (with
a specified speed) will be randomly chosen and performed for each axis.
tier_variation google.protobuf.DoubleValue How much can the output speed vary from the chosen tiered speed.

RippleColorParams

Field Type Label Description
main Color
secondary Color
pattern RippleColorParams.Pattern
light_side RippleColorParams.LightSide
increment_slices google.protobuf.DoubleValue

RotateBodyParams

Parameters for the robot rotating the body.

Field Type Label Description
rotation EulerZYXValue The robot will rotate its body to the specified orientation (roll/pitch/yaw).
return_to_start_pose google.protobuf.BoolValue If true, the robot will transition back to the initial pose we started at before this
choreography sequence move begin execution, and otherwise it will remain in whatever pose it
is in after completing the choreography sequence move.

RunningManParams

Parameters specific to RunningMan move.

Field Type Label Description
velocity bosdyn.api.Vec2Value
swing_height google.protobuf.DoubleValue How high to pick up the forward-moving feet [m].
spread google.protobuf.DoubleValue How far to spread the contralateral pair of feet [m].
reverse google.protobuf.BoolValue Should we reverse the motion?
pre_move_cycles google.protobuf.Int32Value How many full running man cycles should the robot complete in place before starting to move
with the desired velocity.
speed_multiplier google.protobuf.DoubleValue Do the move at some multiple of the dance cadence.
duty_cycle google.protobuf.DoubleValue What fraction of the time to have feet on the ground.
com_height google.protobuf.DoubleValue How high to hold the center of mass above the ground on average.

SetColorParams

Field Type Label Description
left_color Color
right_same_as_left google.protobuf.BoolValue
right_color Color
fade_in_slices google.protobuf.DoubleValue
fade_out_slices google.protobuf.DoubleValue

SideParams

Parameters for moves that can go to either side.

Field Type Label Description
side SideParams.Side

StanceShape

Field Type Label Description
length google.protobuf.DoubleValue
width google.protobuf.DoubleValue
front_wider_than_hind google.protobuf.DoubleValue
left_longer_than_right google.protobuf.DoubleValue
left_forward_of_right google.protobuf.DoubleValue

StepParams

Field Type Label Description
foot Leg Which foot to use (FL = 1, FR = 2, HL = 3, HR = 4).
offset bosdyn.api.Vec2Value Offset of the foot from it's nominal position, in meters.
second_foot Leg Should we use a second foot? (None = 0, FL = 1, FR = 2, HL = 3, HR = 4).
swing_waypoint bosdyn.api.Vec3Value Where should the swing foot go? This vector should be described in a gravity-aligned body
frame relative to the centerpoint of the swing. If set to {0,0,0}, uses the default swing
path.
swing_height google.protobuf.DoubleValue Parameters for altering swing.
Note that these will have no effect if swing_waypoint is specified. As well, a zero (or
nearly zero) value will be considered as an unspecified parameter.

meters
liftoff_velocity google.protobuf.DoubleValue m/s
touchdown_velocity google.protobuf.DoubleValue m/s
mirror_x google.protobuf.BoolValue Should we mirror the offset for the second foot?
Ignored if second_foot is set to None
mirror_y google.protobuf.BoolValue
mirror google.protobuf.BoolValue Deprecated. Deprecation Warning ***
DEPRECATED as of 2.3.0: The mirror field has been deprecated in favor for a more descriptive
break down to mirror_x and mirror_y.
The following field will be deprecated and moved to 'reserved' in a future release.
waypoint_dwell google.protobuf.DoubleValue What fraction of the swing should be spent near the waypoint.
touch google.protobuf.BoolValue Should we touch the ground and come back rather than stepping to a new place?
touch_offset bosdyn.api.Vec2Value

SwayParams

Parameters specific to Sway move.

Field Type Label Description
vertical google.protobuf.DoubleValue How far to move up/down [m].
horizontal google.protobuf.DoubleValue How far to move left/right [m].
roll google.protobuf.DoubleValue How much to roll [rad].
pivot Pivot What point on the robot's body should the swaying be centered at. For example, should the
head move instead of the butt?
style SwayParams.SwayStyle What style motion should we use?
pronounced google.protobuf.DoubleValue How pronounced should the sway-style be? The value is on a scale from [0,1.0].
hold_zero_axes google.protobuf.BoolValue Should the robot hold previous values for the vertical, horizontal, and roll axes if the
value is left unspecified (value of zero).

SwingParams

Field Type Label Description
height google.protobuf.DoubleValue
liftoff_speed google.protobuf.DoubleValue
vertical_speed google.protobuf.DoubleValue
vertical_acceleration google.protobuf.DoubleValue
overlay_outside google.protobuf.DoubleValue
overlay_forward google.protobuf.DoubleValue
low_speed_fraction google.protobuf.DoubleValue

SwingPhases

Field Type Label Description
liftoff_phase google.protobuf.DoubleValue
touchdown_phase google.protobuf.DoubleValue

TurnParams

Parameters specific to turning.

Field Type Label Description
yaw google.protobuf.DoubleValue How far to turn, described in radians with a positive value representing a turn to the left.
absolute_yaw google.protobuf.DoubleValue Orientation to turn to, relative to the orientation at the start of the script. [rad]
yaw_is_absolute google.protobuf.BoolValue Should we turn to a yaw in choreography sequence frame?
swing_height google.protobuf.DoubleValue Swing parameters to describe the footstep pattern during the turning [height in meters].
Note, a zero (or nearly zero) value will be considered as an unspecified parameter.
swing_velocity google.protobuf.DoubleValue Swing parameter to describe the foot's swing velocity during the turning [m/s]. Note, a zero
(or nearly zero) value will be considered as an unspecified parameter.
motion bosdyn.api.Vec2Value How far to move relative to starting position. [m]
absolute_motion bosdyn.api.Vec2Value Where to move relative to position at start of script. [m]
motion_is_absolute google.protobuf.BoolValue Is motion specified relative to pose at start of dance?
absolute google.protobuf.BoolValue Deprecated. Deprecation Warning ***
DEPRECATED as of 3.0.0: The absolute field has been deprecated and split into the
yaw_is_absolute and translation_is_absolute fields. The following field will be deprecated
and moved to 'reserved' in a future release.

TwerkParams

Parameters specific to twerking

Field Type Label Description
height google.protobuf.DoubleValue How far the robot should twerk in meters.

WorkspaceArmMoveParams

Field Type Label Description
rotation EulerZYXValue The robot will rotate its body to the specified orientation (roll/pitch/yaw) [rad].
translation bosdyn.api.Vec3Value The positional offset to the robot's current location [m].
absolute google.protobuf.BoolValue Go to an absolute position/orientation? Otherwise, relative to starting pose.
frame ArmMoveFrame What frame is the motion specified in.
easing Easing How the motion should be paced.
dance_frame_id google.protobuf.Int32Value If we're using the dance frame, which one?

ArmMoveFrame

Name Number Description
ARM_MOVE_FRAME_UNKNOWN 0
ARM_MOVE_FRAME_CENTER_OF_FOOTPRINT 1
ARM_MOVE_FRAME_HAND 2
ARM_MOVE_FRAME_BODY 3
ARM_MOVE_FRAME_SHOULDER 4
ARM_MOVE_FRAME_SHADOW 5
ARM_MOVE_FRAME_DANCE 6

Easing

Enum to describe the type of easing to perform for the slices at either (or both) the beginning and end of a move.

Name Number Description
EASING_UNKNOWN 0
EASING_LINEAR 1
EASING_QUADRATIC_INPUT 2
EASING_QUADRATIC_OUTPUT 3
EASING_QUADRATIC_IN_OUT 4
EASING_CUBIC_INPUT 5
EASING_CUBIC_OUTPUT 6
EASING_CUBIC_IN_OUT 7
EASING_EXPONENTIAL_INPUT 8
EASING_EXPONENTIAL_OUTPUT 9
EASING_EXPONENTIAL_IN_OUT 10

FidgetStandParams.FidgetPreset

Name Number Description
PRESET_UNKNOWN 0
PRESET_CUSTOM 1
PRESET_INTEREST 2
PRESET_PLAYFUL 3
PRESET_FEAR 4
PRESET_NERVOUS 5
PRESET_EXHAUSTED 6

FrameSnapshotParams.Inclusion

Name Number Description
INCLUSION_UNKNOWN 0
INCLUSION_IF_STANCE 1
INCLUSION_INCLUDED 2
INCLUSION_EXCLUDED 3

JumpParams.Lead

If split_fraction is non-zero, which legs to lift first.

Name Number Description
LEAD_UNKNOWN 0
LEAD_AUTO 1
LEAD_FRONT 2
LEAD_HIND 3
LEAD_LEFT 4
LEAD_RIGHT 5

LedLight

Name Number Description
LED_LIGHT_UNKNOWN 0
LED_LIGHT_LEFT1 1
LED_LIGHT_LEFT2 2
LED_LIGHT_LEFT3 3
LED_LIGHT_LEFT4 4
LED_LIGHT_RIGHT1 5
LED_LIGHT_RIGHT2 6
LED_LIGHT_RIGHT3 7
LED_LIGHT_RIGHT4 8

Leg

Enum to describe which leg is being referenced in specific choreography sequence moves.

Name Number Description
LEG_UNKNOWN 0
LEG_FRONT_LEFT 1
LEG_FRONT_RIGHT 2
LEG_HIND_LEFT 3
LEG_HIND_RIGHT 4
LEG_NO_LEG -1

Pivot

Enum for the pivot point for certain choreography sequence moves.

Name Number Description
PIVOT_UNKNOWN 0
PIVOT_FRONT 1
PIVOT_HIND 2
PIVOT_CENTER 3

RippleColorParams.LightSide

Name Number Description
LIGHT_SIDE_UNKNOWN 0
LIGHT_SIDE_LEFT 1
LIGHT_SIDE_RIGHT 2
LIGHT_SIDE_BOTH_IN_SEQUENCE 3
LIGHT_SIDE_BOTH_MATCHING 4

RippleColorParams.Pattern

Name Number Description
PATTERN_UNKNOWN 0
PATTERN_FLASHING 1
PATTERN_SNAKE 2
PATTERN_ALTERNATE_COLORS 3
PATTERN_FINE_GRAINED_ALTERNATE_COLORS 4

SideParams.Side

Name Number Description
SIDE_UNKNOWN 0
SIDE_LEFT 1
SIDE_RIGHT 2

SwayParams.SwayStyle

The type of motion used by the Sway sequence move.

Name Number Description
SWAY_STYLE_UNKNOWN 0
SWAY_STYLE_STANDARD 1
SWAY_STYLE_FAST_OUT 2
SWAY_STYLE_FAST_RETURN 3
SWAY_STYLE_SQUARE 4
SWAY_STYLE_SPIKE 5
SWAY_STYLE_PLATEAU 6

Top

bosdyn/api/spot/choreography_sequence.proto

ActiveMove

Field Type Label Description
move MoveParams Any parameters that had to be adjusted into the legal range will have their adjusted values.
custom_gait_command_limits CustomGaitCommandLimits

AnimateArm

Field Type Label Description
joint_angles ArmJointAngles Full arm joint angle specification.
hand_pose AnimateArm.HandPose The hand position in the animation frame

AnimateArm.HandPose

An SE3 Pose for the hand where orientation is specified using either a quaternion or euler angles

Field Type Label Description
position bosdyn.api.Vec3Value
euler_angles EulerZYXValue The hand's orientation described with euler angles (yaw, pitch, roll).
quaternion bosdyn.api.Quaternion The hand's orientation described with a quaternion.

AnimateBody

The AnimateBody keyframe describes the body’s position and orientation. At least one dimension of the body must be specified.

Field Type Label Description
body_pos bosdyn.api.Vec3Value The body position in the animation frame.
com_pos bosdyn.api.Vec3Value The body's center of mass position in the animation frame.
euler_angles EulerZYXValue The body's orientation described with euler angles (yaw, pitch, roll).
quaternion bosdyn.api.Quaternion The body's orientation described with a quaternion.

AnimateGripper

Field Type Label Description
gripper_angle google.protobuf.DoubleValue

AnimateLegs

The AnimateLegs keyframe describes each leg using either joint angles or the foot position.

Field Type Label Description
fl AnimateSingleLeg Front left leg.
fr AnimateSingleLeg Front right leg.
hl AnimateSingleLeg Hind left leg.
hr AnimateSingleLeg Hind right leg.

AnimateSingleLeg

A single leg keyframe to describe the leg motion.

Field Type Label Description
joint_angles LegJointAngles Full leg joint angle specification.
foot_pos bosdyn.api.Vec3Value The foot position of the leg in the animation frame.
stance google.protobuf.BoolValue 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.

Animation

Represents an animated dance move that can be used within choreographies after uploading.

Field Type Label Description
name string The name of the animated move, which is how it will be referenced in choreographies.
animation_keyframes AnimationKeyframe repeated 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.
controls_arm bool Indicators as to which parts of the robot that the move controls.
controls_legs bool
controls_body bool
controls_gripper bool
track_swing_trajectories bool Track animated swing trajectories. Otherwise, takes standard swings between animated liftoff
and touchdown locations.
assume_zero_roll_and_pitch bool 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.
arm_playback Animation.ArmPlayback
bpm double Optional bpm that the animation is successful at.
retime_to_integer_slices bool 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.
minimum_parameters AnimateParams 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.
default_parameters AnimateParams
maximum_parameters AnimateParams
truncatable bool Indicates if the animated moves can be shortened (the animated move will be cut off). Not
supported for leg moves.
extendable bool Indicates if the animated moves can be stretched (animated move will loop). Not supported for
leg moves.
neutral_start bool Indicates if the move should start in a neutral stand position.
precise_steps bool Step exactly at the animated locations, even at the expense of balance.
By default, the optimizer may adjust step locations slightly.
precise_timing bool Deprecated. DEPRECATED as of 3.3.0: The boolean field has been replaced by the more fine-grained control
of timing_adjustability. The following field will be deprecated and moved to 'reserved' in a
future release.
timing_adjustability double How much the optimizer is allowed to adjust the timing.
On the range [-1, 1].
-1: Everything will be timed exactly as animated, even at the expense of balance.
0: Default value: some timing adjust allowed.
1: Timing can be adjusted drastically.
arm_required bool If set true, this animation will not run unless the robot has an arm.
arm_prohibited bool If set true, this animation will not run unless the robot has no arm.
no_looping bool If the animation completes before the move's duration, freeze rather than looping.
starts_sitting bool If the animation starts from a sit pose. Default starting pose is stand.
custom_gait_cycle bool If true, this animation can be used as direct input to custom gait
to define the gait style

AnimationKeyframe

Field Type Label Description
time double Time from the start of the animation for this frame.
gripper AnimateGripper Different body parts the animated move can control.
It can control multiple body parts at once.
arm AnimateArm
body AnimateBody
legs AnimateLegs

ArmJointAngles

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.

Field Type Label Description
shoulder_0 google.protobuf.DoubleValue
shoulder_1 google.protobuf.DoubleValue
elbow_0 google.protobuf.DoubleValue
elbow_1 google.protobuf.DoubleValue
wrist_0 google.protobuf.DoubleValue
wrist_1 google.protobuf.DoubleValue

ChoreographerDisplayInfo

Information for the Choreographer to display.

Field Type Label Description
color ChoreographerDisplayInfo.Color
markers int32 repeated 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.
description string Textual description to be displayed in the GUI.
image string Image path (local to the UI) to display as an icon. May be an animated gif.
category ChoreographerDisplayInfo.Category

ChoreographerDisplayInfo.Color

Color of the object. Set it to override the default category color.

Field Type Label Description
r int32 RGB values for color ranging from [0,255].
g int32
b int32
a double Alpha value for the coloration ranges from [0,1].

ChoreographerSave

Describes the metadata and information only used by the Choreographer GUI, which isn’t used in the API

Field Type Label Description
choreography_sequence ChoreographySequence The main ChoreographySequence that makes up the dance and is sent to the robot.
music_file string If specified this is the UI local path of the music to load.
music_start_slice double UI specific member that describes exactly when the music should start, in slices. This is for
time sync issues.
choreography_start_slice double The start slice for the choreographer save.

ChoreographyCommandRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
commands MoveCommand repeated Commands intended for individual moves.
Repeated because multiple moves may be playing simultaneously and we may want to command
multiple of them.
lease bosdyn.api.Lease The Lease to show ownership of the robot body.
command_end_time google.protobuf.Timestamp When the commands expire. In the robot's clock.

ChoreographyCommandResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header
lease_use_result bosdyn.api.LeaseUseResult
status ChoreographyCommandResponse.Status repeated One status for each command sent.

ChoreographyInfo

Describes metadata for the Choreography sequence that can be used for a number of different UIs

Field Type Label Description
labels string repeated the list of user assigned categories that the sequence belongs to

ChoreographySequence

Represents a particular choreography sequence, made up of MoveParams.

Field Type Label Description
name string Display name or file name associated with the choreography sequence.
slices_per_minute double Number of slices per minute in the choreography sequence. Typically a slice will correspond
to 1/4 a beat.
moves MoveParams repeated All of the moves in this choreography sequence.
choreography_info ChoreographyInfo Metadata associated with the sequence.
entrance_state MoveInfo.TransitionState Can be used to specify an explicit entrance_state in the case where the first legs-track move
accepts multiple entrance_states.
Will also be used if the sequence contains no legs-track moves.
Can otherwise be left unset.
If set and not within the set of acceptable entrance_states for the first legs-track move,
the Sequence will be considered invalid.

ChoreographyStateLog

Field Type Label Description
key_frames LoggedStateKeyFrame repeated 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.

ChoreographyStatusRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header

ChoreographyStatusResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header
status ChoreographyStatusResponse.Status
execution_id int32 If dancing (or preparing to dance), the unique execution_id matching the one from
ExecuteChoreographyResponse. If not dancing, 0.
current_slice double Where we are in the script. (slice = 1/4 beat; standard unit of "time" within Choreography)
active_moves ActiveMove repeated All of the moves currently executing.
sequence_slices int32 Length of the current sequence.
sequence_slices_per_minute double Cadence of the current sequence.
validity_time google.protobuf.Timestamp When this was true in robot time.
sequence_name string Name of the active sequence, None if the robot is not in a dance state.

ChoreographyTimeAdjustRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
override_start_time google.protobuf.Timestamp The absolute time to start the choreography at. This start time will override the start time
defined in an ExecuteChoreographyRequest if it fits within the limits defined by the
acceptable_time_difference and the override_validity_time. This should be in the robot's
clock.
acceptable_time_difference google.protobuf.Duration The maximum difference in time, in seconds, between an ExecuteChoreography start time and the
override time where the override start time will used instead of the ExecuteChoreography
start time. If the difference between the override time and the ExecuteChoreographyRequest
time is bigger than the acceptable_time_difference value, the override time will not be used.
When specified the acceptable_time_difference can be at most 2 minutes. If not specified, the
acceptable_time_difference will be 20 seconds.
validity_time google.protobuf.Duration For what period of time, in seconds from the current moment, should this override start time
be considered valid. override start times that are further in the future than the override
validity period won't be accepted when received. When specified, override_validity_time can
be at most 5 minutes past the current time. If not specified override_validity_time will be
60 seconds.

ChoreographyTimeAdjustResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header
status ChoreographyTimeAdjustResponse.Status
warnings string repeated If certain parameters didn't fall within the correct limits warning messages describing those
issues will be populated here to indicate those problems. If there were issues with
parameters other than the override_start_time there may be warnings even if the response
status was STATUS_OK.

ClearAllSequenceFilesRequest

Reset to a clean slate with no retained files by deleting all non-permanent choreography related files

Field Type Label Description
header bosdyn.api.RequestHeader Common request header

ClearAllSequenceFilesResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status ClearAllSequenceFilesResponse.Status

DeleteSequenceRequest

Delete the retained file for a choreography sequence so the sequence will be forgotten on reboot

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
sequence_name string Name of the sequence to delete.

DeleteSequenceResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status DeleteSequenceResponse.Status

DownloadRobotStateLogRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
log_type DownloadRobotStateLogRequest.LogType Which data should we download.

DownloadRobotStateLogResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header
status DownloadRobotStateLogResponse.Status Return status for the request.
chunk bosdyn.api.DataChunk 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.

ExecuteChoreographyRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
choreography_sequence_name string The string name of the ChoreographySequence to use.
start_time google.protobuf.Timestamp 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.
choreography_starting_slice double The slice (betas/sub-beats) that the choreography should begin execution at.
lease bosdyn.api.Lease The Lease to show ownership of the robot body.

ExecuteChoreographyResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header
lease_use_result bosdyn.api.LeaseUseResult
status ExecuteChoreographyResponse.Status
execution_id int32 Unique ID for the execution.
Will increment whenever an ExecuteChoreographyRequest is received.
Will reset upon robot boot.

GetChoreographySequenceRequest

Request all the information needed to play a choreography sequence, this includes the sequence itself and any animations the sequence uses.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
sequence_name string Name of the requested sequence.

GetChoreographySequenceResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status GetChoreographySequenceResponse.Status
choreography_sequence ChoreographySequence ChoreographySequence with the name of the requested sequence.
animated_moves Animation repeated All Animations used in the returned ChoreographySequence.

LegJointAngles

Description of each leg joint angle (hip x/y and knee) in radians.

Field Type Label Description
hip_x double
hip_y double
knee double

ListAllMovesRequest

Request a list of all possible moves and the associated parameters (min/max values).

Field Type Label Description
header bosdyn.api.RequestHeader Common request header

ListAllMovesResponse

Response for ListAllMoves that defines the list of available moves and their parameter types.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header
moves MoveInfo repeated List of moves that the robot knows about.
move_param_config string A copy of the MoveParamsConfig.txt that the robot is using.

ListAllSequencesRequest

Request a list of all playable choreography sequences that the robot knows about

Field Type Label Description
header bosdyn.api.RequestHeader Common request header

ListAllSequencesResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
known_sequences string repeated Deprecated. DEPRECATED as of 3.2.0: The string list of known sequence names has been
deprecated and replaced by the repeated field sequence_info.
sequence_info SequenceInfo repeated List of choreography sequences the robot knows about.

LoggedFootContacts

Field Type Label Description
fr_contact bool Boolean indicating whether or not the robot's foot is in contact with the ground.
fl_contact bool
hr_contact bool
hl_contact bool

LoggedJoints

Field Type Label Description
fl LegJointAngles front left leg joint angles.
fr LegJointAngles front right leg joint angles.
hl LegJointAngles hind left leg joint angles.
hr LegJointAngles hind right leg joint angles.
arm ArmJointAngles Full set of joint angles for the arm and gripper.
gripper_angle google.protobuf.DoubleValue

LoggedStateKeyFrame

Field Type Label Description
joint_angles LoggedJoints Full set of joint angles for the robot.
foot_contact_state LoggedFootContacts Foot contacts for the robot.
animation_tform_body bosdyn.api.SE3Pose 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.
timestamp google.protobuf.Timestamp The timestamp (in robot time) for the key frame.

ModifyChoreographyInfoRequest

Edit the metadata of a choreography sequence and update any retained files for that sequence with the new metadata

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
sequence_name string Name of the sequence to be modified
add_labels string repeated Labels to be added to the sequence's metadata
remove_labels string repeated Labels to be removed from the sequence's metadata

ModifyChoreographyInfoResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status ModifyChoreographyInfoResponse.Status

MoveCommand

Either, both, or neither of move_type and move_id can be used to specify which move this command is intended for.

Field Type Label Description
move_type string Name of the move type this command is intended for.
move_id int32 ID of the move this command is intended for.
custom_gait_command CustomGaitCommand

MoveInfo

Defines properties of a choreography move.

Field Type Label Description
name string Unique ID of the move type.
move_length_slices int32 The duration of this move in slices (usually 1/4 beats).
move_length_time double The duration of this move in seconds. If specified, overrides move_length_slices.
is_extendable bool If true, the duration may be adjusted from the default specified by move_length_slices or
move_length_time.
min_move_length_slices int32 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.
max_move_length_slices int32
min_time double Bounds on the duration in time.
These apply to extendable moves, but may also override move_length_slices for some BPM.
max_time double
entrance_states MoveInfo.TransitionState repeated The admissible states the robot can be in currently for this move to execute.
exit_state MoveInfo.TransitionState The state of the robot after the move is complete.
controls_arm bool Indicators as to which parts of the robot that the move controls.
controls_legs bool
controls_body bool
controls_gripper bool
controls_lights bool
controls_annotations bool
is_looping bool
display ChoreographerDisplayInfo Information for the GUI tool to visualize the sequence move info.
animated_move_generated_id google.protobuf.StringValue 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.

MoveParams

Defines varying parameters for a particular instance of a move.

Field Type Label Description
type string Unique ID of the move type that these params are associated with.
start_slice int32 How many slices since the start of the song this move should be executed at.
requested_slices int32 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.
id int32 The ID number can be optionally set by the client as part of the UploadChoreographyRequest.
If not set by the client, the robot will assign an id to each move that is unique within the
sequence. The ID (either set by the client or the robot) will be reported in the ActiveMoves
in the ChoreographyStatusResponse. The ID can be used to specify which move a Command is
intended for.
jump_params JumpParams
rotate_body_params RotateBodyParams
step_params StepParams
butt_circle_params ButtCircleParams
turn_params TurnParams
pace_2step_params Pace2StepParams
twerk_params TwerkParams
chicken_head_params ChickenHeadParams
clap_params ClapParams
front_up_params FrontUpParams
sway_params SwayParams
body_hold_params BodyHoldParams
arm_move_params ArmMoveParams
kneel_leg_move_params KneelLegMoveParams
running_man_params RunningManParams
kneel_circle_params KneelCircleParams
gripper_params GripperParams
hop_params HopParams
random_rotate_params RandomRotateParams
crawl_params CrawlParams
side_params SideParams
bourree_params BourreeParams
workspace_arm_move_params WorkspaceArmMoveParams
figure8_params Figure8Params
kneel_leg_move2_params KneelLegMove2Params
fidget_stand_params FidgetStandParams
goto_params GotoParams
frame_snapshot_params FrameSnapshotParams
set_color_params SetColorParams
ripple_color_params RippleColorParams
fade_color_params FadeColorParams
independent_color_params IndependentColorParams
custom_gait_params CustomGaitParams
leg_joint_params LegJointParams
animate_params AnimateParams

SaveSequenceRequest

Write a choreography sequence as a file to robot memory so it will be retained through reboot

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
sequence_name string Name of the sequence to be added to the selection of retained sequences
add_labels string repeated List of labels to add to the sequence when it is being saved

SaveSequenceResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status SaveSequenceResponse.Status

SequenceInfo

Field Type Label Description
name string
labels string repeated
saved_state SequenceInfo.SavedState Use temporary sequences during development with choreographer, and then tell the robot to
retain the final version of the sequence so that it can be played back later from other
interfaces, like the tablet
exit_state MoveInfo.TransitionState The exit transition state of the sequence.

StartRecordingStateRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
continue_recording_duration google.protobuf.Duration 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.
recording_session_id uint64 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.

StartRecordingStateResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header
status StartRecordingStateResponse.Status
recording_session_id uint64 Unique identifier for the current recording session

StopRecordingStateRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header

StopRecordingStateResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header

UploadAnimatedMoveRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header
animated_move_generated_id google.protobuf.StringValue 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.
animated_move Animation AnimatedMove to upload to the robot and create a dance move from.

UploadAnimatedMoveResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status UploadAnimatedMoveResponse.Status
warnings string repeated 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.

UploadChoreographyRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
choreography_sequence ChoreographySequence ChoreographySequence to upload and store in memory
non_strict_parsing bool 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.

UploadChoreographyResponse

Field Type Label Description
header bosdyn.api.ResponseHeader 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.
warnings string repeated 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.

Animation.ArmPlayback

Mode for hand trajectory playback

Name Number Description
ARM_PLAYBACK_DEFAULT 0 Playback as specified. Arm animations specified with joint angles playback in jointspace
and arm animations specified as hand poses playback in workspace.
ARM_PLAYBACK_JOINTSPACE 1 Playback in jointspace. Arm animation will be most consistent relative to the body
ARM_PLAYBACK_WORKSPACE 2 Playback in workspace. Hand pose animation will be most consistent relative to the
current footprint. Reference frame is animation frame.
ARM_PLAYBACK_WORKSPACE_DANCE_FRAME 3 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.

ChoreographerDisplayInfo.Category

Move Category affects the grouping in the choreographer list view, as well as the color it’s displayed with.

Name Number Description
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

ChoreographyCommandResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_ACCEPTED_WITH_MODIFICATION 2
STATUS_LEASE_ERROR 3
STATUS_NO_MATCHING_MOVE 4
STATUS_INVALID_COMMAND 5
STATUS_ALREADY_EXPIRED 6

ChoreographyStatusResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_DANCING 1
STATUS_COMPLETED_SEQUENCE 2
STATUS_PREPPING 3
STATUS_WAITING_FOR_START_TIME 4
STATUS_VALIDATING 5
STATUS_INTERRUPTED 6
STATUS_FALLEN 7
STATUS_POWERED_OFF 8
STATUS_OTHER 9

ChoreographyTimeAdjustResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status unknown. Do not use.
STATUS_OK 1 The adjusted time value was accepted and stored.
STATUS_BEFORE_CURRENT_TIME 2 The adjusted time was not stored, time requested is too far in the past.
STATUS_EXCEEDS_VALIDITY_TIME 3 The override time was not stored, time requested exceeded the validity time limit.
STATUS_OVERRIDE_TIME_UNSET 4 No override start time was provided.

ClearAllSequenceFilesResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Do not use.
STATUS_OK 1 All retained sequences were successfully removed from robot memory
STATUS_FAILED_TO_DELETE 2 Deletion of all retained files failed

DeleteSequenceResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Do not use.
STATUS_OK 1 The sequence was successfully deleted
STATUS_UNKNOWN_SEQUENCE 2 The sequence does not exist
STATUS_ALREADY_TEMPORARY 3 The sequence is already temporary and will be removed at the next reboot.
STATUS_PERMANENT_SEQUENCE 4 Permanent sequences cannot be deleted

DownloadRobotStateLogRequest.LogType

Name Number Description
LOG_TYPE_UNKNOWN 0 Unknown. Do not use.
LOG_TYPE_MANUAL 1 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_LAST_CHOREOGRAPHY 2 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.

DownloadRobotStateLogResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status unknown. Do not use.
STATUS_OK 1 The log data downloaded successfully and is complete.
STATUS_NO_RECORDED_INFORMATION 2 Error where there is no robot state information logged in the choreography service.
STATUS_INCOMPLETE_DATA 3 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.

ExecuteChoreographyResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_INVALID_UPLOADED_CHOREOGRAPHY 2
STATUS_ROBOT_COMMAND_ISSUES 3
STATUS_LEASE_ERROR 4
STATUS_UNKNOWN_SEQUENCE 5

GetChoreographySequenceResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Do not use.
STATUS_OK 1 Finding + returning the sequence succeeded.
STATUS_UNKNOWN_SEQUENCE 2 The requested sequence was not found.

ModifyChoreographyInfoResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Do not use.
STATUS_OK 1 The sequence was successfully modified
STATUS_UNKNOWN_SEQUENCE 2 The sequence does not exist
STATUS_PERMANENT_SEQUENCE 3 Permanent sequences cannot be modified
STATUS_FAILED_TO_UPDATE 4 The changes were made, but the retained sequence file was not updated and
changes were reverted

MoveInfo.TransitionState

The state that the robot is in at the start or end of a move.

Name Number Description
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.

SaveSequenceResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Do not use.
STATUS_OK 1 The sequence was successfully saved
STATUS_UNKNOWN_SEQUENCE 2 The requested sequence was not found
STATUS_PERMANENT_SEQUENCE 3 This sequence is already saved in the release
STATUS_FAILED_TO_SAVE 4 We failed to save a file with the sequence information to robot

SequenceInfo.SavedState

Name Number Description
SAVED_STATE_UNKNOWN 0 Status unknown; do not use
SAVED_STATE_TEMPORARY 1 Sequence will be forgotten on reboot
SAVED_STATE_RETAINED 2 A file for this sequence is stored on the robot; the sequence will be loaded
to memory each time the robot boots
SAVED_STATE_PERMANENT 3 Sequence was built into the release and can't be deleted

StartRecordingStateResponse.Status

The status for the start recording request.

Name Number Description
STATUS_UNKNOWN 0 Status unknown; do not use.
STATUS_OK 1 The request succeeded and choreography has either started, or continued with an extended
duration based on if a session_id was provided.
STATUS_UNKNOWN_RECORDING_SESSION_ID 2 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_RECORDING_BUFFER_FULL 3 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

UploadAnimatedMoveResponse.Status

Name Number Description
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_PING_RESPONSE 3 Treated this message as a ping. Responding to demonstrate connectivity.

Top

bosdyn/api/spot/choreography_service.proto

ChoreographyService

Method Name Request Type Response Type Description
ListAllMoves ListAllMovesRequest ListAllMovesResponse List the available dance moves and their parameter information.
ListAllSequences ListAllSequencesRequest ListAllSequencesResponse List the available choreography sequences currently on the robot.
GetChoreographySequence GetChoreographySequenceRequest GetChoreographySequenceResponse Return the ChoreographySequence with the given name and any Animations used in that sequence.
DeleteSequence DeleteSequenceRequest DeleteSequenceResponse Delete a retained choreography sequence from the collection of user uploaded
choreography sequences.
SaveSequence SaveSequenceRequest SaveSequenceResponse Save a user uploaded choreography sequence to the robots collection of
retained choreography sequences.
ModifyChoreographyInfo ModifyChoreographyInfoRequest ModifyChoreographyInfoResponse Modify the metadata of a choreography sequence.
ClearAllSequenceFiles ClearAllSequenceFilesRequest ClearAllSequenceFilesResponse Clear all retained choreography sequence files from robot memory.
UploadChoreography UploadChoreographyRequest UploadChoreographyResponse Upload a dance to the robot.
UploadAnimatedMove UploadAnimatedMoveRequest UploadAnimatedMoveResponse Upload an animation to the robot.
ExecuteChoreography ExecuteChoreographyRequest ExecuteChoreographyResponse Execute the uploaded dance.
StartRecordingState StartRecordingStateRequest StartRecordingStateResponse Manually start (or continue) recording the robot state.
StopRecordingState StopRecordingStateRequest StopRecordingStateResponse Manually stop recording the robot state.
DownloadRobotStateLog DownloadRobotStateLogRequest DownloadRobotStateLogResponse stream Download log of the latest recorded robot state information.
ChoreographyStatus ChoreographyStatusRequest ChoreographyStatusResponse Report the status of a dancing robot.
ChoreographyCommand ChoreographyCommandRequest ChoreographyCommandResponse Commands intended for individual dance moves that are currently executing.
ChoreographyTimeAdjust ChoreographyTimeAdjustRequest ChoreographyTimeAdjustResponse Adjust the time when a robot should start dancing within a tolerance.

Top

bosdyn/api/spot/door.proto

DoorCommand

Door Command specific request and Feedback.

DoorCommand.AutoGraspCommand

The robot searches along a ray for the door handle and automatically grasp it before executing door opening.

Field Type Label Description
frame_name string The name of the frame that the following fields are expressed in.
search_ray_start_in_frame bosdyn.api.Vec3 The start of the ray the robot searches along for the door handle.
search_ray_end_in_frame bosdyn.api.Vec3 The end of the ray the robot searches along for the door handle.
hinge_side DoorCommand.HingeSide The side of the hinge with respect to the robot when facing the door.
swing_direction DoorCommand.SwingDirection The direction the door moves with respect to the robot.

DoorCommand.AutoPushCommand

Open doors that do not require a grasp, just a push. This could be a door with no latching mechanism that just requires a push, or a door with a pushbar. The robot will automatically push the door open and walk through.

Field Type Label Description
frame_name string The name of the frame that the following fields are expressed in.
push_point_in_frame bosdyn.api.Vec3 The point that the robot will push on.
hinge_side DoorCommand.HingeSide The side of the hinge with respect to the robot when facing the door.

DoorCommand.Feedback

Field Type Label Description
status DoorCommand.Feedback.Status Current status of the command.
distance_past_threshold double This is the distance the robot (i.e. the origin of the 'body' frame) is past the door
frame threshold. When it's negative the robot is on the starting side of the door, 0 when
the robot is in the middle of the door, and positive when the robot is on the finishing
side.

DoorCommand.Request

Field Type Label Description
auto_grasp_command DoorCommand.AutoGraspCommand
warmstart_command DoorCommand.WarmstartCommand
auto_push_command DoorCommand.AutoPushCommand

DoorCommand.WarmstartCommand

The robot is already grasping the door handle and will continue opening the door based on user specified params.

Field Type Label Description
hinge_side DoorCommand.HingeSide The side of the hinge with respect to the robot when facing the door.
swing_direction DoorCommand.SwingDirection The direction the door moves with respect to the robot.
handle_type DoorCommand.HandleType The type of handle on the door.

OpenDoorCommandRequest

A door command for the robot to execute plus a lease.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease The Lease to show ownership of the robot.
door_command DoorCommand.Request The command to execute.

OpenDoorCommandResponse

Response to the door command request.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.
status OpenDoorCommandResponse.Status Return status for a request.
message string Human-readable error description. Not for programmatic analysis.
door_command_id uint32 Unique identifier for the command, If empty, command was not accepted.

OpenDoorFeedbackRequest

A request for feedback of a specific door command.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
door_command_id uint32 Unique identifier for the command, provided by OpenDoorResponse.

OpenDoorFeedbackResponse

Feedback for a specific door command. This RPC reports the robot’s progress opening a door.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status bosdyn.api.RobotCommandFeedbackStatus.Status Generic robot command feedback.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used (unset if unknown).
feedback DoorCommand.Feedback Specific door full body command feedback.

DoorCommand.Feedback.Status

Name Number Description
STATUS_UNKNOWN 0 STATUS_UNKNOWN should never be used. If used, an internal error has happened.
STATUS_COMPLETED 1 Robot has finished opening the door.
STATUS_IN_PROGRESS 2 Robot is attempting to open the door.
STATUS_STALLED 3 The robot has stopped making progress in opening and going through the door. It will
keep trying but may stay in this state indefinitely.
STATUS_NOT_DETECTED 4 The robot could not detect the door. It will keep trying but may stay in this state
indefinitely.

DoorCommand.HandleType

Specify type of door handle.

Name Number Description
HANDLE_TYPE_UNKNOWN 0
HANDLE_TYPE_LEVER 1
HANDLE_TYPE_KNOB 2
HANDLE_TYPE_FIXED_GRASP 3

DoorCommand.HingeSide

Specify if the hinge is on the left or right side of the door, when looking at the door, relative to the door handle.

Name Number Description
HINGE_SIDE_UNKNOWN 0
HINGE_SIDE_LEFT 1
HINGE_SIDE_RIGHT 2

DoorCommand.SwingDirection

Specify if the door is push or pull, when looking at the door.

Name Number Description
SWING_DIRECTION_UNKNOWN 0
SWING_DIRECTION_INSWING 1
SWING_DIRECTION_PULL 1
SWING_DIRECTION_OUTSWING 2
SWING_DIRECTION_PUSH 2

OpenDoorCommandResponse.Status

Name Number Description
STATUS_UNKNOWN 0 An unknown / unexpected error occurred.
STATUS_OK 1 Request was accepted.
STATUS_ROBOT_COMMAND_ERROR 2 Error sending command to RobotCommandService.
STATUS_DOOR_PLANE_NOT_DETECTED 3 The plane of the door could not be detected.

Top

bosdyn/api/spot/door_area_callback.proto

AreaCallbackDoorConfig

At record time, the robot is only physically required to go through the door in one direction, but the command for both directions must be recorded.

Field Type Label Description
forward_command DoorCommand.Request The door command issued for going through the door in the recorded direction
reverse_command DoorCommand.Request The door command for going through the door in the reverse to recorded direction

Top

bosdyn/api/spot/door_service.proto

DoorService

Method Name Request Type Response Type Description
OpenDoor OpenDoorCommandRequest OpenDoorCommandResponse
OpenDoorFeedback OpenDoorFeedbackRequest OpenDoorFeedbackResponse

Top

bosdyn/api/spot/inverse_kinematics.proto

InverseKinematicsRequest

Request a solution to an inverse kinematics problem for Spot (or an indication that a solution could not be found). This message can be used to make both reachability and stance-selection queries. When filling out the request, the caller specifies one option from each of the following categories:

  • stance specifications (fixed foot positions or feet on a ground plane),

  • tool specifications (wrist-mounted), and

  • task specifications (tool pose or gaze) When evaluating potential robot configurations, the service considers joint limits, and static stability in addition to the requirements specified in the request.

Field Type Label Description
header bosdyn.api.RequestHeader
root_frame_name string The root frame is the parent for the optional scene frame. The root frame must be
either “vision" or “odom”.
root_tform_scene bosdyn.api.SE3Pose The task frame as well as body and foot related fields below are specified in this optional
scene frame. If unset, it defaults to the identity transform and all scene quantities are
therefore expressed in the root frame. This frame is useful in cases where the inverse
kinematics problem is most easily defined relative to some other frame (e.g. the frame
defined by a fiducial detection next to a piece of equipment).
scene_tform_task bosdyn.api.SE3Pose Tool related fields below are specified in this optional task frame. If unset it defaults
to the identity transform and all task frame quantities are therefore expressed in the scene
frame.
nominal_arm_configuration InverseKinematicsRequest.NamedArmConfiguration The solver will prefer arm configurations close to the specified named configuration.
Defaults to ARM_CONFIG_CURRENT.
nominal_arm_configuration_overrides bosdyn.api.ArmJointPosition Entries override the nominal joint positions for the specified arm joints. Unspecified joints
will use the values specified by nominal_arm_configuration.
scene_tform_body_nominal bosdyn.api.SE3Pose The solver will prefer configurations that put the body close to this pose. Default to the
current body pose.
fixed_stance InverseKinematicsRequest.FixedStance
on_ground_plane_stance InverseKinematicsRequest.OnGroundPlaneStance
wrist_mounted_tool InverseKinematicsRequest.WristMountedTool
body_mounted_tool InverseKinematicsRequest.BodyMountedTool
tool_pose_task InverseKinematicsRequest.ToolPoseTask The tool will be constrained to be at the desired pose.
tool_gaze_task InverseKinematicsRequest.ToolGazeTask The tool's x-axis will be constrained to point at a target point while the solver will
prefer configurations that put the tool frame closer to the desired pose.

InverseKinematicsRequest.BodyMountedTool

Field Type Label Description
body_tform_tool bosdyn.api.SE3Pose The tool pose relative to the parent link (body). Defaults to identity, making the tool
frame coincident with the body frame

InverseKinematicsRequest.FixedStance

Field Type Label Description
fl_rt_scene bosdyn.api.Vec3 The feet will be constrained to the specified positions relative to the scene frame. If
unspecified, these will default to the current positions of the feet.
fr_rt_scene bosdyn.api.Vec3
hl_rt_scene bosdyn.api.Vec3
hr_rt_scene bosdyn.api.Vec3

InverseKinematicsRequest.OnGroundPlaneStance

Field Type Label Description
scene_tform_ground bosdyn.api.SE3Pose The feet will be constrained to lie on the XY-plane of the ground frame. If unspecified
the ground plane will be the robot's current ground plane estimate.

InverseKinematicsRequest.ToolGazeTask

Field Type Label Description
target_in_task bosdyn.api.Vec3 The point to “look at” with the x-axis of the tool frame. Defaults to the zero vector.
task_tform_desired_tool bosdyn.api.SE3Pose Optional desired pose of the tool expressed in the task frame. Will be
constrained to 'look at' the target regardless of the requested orientation. If unset,
only the “look at” constraint will be applied.

InverseKinematicsRequest.ToolPoseTask

Field Type Label Description
task_tform_desired_tool bosdyn.api.SE3Pose The desired pose of the tool expressed in the task frame. Defaults to identity.

InverseKinematicsRequest.WristMountedTool

Field Type Label Description
wrist_tform_tool bosdyn.api.SE3Pose The tool pose relative to the parent link (wrist).
Defaults to
    [0.19557 0 0]
    [1 0 0 0]
a frame with its origin slightly in front of the gripper's palm plate aligned with the
wrist's orientation.

InverseKinematicsResponse

Response type for InverseKinematicsRequest. If a solution was found (STATUS_OK) the robot_configuration field will contain that solution. Otherwise robot_configuration will be empty.

Field Type Label Description
header bosdyn.api.ResponseHeader
status InverseKinematicsResponse.Status Return status of the request.
robot_configuration bosdyn.api.KinematicState The transforms_snapshot subfield will include the root, scene, and task frames of the request
as well as the body, tool, and foot frames in the solved configuration. The joint_states
subfield will include the name and position for each joint in the solved configuration.

InverseKinematicsRequest.NamedArmConfiguration

Name Number Description
ARM_CONFIG_UNKNOWN 0 Unknown arm configuration
ARM_CONFIG_CURRENT 1 The current configuration of the arm joints
ARM_CONFIG_READY 2 The configuration of the arm joints in the 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.

InverseKinematicsResponse.Status

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1
STATUS_NO_SOLUTION_FOUND 2

Top

bosdyn/api/spot/inverse_kinematics_service.proto

InverseKinematicsService

Method Name Request Type Response Type Description
InverseKinematics InverseKinematicsRequest InverseKinematicsResponse

Top

bosdyn/api/spot/robot_command.proto

BodyControlParams

Parameters for offsetting the body from the normal default.

Field Type Label Description
base_offset_rt_footprint bosdyn.api.SE3Trajectory Desired base offset relative to the footprint pseudo-frame.
The footprint pseudo-frame is a gravity aligned frame with its origin located at the
geometric center of the feet in the X-Y axis, and at the nominal height of the hips in
the Z axis. The yaw of the frame (wrt the world) is calcuated by the average foot
locations, and is aligned with the feet.
body_assist_for_manipulation BodyControlParams.BodyAssistForManipulation The base will adjust to assist with manipulation, adjusting its height, pitch, and yaw as
a function of the hand's location. Note, manipulation assisted body control is only
available for ArmCommand requests that control the end-effector, and are expressed in an
inertial frame. For example, sending a ArmCartesianCommand request with root_frame_name
set to "odom" will allow the robot to compute a body adjustment. However, sending a
ArmCartesianCommand request with root_frame_name set to "body" or sending an
ArmJointMoveCommand request is incompatible, and the body will reset to default height
and orientation.
body_pose BodyControlParams.BodyPose An absolute desired position and orientation of the robot body origin. Command may be
saturated to achievable or safe postures on receipt. Note: This parameter only has effect
when coupled with a StandCommand. For other commands, the robot will fall back to
defaults.
rotation_setting BodyControlParams.RotationSetting The rotation setting for the robot body. Ignored if body_assist_for_manipulation or
body_pose are enabled.

BodyControlParams.BodyAssistForManipulation

Instead of directly specify the base offset trajectory, these options allow the robot to calcuate offsets based on the hand’s location. If the robot does not have a SpotArm attached, sending this request will have no effect.

Field Type Label Description
enable_body_yaw_assist bool Enable the use of body yaw to assist with manipulation.
enable_hip_height_assist bool Enable use of hip height (e.g. body height/pitch) to assist with manipulation.

BodyControlParams.BodyPose

An SE3 based desired body pose trajectory with a specified base frame.

Field Type Label Description
root_frame_name string The root frame for the desired pose, e.g. "vision" or "odom"
base_offset_rt_root bosdyn.api.SE3Trajectory The SE3 pose trajectory

BodyExternalForceParams

External Force on robot body parameters. This is a beta feature and still can have some odd behaviors. By default, the external force estimator is disabled on the robot.

Field Type Label Description
external_force_indicator BodyExternalForceParams.ExternalForceIndicator The type of external force described by the parameters.
frame_name string The frame name for which the external_force_override is defined in. The frame must be known
to the robot.
external_force_override bosdyn.api.Vec3 Specifies a force that the body should expect to feel. This allows the robot to "lean into"
an external force. Be careful using this override, since incorrect information can cause
the robot to fall over.
For example, if the robot is leaning against a wall in front of it, the force override would
be in the negative x dimension. If the robot was pulling something directly behind it, the
force override would be in the negative x dimension as well.

MobilityParams

Params common across spot movement and mobility.

Field Type Label Description
vel_limit bosdyn.api.SE2VelocityLimit Max allowable velocity at any point in trajectory.
body_control BodyControlParams Parameters for controlling Spot's body during motion.
locomotion_hint LocomotionHint Desired gait during locomotion
stair_hint bool Deprecated. DEPRECATED as of 3.2.0: The boolean field has been replaced by the field stairs_mode.
The following field will be deprecated and moved to 'reserved' in a future release.
stairs_mode MobilityParams.StairsMode The selected option for stairs mode.
If unset, will use the deprecated stair_hint instead.
If falling back on stair_hint, false will map to STAIRS_MODE_OFF.
This will be changed to STAIRS_MODE_AUTO in a future release.
allow_degraded_perception bool Allow the robot to move with degraded perception when there are perception faults.
obstacle_params ObstacleParams Control of obstacle avoidance.
swing_height SwingHeight Swing height setting
terrain_params TerrainParams Ground terrain parameters.
disallow_stair_tracker bool Prevent the robot from using StairTracker even if in stairs mode.
disable_stair_error_auto_descent bool Prevent the robot from automatically walking off a staircase in the case of an error
(ex: e-stop settle_then_cut, critical battery level)
external_force_params BodyExternalForceParams Robot Body External Force parameters
disallow_non_stairs_pitch_limiting bool Prevent the robot from pitching to get a better look at rearward terrain except in stairs
mode.
disable_nearmap_cliff_avoidance bool Disable the secondary nearmap-based cliff avoidance that runs while on stairs.

ObstacleParams

Parameters for obstacle avoidance types.

Field Type Label Description
disable_vision_foot_obstacle_avoidance bool Use vision to make the feet avoid obstacles by swinging higher?
disable_vision_foot_constraint_avoidance bool Use vision to make the feet avoid constraints like edges of stairs?
disable_vision_body_obstacle_avoidance bool Use vision to make the body avoid obstacles?
obstacle_avoidance_padding double Desired padding around the body to use when attempting to avoid obstacles.
Described in meters. Must be >= 0.
disable_vision_foot_obstacle_body_assist bool Prevent the robot body from raising above nominal height to avoid lower-leg collisions with
the terrain.
disable_vision_negative_obstacles bool Use vision to make the robot avoid stepping into negative obstacles?

TerrainParams

Ground contact parameters that describe the terrain.

Field Type Label Description
ground_mu_hint google.protobuf.DoubleValue Terrain coefficient of friction user hint. This value must be postive and will clamped if
necessary on the robot side. Best suggested values lie in the range between 0.4 and 0.8
(which is the robot's default.)
enable_grated_floor bool Deprecated. Deprecation Warning ***
DEPRECATED as of 3.0.0: The boolean field has been replaced by the field grated_surfaces_mode
The following field will be deprecated and moved to 'reserved' in a future release.
grated_surfaces_mode TerrainParams.GratedSurfacesMode The selected option for grated surfaces mode

BodyControlParams.RotationSetting

Setting for how the robot interprets base offset pitch & roll components. In the default case (ROTATION_SETTING_OFFSET) the robot will naturally align the body to the pitch of the current terrain. In some circumstances, the user may wish to override this value and try to maintain alignment with respect to gravity. Be careful with this setting as it may likely degrade robot performance in complex terrain, e.g. stairs, platforms, or slopes of sufficiently high grade.

Name Number Description
ROTATION_SETTING_UNKNOWN 0 Invalid; do not use.
ROTATION_SETTING_OFFSET 1 Pitch & Roll are offset with respect to orientation of the footprint.
ROTATION_SETTING_ABSOLUTE 2 Pitch & Roll are offset with respect to gravity.

BodyExternalForceParams.ExternalForceIndicator

Indicates what external force estimate/override the robot should use. By default, the external force estimator is disabled on the robot.

Name Number Description
EXTERNAL_FORCE_NONE 0 No external forces considered.
EXTERNAL_FORCE_USE_ESTIMATE 1 Use external forces estimated by the robot
EXTERNAL_FORCE_USE_OVERRIDE 2 Use external forces specified in an override vector.

LocomotionHint

The locomotion hint specifying the gait of the robot.

Name Number Description
HINT_UNKNOWN 0 Invalid; do not use.
HINT_AUTO 1 No hint, robot chooses an appropriate gait (typically trot.)
HINT_TROT 2 Most robust gait which moves diagonal legs together.
HINT_SPEED_SELECT_TROT 3 Trot which comes to a stand when not commanded to move.
HINT_CRAWL 4 Slow and steady gait which moves only one foot at a time.
HINT_SPEED_SELECT_CRAWL 10 Crawl which comes to a stand when not commanded to move.
HINT_AMBLE 5 Four beat gait where one foot touches down at a time.
HINT_SPEED_SELECT_AMBLE 6 Amble which comes to a stand when not commanded to move.
HINT_JOG 7 Demo gait which moves diagonal leg pairs together with an aerial phase.
HINT_HOP 8 Demo gait which hops while holding some feet in the air.
HINT_AUTO_TROT 3 HINT_AUTO_TROT is deprecated due to the name being too similar to the Spot Autowalk feature.
It has been replaced by HINT_SPEED_SELECT_TROT. Keeping this value in here for now for
backwards compatibility, but this may be removed in future releases.
HINT_AUTO_AMBLE 6 HINT_AUTO_AMBLE is deprecated due to the name being too similar to the Spot Autowalk feature.
It has been replaced by HINT_SPEED_SELECT_AMBLE. Keeping this value in here for now for
backwards compatibility, but this may be removed in future releases.

MobilityParams.StairsMode

Stairs are only supported in trot gaits. Enabling stairs mode will override some user defaults in order to optimize stair behavior.

Name Number Description
STAIRS_MODE_UNKNOWN 0 Invalid; do not use.
STAIRS_MODE_OFF 1
STAIRS_MODE_ON 2
STAIRS_MODE_AUTO 3 Robot will automatically turn mode on or off

SwingHeight

The type of swing height for a step.

Name Number Description
SWING_HEIGHT_UNKNOWN 0 Invalid; do not use.
SWING_HEIGHT_LOW 1 Low-stepping. Robot will try to only swing legs a few cm away from ground.
SWING_HEIGHT_MEDIUM 2 Default for most cases, use other values with caution.
SWING_HEIGHT_HIGH 3 High-stepping. Possibly useful with degraded vision operation.
SWING_HEIGHT_AUTO 4 Swing height is automatically adjusted depending on the current state of the robot and environment.

TerrainParams.GratedSurfacesMode

Options for Grated Surfaces Mode. When Grated Surfaces Mode is on, the robot assumes the ground below it is made of grated metal or other repeated pattern. When on, the robot will make assumptions about the environment structure and more aggressively filter noise in perception data.

Name Number Description
GRATED_SURFACES_MODE_UNKNOWN 0 Invalid; do not use.
GRATED_SURFACES_MODE_OFF 1
GRATED_SURFACES_MODE_ON 2
GRATED_SURFACES_MODE_AUTO 3 Robot will automatically turn mode on or off

Top

bosdyn/api/spot/spot_check.proto

CameraCalibrationCommandRequest

Request for the CameraCalibrationCommand service.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease The Lease to show ownership of the robot. Lease is required for all cal commands.
command CameraCalibrationCommandRequest.Command Command to start/stop the calibration.

CameraCalibrationCommandResponse

Response for the CameraCalibrationCommand service.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.

CameraCalibrationFeedbackRequest

Request for the CameraCalibrationFeedback service.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

CameraCalibrationFeedbackResponse

Response for the CameraCalibrationFeedback service.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status CameraCalibrationFeedbackResponse.Status Status of camera calibration procedure.
progress float The approximate progress of the calibration routine, range [0-1].
Status takes precedence over progress value.

DepthPlaneSpotCheckResult

Results from camera check.

Field Type Label Description
status DepthPlaneSpotCheckResult.Status Return status for the request.
severity_score float Higher is worse. Above 100 means the camera is severely out of calibration.

FootHeightCheckResult

Results from foot height checks.

Field Type Label Description
status FootHeightCheckResult.Status Return status for the request.
foot_height_error_from_mean float The difference between foot height and mean feet height (m).

GripperCameraCalibrationCommandRequest

Request for the GripperCameraCalibrationCommand service.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease The Lease to show ownership of the robot. Lease required to issue any
GripperCameraCalibration command.
command GripperCameraCalibrationCommandRequest.Command The command describing what the GripperCameraCalibration service should do.

GripperCameraCalibrationCommandResponse

Response for the GripperCameraCalibrationCommand service.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.

GripperCameraCalibrationFeedbackRequest

Request for the GripperCameraCalibrationFeedback service.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GripperCameraCalibrationFeedbackResponse

Response for the GripperCameraCalibrationFeedback service.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status GripperCameraCalibrationFeedbackResponse.Status Status of camera calibration procedure.
progress float The approximate progress of the calibration routine, range [0-1].
Status takes precedence over progress value.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.

HipRangeOfMotionResult

Field Type Label Description
error HipRangeOfMotionResult.Error
hx float repeated The measured angles (radians) of the HX and HY joints where the obstruction was detected
hy float repeated

JointKinematicCheckResult

Kinematic calibration results

Field Type Label Description
error JointKinematicCheckResult.Error A flag to indicate if results has an error.
offset float The current offset [rad]
old_offset float The previous offset [rad]
health_score float Joint calibration health score. range [0-1]
0 indicates an unhealthy kinematic joint calibration
1 indicates a perfect kinematic joint calibration
Typically, values greater than 0.8 should be expected.

LegPairCheckResult

Results from leg pair checks..

Field Type Label Description
status LegPairCheckResult.Status Return status for the request.
leg_pair_distance_change float The change in estimated distance between two feet from tall to short stand (m)

LoadCellSpotCheckResult

Results from load cell check.

Field Type Label Description
error LoadCellSpotCheckResult.Error A flag to indicate if results has an error.
zero float The current loadcell zero as fraction of full range [0-1]
old_zero float The previous loadcell zero as fraction of full range [0-1]

PayloadCheckResult

Results of payload check.

Field Type Label Description
error PayloadCheckResult.Error A flag to indicate if configuration has an error.
extra_payload float Indicates how much extra payload (in kg) we think the robot has
Positive indicates robot has more payload than it is configured.
Negative indicates robot has less payload than it is configured.

SpotCheckCommandRequest

Request for the SpotCheckCommand service.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
lease bosdyn.api.Lease The Lease to show ownership of the robot. Lease required to issue any SpotCheck command.
command SpotCheckCommandRequest.Command The command describing what the spot check service should do.

SpotCheckCommandResponse

Response for the SpotCheckCommand service.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
lease_use_result bosdyn.api.LeaseUseResult Details about how the lease was used.
status SpotCheckCommandResponse.Status Command status
message string Human-readable description if an error occurred.

SpotCheckFeedbackRequest

Request for the SpotCheckFeedback service.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

SpotCheckFeedbackResponse

Response for the SpotCheckFeedback service.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
state SpotCheckFeedbackResponse.State The state of the spot check routine.
last_command SpotCheckCommandRequest.Command The last command executed by Spotcheck. When SpotCheck is in state WAITING_FOR_COMMAND,
the last command has completed.
error SpotCheckFeedbackResponse.Error The specifics of the error for the SpotCheck service.
camera_results SpotCheckFeedbackResponse.CameraResultsEntry repeated Results from camera check.
The key string is the location of the camera (e.g. frontright, frontleft, left, ...)
load_cell_results SpotCheckFeedbackResponse.LoadCellResultsEntry repeated Results from load cell calibration.
The key string is the location of the joint (e.g. fl.hxa, fl.hya, fl.kna, ...)
kinematic_cal_results SpotCheckFeedbackResponse.KinematicCalResultsEntry repeated Results from output position sensor calibration.
The key string is the location of the joint (e.g. fl.hx, fl.hy, fl.kn, ...)
payload_result PayloadCheckResult Result from the payload check
hip_range_of_motion_results SpotCheckFeedbackResponse.HipRangeOfMotionResultsEntry repeated Results of the hip range of motion check
The key string is the name of the leg (e.g. fl, fr, hl, ...)
progress float The approximate progress of the spot check routine, range [0-1].
last_cal_timestamp google.protobuf.Timestamp Timestamp for the most up-to-date calibration

SpotCheckFeedbackResponse.CameraResultsEntry

Field Type Label Description
key string
value DepthPlaneSpotCheckResult

SpotCheckFeedbackResponse.HipRangeOfMotionResultsEntry

Field Type Label Description
key string
value HipRangeOfMotionResult

SpotCheckFeedbackResponse.KinematicCalResultsEntry

Field Type Label Description
key string
value JointKinematicCheckResult

SpotCheckFeedbackResponse.LoadCellResultsEntry

Field Type Label Description
key string
value LoadCellSpotCheckResult

CameraCalibrationCommandRequest.Command

Name Number Description
COMMAND_UNKNOWN 0 Unused enum.
COMMAND_START 1 Start calibration routine.
COMMAND_CANCEL 2 Cancel calibration routine.

CameraCalibrationFeedbackResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Unused enum.
STATUS_PROCESSING 1 The robot is actively running calibration routine.
STATUS_SUCCESS 2 The robot successfully ran calibration routine and
is ready to use again.
STATUS_USER_CANCELED 3 API client canceled calibration.
STATUS_POWER_ERROR 4 The robot is not powered on.
STATUS_LEASE_ERROR 5 Ownership error during calibration.
STATUS_ROBOT_COMMAND_ERROR 7 Robot encountered an error while trying to move
around the calibration target. Robot possibly
encountered a fault. Check robot state for more
details
STATUS_CALIBRATION_ERROR 8 Calibration procedure produced an invalid result.
This may occur in poor lighting conditions or if
calibration target moved during calibration
procedure.
STATUS_INTERNAL_ERROR 9 Something extraordinary happened. Try power cycling robot or contact BD.
STATUS_CAMERA_FOCUS_ERROR 14 Camera focus issue detected. This is a hardware issue.
STATUS_TARGET_NOT_CENTERED 6 Target partially, but not fully, in view when starting calibration.
STATUS_TARGET_NOT_IN_VIEW 11 Target not visible when starting calibration.
STATUS_TARGET_NOT_GRAVITY_ALIGNED 12 Target not aligned with gravity when starting calibration.
STATUS_TARGET_UPSIDE_DOWN 13 Target upside down when starting calibration.
STATUS_NEVER_RUN 10 Calibration routine has never been run. No feedback to give.
STATUS_CAMERA_NOT_DETECTED 15 One of the cameras is not detected on the USB bus.
STATUS_INTRINSIC_WRITE_FAILED 16 Failed to write intrinsic calibration.
STATUS_EXTRINSIC_WRITE_FAILED 17 Failed to write extrinsic calibration.
STATUS_CALIBRATION_VERIFICATION_FAILED 18 Spotcheck failed after the camera calibration.

DepthPlaneSpotCheckResult.Status

Errors reflect an issue with camera hardware.

Name Number Description
STATUS_UNKNOWN 0 Unused enum.
STATUS_OK 1 No detected calibration error.
STATUS_WARNING 2 Possible calibration error detected.
STATUS_ERROR 3 Error with robot calibration.

FootHeightCheckResult.Status

Errors reflect an issue with robot calibration.

Name Number Description
STATUS_UNKNOWN 0 Unused enum.
STATUS_OK 1 No detected calibration error.
STATUS_WARNING 2 Possible calibration error detected.
STATUS_ERROR 3 Error with robot calibration.

GripperCameraCalibrationCommandRequest.Command

Name Number Description
COMMAND_UNKNOWN 0 Unused enum.
COMMAND_START 1 Start calibration routine.
COMMAND_CANCEL 2 Cancel calibration routine.

GripperCameraCalibrationFeedbackResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Unused enum.
STATUS_PROCESSING 1 The robot is actively running calibration routine.
STATUS_SUCCESS 2 The robot successfully ran calibration routine and
is ready to use again.
STATUS_NEVER_RUN 3 Calibration routine has never been run. No feedback to give.
STATUS_USER_CANCELED 4 Calibration routine has been canceled mid-routine.
STATUS_POWER_ERROR 5 The robot is not powered on.
STATUS_LEASE_ERROR 6 Ownership error during calibration.
STATUS_CALIBRATION_ERROR 8 Calibration procedure produced an invalid result.
This may occur in poor lighting conditions or if
calibration target moved during calibration
procedure.
STATUS_INITIALIZATION_ERROR 9 Something went wrong during initialization. Try running the command again or, if it
persists, restarting the robot.
STATUS_INTERNAL_ERROR 10 Something extraordinary happened. Try power cycling robot or contact BD.
STATUS_TARGET_NOT_CENTERED 11 Target partially, but not fully, in view when starting calibration.
STATUS_TARGET_NOT_IN_VIEW 12 Target not visible when starting calibration.
STATUS_TARGET_NOT_GRAVITY_ALIGNED 13 Target not aligned with gravity when starting calibration.
STATUS_TARGET_UPSIDE_DOWN 14 Target upside down when starting calibration.
STATUS_STUCK 15 The robot took too long to reach the goal pose.

HipRangeOfMotionResult.Error

Errors reflect an issue with hip range of motion

Name Number Description
ERROR_UNKNOWN 0
ERROR_NONE 1
ERROR_OBSTRUCTED 2

JointKinematicCheckResult.Error

Errors reflect an issue with robot hardware.

Name Number Description
ERROR_UNKNOWN 0 Unused enum.
ERROR_NONE 1 No hardware error detected.
ERROR_CLUTCH_SLIP 2 Error detected in clutch performance.
ERROR_INVALID_RANGE_OF_MOTION 3 Error if a joint has an incorrect range of motion.
ERROR_ENCODER_SHIFTED 4 Error if the measured endstops shifted from kin cal.
ERROR_COLLISION 5 Error if checking the joint would have a collsion.

LegPairCheckResult.Status

Name Number Description
STATUS_UNKNOWN 0 Unused enum.
STATUS_OK 1 No detected calibration error.
STATUS_WARNING 2 Possible calibration error detected.
STATUS_ERROR 3 Error with robot calibration.

LoadCellSpotCheckResult.Error

Errors reflect an issue with robot hardware.

Name Number Description
ERROR_UNKNOWN 0 Unused enum.
ERROR_NONE 1 No hardware error detected.
ERROR_ZERO_OUT_OF_RANGE 2 Load cell calibration failure.

PayloadCheckResult.Error

Errors reflect an issue with payload configuration.

Name Number Description
ERROR_UNKNOWN 0 Unused enum.
ERROR_NONE 1 No error found in the payloads.
ERROR_MASS_DISCREPANCY 2 There is a mass discrepancy between the registered payload and what is estimated.

SpotCheckCommandRequest.Command

Name Number Description
COMMAND_UNKNOWN 0 Unused enum.
COMMAND_START 1 Start spot check joint calibration and camera checks.
COMMAND_ABORT 2 Abort spot check joint calibration and camera check.
COMMAND_REVERT_CAL 3 Revert joint calibration back to the previous values.

SpotCheckCommandResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Unknown
STATUS_OK 1 Request was accepted.
STATUS_ERROR 2 An error ocurred.

SpotCheckFeedbackResponse.Error

If SpotCheck experienced an error, specific error details reported here. This reflects an error in the routine.

Name Number Description
ERROR_UNKNOWN 0 Unused enum.
ERROR_NONE 1 No error has occurred.
ERROR_UNEXPECTED_POWER_CHANGE 2 Unexpected motor power state transition.
ERROR_INIT_IMU_CHECK 3 Robot body is not flat on the ground.
ERROR_INIT_NOT_SITTING 4 Robot body is not close to a sitting pose
ERROR_LOADCELL_TIMEOUT 5 Timeout during loadcell calibration.
ERROR_POWER_ON_FAILURE 6 Error enabling motor power.
ERROR_ENDSTOP_TIMEOUT 7 Timeout during endstop calibration.
ERROR_FAILED_STAND 8 Robot failed to stand.
ERROR_CAMERA_TIMEOUT 9 Timeout during camera check.
ERROR_GROUND_CHECK 10 Flat ground check failed.
ERROR_POWER_OFF_FAILURE 11 Robot failed to power off.
ERROR_REVERT_FAILURE 12 Robot failed to revert calibration.
ERROR_FGKC_FAILURE 13 Robot failed to do flat ground kinematic calibration.
ERROR_GRIPPER_CAL_TIMEOUT 14 Timeout during gripper calibration.
ERROR_ARM_CHECK_COLLISION 15 Arm motion would cause collisions (eg. w/ a payload).
ERROR_ARM_CHECK_TIMEOUT 16 Timeout during arm joint check.

SpotCheckFeedbackResponse.State

Name Number Description
STATE_UNKNOWN 0 Unused enum.
STATE_USER_ABORTED 1 SpotCheck is aborted by the user.
STATE_STARTING 2 SpotCheck is initializing.
STATE_LOADCELL_CAL 3 Load cell calibration underway.
STATE_ENDSTOP_CAL 4 Endstop calibration underway.
STATE_CAMERA_CHECK 5 Camera check underway.
STATE_BODY_POSING 6 Body pose routine underway.
STATE_FINISHED 7 Spot check successfully finished.
STATE_REVERTING_CAL 8 Reverting calibration to previous values.
STATE_ERROR 9 Error occurred while running spotcheck. Inspect error for more info.
STATE_WAITING_FOR_COMMAND 10 Waiting for user command.
STATE_HIP_RANGE_OF_MOTION_CHECK 11 Hip range of motion check underway.
STATE_GRIPPER_CAL 12 Gripper calibration underway.
STATE_SIT_DOWN_AFTER_RUN 13 Sitting down after run.
STATE_ARM_JOINT_CHECK 14 Arm joint endstops and cross error check underway.

Top

bosdyn/api/spot/spot_check_service.proto

SpotCheckService

RPCs for monitoring robot health and recalibration various sensors. These procedures should be run periodically in order to keep the system running in the best possible condition.

Method Name Request Type Response Type Description
SpotCheckCommand SpotCheckCommandRequest SpotCheckCommandResponse Send a command to the SpotCheck service. The spotcheck service is responsible to both
recalibrating actuation sensors and checking camera health.
SpotCheckFeedback SpotCheckFeedbackRequest SpotCheckFeedbackResponse Check the status of the spot check procedure. After procedure completes, this reports back
results for specific joints and cameras.
CameraCalibrationCommand CameraCalibrationCommandRequest CameraCalibrationCommandResponse Send a camera calibration command to the robot. Used to start or abort a calibration routine.
CameraCalibrationFeedback CameraCalibrationFeedbackRequest CameraCalibrationFeedbackResponse Check the status of the camera calibration procedure.
GripperCameraCalibrationCommand GripperCameraCalibrationCommandRequest GripperCameraCalibrationCommandResponse Send a command to the GripperCameraCalibration service.
GripperCameraCalibrationFeedback GripperCameraCalibrationFeedbackRequest GripperCameraCalibrationFeedbackResponse Check the status of the GripperCameraCalibration procedure.

Top

bosdyn/api/spot_cam/LED.proto

GetLEDBrightnessRequest

Request the current state of LEDs on the SpotCam.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetLEDBrightnessResponse

Describes the current brightnesses of all LEDs.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
brightnesses float repeated Brightness [0, 1] of the LED located at indices [0, 3].

SetLEDBrightnessRequest

Set individual LED brightnesses.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
brightnesses SetLEDBrightnessRequest.BrightnessesEntry repeated Brightness [0, 1] to assign to the LED located at indices [0, 3].

SetLEDBrightnessRequest.BrightnessesEntry

Field Type Label Description
key int32
value float

SetLEDBrightnessResponse

Response with any errors setting LED brightnesses.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

Top

bosdyn/api/spot_cam/audio.proto

DeleteSoundRequest

Remove a loaded sound from the library of loaded sounds.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
sound Sound The sound identifier as uploaded by LoadSoundRequest or listed in ListSoundsResponse.

DeleteSoundResponse

Result of deleting a sound from the library.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

GetAudioCaptureChannelRequest

Request to get the audio capture channel

Field Type Label Description
header bosdyn.api.RequestHeader

GetAudioCaptureChannelResponse

Result of getting the audio capture channel

Field Type Label Description
header bosdyn.api.ResponseHeader
channel AudioCaptureChannel

GetAudioCaptureGainRequest

Request to get the audio capture channel

Field Type Label Description
header bosdyn.api.RequestHeader
channel AudioCaptureChannel

GetAudioCaptureGainResponse

Result of getting the audio capture gain

Field Type Label Description
header bosdyn.api.ResponseHeader
gain double Gain for microphone, range from 0.0 to 1.0

GetVolumeRequest

Query the current volume level of the system.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetVolumeResponse

Provides the current volume level of the system.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
volume float volume, as a percentage of maximum.

ListSoundsRequest

Request for all sounds present on the robot.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

ListSoundsResponse

List of all sounds present on the robot.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
sounds Sound repeated All sounds currently loaded.

LoadSoundRequest

Load a new sound onto the robot for future playback.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
sound Sound Identifier for the sound.
If the same identifier is used as a previously loaded sound, that sound will be overwritten
with the new data.
data bosdyn.api.DataChunk WAV bytes to be joined.

LoadSoundResponse

Result of uploading a sound.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

PlaySoundRequest

Begin playing a loaded sound from the robot’s speakers.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
sound Sound The sound identifier as uploaded by LoadSoundRequest or listed in ListSoundsResponse.
gain google.protobuf.FloatValue If the gain field is populated, then volume of the sound is
multiplied by this value. Does not modify the system volume level.

PlaySoundResponse

Result of staring playback of a sound.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

SetAudioCaptureChannelRequest

Request to set the audio capture channel

Field Type Label Description
header bosdyn.api.RequestHeader
channel AudioCaptureChannel

SetAudioCaptureChannelResponse

Result of setting the audio capture channel

Field Type Label Description
header bosdyn.api.ResponseHeader

SetAudioCaptureGainRequest

Request to set the audio capture channel

Field Type Label Description
header bosdyn.api.RequestHeader
channel AudioCaptureChannel
gain double Gain for microphone, range from 0.0 to 1.0

SetAudioCaptureGainResponse

Result of setting the audio capture gain

Field Type Label Description
header bosdyn.api.ResponseHeader

SetVolumeRequest

Set the desired volume level of the system.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
volume float volume, as a percentage of maximum.

SetVolumeResponse

Result of changing the system volume level.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

Sound

Identifier for a playable sound.

Field Type Label Description
name string internally, sounds are stored in a flat table. This name is the
identifier of a sound effect

AudioCaptureChannel

Audio capture channel

Name Number Description
AUDIO_CHANNEL_UNKNOWN 0
AUDIO_CHANNEL_INTERNAL_MIC 1
AUDIO_CHANNEL_EXTERNAL_MIC 2

Top

bosdyn/api/spot_cam/camera.proto

Camera

Field Type Label Description
name string Identifier for the camera.
resolution bosdyn.api.Vec2 Resolution of the sensor, where x = width and y = height.
base_frame_name string The frame name for the parent frame of this camera. This frame will show up in the
FrameTreeSnapshot grabbed from the payload registration service.
base_tfrom_sensor bosdyn.api.SE3Pose Deprecated. 'base_tfrom_sensor' defines the transform from the specific camera to the named base from.
DEPRECATED as of 3.0.1 in favor of 'base_tform_sensor' which follows the intended naming
convention and FrameTree directionality convention of the Spot system as defined in
geometry.proto.
base_tform_sensor bosdyn.api.SE3Pose The transform from the named base frame to this specific camera
pinhole Camera.PinholeIntrinsics Physical cameras
spherical Camera.SphericalLimits Only synthetic spherical panoramas

Camera.PinholeIntrinsics

Field Type Label Description
focal_length bosdyn.api.Vec2 Focal_length in pixels
center_point bosdyn.api.Vec2 Center point in pixels
k1 float The following 4 parameters are radial distortion coefficeints to 4 orders.
See: https://en.wikipedia.org/wiki/Distortion_(optics)#Software_correction
If all 4 of these values are 0, do not apply any correction.
k2 float
k3 float
k4 float

Camera.SphericalLimits

Spherical limits are the minimum and maximum angle of the image. IE the upper left pixel is at min_angle.x, min_angle.y and the lower right pixel is at max_angle.x, max_angle.y for a full-FOV image this will be (-180, 90) and (180, -90)

Field Type Label Description
min_angle bosdyn.api.Vec2
max_angle bosdyn.api.Vec2

Top

bosdyn/api/spot_cam/compositor.proto

GetIrColormapRequest

Field Type Label Description
header bosdyn.api.RequestHeader

GetIrColormapResponse

Field Type Label Description
header bosdyn.api.ResponseHeader
map IrColorMap

GetIrMeterOverlayRequest

Field Type Label Description
header bosdyn.api.RequestHeader

GetIrMeterOverlayResponse

Field Type Label Description
header bosdyn.api.ResponseHeader
overlay IrMeterOverlay

GetScreenRequest

Request the current screen in use.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetScreenResponse

Specify which screen is currently being displayed in the video stream.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
name string Identifier of the current screen.

GetVisibleCamerasRequest

Request information about the current cameras in the video stream.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetVisibleCamerasResponse

Description of the parameters and locations of each camera in the current video stream.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
streams GetVisibleCamerasResponse.Stream repeated List of all camera streams visible in the current video stream.

GetVisibleCamerasResponse.Stream

The location and camera parameters for a single camera.

Field Type Label Description
window GetVisibleCamerasResponse.Stream.Window The location of this camera stream within the larger stream.
camera Camera The name field in this camera member is of the form 'c:w',
where c is the name of the camera and w is the name of the
window that's projecting it.

GetVisibleCamerasResponse.Stream.Window

The location of a sub-image within a larger image.

Field Type Label Description
xoffset int32
yoffset int32
width int32 The image should be cropped out of the stream at this
resolution, and then scaled to the resolution described
in the 'camera' member, below. once that scaling takes
place, the intrinsics will be valid.
height int32

IrColorMap

the colormap is a mapping of radiometric data to color, to make the images easier for people to look at in real time.

Field Type Label Description
colormap IrColorMap.ColorMap
scale IrColorMap.ScalingPair
auto_scale google.protobuf.BoolValue if auto_scale is true, then the min and max values are derived from the data itself, and the
settings above are ignored

IrColorMap.ScalingPair

Field Type Label Description
min double the minimum value to do color mapping, in degrees Celsius
max double the maximum value to do color mapping, in degrees Celsius

IrMeterOverlay

the ir meter overlay allows for pixel-accurate measurements to be taken and displayed to the user

Field Type Label Description
enable bool If enable isn't true, don't overlay any IR meter
coords IrMeterOverlay.NormalizedCoordinates Deprecated. DEPRECATED as of 3.3.0.
meter IrMeterOverlay.NormalizedCoordinates repeated
unit IrMeterOverlay.TempUnit
delta IrMeterOverlay.DeltaPair repeated

IrMeterOverlay.DeltaPair

each delta pair should be a pair of indices in the above ‘meter’ list that need to have deltas generated

Field Type Label Description
a int32
b int32

IrMeterOverlay.NormalizedCoordinates

these coordinates, normalized from 0-1, are within the ir camera ‘window’ note: if the coordinates lie within an ‘invalid’ region of the window, then the meter will be disabled.

Field Type Label Description
x double
y double

IrMeterOverlay.TempUnit

Field Type Label Description
value IrMeterOverlay.TempUnit.TempUnitType

ListScreensRequest

Request the different screen layouts available.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

ListScreensResponse

Response with all screen layouts available.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
screens ScreenDescription repeated List of all screen layouts that can be selected.

ScreenDescription

A “Screen” represents a particular layout of camera images used by the video stream.

Field Type Label Description
name string Unique identifer for a screen.

SetIrColormapRequest

Field Type Label Description
header bosdyn.api.RequestHeader
map IrColorMap

SetIrColormapResponse

Field Type Label Description
header bosdyn.api.ResponseHeader

SetIrMeterOverlayRequest

Field Type Label Description
header bosdyn.api.RequestHeader
overlay IrMeterOverlay

SetIrMeterOverlayResponse

Field Type Label Description
header bosdyn.api.ResponseHeader

SetScreenRequest

Switch the camera layout in the video stream to the one specified.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
name string Identifier as specified in ListScreensResponse.

SetScreenResponse

Result of setting the camera layout.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
name string Identifier of the screen used.

IrColorMap.ColorMap

Name Number Description
COLORMAP_UNKNOWN 0
COLORMAP_GREYSCALE 1 the greyscale colormap maps the minimum value (defined below) to black and the maximum
value (defined below) to white
COLORMAP_JET 2 the jet colormap uses blues for values closer to the minimum, and red values for values
closer to the maximum.
COLORMAP_INFERNO 3 the inferno colormap maps the minimum value to black and the maximum value to light
yellow RGB(252, 252, 164). It is also easier to view by those with color blindness
COLORMAP_TURBO 4 the turbo colormap uses blues for values closer to the minumum, red values for values
closer to the maximum, and addresses some short comings of the jet color map such as
false detail, banding and color blindness

IrMeterOverlay.TempUnit.TempUnitType

Name Number Description
TEMPUNIT_UNKNOWN 0
TEMPUNIT_CELSIUS 1
TEMPUNIT_FAHRENHEIT 2
TEMPUNIT_KELVIN 3

Top

bosdyn/api/spot_cam/health.proto

ClearBITEventsRequest

Clear Built-in Test events.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

ClearBITEventsResponse

Response to clearing built-in test events.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

GetBITStatusRequest

Request the status of all built-in tests.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetBITStatusResponse

Data on the current status of built-in tests.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
events bosdyn.api.SystemFault repeated Fault events that have been reported.
degradations GetBITStatusResponse.Degradation repeated List of system states that may effect performance.

GetBITStatusResponse.Degradation

Degredations are not necessesarily faults; a unit with no installed mechanical PTZ will behave differently, but nothing’s actually wrong.

Field Type Label Description
type GetBITStatusResponse.Degradation.DegradationType System affected.
description string Description of the kind of degradation being experienced.

GetSystemLogRequest

Field Type Label Description
header bosdyn.api.RequestHeader

GetSystemLogResponse

Field Type Label Description
header bosdyn.api.ResponseHeader
data bosdyn.api.DataChunk

GetTemperatureRequest

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetTemperatureResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
temps Temperature repeated List of all temperatures measured.

Temperature

The temperature of a particular component.

Field Type Label Description
channel_name string Identifier of the hardware measured.
temperature int64 Temperature is expressed in millidegrees C.

GetBITStatusResponse.Degradation.DegradationType

Systems that can experience performance degredations.

Name Number Description
STORAGE 0
PTZ 1
LED 2

Top

bosdyn/api/spot_cam/logging.proto

DebugRequest

Change debug logging settings on the SpotCam.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
enable_temperature bool Set true to enable logging of temperature data;
enable_humidity bool Set true to enable logging of humidity data;
enable_BIT bool Set true to enable logging of BIT events;
BIT events are always recorded to volatile memory
and can be viewed (and cleared) with the Health service,
but this enables writing them to disk.
enable_shock bool Set true to enable logging of Shock data;
this is on by default.
enable_system_stat bool Set to true to enable logging of system load stats
cpu, gpu, memory, and network utilization

Nowow a BIT, set true to enable logging of led driver status.
bool enable_led_stat = 7;

DebugResponse

Response with any errors for debug setting changes.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

DeleteRequest

Delete a log point from the store.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
point Logpoint Log point to delete. Only the name is used.

DeleteResponse

Response to a deletion with any errors that occurred.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

GetStatusRequest

Request for status about the current stage of data acquisition.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
point Logpoint Log point to query. Only the name is used.

GetStatusResponse

Provide an update on the stage of data acquisition.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
point Logpoint The logpoint returned here can be used to add a tag to the Logpoint later

ListCamerasRequest

Request the available cameras.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

ListCamerasResponse

Provide the list of available cameras.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
cameras Camera repeated List of all cameras which can be used in a StoreRequest.

ListLogpointsRequest

List all available log points, whether they have completed or not.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

ListLogpointsResponse

Provide all log points in the system.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
logpoints Logpoint repeated List of all the individual log points concatenated into a list.
This stream may take a long time to complete if there are a lot of stored images.

Logpoint

A representation of a stored data acquisition.

Field Type Label Description
name string Unique identifier for a data acquisition event.
type Logpoint.RecordType Type of data held in this log point.
status Logpoint.LogStatus Current stage of acquisition.
queue_status Logpoint.QueueStatus Only filled out when status == QUEUED
tag string An arbitrary string to be stored with the log data.
timestamp google.protobuf.Timestamp Time of acquisition.
image_params Logpoint.ImageParams Image format of the stored data.
calibration Logpoint.Calibration repeated Camera data for all sub-images contained within the image data.

Logpoint.Calibration

Data describing the camera intrinsics and extrinsics for a window of the image.

Field Type Label Description
xoffset int32
yoffset int32
width int32
height int32
base_frame_name string
base_tfrom_sensor bosdyn.api.SE3Pose Deprecated. 'base_tfrom_sensor' defines the transform from the specific camera to the named base
from. DEPRECATED as of 3.0.1 in favor of 'base_tform_sensor' which follows the intended
naming convention and FrameTree directionality convention of the Spot system as defined
in geometry.proto.
base_tform_sensor bosdyn.api.SE3Pose The transform from the named base frame to this specific camera
intrinsics Camera.PinholeIntrinsics

Logpoint.ImageParams

Description of image format.

Field Type Label Description
width int32
height int32
format bosdyn.api.Image.PixelFormat

RetrieveRawDataRequest

Retrieve the binary data associated with a log point, with no processing applied. Storing a panorama will retrieve tiled individual images. For IR, the temperature at each pixel is 0.1 * the int value in Kelvin.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
point Logpoint Log point to retrieve. Only the name is used.

RetrieveRawDataResponse

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
logpoint Logpoint Log point retrieved.
data bosdyn.api.DataChunk Data chunk bytes field should be concatenated together to recover the binary data.

RetrieveRequest

Retrieve the binary data associated with a log point.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
point Logpoint Log point to retrieve. Only the name is used.

RetrieveResponse

Provide the data stored at a log point. Store() dictates what processing happens in this response. c0 -> c4 will return the raw (rgb24) fisheye image of the camera at that index. Storing a panorama will process the data into a stitched image.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
logpoint Logpoint Log point retrieved.
data bosdyn.api.DataChunk Data chunk bytes field should be concatenated together to recover the binary data.

SetPassphraseRequest

Set encryption for the disk.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
passphrase string After setting the passphrase, please reboot the system to
remount the encrypted filesystem layer.

SetPassphraseResponse

Response from setting the disk encryption. After setting the passphrase, please reboot the system to remount the encrypted filesystem layer.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

StoreRequest

Trigger a data acquisition.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
camera Camera Which camera to capture.
type Logpoint.RecordType Type of data capture to perform.
tag string Metadata to associate with the store.

StoreResponse

Result of data acquisition trigger.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
point Logpoint The log point returned here can be used to add a tag to the Logpoint later
It will very likely be in th 'QUEUED' state.

TagRequest

Add tag metadata to an existing log point.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
point Logpoint Logpoint to add metadata to. Name and tag are used.

TagResponse

Result of adding tag metadata to a log point.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

Logpoint.LogStatus

Possible stages of data acquisition.

Name Number Description
FAILED 0
QUEUED 1 the logpoint has been queued to be downloaded from the renderer
COMPLETE 2 the logpoint is written to the disk
UNKNOWN -1

Logpoint.QueueStatus

Name Number Description
QUEUED_UNKNOWN 0
QUEUED_RENDER 1 The logpoint has been queued to be downloaded from the renderer
QUEUED_DISK 2 The logpoint is in general ram, and will be written to the disk when

Logpoint.RecordType

Possible types of media that can be stored.

Name Number Description
STILLIMAGE 0

Top

bosdyn/api/spot_cam/network.proto

GetICEConfigurationRequest

Request the servers used for ICE resolution.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetICEConfigurationResponse

Provides the ICE resolution servers.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
servers ICEServer repeated List of servers used for ICE resolution.

GetNetworkSettingsRequest

Retrieve current network configuration.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetNetworkSettingsResponse

Provides the current network configuration.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
settings NetworkTuple Current network configuration.

GetSSLCertRequest

Request the SSL certificate currently in use.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetSSLCertResponse

Provides the SSL certificate currently in use.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
certificate string An ASCII-armored representation of the SSL certificate

ICEServer

Servers used in the ICE resolution process.

Field Type Label Description
type ICEServer.servertype STUN or TURN server.
address string Network address of the server.
port uint32 Only the least significant 16 bits are used.
transport ICEServer.icetransport
auth ICEServer.auth_params auth is optional, and is only used for TURN

ICEServer.auth_params

Field Type Label Description
username google.protobuf.StringValue username is optional, and is only used for authenticated TURN servers
oauth ICEServer.auth_params.oauth_pair
password google.protobuf.StringValue

ICEServer.auth_params.oauth_pair

Field Type Label Description
MACKey string
AccessToken string

NetworkTuple

Network configuration data.

Field Type Label Description
address google.protobuf.UInt32Value a big-endian representation of an IPv4 address
netmask google.protobuf.UInt32Value The mask used for defining the system's subnet
gateway google.protobuf.UInt32Value A global routing is set up for the address defined below (if present)
mtu google.protobuf.UInt32Value If MTU is present, and <16 bits wide, then it is set for the ethernet interface's MTU
if not, the MTU is set to 1500

SetICEConfigurationRequest

Modify the ICE configuration. Note: this configuration replaces any configuration currently present. It is not appended.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
servers ICEServer repeated List of servers used for ICE resolution.

SetICEConfigurationResponse

Result of modifying the ICE configuration.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

ICEServer.icetransport

Name Number Description
TRANSPORT_UNKNOWN 0
TRANSPORT_UDP 1
TRANSPORT_TCP 2

ICEServer.servertype

Possible types of servers

Name Number Description
UNKNOWN 0
STUN 1
TURN 2

Top

bosdyn/api/spot_cam/power.proto

CyclePowerRequest

Turn components off and then back on without needing two separate requests.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
status PowerStatus status indicates the devices for which cycle-power is requested
'true' for cycle-power, else no effect
power cycle will not be performed on a given device if its state is power-off prior to this call

CyclePowerResponse

Result of power cycling components.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status PowerStatus status indicates the power status of the controllable devices after a successful power cycle
'true' for power-on, 'false' for power-off

GetPowerStatusRequest

Request component power status.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetPowerStatusResponse

Provides the power status of all components.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status PowerStatus status indicates the power status of the controllable devices
'true' for power-on, 'false' for power-off

PowerStatus

Power on or off of components of the SpotCam.

Field Type Label Description
ptz google.protobuf.BoolValue these switches are 'true' for power-on, 'false' for power-off
aux1 google.protobuf.BoolValue
aux2 google.protobuf.BoolValue
external_mic google.protobuf.BoolValue

SetPowerStatusRequest

Turn components on or off.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
status PowerStatus status indicates the requested power status of the controllable devices
'true' for power-on, 'false' for power-off

SetPowerStatusResponse

Result of turning components on or off.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
status PowerStatus status indicates the requested changes upon success
'true' for power-on, 'false' for power-off

Top

bosdyn/api/spot_cam/ptz.proto

GetPtzFocusStateRequest

Field Type Label Description
header bosdyn.api.RequestHeader

GetPtzFocusStateResponse

Field Type Label Description
header bosdyn.api.ResponseHeader
focus_state PtzFocusState

GetPtzPositionRequest

Request the current position of a ptz.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
ptz PtzDescription Only the name is used.

GetPtzPositionResponse

Provides the current measured position.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
position PtzPosition Current position of the mechanism.

GetPtzVelocityRequest

Request the velocity of a ptz

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
ptz PtzDescription Only the name is used.

GetPtzVelocityResponse

Provides the current measured velocity.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
velocity PtzVelocity Current velocity of the mechanism.

InitializeLensRequest

Command to reset PTZ autofocus

Field Type Label Description
header bosdyn.api.RequestHeader Common response header.

InitializeLensResponse

Result of a InitializeLensRequest.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.

ListPtzRequest

Request all available ptzs on the SpotCam.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

ListPtzResponse

Provide all available ptz on the SpotCam.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
ptzs PtzDescription repeated List of ptzs, real and virtual.

PtzDescription

PtzDescription provides information about a given PTZ. The name is usually all that’s required to describe a PTZ, but ListPtzResponse will include more information.

Field Type Label Description
name string Identifier of a particular controllable PTZ mechanism (real or virtual).
pan_limit PtzDescription.Limits If a limit is not set, all positions are valid

Limits in degrees.
tilt_limit PtzDescription.Limits Limits in degrees.
zoom_limit PtzDescription.Limits Limits in zoom level.

PtzDescription.Limits

Limits for a single axis.

Field Type Label Description
min google.protobuf.FloatValue Units depend on the axis being controlled.
max google.protobuf.FloatValue Units depend on the axis being controlled.

PtzFocusState

focus commands only affect the mech EO camera

Field Type Label Description
mode PtzFocusState.PtzFocusMode
focus_position google.protobuf.Int32Value focus_position only settable in PTZ_FOCUS_MANUAL mode
this represents a precise lens position for the camera for repeatable operations
approx_distance google.protobuf.FloatValue approx_distance only settable in PTZ_FOCUS_MANUAL mode
approx_distance is most accurate between 1.2m and 20m
approx_distance is ignored on a Set operation if focus_position is included

PtzPosition

Doubles as a description of current state, or a command for a new position.

Field Type Label Description
ptz PtzDescription The "mech" ptz can pan [0, 360] degrees,
tilt approximately [-30, 100] degrees where 0 is the horizon, IR and PTZ models differ
and zoom between 1x and 30x.
pan google.protobuf.FloatValue degrees
tilt google.protobuf.FloatValue degrees
zoom google.protobuf.FloatValue zoom level

PtzVelocity

Doubles as a description of current state, or a command for a new velocity.

Field Type Label Description
ptz PtzDescription The "mech" ptz cannot be used with Velocity.
pan google.protobuf.FloatValue degrees/second
tilt google.protobuf.FloatValue degrees/second
zoom google.protobuf.FloatValue zoom level/second

SetPtzFocusStateRequest

Field Type Label Description
header bosdyn.api.RequestHeader
focus_state PtzFocusState

SetPtzFocusStateResponse

Field Type Label Description
header bosdyn.api.ResponseHeader

SetPtzPositionRequest

Command the ptz to move to a position.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
position PtzPosition Desired position to achieve.

SetPtzPositionResponse

Result of a SetPtzPositionRequest.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
position PtzPosition Applied desired position.

SetPtzVelocityRequest

Command a velocity for a ptz.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
velocity PtzVelocity Desired velocity to achieve.

SetPtzVelocityResponse

Result of a SetPtzVelocityRequest.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
velocity PtzVelocity Applied desired position.

PtzFocusState.PtzFocusMode

Name Number Description
PTZ_FOCUS_UNDEFINED 0
PTZ_FOCUS_AUTO 1
PTZ_FOCUS_MANUAL 2

Top

bosdyn/api/spot_cam/service.proto

AudioService

Upload and play sounds over the SpotCam’s speakers.

Method Name Request Type Response Type Description
PlaySound PlaySoundRequest PlaySoundResponse Given a soundRequest that identifies a single sound present in the system's sound effects
table, PlaySound executes the sound effect.
LoadSound LoadSoundRequest stream LoadSoundResponse LoadSound loads a sound effect into the system's sound table. The stream must contain a wav
file, with a RIFF header describing it. The arguement is a stream, to allow for sounds that
are bigger then the MTU of the network; in this case, the complete stream must contain the
entire sound. If the stream ends early, an error will be returned. The header and sound
fields of the entire stream must be the same.
DeleteSound DeleteSoundRequest DeleteSoundResponse Delete the sound identified in the argument from the system's sound table.
ListSounds ListSoundsRequest ListSoundsResponse ListSounds returns a list of all of the sound effects that the system knows about.
SetVolume SetVolumeRequest SetVolumeResponse Set the overall volume level for playing sounds.
GetVolume GetVolumeRequest GetVolumeResponse Set the overall volume level for playing sounds.
SetAudioCaptureChannel SetAudioCaptureChannelRequest SetAudioCaptureChannelResponse
GetAudioCaptureChannel GetAudioCaptureChannelRequest GetAudioCaptureChannelResponse
SetAudioCaptureGain SetAudioCaptureGainRequest SetAudioCaptureGainResponse
GetAudioCaptureGain GetAudioCaptureGainRequest GetAudioCaptureGainResponse

CompositorService

Change the layout of of the video stream between available presets.

Method Name Request Type Response Type Description
SetScreen SetScreenRequest SetScreenResponse SetScreen changes the current view that is streamed over the network
GetScreen GetScreenRequest GetScreenResponse GetScreen returns the currently-selected screen
ListScreens ListScreensRequest ListScreensResponse ListScreens returns a list of available screens
GetVisibleCameras GetVisibleCamerasRequest GetVisibleCamerasResponse GetVisibleCameras returns a list of currently visible windows, with any available metadata
SetIrColormap SetIrColormapRequest SetIrColormapResponse set the mapping between radiometric IR samples to color, for video
GetIrColormap GetIrColormapRequest GetIrColormapResponse get the mapping between radiometric IR samples to color, for video
SetIrMeterOverlay SetIrMeterOverlayRequest SetIrMeterOverlayResponse apply settings for the 'ir meter overlay'
GetIrMeterOverlay GetIrMeterOverlayRequest GetIrMeterOverlayResponse retrieve settings for the 'ir meter overlay'

HealthService

Query temperature and built-in test results.

Method Name Request Type Response Type Description
GetTemperature GetTemperatureRequest GetTemperatureResponse GetTemperature returns a list of thermometers in the system, and the temperature that they
measure.
GetBITStatus GetBITStatusRequest GetBITStatusResponse GetBitStatus returns two lists; a list of system events, and a list of ways that the system
is degraded; for instance, a degredation may include a missing PTZ unit, or a missing USB
storage device.
ClearBITEvents ClearBITEventsRequest ClearBITEventsResponse ClearBitEvents clears out the events list of the BITStatus structure.
GetSystemLog GetSystemLogRequest GetSystemLogResponse stream GetSystemLog retrieves an encrypted log of system events, for factory diagnosis of possible
issues. The data streamed back should be concatenated to a single file, before sending to the
manufacturer.

LightingService

Change the brightness level of individual LEDs.

Method Name Request Type Response Type Description
SetLEDBrightness SetLEDBrightnessRequest SetLEDBrightnessResponse
GetLEDBrightness GetLEDBrightnessRequest GetLEDBrightnessResponse

MediaLogService

Trigger data acquisitions, and retrieve resulting data.

Method Name Request Type Response Type Description
Store StoreRequest StoreResponse Store queues up a Logpoint, which is a bit of media that the user wishes to store to disk
(still images are supported for now, more media types will be supported in the future)
GetStatus GetStatusRequest GetStatusResponse GetStatus reads the 'name' field of the Logpoint contained in GetStatusRequest, and fills in
the rest of the fields. Mainly useful for getting the 'state' of the logpoint.
Tag TagRequest TagResponse Tag updates the 'tag' field of the Logpoint that's passed, which must exist.
EnableDebug DebugRequest DebugResponse EnableDebug starts the periodic logging of health data to the database; this increases disk
utilization, but will record data that is useful post-mortum
ListCameras ListCamerasRequest ListCamerasResponse ListCameras returns a list of strings that identify valid cameras for logging
RetrieveRawData RetrieveRawDataRequest RetrieveRawDataResponse stream Retrieve returns all raw data associated with a given logpoint
Retrieve RetrieveRequest RetrieveResponse stream Retrieve returns all data associated with a given logpoint
Delete DeleteRequest DeleteResponse Delete removes a Logpoint from the system
ListLogpoints ListLogpointsRequest ListLogpointsResponse stream ListLogpoints returns a list of all logpoints in the database.
Warning: this may be a lot of data.
SetPassphrase SetPassphraseRequest SetPassphraseResponse SetPassphrase sets the eCryptFS passphrase used by the filesystem.
there is no symmetry here, because key material is write-only
This rpc is now deprecated as of the switch from EXT4 to NTFS and returns UnimplementedError

NetworkService

Modify or query network settings of the SpotCam and ICE resolution servers.

Method Name Request Type Response Type Description
SetICEConfiguration SetICEConfigurationRequest SetICEConfigurationResponse SetICEConfiguration sets up parameters for ICE, including addresses for STUN and TURN
services
GetICEConfiguration GetICEConfigurationRequest GetICEConfigurationResponse GetICEConfiguration retrieves currently set parameters for ICE, including addresses for STUN
and TURN services

PowerService

Turn hardware components’ power on or off.

Method Name Request Type Response Type Description
SetPowerStatus SetPowerStatusRequest SetPowerStatusResponse Turn components' power on or off. This should not be used to power cycle a component
Turning PTZ power off for too long will cause the video stream to fail
GetPowerStatus GetPowerStatusRequest GetPowerStatusResponse Get current status of a component
CyclePower CyclePowerRequest CyclePowerResponse Cycle power for a component

PtzService

Control real and virtual ptz mechanisms.

Method Name Request Type Response Type Description
SetPtzPosition SetPtzPositionRequest SetPtzPositionResponse SetPosition points the referenced camera to a given vector (in PTZ-space)
GetPtzPosition GetPtzPositionRequest GetPtzPositionResponse GetPosition returns the current settings of the referenced camera
SetPtzVelocity SetPtzVelocityRequest SetPtzVelocityResponse
GetPtzVelocity GetPtzVelocityRequest GetPtzVelocityResponse
ListPtz ListPtzRequest ListPtzResponse
InitializeLens InitializeLensRequest InitializeLensResponse Reinitializes PTZ autofocus
SetPtzFocusState SetPtzFocusStateRequest SetPtzFocusStateResponse
GetPtzFocusState GetPtzFocusStateRequest GetPtzFocusStateResponse

StreamQualityService

Set quality parameters for the stream, such as compression and image postprocessing settings.

Method Name Request Type Response Type Description
SetStreamParams SetStreamParamsRequest SetStreamParamsResponse
GetStreamParams GetStreamParamsRequest GetStreamParamsResponse
EnableCongestionControl EnableCongestionControlRequest EnableCongestionControlResponse

VersionService

Query the version of the software release running on the SpotCam.

Method Name Request Type Response Type Description
GetSoftwareVersion GetSoftwareVersionRequest GetSoftwareVersionResponse

Top

bosdyn/api/spot_cam/streamquality.proto

EnableCongestionControlRequest

Field Type Label Description
header bosdyn.api.RequestHeader
enable_congestion_control bool A boolean 'true' enables receiver congestion control while 'false' disables it

EnableCongestionControlResponse

Field Type Label Description
header bosdyn.api.ResponseHeader

GetStreamParamsRequest

Request the current video stream parameters.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetStreamParamsResponse

Provides the current video stream parameters.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
params StreamParams Current video stream parameters.

SetStreamParamsRequest

Modify the video stream parameters.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.
params StreamParams Set only the fields that should be modified.

SetStreamParamsResponse

Result of setting video stream parameters.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
params StreamParams Applied video stream parameters.

StreamParams

Parameters for how the video stream should be processed and compressed.

Field Type Label Description
targetbitrate google.protobuf.Int64Value The compression level in target BPS
refreshinterval google.protobuf.Int64Value How often should the entire feed be refreshed? (in frames)
Note: the feed is refreshed on a macroblock level; there are no full I-frames
idrinterval google.protobuf.Int64Value How often should an IDR message get sent? (in frames)
awb StreamParams.AwbMode Optional setting of automatic white balancing mode.
auto_exposure StreamParams.AutoExposure the AutoExposure option runs exposure independently on each of the ring cameras
sync_exposure StreamParams.SyncAutoExposure the SyncAutoExposure option runs a single autoexposure algorithm that takes into
account data from all ring cameras
manual_exposure StreamParams.ManualExposure manual exposure sets an exposure for all ring cameras.

StreamParams.AutoExposure

StreamParams.AwbMode

Wrapper for AwbModeEnum to allow it to be optionally set.

Field Type Label Description
awb StreamParams.AwbModeEnum

StreamParams.ManualExposure

Field Type Label Description
exposure google.protobuf.Duration duration is required, and may be clamped depending
on the parameters of the camera
gain google.protobuf.FloatValue if gain is omitted, it is assumed to be 1.0

StreamParams.SyncAutoExposure

Field Type Label Description
brightness_target google.protobuf.Int32Value brightness_target is a value between 0 and 255 which
controls the setpoint for the exposure control algorithm
if brightness_target is not set, a sensible default is chosen by the system

StreamParams.AwbModeEnum

Options for automatic white balancing mode.

Name Number Description
OFF 0
AUTO 1
INCANDESCENT 2
FLUORESCENT 3
WARM_FLUORESCENT 4
DAYLIGHT 5
CLOUDY 6
TWILIGHT 7
SHADE 8
DARK 9

Top

bosdyn/api/spot_cam/version.proto

GetSoftwareVersionRequest

Request the software version running on the SpotCam.

Field Type Label Description
header bosdyn.api.RequestHeader Common request header.

GetSoftwareVersionResponse

Provide the SpotCam’s software release version.

Field Type Label Description
header bosdyn.api.ResponseHeader Common response header.
version bosdyn.api.SoftwareVersion Version of the software currently running on the SpotCam.
detail string Extra detail about the version of software running on spotcam.
May contain metadata about build dates and configuration.

Top

bosdyn/api/stairs.proto

StairTransform

Field Type Label Description
frame_tform_stairs SE3Pose The staircase origin is the bottom-center of the first rise.
X-axis is oriented pointing up the stairs.
Y-axis is oriented to the left when facing up the stairs.
Z-axis is oriented facing up (opposite gravity).
frame_name string

Staircase

Field Type Label Description
knowledge_type Staircase.KnowledgeType How do we know about this staircase.
stair_tform StairTransform Location of the stairs origin relative to some named frame.
Origin defined as the center of the bottom of the lowest riser.
number_of_steps int32 Deprecated. Number of vertical risers.
DEPRECATED as of 4.0. Use the length of the steps field instead.
average_rise double Average vertical height of each step in meters.
average_run double Average horizontal distance between risers in meters.
average_width Staircase.Width Average width.
steps Staircase.Step repeated The individual steps ordered from lowest to highest.
id string Unique identifier used to equate staircases shared across edges and externally. This should
be randomly generated.

Staircase.Step

Field Type Label Description
point Vec3 Center of edge in stairs frame.
north Vec2 Unit vector pointing up the stairs in stairs frame, perpendicular to edge.
width Staircase.Width Width of stairs at this step.

Staircase.Width

Field Type Label Description
width double The distance in meters between the left and right side of the staircase.
bounded_width Staircase.Width.BoundedWidth

StaircaseLanding

Landing associated with a staircase

Field Type Label Description
stairs_tform_landing_center SE3Pose Pose of the landing's center relative to the stairs frame.
landing_extent_x double The half-size of the box representing the landing in the x axis.
landing_extent_y double The half-size of the box representing the landing in the y axis.

StaircaseWithLandings

Stairs and their associated landings.

Field Type Label Description
bottom_landing StaircaseLanding
staircase Staircase
top_landing StaircaseLanding

StraightStaircase

Field Type Label Description
from_ko_tform_stairs SE3Pose It is expressed in ko frame of the from_waypoint.
This field is only used in GraphNav.
tform StairTransform Outside GraphNav, this field specifies the stair origin.
stairs StraightStaircase.Stair repeated Each stair should be rise followed by run. The last stair will have zero run.
bottom_landing StraightStaircase.Landing The lowermost landing of the stairs. The robot will try to
align itself to the stairs while on this landing.
top_landing StraightStaircase.Landing The uppermost landing of the stairs.

StraightStaircase.Landing

Straight staircases have two landings, one at the top and one at the bottom. Landings are areas of free space before and after the stairs, and are represented as oriented bounding boxes.

Field Type Label Description
stairs_tform_landing_center SE3Pose Pose of the landing's center relative to the stairs frame.
landing_extent_x double The half-size of the box representing the landing in the x axis.
landing_extent_y double The half-size of the box representing the landing in the y axis.

StraightStaircase.Stair

A single stair from a staircase.

Field Type Label Description
rise float Height of each stair.
run float Depth of each stair.

Staircase.KnowledgeType

Name Number Description
KNOWLEDGE_TYPE_UNKNOWN 0
KNOWLEDGE_TYPE_MAPPED 1 A staircase that was in a map (e.g. an AutoWalk edge annotation).
Dimensions are expected to be accurate, but location is subject to localization accuracy.
KNOWLEDGE_TYPE_TRACKED_ONGOING 2 A staircase that we are currently tracking.
Location should be accurate, but the farther-away portions may be inaccurate.
KNOWLEDGE_TYPE_TRACKED_COMPLETED 3 A recently-traversed staircase that we tracked during the traversal.
This should be accurate in both dimensions and location, but behind us.
KNOWLEDGE_TYPE_OTHER 4 Something else?

Staircase.Width.BoundedWidth

The two sides of a staircase are designated “east” and “west” as if north is up. The “west” side is the left when facing up the stairs and the right when facing down. The “east” side is the right when facing up the stairs and the left when facing down.

Name Number Description
BOUNDED_WIDTH_UNKNOWN 0
BOUNDED_WIDTH_NEITHER 1
BOUNDED_WIDTH_WEST 2
BOUNDED_WIDTH_EAST 3
BOUNDED_WIDTH_BOTH 4

Top

bosdyn/api/synchronized_command.proto

SynchronizedCommand

SynchronizedCommand.Feedback

Field Type Label Description
arm_command_feedback ArmCommand.Feedback
mobility_command_feedback MobilityCommand.Feedback
gripper_command_feedback GripperCommand.Feedback

SynchronizedCommand.Request

Field Type Label Description
arm_command ArmCommand.Request
mobility_command MobilityCommand.Request
gripper_command GripperCommand.Request

Top

bosdyn/api/time_range.proto

TimeRange

Representation of a time range from a start time through an end time.

Field Type Label Description
start google.protobuf.Timestamp
end google.protobuf.Timestamp

Top

bosdyn/api/time_sync.proto

TimeSyncEstimate

Estimate of network speed and clock skew. Both for the last complete sample and a recent average. Populated by the server.

Field Type Label Description
round_trip_time google.protobuf.Duration Observed network delay (excludes processing between server_rx and server_tx).
If zero, this estimate is unpopulated.
clock_skew google.protobuf.Duration Add the skew to the client system clock to get the server clock.

TimeSyncRoundTrip

Timestamp information from a full GRPC call round-trip. These are used to estimate the round-trip communication time and difference between client and server clocks.

Field Type Label Description
client_tx google.protobuf.Timestamp Client system time when the message was sent, if not zero.
server_rx google.protobuf.Timestamp Server system time when the message was received, if not zero.
server_tx google.protobuf.Timestamp Server system time when the response was sent, if not zero.
client_rx google.protobuf.Timestamp Client time when the response was received, if not zero.

TimeSyncState

Current best estimate status of time sync.

Field Type Label Description
best_estimate TimeSyncEstimate Best clock synchronization estimate currently available, if any.
status TimeSyncState.Status STATUS_OK once time sync is established.
measurement_time google.protobuf.Timestamp Time of best estimate, in server time.

TimeSyncUpdateRequest

Request message for a time-sync Update RPC.

Field Type Label Description
header RequestHeader Common request header.
previous_round_trip TimeSyncRoundTrip Round-trip timing information from the previous Update request.
clock_identifier string Identifier to verify time sync between robot and client. If unset, server will assign
one to client.

TimeSyncUpdateResponse

Request message for a time-sync Update RPC.

Field Type Label Description
header ResponseHeader Common response header.
previous_estimate TimeSyncEstimate Clock synchronization estimate from the previous RPC round-trip, if available.
state TimeSyncState Current best clock synchronization estimate according to server.
clock_identifier string Identifier to verify time sync between robot and client. Assigned upon first Request and
echoed with each subsequent request.

TimeSyncState.Status

Name Number Description
STATUS_UNKNOWN 0 Invalid, do not use.
STATUS_OK 1 Clock skew is available.
STATUS_MORE_SAMPLES_NEEDED 2 More updates are required to establish a synchronization estimate.
STATUS_SERVICE_NOT_READY 3 Server still establishing time sync internally.

Top

bosdyn/api/time_sync_service.proto

TimeSyncService

The time-sync service estimates the difference between server and client clocks. Time synchronization is a tool which allows applications to work in a unified timebase with precision. It is useful in cases where a precise time must be set, independently of network communication lag. In distributed systems and robotics, hardware, system-level, and per-process approaches can be used to obtain synchronization. This service implements a stand alone time synchronization service. It enables clients to establish a per-process offset between two processes which may be on separate systems.

Method Name Request Type Response Type Description
TimeSyncUpdate TimeSyncUpdateRequest TimeSyncUpdateResponse See the exchange documentation in time_sync.proto. This call makes one client/server
round trip toward clock synchronization.

Top

bosdyn/api/trajectory.proto

SE2Trajectory

A 2D pose trajectory, which specified multiple points and the desired times the robot should reach these points.

Field Type Label Description
points SE2TrajectoryPoint repeated The points in trajectory
reference_time google.protobuf.Timestamp All trajectories 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.
interpolation PositionalInterpolation Parameters for how trajectories will be interpolated on robot.

SE2TrajectoryPoint

A SE2 pose that can be used as a point within a trajectory.

Field Type Label Description
pose SE2Pose Required pose the robot will try and achieve.
time_since_reference google.protobuf.Duration The duration to reach the point relative to the trajectory reference time.

SE3Trajectory

A 3D pose trajectory, which specified multiple poses (and velocities for each pose) and the desired times the robot should reach these points.

Field Type Label Description
points SE3TrajectoryPoint repeated The points in trajectory
reference_time google.protobuf.Timestamp All trajectories 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.
pos_interpolation PositionalInterpolation Parameters for how trajectories will be interpolated on robot.
ang_interpolation AngularInterpolation

SE3TrajectoryPoint

A SE3 pose and velocity that can be used as a point within a trajectory.

Field Type Label Description
pose SE3Pose Required pose the robot will try and achieve.
velocity SE3Velocity Optional velocity (linear and angular) the robot will try and achieve.
time_since_reference google.protobuf.Duration The duration to reach the point relative to the trajectory reference time.

ScalarTrajectory

A Point trajectory.

Field Type Label Description
points ScalarTrajectoryPoint repeated The points in trajectory
reference_time google.protobuf.Timestamp All trajectories 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.
interpolation PositionalInterpolation Parameters for how trajectories will be interpolated on robot.
(Note: ignored for ClawGripperCommand.Request, which will automatically
select between cubic interpolation or a minimum time trajectory)

ScalarTrajectoryPoint

Field Type Label Description
point double Required position at the trajectory point's reference time.
velocity google.protobuf.DoubleValue Optional speed at the trajectory point's reference time.
time_since_reference google.protobuf.Duration The duration to reach the point relative to the trajectory reference time.

Vec3Trajectory

A 3D point trajectory, described by 3D points, a starting and ending velocity, and a reference time.

Field Type Label Description
points Vec3TrajectoryPoint repeated The points in trajectory.
reference_time google.protobuf.Timestamp All trajectories 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.
pos_interpolation PositionalInterpolation Parameters for how trajectories will be interpolated on robot.
starting_velocity Vec3 Velocity at the starting point of the trajectory.
ending_velocity Vec3 Velocity at the ending point of the trajectory.

Vec3TrajectoryPoint

A 3D point (and linear velocity) that can be used as a point within a trajectory.

Field Type Label Description
point Vec3 The point 3D position.
linear_speed double These are all optional. If nothing is specified, good defaults will be chosen
server-side.
time_since_reference google.protobuf.Duration The duration to reach the point relative to the trajectory reference time.

WrenchTrajectory

A time-based trajectories of wrenches.

Field Type Label Description
points WrenchTrajectoryPoint repeated The wrenches in the trajectory
reference_time google.protobuf.Timestamp All trajectories 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.

WrenchTrajectoryPoint

Field Type Label Description
wrench Wrench The wrench to apply at this point in time.
time_since_reference google.protobuf.Duration The duration to reach the point relative to the trajectory reference time.

AngularInterpolation

Parameters for how angular trajectories will be interpolated on robot.

Name Number Description
ANG_INTERP_UNKNOWN 0 Unknown interpolation, do not use.
ANG_INTERP_LINEAR 1 Linear interpolation for angular data.
ANG_INTERP_CUBIC_EULER 2 Cubic interpolation (using Euler method) for angular data.

PositionalInterpolation

Parameters for how positional trajectories will be interpolated on robot.

Name Number Description
POS_INTERP_UNKNOWN 0 Unknown interpolation, do not use.
POS_INTERP_LINEAR 1 Linear interpolation for positional data.
POS_INTERP_CUBIC 2 Cubic interpolation for positional data.

Top

bosdyn/api/units.proto

Units

Field Type Label Description
name string Use this field if the desired unit is not a supported enum.
temp TemperatureEnum
press PressureEnum
is_relative bool If a service wants an absolute temperature threshold between 0 C and 100 C, that would show
up as 32 F to 212 F on any Fahrenheit loving clients IF is_relative is set to false. Note
the change from 0 C to 32 F.

If a service wants a relative temperate threshold (region A must be no more than X degrees
hotter than region B), between 0 and 100 C, that would show up as 0 F to 180 F on any
Fahrenheit loving clients IF is_relative is set to true. Note that 0 C now maps to 0 F.

NOTE: Only relevant for units with non equal zero points.

PressureEnum

Name Number Description
PRESSURE_UNKNOWN 0
PRESSURE_PSI 1 Pound-force per square inch
PRESSURE_KPA 2 KiloPascal
PRESSURE_BAR 3 Bar

TemperatureEnum

Name Number Description
TEMPERATURE_UNKNOWN 0
TEMPERATURE_KELVIN 1
TEMPERATURE_CELSIUS 2
TEMPERATURE_FAHRENHEIT 3

Top

bosdyn/api/world_object.proto

AprilTagProperties

World object properties describing a fiducial object.

Field Type Label Description
tag_id int32 Consistent integer id associated with a given apriltag. April Tag detections will be from the
tag family 36h11.
dimensions Vec2 Apriltag size in meters, where x is the row/width length and y is the
height/col length of the tag
frame_name_fiducial string The frame name for the raw version of this fiducial. This will be included in the transform
snapshot.
fiducial_pose_status AprilTagProperties.AprilTagPoseStatus Status of the pose estimation of the unfiltered fiducial frame.
frame_name_fiducial_filtered string The frame name for the filtered version of this fiducial. This will be included in the
transform snapshot.
fiducial_filtered_pose_status AprilTagProperties.AprilTagPoseStatus Status of the pose estimation of the filtered fiducial frame.
frame_name_camera string The frame name for the camera that detected this fiducial.
detection_covariance SE3Covariance A 6 x 6 Covariance matrix representing the marginal uncertainty of the last detection.
The rows/columns are:
rx, ry, rz, tx, ty, tz
which represent incremental rotation and translation along the x, y, and z axes of the
given frame, respectively.
This is computed using the Jacobian of the pose estimation algorithm.
detection_covariance_reference_frame string The frame that the detection covariance is expressed in.

BoundingBoxProperties

Field Type Label Description
size_ewrt_frame Vec3 An Oriented Bounding Box, with position and orientation at the frame provided in the
transforms snapshot.

The size of the box is expressed with respect to the frame.
frame string Frame the size is expressed with respect to.

DockProperties

World object properties describing a dock

Field Type Label Description
dock_id uint32 Consistent id associated with a given dock.
type docking.DockType Type of dock.
frame_name_dock string The frame name for the location of dock origin. This will be included in the transform
snapshot.
unavailable bool Availability if the dock can be used
from_prior bool The dock is an unconfirmed prior detection

DrawableArrow

A directed arrow drawing object.

Field Type Label Description
direction Vec3
radius double

DrawableBox

A three dimensional box drawing object.

Field Type Label Description
size Vec3

DrawableCapsule

A oval-like capsule drawing object.

Field Type Label Description
direction Vec3
radius double

DrawableCylinder

A cylinder drawing object.

Field Type Label Description
direction Vec3
radius double

DrawableFrame

A coordinate frame drawing object, describing how large to render the arrows.

Field Type Label Description
arrow_length double
arrow_radius double

DrawableLineStrip

A line strip drawing object.

Field Type Label Description
points Vec3

DrawablePoints

A set of points drawing object.

Field Type Label Description
points Vec3 repeated

DrawableProperties

The drawing and visualization information for a world object.

Field Type Label Description
color DrawableProperties.Color Color of the object.
label string Label to be drawn at the origin of the object.
wireframe bool Drawn objects in wireframe.
frame DrawableFrame A drawable frame (oneof drawable field).
sphere DrawableSphere A drawable sphere (oneof drawable field).
box DrawableBox A drawable box (oneof drawable field).
arrow DrawableArrow A drawable arrow (oneof drawable field).
capsule DrawableCapsule A drawable capsule (oneof drawable field).
cylinder DrawableCylinder A drawable cylinder (oneof drawable field).
linestrip DrawableLineStrip A drawable linestrip (oneof drawable field).
points DrawablePoints A drawable set of points (oneof drawable field).
frame_name_drawable string The frame name for the drawable object. This will optionally be
included in the frame tree snapshot.

DrawableProperties.Color

RGBA values for color ranging from [0,255] for R/G/B, and [0,1] for A.

Field Type Label Description
r int32 Red value ranging from [0,255].
g int32 Green value ranging from [0,255].
b int32 Blue value ranging from [0,255].
a double Alpha (transparency) value ranging from [0,1].

DrawableSphere

A sphere drawing object.

Field Type Label Description
radius double

GpsProperties

Properties related to GPS measurements of our location with respect to the Earth.

Field Type Label Description
registration gps.Registration

ImageProperties

World object properties describing image coordinates associated with an object or scene.

Field Type Label Description
camera_source string Camera Source of such as "back", "frontleft", etc.
coordinates Polygon Image coordinates of the corners of a polygon (pixels of x[row], y[col]) in either
clockwise/counter clockwise order
keypoints KeypointSet A set of keypoints and their associated metadata.
image_source ImageSource Camera parameters.
image_capture ImageCapture Image that produced the data.
frame_name_image_coordinates string Frame name for the object described by image coordinates.

ListWorldObjectRequest

The ListWorldObject request message, which can optionally include filters for the object type or timestamp.

Field Type Label Description
header RequestHeader Common request header
object_type WorldObjectType repeated Optional filters to apply to the world object request
Specific type of object; can request multiple different properties
timestamp_filter google.protobuf.Timestamp Timestamp to filter objects based on. The time should be in robot time
All objects with header timestamps after (>) timestamp_filter will be returned

ListWorldObjectResponse

The ListWorldObject response message, which contains all of the current world objects in the robot’s perception scene.

Field Type Label Description
header ResponseHeader Common response header
world_objects WorldObject repeated The currently perceived world objects.

MutateWorldObjectRequest

The MutateWorldObject request message, which specifies the type of mutation and which object the mutation should be applied to.

Field Type Label Description
header RequestHeader Common request header
mutation MutateWorldObjectRequest.Mutation The mutation for this request.

MutateWorldObjectRequest.Mutation

Field Type Label Description
action MutateWorldObjectRequest.Action The action (add, change, or delete) to be applied to a world object.
object WorldObject World object to be mutated.
If an object is being changed/deleted, then the world object id must match a world
object id known by the service.

MutateWorldObjectResponse

The MutateWorldObject response message, which includes the world object id for the object that the mutation was applied to if the request succeeds.

Field Type Label Description
header ResponseHeader Common response header
status MutateWorldObjectResponse.Status Return status for the request.
mutated_object_id int32 ID set by the world object service for the mutated object

NoGoRegionProperties

A box no-go region

Field Type Label Description
box Box2WithFrame
disable_foot_obstacle_generation bool If set true, will NOT create a foot obstacle for this region.
disable_body_obstacle_generation bool If set true, will NOT create a body obstacle for this region.
disable_foot_obstacle_inflation bool If set true, and a foot obstacle is being generated, will make the foot obstacle the exact
size specified in the "region" field and NOT inflate by approx. robot foot width.

RayProperties

Field Type Label Description
ray Ray Ray, usually pointing from the camera to the object.
frame string Frame the ray is expressed with respect to.

StaircaseProperties

Field Type Label Description
staircase Staircase

WorldObject

The world object message is used to describe different objects seen by a robot. It contains information about the properties of the object in addition to a unique id and the transform snapshot. The world object uses “properties” to describe different traits about the object, such as image coordinates associated with the camera the object was detected in. A world object can have multiple different properties that are all associated with the single object.

Field Type Label Description
id int32 Unique integer identifier that will be consistent for the duration of a robot's battery life
The id is set internally by the world object service.
name string A human readable name for the world object. Note that this differs from any frame_name's
associated with the object (since there can be multiple frames describing a single object).
acquisition_time google.protobuf.Timestamp Time in robot time clock at which this object was most recently detected and valid.
transforms_snapshot FrameTreeSnapshot A tree-based collection of transformations, which will include the transformations to each
of the returned world objects in addition to transformations to the common frames ("vision",
"body", "odom"). All transforms within the snapshot are at the acquisition time of the world
object. Note that each object's frame names are defined within the properties submessage. For
example, the apriltag frame name is defined in the AprilTagProperties message as
"frame_name_fiducial"
object_lifetime google.protobuf.Duration Duration of time after which the obstacle expires. If this field is left blank, the object
will expire according to a default time set in the world object service. The duration is
relative to the acquisition_time if filled out, or relative to the time the object is
added to the world object service if acquisition_time is left blank.
drawable_properties DrawableProperties repeated The drawable properties describe geometric shapes associated with an object.
apriltag_properties AprilTagProperties The apriltag properties describe any fiducial identifying an object.
nogo_region_properties NoGoRegionProperties Property for a user no-go
image_properties ImageProperties The image properties describe any camera and image coordinates associated with an object.
dock_properties DockProperties Properties describing a dock
ray_properties RayProperties A ray pointing at the object. Useful in cases where position is unknown but direction is
known.
bounding_box_properties BoundingBoxProperties Bounding box in the world, oriented at the location provided in the transforms_snapshot.
staircase_properties StaircaseProperties The staircase properties provide information that helps the robot traverse or see a staircase.
gps_properties GpsProperties Information about the Earth relative to the robot, localized by GPS.
additional_properties google.protobuf.Any An extra field for application-specific object properties.

AprilTagProperties.AprilTagPoseStatus

Name Number Description
STATUS_UNKNOWN 0
STATUS_OK 1 No known issues with the pose estimate.
STATUS_AMBIGUOUS 2 The orientation of the tag is ambiguous.
STATUS_HIGH_ERROR 3 The pose may be unreliable due to high reprojection error.

MutateWorldObjectRequest.Action

Name Number Description
ACTION_UNKNOWN 0 Invalid action.
ACTION_ADD 1 Add a new object.
ACTION_CHANGE 2 Change an existing objected (ID'd by integer ID number). This is
only allowed to change objects added by the API-user, and not
objects detected by Spot's perception system.
ACTION_DELETE 3 Delete the object, ID'd by integer ID number. This is
only allowed to change objects added by the API-user, and not
objects detected by Spot's perception system.

MutateWorldObjectResponse.Status

Name Number Description
STATUS_UNKNOWN 0 Status of request is unknown. Check the status code of the response header.
STATUS_OK 1 Request was accepted; GetObjectListResponse must still be checked to verify the changes.
STATUS_INVALID_MUTATION_ID 2 The mutation object's ID is unknown such that the service could not recognize this
object. This error applies to the CHANGE and DELETE actions, since it must identify the
object by it's id number given by the service.
STATUS_NO_PERMISSION 3 The mutation request is not allowed because it is attempting to change or delete an
object detected by Spot's perception system.
STATUS_INVALID_WORLD_OBJECT 4 The mutation request is not allowed because some aspect of the world object is invalid.
For example, something could be defined in an unallowed reference frame.

WorldObjectType

A type for the world object, which is associated with whatever properties the world object includes. This can be used to request specific kinds of objects; for example, a request for only fiducials.

Name Number Description
WORLD_OBJECT_UNKNOWN 0
WORLD_OBJECT_DRAWABLE 1
WORLD_OBJECT_APRILTAG 2
WORLD_OBJECT_IMAGE_COORDINATES 5
WORLD_OBJECT_DOCK 6
WORLD_OBJECT_USER_NOGO 8
WORLD_OBJECT_STAIRCASE 9

Top

bosdyn/api/world_object_service.proto

WorldObjectService

The world object service provides a way to track and store objects detected in the world around the robot.

Method Name Request Type Response Type Description
ListWorldObjects ListWorldObjectRequest ListWorldObjectResponse Request a list of all the world objects in the robot's perception scene.
MutateWorldObjects MutateWorldObjectRequest MutateWorldObjectResponse Mutate (add, change, or delete) the world objects.

Scalar Value Types

.proto Type Notes C++ Java Python Go C# PHP Ruby
double double double float float64 double float Float
float float float float float32 float float Float
int32 Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint32 instead. int32 int int int32 int integer Bignum or Fixnum (as required)
int64 Uses variable-length encoding. Inefficient for encoding negative numbers – if your field is likely to have negative values, use sint64 instead. int64 long int/long int64 long integer/string Bignum
uint32 Uses variable-length encoding. uint32 int int/long uint32 uint integer Bignum or Fixnum (as required)
uint64 Uses variable-length encoding. uint64 long int/long uint64 ulong integer/string Bignum or Fixnum (as required)
sint32 Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int32s. int32 int int int32 int integer Bignum or Fixnum (as required)
sint64 Uses variable-length encoding. Signed int value. These more efficiently encode negative numbers than regular int64s. int64 long int/long int64 long integer/string Bignum
fixed32 Always four bytes. More efficient than uint32 if values are often greater than 2^28. uint32 int int uint32 uint integer Bignum or Fixnum (as required)
fixed64 Always eight bytes. More efficient than uint64 if values are often greater than 2^56. uint64 long int/long uint64 ulong integer/string Bignum
sfixed32 Always four bytes. int32 int int int32 int integer Bignum or Fixnum (as required)
sfixed64 Always eight bytes. int64 long int/long int64 long integer/string Bignum
bool bool boolean boolean bool bool boolean TrueClass/FalseClass
string A string must always contain UTF-8 encoded or 7-bit ASCII text. string String str/unicode string string string String (UTF-8)
bytes May contain any arbitrary sequence of bytes. string ByteString str []byte ByteString string String (ASCII-8BIT)