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 |
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 |
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. |
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.
ArmCommand.Request
The arm request must be one of the basic command primitives.
ArmJointMoveCommand
Specify a set of joint angles to move the arm.
ArmJointMoveCommand.Feedback
Field |
Type |
Description |
status |
ArmJointMoveCommand.Feedback.Status |
Current status of the request. |
planner_status |
ArmJointMoveCommand.Feedback.PlannerStatus |
Current status of the trajectory planner. |
planned_points |
ArmJointTrajectoryPoint |
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. |
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 |
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.
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 |
Description |
points |
ArmJointTrajectoryPoint |
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 |
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.
ArmParams
Parameters common across arm commands.
Field |
Type |
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 |
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 |
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 |
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 |
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 |
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
NamedArmPositionsCommand.Request
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 |
|
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. |
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 positions may refuse to execute if the gripper is holding an item, for example stow. |
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. |
basic_command.proto
BatteryChangePoseCommand
Get the robot into a convenient pose for changing the battery
BatteryChangePoseCommand.Feedback
BatteryChangePoseCommand.Request
ConstrainedManipulationCommand
ConstrainedManipulationCommand.Feedback
ConstrainedManipulationCommand.Request
Field |
Type |
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. |
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 |
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 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.
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.
SE2TrajectoryCommand.Request
Field |
Type |
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 |
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.
SafePowerOffCommand.Request
SelfRightCommand
Move the robot into a “ready” position from which it can sit or stand up.
SelfRightCommand.Feedback
SelfRightCommand.Request
SelfRight command request takes no additional arguments.
SitCommand
Sit the robot down in its current position.
SitCommand.Request
Sit command request takes no additional arguments.
Stance
Field |
Type |
Description |
se2_frame_name |
string |
The frame name which the desired foot_positions are described in. |
foot_positions |
Stance.FootPositionsEntry |
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) |
StanceCommand
Precise foot placement
This can be used to reposition the robots feet in place.
StanceCommand.Request
Field |
Type |
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.
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.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. |
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.Status
Name |
Number |
Description |
STATUS_UNKNOWN |
0 |
STATUS_UNKNOWN should never be used. If used, an internal error has happened. |
STATUS_AT_GOAL |
1 |
The robot has arrived and is standing at the goal. |
STATUS_NEAR_GOAL |
3 |
The robot has arrived at the goal and is doing final positioning. |
STATUS_GOING_TO_GOAL |
2 |
The robot is attempting to go to a goal. |
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. |
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 |
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 |
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.
FileFormatDescriptor.AnnotationsEntry
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 |
Description |
series_identifiers |
SeriesIdentifier |
SeriesIdentifer for each series in this file. |
series_block_index_offsets |
uint64 |
The offset from the start of the file of the SeriesBlockIndex block for each series. |
series_identifier_hashes |
uint64 |
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 MesssageTypeDescriptor.
Field |
Type |
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 |
Description |
pod_type |
PodTypeEnum |
The type of machine-readable values stored. |
dimension |
uint32 |
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 |
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 |
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 |
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 |
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 |
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 |
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 |
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
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 |
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 |
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
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.
StructTypeDescriptor.KeyToSeriesIdentifierHashEntry
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 |
|
data_acquisition.proto
AcquireDataRequest
Field |
Type |
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 DAQ 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 |
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 DAQ service to all data acquisition plugin services.
Field |
Type |
Description |
header |
RequestHeader |
Common request header |
data_id |
DataIdentifier |
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 DAQ plugin. |
AcquirePluginDataResponse
Field |
Type |
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. |
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.
AcquisitionRequestList
The grouping of all individual image and data captures for a given capture action.
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 |
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. |
CancelAcquisitionRequest
Field |
Type |
Description |
header |
RequestHeader |
Common request header |
request_id |
uint32 |
Which acquisition request to cancel. |
CancelAcquisitionResponse
Field |
Type |
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 |
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 recieved. |
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 |
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. |
DataCapture
An individual capture which can be specified in the AcquireData request to identify a piece of
non-image data to be collected.
Field |
Type |
Description |
name |
string |
Name of the data to be captured. This should match the uniquely identifying name from the DataAcquisitionCapability. |
DataError
An error associated with a particular capture action and piece of data.
Field |
Type |
Description |
data_id |
DataIdentifier |
Identifier for the data to be saved. |
error_message |
string |
Human-readable message describing the error. |
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 |
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. |
GetServiceInfoRequest
Field |
Type |
Description |
header |
RequestHeader |
Common request header |
GetServiceInfoResponse
Field |
Type |
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 |
Description |
header |
RequestHeader |
Common request header |
request_id |
uint32 |
Which acquisition to check the status of. |
GetStatusResponse
Field |
Type |
Description |
header |
ResponseHeader |
Common response header |
status |
GetStatusResponse.Status |
|
data_saved |
DataIdentifier |
Data that has been successfully saved into the data buffer for the capture action. |
data_errors |
DataError |
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 |
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 |
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 |
Description |
service_name |
string |
The image service's service name used in directory registration. |
image_source_names |
string |
(Depricate) Please use "image_sources" below for information regarding the image source associated with the service. |
image_sources |
ImageSource |
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 |
Description |
image_service |
string |
Name of the image service that the data should be requested from. |
image_source |
string |
Specific image source to use from the list reported by the image service within the ImageAcquisitionCapability message. |
pixel_format |
Image.PixelFormat |
Specific pixel format to capture reported by the ImageAcquisitionCapability message. |
PluginServiceError
An error associated with a particular data acquisition plugin service that was
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. |
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 |
[Status] Data has been acquired, processing and storage is now in progress. |
STATUS_COMPLETE |
3 |
[Status] Data acquisition is complete. |
STATUS_CANCEL_IN_PROGRESS |
4 |
[Status] The data acquisition service is working to cancel the request. |
STATUS_ACQUISITION_CANCELLED |
5 |
[Status] 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 |
[Error - AcquireData] The data collection has passed the deadline for completion. |
STATUS_INTERNAL_ERROR |
12 |
[Error - AcquireData] 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. |
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. |
data_buffer.proto
DataBlob
Message-style data to add to the log.
Field |
Type |
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 |
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 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 should not be set. - 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 |
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. |
RecordDataBlobsRequest
Field |
Type |
Description |
header |
RequestHeader |
Common request header. |
blob_data |
DataBlob |
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.Error
DataBlob recording error.
RecordEventsRequest
Field |
Type |
Description |
header |
RequestHeader |
Common request header. |
events |
Event |
The events to be logged. |
RecordEventsResponse.Error
Event recording error.
Field |
Type |
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. |
RecordSignalTicksRequest
Field |
Type |
Description |
header |
RequestHeader |
Common request header. |
tick_data |
SignalTick |
The signals data to be logged. |
RecordSignalTicksResponse
RecordSignalTicksResponse.Error
Signal tick recording error.
RecordTextMessagesRequest
Field |
Type |
Description |
header |
RequestHeader |
Common request header. |
text_messages |
TextMessage |
The text messages to be logged. |
RecordTextMessagesResponse
RecordTextMessagesResponse.Error
Text message recording error.
RegisterSignalSchemaRequest
Field |
Type |
Description |
header |
RequestHeader |
Common request/response header. |
schema |
SignalSchema |
Defines a schema for interpreting SignalTick data containing packed signals-type data. |
RegisterSignalSchemaResponse
Field |
Type |
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 |
Description |
vars |
SignalSchema.Variable |
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 |
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. |
SignalTick
A timestamped set of signals variable values.
Field |
Type |
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 |
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-occurence basis.
Lower level events should be less consequential on a per occurence 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 guarentee 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 |
|
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 concatination 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. |
data_index.proto
BlobPage
A set of blob messages of a given channel/msgtype within a given data page.
BlobPages
A set of pages of data which contain specified Blob messages from the data-buffer.
BlobSpec
Specification for selecting of blob messages.
Field |
Type |
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/'. |
DataIndex
Description of data matching a given DataQuery.
DataQuery
A query for pages containing the desired data.
Field |
Type |
Description |
time_range |
TimeRange |
Timespan for data we want to query |
blobs |
BlobSpec |
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 |
Description |
header |
RequestHeader |
|
time_range |
TimeRange |
Delete all pages in this time range |
page_ids |
string |
Delete all pages with matching ids |
EventSpec
Specification for selecting Events.
GetDataBufferStatusRequest
GetDataBufferStatusResponse
GetDataIndexRequest
GRPC response with requested data index information.
GetDataIndexResponse
GRPC request for data index information.
GrpcPages
A set of pages of data which contain specied GRPC request and response messages.
GrpcSpec
Specification for selecting of GRPC logs.
Field |
Type |
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 |
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.
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 |
estop.proto
DeregisterEstopEndpointRequest
Deregister the specified E-Stop endpoint registration.
Field |
Type |
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.
EstopCheckInRequest
Client request for setting/maintaining an E-Stop system level.
After the first CheckIn, must include response to previous challenge.
Field |
Type |
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.
EstopConfig
Configuration of a root / server.
Field |
Type |
Description |
endpoints |
EstopEndpoint |
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 |
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.
EstopSystemStatus
Status of Estop system.
Field |
Type |
Description |
endpoints |
EstopEndpointWithStatus |
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 |
Description |
header |
RequestHeader |
Common request header. |
target_config_id |
string |
The 'unique_id' of EstopConfig to get. |
GetEstopConfigResponse
Response to EstopConfigRequest.
GetEstopSystemStatusRequest
Ask for the current status of the Estop system.
Field |
Type |
Description |
header |
RequestHeader |
Common request header. |
GetEstopSystemStatusResponse
Respond with the current Estop system status.
RegisterEstopEndpointRequest
Register an endpoint.
EstopEndpoints must be registered before they can send commands or request challenges.
Field |
Type |
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.
SetEstopConfigRequest
Set a new active EstopConfig.
Field |
Type |
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.
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. |
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.
FullBodyCommand.Request
The full body request must be one of the basic command primitives.
geometry.proto
Area
Represents an area in the XY plane.
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.
Box2
Geometric primitive describing a two-dimensional box.
Field |
Type |
Description |
size |
Vec2 |
|
Box2WithFrame
Geometric primitive to describe a 2D box in a specific frame.
Field |
Type |
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 |
Description |
size |
Vec3 |
|
Box3WithFrame
Geometric primitive to describe a 3D box in a specific frame.
Field |
Type |
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 |
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 |
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 “child” 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 frame,
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. \
FrameTreeSnapshot.ChildToParentEdgeMapEntry
FrameTreeSnapshot.ParentEdge
ParentEdge represents the relationship from a child frame to a parent frame.
Field |
Type |
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.
Plane
Plane primitive, described with a point and normal.
Field |
Type |
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 |
Description |
points |
Vec2 |
|
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 |
Description |
vertexes |
Vec2 |
|
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.
Quad
A square oriented in 3D space.
Field |
Type |
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.
Ray
A ray in 3D space.
Field |
Type |
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 |
Description |
position |
Vec2 |
(m) |
angle |
double |
(rad) |
SE2Velocity
Geometric primitive that describes a 2D velocity through it’s linear and angular components.
Field |
Type |
Description |
linear |
Vec2 |
(m/s) |
angular |
double |
(rad/s) |
SE2VelocityLimit
Geometric primitive to couple minimum and maximum SE2Velocities in a single message.
Field |
Type |
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 |
Description |
matrix |
Matrix |
Row-major order representation of the covariance matrix. |
yaw_variance |
double |
Variance of the yaw component of the SE3 Pose. Warning: deprecated in 2.1. This should equal cov_rzrz, inside matrix . |
cov_xx |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
cov_xy |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
cov_xz |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
cov_yx |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
cov_yy |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
cov_yz |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
cov_zx |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
cov_zy |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
cov_zz |
double |
Warning: deprecated in 2.1. Use 'matrix.' |
SE3Pose
Geometric primitive to describe 3D position and rotation.
SE3Velocity
Geometric primitive that describes a 3D velocity through it’s linear and angular components.
Field |
Type |
Description |
linear |
Vec3 |
(m/s) |
angular |
Vec3 |
(rad/s) |
Vec2
Two dimensional vector primitive.
Vec2Value
A 2D vector of doubles that uses wrapped values so we can tell which elements are set.
Vec3
Three dimensional vector primitive.
Vec3Value
A 3D vector of doubles that uses wrapped values so we can tell which elements are set.
Volume
Represents a volume of space in an unspecified frame.
Field |
Type |
Description |
box |
Vec3 |
Dimensions in m, centered on frame origin. |
Wrench
Geometric primitive used to specify forces and torques.
Field |
Type |
Description |
force |
Vec3 |
(N) |
torque |
Vec3 |
(Nm) |
graph_nav/graph_nav.proto
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.
ClearGraphResponse
The results of the ClearGraphRequest.
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.
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 |
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.
DownloadGraphResponse
The DownloadGraph response message includes the current graph on the robot.
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 |
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 |
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. |
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 |
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. |
GetLocalizationStateResponse
The GetLocalizationState response message returns the current localization and robot state, as well
as any requested live data information.
Field |
Type |
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 |
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. |
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:
Field |
Type |
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. |
NavigateRouteRequest
A NavigateRoute request message specifies a route of waypoints/edges and parameters
about how to get there. Like NavigateTo, this command returns immediately upon
processing and provides a command_id that the user can use along with a NavigationFeedbackRequest RPC to
poll the system for feedback on this command. The RPC does not block until the route is completed.
Field |
Type |
Description |
header |
bosdyn.api.RequestHeader |
Common request header. |
leases |
bosdyn.api.Lease |
The Lease to show ownership of the robot. |
route |
Route |
A route for the robot to follow. |
route_follow_params |
RouteFollowingParams |
What should the robot do if it is not at the expected point in the route, or the route is blocked. |
travel_params |
TravelParams |
How to travel the route. |
end_time |
google.protobuf.Timestamp |
The timestamp (in robot time) that the navigation command is valid until. |
clock_identifier |
string |
Identifier provided by the time sync service to verify time sync between robot and client. |
destination_waypoint_tform_body_goal |
bosdyn.api.SE2Pose |
If provided, graph_nav will move the robot to an SE2 pose relative to the final waypoint in the route. Note that the robot will treat this as a simple goto request. It will first arrive at the destination waypoint, and then travel in a straight line from the destination waypoint to the offset goal, attempting to avoid obstacles along the way. |
command_id |
uint32 |
Unique identifier for the command. If 0, this is a new command, otherwise it is a continuation of an existing command. |
NavigateRouteResponse
Response to a NavigateRouteRequest. This is returned immediately after the request is processed. A command_id
is provided to specify the ID that the user may use to poll the system for feedback on the NavigateRoute command.
Field |
Type |
Description |
header |
bosdyn.api.ResponseHeader |
Common response header. |
lease_use_results |
bosdyn.api.LeaseUseResult |
Details about how the lease was used. |
status |
NavigateRouteResponse.Status |
Return status for the request. |
impaired_state |
bosdyn.api.RobotImpairedState |
If the status is ROBOT_IMPAIRED, this is why the robot is impaired. |
command_id |
uint32 |
Unique identifier for the command, If 0, command was not accepted. |
error_waypoint_ids |
string |
On a relevant error status code, these fields contain the waypoint/edge IDs that caused the error. |
error_edge_ids |
Edge.Id |
On a relevant error status code (STATUS_INVALID_EDGE), this is populated with the edge ID's that cased the error. |
NavigateToAnchorRequest
The NavigateToAnchorRequest can be used to command GraphNav to drive the robot to a specific
place in an anchoring. GraphNav will find the waypoint that has the shortest path length from
robot’s current position but is still close to the goal. GraphNav will plan a path through the
map which most efficiently gets the robot to the goal waypoint, and will then travel
in a straight line from the destination waypoint to the offset goal, attempting to avoid
obstacles along the way.
Parameters are provided which influence how GraphNav will generate and follow the path.
This RPC returns immediately after the request is processed. It does not block until GraphNav
completes the path to the goal waypoint. The user is expected to periodically check the status
of the NavigateToAnchor command using the NavigationFeedbackRequest RPC.
Field |
Type |
Description |
header |
bosdyn.api.RequestHeader |
Common request header. |
leases |
bosdyn.api.Lease |
The Leases to show ownership of the robot and the graph. |
seed_tform_goal |
bosdyn.api.SE3Pose |
The goal, expressed with respect to the seed frame of the current anchoring. The robot will use the z value to find the goal waypoint, but the final z height the robot achieves will depend on the terrain height at the offset from the goal. |
goal_waypoint_rt_seed_ewrt_seed_tolerance |
bosdyn.api.Vec3 |
These parameters control selection of the goal waypoint. In seed frame, they are the x, y, and z tolerances with respect to the goal pose within which waypoints will be considered. If these values are negative, or too small, reasonable defaults will be used. |
route_params |
RouteGenParams |
Preferences on how to pick the route. |
travel_params |
TravelParams |
Parameters that define how to traverse and end the route. |
end_time |
google.protobuf.Timestamp |
The timestamp (in robot time) that the navigation command is valid until. |
clock_identifier |
string |
Identifier provided by the time sync service to verify time sync between robot and client. |
command_id |
uint32 |
Unique identifier for the command. If 0, this is a new command, otherwise it is a continuation of an existing command. If this is a continuation of an existing command, all parameters will be ignored, and the old parameters will be preserved. |
NavigateToAnchorResponse
Response to a NavigateToAnchorRequest. This is returned immediately after the request is
processed. A command_id is provided to specify the ID that the user may use to poll the system
for feedback on the NavigateTo command.
NavigateToRequest
The NavigateToRequest can be used to command GraphNav to drive the robot to a specific waypoint.
GraphNav will plan a path through the map which most efficiently gets the robot to the specified goal waypoint.
Parameters are provided which influence how GraphNav will generate and follow the path.
This RPC returns immediately after the request is processed. It does not block until GraphNav completes the path
to the goal waypoint. The user is expected to periodically check the status of the NavigateTo command using
the NavigationFeedbackRequest RPC.
Field |
Type |
Description |
header |
bosdyn.api.RequestHeader |
Common request header. |
leases |
bosdyn.api.Lease |
The Leases to show ownership of the robot and the graph. |
destination_waypoint_id |
string |
ID of the waypoint to go to. |
route_params |
RouteGenParams |
Preferences on how to pick the route. |
travel_params |
TravelParams |
Parameters that define how to traverse and end the route. |
end_time |
google.protobuf.Timestamp |
The timestamp (in robot time) that the navigation command is valid until. |
clock_identifier |
string |
Identifier provided by the time sync service to verify time sync between robot and client. |
destination_waypoint_tform_body_goal |
bosdyn.api.SE2Pose |
If provided, graph_nav will move the robot to an SE2 pose relative to the waypoint. Note that the robot will treat this as a simple goto request. It will first arrive at the destination waypoint, and then travel in a straight line from the destination waypoint to the offset goal, attempting to avoid obstacles along the way. |
command_id |
uint32 |
Unique identifier for the command. If 0, this is a new command, otherwise it is a continuation of an existing command. If this is a continuation of an existing command, all parameters will be ignored, and the old parameters will be preserved. |
NavigateToResponse
Response to a NavigateToRequest. This is returned immediately after the request is processed. A command_id
is provided to specify the ID that the user may use to poll the system for feedback on the NavigateTo command.
NavigationFeedbackRequest
The NavigationFeedback request message uses the command_id of a navigation request to get
the robot’s progress and current status for the command. Note that all commands return immediately
after they are processed, and the robot will continue to execute the command asynchronously until
it times out or completes. New commands override old ones.
Field |
Type |
Description |
header |
bosdyn.api.RequestHeader |
Common request header. |
command_id |
uint32 |
Unique identifier for the command, provided by nav command response. Omit to get feedback on currently executing command. |
NavigationFeedbackResponse
The NavigationFeedback response message returns the robot’s
progress and current status for the command.
RemotePointCloudStatus
Message describing the state of a remote point cloud service (such as a velodyne).
Field |
Type |
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.
SensorCompatibilityStatus
Info on whether the robot’s current sensor setup is compatible with the recorded data
in the map.
Field |
Type |
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 |
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. |
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. |
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. |
SetLocalizationResponse
The SetLocalization response message contains the resulting localization to the map.
SetLocalizationResponse.SuspectedAmbiguity
Field |
Type |
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 |
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. |
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 |
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.
UploadGraphRequest
Uploads a graph to the server. This graph will be appended to the graph that
currently exists on the server.
Field |
Type |
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. |
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.
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 |
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.
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. |
NavigateRouteResponse.Status
Name |
Number |
Description |
STATUS_UNKNOWN |
0 |
An unknown / unexpected error occurred. |
STATUS_OK |
1 |
Request was accepted. |
STATUS_NO_TIMESYNC |
2 |
[Time Error] Client has not done timesync with robot. |
STATUS_EXPIRED |
3 |
[Time Error] The command was received after its end time had already passed. |
STATUS_TOO_DISTANT |
4 |
[Time Error] The command end time was too far in the future. |
STATUS_ROBOT_IMPAIRED |
5 |
[Robot State Error] Cannot navigate a route if the robot has a crtical perception fault, or behavior fault, or LIDAR not working. |
STATUS_RECORDING |
6 |
[Robot State Error] Cannot navigate a route while recording a map. |
STATUS_UNKNOWN_ROUTE_ELEMENTS |
8 |
[Route Error] One or more waypoints/edges are not in the map. |
STATUS_INVALID_EDGE |
9 |
[Route Error] One or more edges do not connect to expected waypoints. |
STATUS_NO_PATH |
20 |
[Route Error] There is no path to the specified route. |
STATUS_CONSTRAINT_FAULT |
11 |
[Route Error] Route contained a constraint fault. |
STATUS_FEATURE_DESERT |
13 |
[Route Error] Route contained too many waypoints with low-quality features. |
STATUS_LOST |
14 |
[Route Error] Happens when you try to issue a navigate route while the robot is lost. |
STATUS_NOT_LOCALIZED_TO_ROUTE |
16 |
[Route Error] Happens when the current localization doesn't refer to any waypoint in the route (possibly uninitialized localization). |
STATUS_NOT_LOCALIZED_TO_MAP |
19 |
[Route Error] Happens when the current localization doesn't refer to any waypoint in the map (possibly uninitialized localization). |
STATUS_COULD_NOT_UPDATE_ROUTE |
15 |
[Wrestling Errors] Happens when graph nav refuses to follow the route you specified. Try saying please? |
STATUS_STUCK |
17 |
[Route Error] Happens when you try to issue a navigate to while the robot is stuck. Navigate a different route, or clear the route and try again. |
STATUS_UNRECOGNIZED_COMMAND |
18 |
[Request Error] Happens when you try to continue a command that was either expired, or had an unrecognized id. |
NavigateToAnchorResponse.Status
Name |
Number |
Description |
STATUS_UNKNOWN |
0 |
An unknown / unexpected error occurred. |
STATUS_OK |
1 |
Request was accepted. |
STATUS_NO_TIMESYNC |
2 |
[Time error] Client has not done timesync with robot. |
STATUS_EXPIRED |
3 |
[Time error] The command was received after its end time had already passed. |
STATUS_TOO_DISTANT |
4 |
[Time error]The command end time was too far in the future. |
STATUS_ROBOT_IMPAIRED |
5 |
[Robot State Error] Cannot navigate a route if the robot has a critical perception fault, or behavior fault, or LIDAR not working. |
STATUS_RECORDING |
6 |
[Robot State Error] Cannot navigate a route while recording a map. |
STATUS_NO_ANCHORING |
7 |
[Route Error] There is no anchoring. |
STATUS_NO_PATH |
8 |
[Route Error] There is no path to a waypoint near the specified goal. If any waypoints were found (but no path), the error_waypoint_ids field will be filled. |
STATUS_FEATURE_DESERT |
10 |
[Route Error] Route contained too many waypoints with low-quality features. |
STATUS_LOST |
11 |
[Route Error] Happens when you try to issue a navigate to while the robot is lost. |
STATUS_NOT_LOCALIZED_TO_MAP |
13 |
[Route Error] Happens when the current localization doesn't refer to any waypoint in the map (possibly uninitialized localization). |
STATUS_COULD_NOT_UPDATE_ROUTE |
12 |
[Wrestling error] Happens when graph nav refuses to follow the route you specified. |
STATUS_STUCK |
14 |
[Route Error] Happens when you try to issue a navigate to while the robot is stuck. Navigate to a different waypoint, or clear the route and try again. |
STATUS_UNRECOGNIZED_COMMAND |
15 |
[Request Error] Happens when you try to continue a command that was either expired, or had an unrecognized id. |
STATUS_INVALID_POSE |
16 |
[Route Error] The pose is invalid, or known to be unachievable (upside-down, etc). |
NavigateToResponse.Status
Name |
Number |
Description |
STATUS_UNKNOWN |
0 |
An unknown / unexpected error occurred. |
STATUS_OK |
1 |
Request was accepted. |
STATUS_NO_TIMESYNC |
2 |
[Time error] Client has not done timesync with robot. |
STATUS_EXPIRED |
3 |
[Time error] The command was received after its end time had already passed. |
STATUS_TOO_DISTANT |
4 |
[Time error]The command end time was too far in the future. |
STATUS_ROBOT_IMPAIRED |
5 |
[Robot State Error] Cannot navigate a route if the robot has a critical perception fault, or behavior fault, or LIDAR not working. |
STATUS_RECORDING |
6 |
[Robot State Error] Cannot navigate a route while recording a map. |
STATUS_UNKNOWN_WAYPOINT |
7 |
[Route Error] One or more of the waypoints specified weren't in the map. |
STATUS_NO_PATH |
8 |
[Route Error] There is no path to the specified waypoint. |
STATUS_FEATURE_DESERT |
10 |
[Route Error] Route contained too many waypoints with low-quality features. |
STATUS_LOST |
11 |
[Route Error] Happens when you try to issue a navigate to while the robot is lost. |
STATUS_NOT_LOCALIZED_TO_MAP |
13 |
[Route Error] Happens when the current localization doesn't refer to any waypoint in the map (possibly uninitialized localization). |
STATUS_COULD_NOT_UPDATE_ROUTE |
12 |
[Wrestling error] Happens when graph nav refuses to follow the route you specified. |
STATUS_STUCK |
14 |
[Route Error] Happens when you try to issue a navigate to while the robot is stuck. Navigate to a different waypoint, or clear the route and try again. |
STATUS_UNRECOGNIZED_COMMAND |
15 |
[Request Error] Happens when you try to continue a command that was either expired, or had an unrecognized id. |
NavigationFeedbackResponse.Status
Name |
Number |
Description |
STATUS_UNKNOWN |
0 |
An unknown / unexpected error occurred. |
STATUS_FOLLOWING_ROUTE |
1 |
The robot is currently, successfully following the route. |
STATUS_REACHED_GOAL |
2 |
The robot has reached the final goal of the navigation request. |
STATUS_NO_ROUTE |
3 |
There's no route currently being navigated. This can happen if no command has been issued, or if the graph has been changed during navigation. |
STATUS_NO_LOCALIZATION |
4 |
Robot is not localized to a route. |
STATUS_LOST |
5 |
Robot appears to be lost. |
STATUS_STUCK |
6 |
Robot appears stuck against an obstacle. |
STATUS_COMMAND_TIMED_OUT |
7 |
The command expired. |
STATUS_ROBOT_IMPAIRED |
8 |
Cannot navigate a route if the robot has a crtical perception fault, or behavior fault, or LIDAR not working. See impared_status for details. |
STATUS_CONSTRAINT_FAULT |
11 |
The route constraints were not feasible. |
STATUS_COMMAND_OVERRIDDEN |
12 |
The command was replaced by a new command |
STATUS_NOT_LOCALIZED_TO_ROUTE |
13 |
The localization or route changed mid-traverse. |
STATUS_LEASE_ERROR |
14 |
The lease is no longer valid. |
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 |
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.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. |
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 is invalid topologically, for example containing missing waypoints referenced by edges. |
STATUS_INCOMPATIBLE_SENSORS |
5 |
|
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. |
graph_nav/map.proto
Anchor
This associates a waypoint with a common reference frame, which is not necessarily metric.
Field |
Type |
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 |
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 |
Description |
anchors |
Anchor |
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 |
World objects, located in the common reference frame. |
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 |
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 |
Description |
vel_limit |
bosdyn.api.SE2VelocityLimit |
Velocity limits to use while traversing the edge. These are maxima and minima, NOT target speeds. NOTE: as of 2.4 this is deprecated. Please use mobility_params.vel_limit. |
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 |
If true, the edge crosses flat ground and the robot shouldn't try to climb over obstacles. |
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.) WARNING: deprecated as of 2.1. Use mobility_params instead, which includes ground_mu_hint as part of the terrain_params. |
grated_floor |
google.protobuf.BoolValue |
If true, the edge crosses over grated metal. This changes some parameters of the robot's perception system to allow it to see grated floors bettter. WARNING: deprecated as of 2.1. Use mobility_params instead, which includes grated_floor as part of the terrain_params. |
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 "stair_hint" and "terrain_params.enable_grated_floor", then the map will be annotated with "stair_hint" 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. |
Edge.Annotations.StairData
Defines any parameters of the stairs
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 |
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 |
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 |
Sampling of stances as robot traversed this edge. |
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 |
Description |
waypoints |
Waypoint |
The waypoints for the graph (containing frames, annotations, and sensor data). |
edges |
Edge |
The edges connecting the graph's waypoints. |
anchoring |
Anchoring |
The anchoring (mapping from waypoints to their pose in a shared reference frame). |
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 |
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.
Waypoint.Annotations.LocalizeRegion
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 |
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.
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 |
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 |
Any images captured at the waypoint. |
point_cloud |
bosdyn.api.PointCloud |
Aggregated point cloud data. |
objects |
bosdyn.api.WorldObject |
Perception objects seen at snapshot time. |
robot_state |
bosdyn.api.RobotState |
Full robot state during snapshot. |
robot_local_grids |
bosdyn.api.LocalGrid |
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 |
Defines the payloads attached to the robot at this waypoint. |
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.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. |
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. |
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 |
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 |
Description |
waypoint_anchors |
WaypointAnchorHint |
List of waypoints and hints as to where they are in the seed frame. |
world_objects |
WorldObjectAnchorHint |
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 |
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 |
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. |
ProcessAnchoringRequest.Params
Parameters for procesing an anchoring.
Field |
Type |
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 |
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. |
ProcessAnchoringRequest.Params.OptimizerParams
Parameters affecting the underlying optimizer.
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 |
Description |
kinematic_odometry_weight |
double |
|
visual_odometry_weight |
double |
|
world_object_weight |
double |
|
hint_weight |
double |
|
gyroscope_weight |
double |
|
loop_closure_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 |
Description |
header |
bosdyn.api.ResponseHeader |
|
status |
ProcessAnchoringResponse.Status |
|
waypoint_results |
Anchor |
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 |
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 |
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 |
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 |
When there are missing waypoint snapshots, these are the IDs of the missing snapshots. Upload them to continue. |
missing_waypoint_ids |
string |
When there are missing waypoints, these are the IDs of the missing waypoints. Upload them to continue. |
invalid_hints |
string |
Unorganized list of waypoints and object IDs which were invalid (missing from the map). |
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 |
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 |
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 |
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. |
ProcessTopologyRequest.ICPParams
Parameters for how to refine loop closure edges using iterative
closest point matching.
Field |
Type |
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 |
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. |
ProcessTopologyRequest.Params
Parameters which control topology processing. In general, anything which isn’t filled out
will be replaced by reasonable defaults.
Field |
Type |
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 |
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 |
When there are missing waypoint snapshots, these are the IDs of the missing snapshots. Upload them to continue. |
missing_waypoint_ids |
string |
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.
Field |
Type |
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.
Field |
Type |
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.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. |
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 |
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 |
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.
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 |
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 |
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 |
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 |
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 |
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 |
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. |
GetRecordStatusRequest
The GetRecordStatus request message asks for the current state of the recording service.
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.
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 |
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 waypoints in this recording. |
SetRecordingEnvironmentRequest
The SetRecordingEnvironment request message sets a persistent recording environment
until changed with another SetRecordingEnvironment rpc.
Field |
Type |
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.
StartRecordingRequest
The StartRecording request tells the recording service to begin creating waypoints with the
specified recording_environment.
Field |
Type |
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 |
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. |
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 |
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 |
If the status is STATUS_MISSING_FIDUCIALS, these are the fiducials that are not currently visible. |
bad_pose_fiducials |
int32 |
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. |
StopRecordingRequest
The StopRecording request message tells the robot to no longer continue adding waypoints and
edges to the graph.
Field |
Type |
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.
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. |
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. |
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. |
image.proto
CaptureParameters
Sensor parameters associated with an image capture.
GetImageRequest
The GetImage request message which can send multiple different image source requests at once.
Field |
Type |
Description |
header |
RequestHeader |
Common request header. |
image_requests |
ImageRequest |
The different image requests for this rpc call. |
GetImageResponse
The GetImage response message which includes image data for all requested sources.
Field |
Type |
Description |
header |
ResponseHeader |
Common response header. |
image_responses |
ImageResponse |
The ordering of these image responses is defined by the order of the ImageRequests. |
Image
Rectangular color/greyscale/depth images.
Field |
Type |
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 |
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. |
ImageRequest
The image request specifying the image source and data format desired.
Field |
Type |
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. |
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. |
ImageResponse
The image response for each request, that includes image data and image source information.
Field |
Type |
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. |
ImageSource
Proto for a description of an image source on the robot.
Field |
Type |
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 |
The pixel formats a specific image source supports. |
image_formats |
Image.Format |
The image formats a specific image source supports. |
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]]
ImageSource.PinholeModel.CameraIntrinsics
Intrinsic parameters are in pixel space.
Field |
Type |
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 |
Description |
header |
RequestHeader |
Common request header. |
ListImageSourcesResponse
The ListImageSources response message which contains all known image sources for the robot.
Field |
Type |
Description |
header |
ResponseHeader |
Common response Header. |
image_sources |
ImageSource |
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). |
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 |
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. |
lease.proto
AcquireLeaseRequest
The AcquireLease request message which sends which resource the lease should be for.
Field |
Type |
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 |
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 |
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 |
Logical vector clock indicating when the Lease was generated. |
client_names |
string |
The set of different clients which have sent/receieved the lease. |
LeaseOwner
Details about who currently owns the Lease for a resource.
Field |
Type |
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 |
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 |
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. |
LeaseUseResult
Result for when a Lease is used - for example, in a LeaseRetainer, or
associated with a command.
Field |
Type |
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 |
Represents the latest "leaf" resources of the hierarchy. |
ListLeasesRequest
The ListLease request message asks for information about any known lease resources.
Field |
Type |
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 |
Description |
header |
ResponseHeader |
Common response header. |
resources |
LeaseResource |
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 |
Description |
resource |
string |
The name of this resource. |
sub_resources |
ResourceTree |
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 |
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.
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 |
Description |
header |
RequestHeader |
Common request header. |
lease |
Lease |
The Lease to return back to the LeaseService. |
ReturnLeaseResponse
The ReturnLease response message
TakeLeaseRequest
The TakeLease request message which sends which resource the lease should be for.
Field |
Type |
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 |
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. |
local_grid.proto
GetLocalGridTypesRequest
The GetLocalGridTypes request message asks to the local grid types.
Field |
Type |
Description |
header |
RequestHeader |
Common request header. |
GetLocalGridTypesResponse
The GetLocalGridTypes response message returns to get all known string names for local grid types.
Field |
Type |
Description |
header |
ResponseHeader |
Common response header. |
local_grid_type |
LocalGridType |
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 |
Description |
header |
RequestHeader |
Common request header. |
local_grid_requests |
LocalGridRequest |
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 |
Description |
header |
ResponseHeader |
Common response header. |
local_grid_responses |
LocalGridResponse |
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 |
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 |
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 |
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 |
Description |
local_grid_type_name |
string |
|
LocalGridResponse
The local grid response message will contain either the local grid or an error status.
Field |
Type |
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 |
Description |
name |
string |
|
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. |
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.
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.
ApiGraspOverrideRequest
Field |
Type |
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. |
ApiGraspedCarryStateOverride
Use this message to assert properties about the grasped item.
By default, the robot will assume all grasped items are not carriable.
GraspParams
Field |
Type |
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 |
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 |
Description |
header |
RequestHeader |
Common request header. |
manipulation_cmd_id |
int32 |
Unique identifier for the command, provided by ManipulationApiResponse. |
ManipulationApiFeedbackResponse
Field |
Type |
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 |
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 |
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 |
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 |
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 |
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 |
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 |
Description |
squeeze_grasp_disallowed |
bool |
|
VectorAlignmentWithTolerance
Field |
Type |
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 |
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 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. |
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 |
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) |
mission/mission.proto
AnswerQuestionRequest
Answer one of the outstanding questions.
Field |
Type |
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. |
AnswerQuestionResponse
Response from the server after a client has answered one of its questions.
FailedNode
General message describing a node that has failed, for example as part of a PlayMission or
LoadMission RPC.
Field |
Type |
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.
GetInfoResponse
Provides the currently loaded mission’s information.
Field |
Type |
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.
GetMissionResponse
Responding with the mission as it was loaded in LoadMission.
Field |
Type |
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 |
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.
LoadMissionRequest
The LoadMission request specifies a root node for the mission that should be used.
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 |
Description |
header |
bosdyn.api.ResponseHeader |
Common response header. |
status |
LoadMissionResponse.Status |
Result of loading the mission. |
lease_use_results |
bosdyn.api.LeaseUseResult |
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 |
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 |
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 |
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 |
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.
PauseMissionResponse
The PauseMission response message will return the status of the request.
PlayMissionRequest
A request to play the currently loaded mission for a fixed amount of time.
Field |
Type |
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 |
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.
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 |
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. |
Question
A question posed by a Prompt node, or by the internal operation of another node.
Field |
Type |
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 |
Options to choose from. Uses the submessage from the "prompt" node message. |
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. |
RestartMissionRequest
A request to restart the currently loaded mission.
Field |
Type |
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 |
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.
State
State of the mission service.
Field |
Type |
Description |
questions |
Question |
What questions are outstanding? |
answered_questions |
State.AnsweredQuestion |
History of questions that have been answered. The server will set some limit on the available history. |
history |
State.NodeStatesAtTick |
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 |
Description |
question |
Question |
The question that this state information is related to. |
accepted_answer_code |
int64 |
The answer that was provided. |
State.NodeStatesAtTick
Field |
Type |
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 |
At this tick, the state of every node that was ticked, in the order they were ticked. |
State.NodeStatesAtTick.NodeState
Field |
Type |
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. |
StopMissionRequest
The StopMission request message will fully stop the mission.
StopMissionResponse
The StopMission response message will return the status of the 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. |
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 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. |
mission/nodes.proto
BosdynDockState
Get the state of the docking service from the robot.
Field |
Type |
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 |
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). |
BosdynGraphNavState
Get GraphNav state from the robot and save it to the blackboard.
Field |
Type |
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. |
BosdynNavigateRoute
Tell the robot to navigate a route.
Field |
Type |
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 |
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. |
BosdynPowerRequest
Make a robot power request
BosdynRecordEvent
Record an APIEvent
Field |
Type |
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. |
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 |
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 |
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:
Check if there are behavior faults. If there are none, it will return success.
Check if all behavior faults are clearable. If not, it will return failure.
Try to clear the clearable behavior faults. If it cannot, it will return failure.
Field |
Type |
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. |
Condition
Checks a simple comparison statement.
Condition.Operand
Options for where to retrieve values from.
ConstantResult
Just returns a constant when calling tick().
Field |
Type |
Description |
result |
Result |
This result is always returned when calling tick(). |
DataAcquisition
Trigger the acquisition and storage of data.
Field |
Type |
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. 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. |
request_name_in_blackboard |
string |
If populated, name of the variable in the blackboard in which to store the AcquireDataRequest. |
DateToBlackboard
Record a datetime string into the blackboard. Writes the date according to ISO8601 format.
Field |
Type |
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 |
Description |
blackboard_variables |
KeyValue |
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 |
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 |
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! Use docking_command_response_blackboard_key and docking_command_feedback_response_blackboard_key instead. |
| command_status_name | string | 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! Use docking_command_response_blackboard_key and docking_command_feedback_response_blackboard_key instead. |
| feedback_status_name | string | 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! 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. |
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 |
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. |
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 |
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 |
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. |
parameter_values |
KeyValue |
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 |
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 |
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. |
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 |
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 |
The set of options that can be chosen 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. |
Prompt.Option
Data about the options to choose from.
Field |
Type |
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. |
RemoteGrpc
Call out to another system using the RemoteMission service.
Field |
Type |
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 |
Resources that we will need leases on. |
inputs |
KeyValue |
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. |
Repeat
Repeat a child node.
Field |
Type |
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. |
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 |
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 |
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 |
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 |
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 |
List of all children to iterate through. |
Sequence
Run all children in order until a child fails.
Field |
Type |
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 |
List of all children to iterate through. |
SetBlackboard
Sets existing blackboard variables within this scope to specific values, returning SUCCESS.
Field |
Type |
Description |
blackboard_variables |
KeyValue |
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. |
SimpleParallel
Run two child nodes together, returning the primary child’s result when it completes.
Field |
Type |
Description |
primary |
Node |
Primary node, whose completion will end the execution of SimpleParallel. |
secondary |
Node |
Secondary node, which will be ticked as long as the primary is still running. |
Sleep
When started, begins a sleep timer for X seconds. Returns “success” after the timer elapses,
“running” otherwise.
Field |
Type |
Description |
seconds |
float |
Number of seconds to sleep for. |
restart_after_stop |
bool |
If this node is stopped, should it restart the timer? |
SpotCamLed
Set the LEDs to a specified brightness
Field |
Type |
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 |
Brightnesses of the LEDs, from SetLEDBrightnessRequest |
SpotCamLed.BrightnessesEntry
SpotCamPtz
Point the PTZ to a specified orientation
Field |
Type |
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 |
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 |
Description |
service_name |
string |
Name of the service to use. |
host |
string |
Host machine of the directory server that the Spot CAM registered with. |
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. |
mission/remote.proto
EstablishSessionRequest
Information to initialize a session to the remote service
for a particular mission node.
Field |
Type |
Description |
header |
bosdyn.api.RequestHeader |
Common request header. |
leases |
bosdyn.api.Lease |
All leases that the remote service may need. |
inputs |
VariableDeclaration |
Use this to provide other data (e.g. from the blackboard). The RemoteGrpc node will provide the name of the node automatically. |
EstablishSessionResponse
Provide the id to use for the particular mission node to tick this remote service.
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 |
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.
TeardownSessionRequest
End the session originally established by an EstablishSessionRequest.
Field |
Type |
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.
TickRequest
Request that the remote tick itself for a particular node in the mission.
Field |
Type |
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 |
All leases that the remote service may need. |
inputs |
KeyValue |
Inputs provided to the servicer. |
TickResponse
Response with the results of the tick.
Remote services should strive to return quickly, even if only returning RUNNING.
Field |
Type |
Description |
header |
bosdyn.api.ResponseHeader |
Common response header. |
status |
TickResponse.Status |
Result of the current tick. |
missing_lease_resources |
string |
Need to provide leases on these resources. |
lease_use_results |
bosdyn.api.LeaseUseResult |
Details about how any leases were used. Allowed to be empty, if leases were not actually used. |
missing_inputs |
VariableDeclaration |
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. |
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. |
robot_state.proto
BatteryState
The battery state for the robot. This includes information about the charge or the
battery temperature.
Field |
Type |
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 |
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.
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 |
Description |
faults |
BehaviorFault |
Current errors potentially blocking commands on robot |
CommsState
The current comms information, including what comms the robot is using and the current status
of the comms network.
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 |
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. |
HardwareConfiguration
Robot Hardware Configuration, described with the robot skeleton.
Field |
Type |
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. |
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 |
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 |
Description |
joint_states |
JointState |
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, which will include the transformations to the robot body ("body") in addition to transformations to the common frames ("world", "dr") and ground plane estimate "gpe". 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 |
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 |
|
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 |
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 |
Description |
header |
RequestHeader |
Common request header. |
RobotHardwareConfigurationResponse
The RobotHardwareConfiguration response message, which returns the hardware config from the time
the request was received.
RobotImpairedState
Keeps track of why the robot is not able to drive autonomously.
Field |
Type |
Description |
impaired_status |
RobotImpairedState.ImpairedStatus |
If the status is ROBOT_IMPAIRED, this is specifically why the robot is impaired. |
system_faults |
SystemFault |
If impaired_status is STATUS_SYSTEM_FAULT, these are the faults which caused the robot to stop. |
service_faults |
ServiceFault |
If impaired_status is STATUS_SERVICE_FAULT, these are the service faults which caused the robot to stop. |
behavior_faults |
BehaviorFault |
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 |
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.
RobotMetrics
Key robot metrics (e.g., Gait cycles (count), distance walked, time moving, etc…).
Field |
Type |
Description |
timestamp |
google.protobuf.Timestamp |
Robot timestamp corresponding to these metrics. |
metrics |
Parameter |
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 |
Description |
header |
RequestHeader |
Common request header. |
RobotMetricsResponse
The RobotMetrics response message, which returns the metrics information from the time
the request was received.
RobotState
The current state of the robot.
Field |
Type |
Description |
power_state |
PowerState |
Power state (e.g. motor power). |
battery_states |
BatteryState |
Battery state (e.g. charge, temperature, current). |
comms_states |
CommsState |
Communication state (e.g. type of comms network). |
system_fault_state |
SystemFaultState |
Different system faults for the robot. |
estop_states |
EStopState |
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 |
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 |
RobotStateRequest
The RobotState request message to get the current state of the robot.
Field |
Type |
Description |
header |
RequestHeader |
Common request header. |
RobotStateResponse
The RobotState response message, which returns the robot state information from the time
the request was received.
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 |
Description |
faults |
ServiceFault |
Currently active faults |
historical_faults |
ServiceFault |
Service faults that have been cleared. Acts as a ring buffer with size of 50. |
aggregated |
ServiceFaultState.AggregatedEntry |
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
Skeleton
Kinematic model of the robot skeleton.
Field |
Type |
Description |
links |
Skeleton.Link |
The list of links that make up the robot skeleton. |
urdf |
string |
URDF description of the robot skeleton. |
Skeleton.Link
Each link of the robot skeleton.
Field |
Type |
Description |
name |
string |
The link name, which matches those used in the urdf. |
obj_model |
Skeleton.Link.ObjModel |
The OBJ file representing the model of this link. |
Skeleton.Link.ObjModel
Model to draw, expressed as an obj file.
Note: To limit the size of responses, obj_file_contents might be omitted.
Field |
Type |
Description |
file_name |
string |
Name of the file. |
file_contents |
string |
The contents of the file. |
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 |
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 |
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 |
Description |
faults |
SystemFault |
Currently active faults |
historical_faults |
SystemFault |
Inactive faults that cleared within the last 10 minutes |
aggregated |
SystemFaultState.AggregatedEntry |
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
TerrainState
Relevant terrain data beneath and around the robot
Field |
Type |
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 |
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 |
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. |
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. |
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 |
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 |
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.WarmstartCommand
The robot is already grasping the door handle and will continue opening the door based on
user specified params.
OpenDoorCommandRequest
A door command for the robot to execute plus a lease.
OpenDoorCommandResponse
Response to the door command request.
OpenDoorFeedbackRequest
A request for feedback of a specific door command.
Field |
Type |
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.
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. |
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. |
spot/robot_command.proto
BodyControlParams
Parameters for offsetting the body from the normal default.
Field |
Type |
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. |
rotation_setting |
BodyControlParams.RotationSetting |
The rotation setting for the robot body. Ignored if body_assist_for_manipulation is requested. |
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
hvae no effect.
Field |
Type |
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. |
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 |
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 |
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 |
Stairs are only supported in trot gaits. Using this hint will override some user defaults in order to optimize stair behavior. |
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 |
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 |
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 |
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. |
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. |
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 |
spot/spot_check.proto
CameraCalibrationCommandRequest
Request for the CameraCalibrationCommand service.
CameraCalibrationCommandResponse
Response for the CameraCalibrationCommand service.
CameraCalibrationFeedbackRequest
Request for the CameraCalibrationFeedback service.
CameraCalibrationFeedbackResponse
Response for the CameraCalibrationFeedback service.
DepthPlaneSpotCheckResult
Results from camera check.
Field |
Type |
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. |
JointKinematicCheckResult
Kinematic calibration results
Field |
Type |
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 |
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 |
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 |
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.
SpotCheckCommandResponse
Response for the SpotCheckCommand service.
SpotCheckFeedbackRequest
Request for the SpotCheckFeedback service.
SpotCheckFeedbackResponse
Response for the SpotCheckFeedback service.
Field |
Type |
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 |
Results from camera check. The key string is the location of the camera (e.g. frontright, frontleft, left, ...) |
load_cell_results |
SpotCheckFeedbackResponse.LoadCellResultsEntry |
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 |
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 |
foot_height_results |
SpotCheckFeedbackResponse.FootHeightResultsEntry |
Deprecated. Results of foot height validation. The key string is the name of the leg (e.g. fl, fr, hl, ...) |
leg_pair_results |
SpotCheckFeedbackResponse.LegPairResultsEntry |
Deprecated. Results of leg pair validation. The key string is the name of the leg pair (e.g. fl-fr, fl-hl, ...) |
hip_range_of_motion_results |
SpotCheckFeedbackResponse.HipRangeOfMotionResultsEntry |
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
SpotCheckFeedbackResponse.HipRangeOfMotionResultsEntry
SpotCheckFeedbackResponse.KinematicCalResultsEntry
SpotCheckFeedbackResponse.LegPairResultsEntry
SpotCheckFeedbackResponse.LoadCellResultsEntry
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. |
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. |
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. |
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. |
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. |
spot_cam/audio.proto
DeleteSoundRequest
Remove a loaded sound from the library of loaded sounds.
Field |
Type |
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.
GetAudioCaptureChannelRequest
Request to get the audio capture channel
GetAudioCaptureChannelResponse
Result of getting the audio capture channel
GetAudioCaptureGainRequest
Request to get the audio capture channel
GetAudioCaptureGainResponse
Result of getting the audio capture gain
GetVolumeRequest
Query the current volume level of the system.
GetVolumeResponse
Provides the current volume level of the system.
ListSoundsRequest
Request for all sounds present on the robot.
ListSoundsResponse
List of all sounds present on the robot.
LoadSoundRequest
Load a new sound onto the robot for future playback.
Field |
Type |
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.
PlaySoundRequest
Begin playing a loaded sound from the robot’s speakers.
Field |
Type |
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.
SetAudioCaptureChannelRequest
Request to set the audio capture channel
SetAudioCaptureChannelResponse
Result of setting the audio capture channel
SetAudioCaptureGainRequest
Request to set the audio capture channel
SetAudioCaptureGainResponse
Result of setting the audio capture gain
SetVolumeRequest
Set the desired volume level of the system.
SetVolumeResponse
Result of changing the system volume level.
Sound
Identifier for a playable sound.
Field |
Type |
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 |
|
spot_cam/compositor.proto
GetScreenRequest
Request the current screen in use.
GetScreenResponse
Specify which screen is currently being displayed in the video stream.
GetVisibleCamerasRequest
Request information about the current cameras in the video stream.
GetVisibleCamerasResponse
Description of the parameters and locations of each camera in the
current video stream.
GetVisibleCamerasResponse.Stream
The location and camera parameters for a single camera.
Field |
Type |
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 |
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.
IrColorMap.ScalingPair
Field |
Type |
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
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.
ListScreensRequest
Request the different screen layouts available.
ListScreensResponse
Response with all screen layouts available.
ScreenDescription
A “Screen” represents a particular layout of camera images
used by the video stream.
Field |
Type |
Description |
name |
string |
Unique identifer for a screen. |
SetIrMeterOverlayResponse
SetScreenRequest
Switch the camera layout in the video stream to the one specified.
SetScreenResponse
Result of setting the camera layout.
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 |