Robot Command

For clients to the robot command service.

exception bosdyn.client.robot_command.RobotCommandResponseError(response, error_message=None)[source]

Bases: ResponseError

General class of errors for RobotCommand service.

exception bosdyn.client.robot_command.Error[source]

Bases: Error

Base class for non-response errors in this module.

exception bosdyn.client.robot_command.NoTimeSyncError(response, error_message=None)[source]

Bases: RobotCommandResponseError

Client has not done timesync with robot.

exception bosdyn.client.robot_command.ExpiredError(response, error_message=None)[source]

Bases: RobotCommandResponseError

The command was received after its max_duration had already passed.

exception bosdyn.client.robot_command.TooDistantError(response, error_message=None)[source]

Bases: RobotCommandResponseError

The command end time was too far in the future.

exception bosdyn.client.robot_command.NotPoweredOnError(response, error_message=None)[source]

Bases: RobotCommandResponseError

The robot must be powered on to accept a command.

exception bosdyn.client.robot_command.BehaviorFaultError(response, error_message=None)[source]

Bases: RobotCommandResponseError

The robot may not be commanded with uncleared behavior faults.

exception bosdyn.client.robot_command.DockedError(response, error_message=None)[source]

Bases: RobotCommandResponseError

The command cannot be executed while the robot is docked.

exception bosdyn.client.robot_command.NotClearedError(response, error_message=None)[source]

Bases: RobotCommandResponseError

Behavior fault could not be cleared.

exception bosdyn.client.robot_command.UnsupportedError(response, error_message=None)[source]

Bases: RobotCommandResponseError

The API supports this request, but the system does not support this request.

exception bosdyn.client.robot_command.CommandFailedError[source]

Bases: Error

Command indicated it failed in its feedback.

exception bosdyn.client.robot_command.CommandFailedErrorWithFeedback(message, feedback)[source]

Bases: CommandFailedError

Command indicated it failed in its feedback. This subclass contains the feedback response causing the error.

exception bosdyn.client.robot_command.CommandTimedOutError[source]

Bases: Error

Timed out waiting for SUCCESS response from robot command.

exception bosdyn.client.robot_command.UnknownFrameError(response, error_message=None)[source]

Bases: RobotCommandResponseError

Robot does not know how to handle supplied frame.

class bosdyn.client.robot_command.RobotCommandClient[source]

Bases: BaseClient

Client for calling RobotCommand services.

default_service_name = 'robot-command'
service_type = 'bosdyn.api.RobotCommandService'
update_from(other)[source]

Update instance from another object.

Parameters:

other – The object where to copy from.

property timesync_endpoint

Accessor for timesync-endpoint that was grabbed via ‘update_from()’.

robot_command(command, end_time_secs=None, timesync_endpoint=None, lease=None, **kwargs)[source]

Issue a command to the robot synchronously.

Parameters:
  • command – Command to issue.

  • end_time_secs – End time for the command in seconds.

  • timesync_endpoint – Timesync endpoint.

  • lease – Lease object to use for the command.

Returns:

ID of the issued robot command.

Raises:
robot_command_async(command, end_time_secs=None, timesync_endpoint=None, lease=None, **kwargs)[source]

Async version of robot_command().

Parameters:
  • command – Command to issue.

  • end_time_secs – End time for the command in seconds.

  • timesync_endpoint – Timesync endpoint.

  • lease – Lease object to use for the command.

Returns:

ID of the issued robot command.

Raises:
robot_command_feedback(robot_command_id, **kwargs)[source]

Get feedback from a previously issued command.

Parameters:

robot_command_id – ID of the robot command to get feedback on.

Raises:

RpcError – Problem communicating with the robot.

robot_command_feedback_async(robot_command_id, **kwargs)[source]

Async version of robot_command_feedback().

Parameters:

robot_command_id – ID of the robot command to get feedback on.

Raises:

RpcError – Problem communicating with the robot.

clear_behavior_fault(behavior_fault_id, lease=None, **kwargs)[source]

Clear a behavior fault on the robot.

Parameters:
  • behavior_fault_id – ID of the behavior fault.

  • lease – Lease information to use in the message.

Returns:

Boolean whether response status is STATUS_CLEARED.

Raises:
clear_behavior_fault_async(behavior_fault_id, lease=None, **kwargs)[source]

Async version of clear_behavior_fault().

Parameters:
  • behavior_fault_id

  • lease

  • behavior_fault_id – ID of the behavior fault.

  • lease – Lease information to use in the message.

Returns:

Boolean whether response status is STATUS_CLEARED.

Raises:
class bosdyn.client.robot_command.RobotCommandStreamingClient[source]

Bases: BaseClient

Client for calling RobotCommand services.

This client is in BETA and may undergo changes in future releases.

default_service_name = 'robot-command-streaming'
service_type = 'bosdyn.api.RobotCommandStreamingService'
send_joint_control_commands(command_iterator)[source]
class bosdyn.client.robot_command.RobotCommandBuilder[source]

Bases: object

This class contains a set of static helper functions to build and issue robot commands.

This is not intended to cover every use case, but rather give developers a starting point for issuing commands to the robot.The robot command proto uses several advanced protobuf techniques, including the use of Any and OneOf.

A RobotCommand is composed of one or more commands. The set of valid commands is robot / hardware specific. An armless spot only accepts one command at a time. Each command may or may not take a generic param object. These params are also robot / hardware dependent.

static stop_command()[source]

Command to stop with minimal motion. If the robot is walking, it will transition to stand. If the robot is standing or sitting, it will do nothing.

Returns:

RobotCommand, which can be issued to the robot command service.

static freeze_command()[source]

Command to freeze all joints at their current positions (no balancing control)

Returns:

RobotCommand, which can be issued to the robot command service.

static selfright_command()[source]

Command to get the robot in a ready, sitting position. If the robot is on its back, it will attempt to flip over.

Returns:

RobotCommand, which can be issued to the robot command service.

static battery_change_pose_command(dir_hint=1)[source]

Command that will have the robot sit down (if not already sitting) and roll onto its side for easier battery access.

Parameters:

dir_hint – Direction to roll over: 1-right/2-left

Returns:

RobotCommand, which can be issued to the robot command service.

static payload_estimation_command()[source]

Command to get the robot estimate payload mass.

Commands robot to stand and execute a routine to estimate the mass properties of an unregistered payload attached to the robot.

Returns:

RobotCommand, which can be issued to the robot command service.

static safe_power_off_command()[source]

Command to 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 not in a safe position, it will get to a safe position before powering down. The robot will not power down until it is in a safe state.

Returns:

RobotCommand, which can be issued to the robot command service.

static constrained_manipulation_command(task_type, init_wrench_direction_in_frame_name, force_limit, torque_limit, frame_name, tangential_speed=None, rotational_speed=None, target_linear_position=None, target_angle=None, control_mode=2, reset_estimator=value: true)[source]

Command constrained manipulation.

static joint_command()[source]
static synchro_se2_trajectory_point_command(goal_x, goal_y, goal_heading, frame_name, params=None, body_height=0.0, locomotion_hint=1, build_on_command=None)[source]

Command robot to move to pose along a 2D plane. Pose can be specified in the world (kinematic odometry) frame or the robot body frame. The arguments body_height and locomotion_hint are ignored if params argument is passed.

A trajectory command requires an end time. End time is not set in this function, but rather is set externally before call to RobotCommandService.

Parameters:
  • goal_x – Position X coordinate.

  • goal_y – Position Y coordinate.

  • goal_heading – Pose heading in radians.

  • frame_name – Name of the frame to use.

  • params (spot.MobilityParams) – Spot specific parameters for mobility commands. If not set, this will be constructed using other args.

  • body_height – Height, meters, relative to a nominal stand height.

  • locomotion_hint – Locomotion hint to use for the trajectory command.

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and gripper_command from this incoming RobotCommand will be added to the returned RobotCommand.

Returns:

RobotCommand, which can be issued to the robot command service.

static synchro_se2_trajectory_command(goal_se2, frame_name, params=None, body_height=0.0, locomotion_hint=1, build_on_command=None)[source]

Command robot to move to pose along a 2D plane. Pose can be specified in the world (kinematic odometry or vision world) frames. The arguments body_height and locomotion_hint are ignored if params argument is passed.

A trajectory command requires an end time. End time is not set in this function, but rather is set externally before call to RobotCommandService.

Parameters:
  • goal_se2 – SE2Pose goal.

  • frame_name – Name of the frame to use.

  • params (spot.MobilityParams) – Spot specific parameters for mobility commands. If not set, this will be constructed using other args.

  • body_height – Height, meters, relative to a nominal stand height.

  • locomotion_hint – Locomotion hint to use for the trajectory command.

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and gripper_command from this incoming RobotCommand will be added to the returned RobotCommand.

Returns:

RobotCommand, which can be issued to the robot command service.

static synchro_trajectory_command_in_body_frame(goal_x_rt_body, goal_y_rt_body, goal_heading_rt_body, frame_tree_snapshot, params=None, body_height=0.0, locomotion_hint=1, build_on_command=None)[source]

Command robot to move to pose described relative to the robots body along a 2D plane. For example, a command to move forward 2 meters at the same heading will have goal_x_rt_body=2.0, goal_y_rt_body=0.0, goal_heading_rt_body=0.0.

The arguments body_height and locomotion_hint are ignored if params argument is passed. A trajectory command requires an end time. End time is not set in this function, but rather is set externally before call to RobotCommandService.

Parameters:
  • goal_x_rt_body – Position X coordinate described relative to the body frame.

  • goal_y_rt_body – Position Y coordinate described relative to the body frame.

  • goal_heading_rt_body – Pose heading in radians described relative to the body frame.

  • frame_tree_snapshot – Dictionary representing the child_to_parent_edge_map describing different transforms. This can be acquired using the robot state client directly, or using the robot object’s helper function robot.get_frame_tree_snapshot().

  • params (spot.MobilityParams) – Spot specific parameters for mobility commands. If not set, this will be constructed using other args.

  • body_height – Height, meters, relative to a nominal stand height.

  • locomotion_hint – Locomotion hint to use for the trajectory command.

Returns:

RobotCommand, which can be issued to the robot command service. The go-to point will be converted to a non-moving world frame (odom frame) to be issued to the robot.

static synchro_velocity_command(v_x, v_y, v_rot, params=None, body_height=0.0, locomotion_hint=1, frame_name='body', build_on_command=None)[source]

Command robot to move along 2D plane. Velocity should be specified in the robot body frame. Other frames are currently not supported. The arguments body_height and locomotion_hint are ignored if params argument is passed.

A velocity command requires an end time. End time is not set in this function, but rather is set externally before call to RobotCommandService.

Parameters:
  • v_x – Velocity in X direction.

  • v_y – Velocity in Y direction.

  • v_rot – Velocity heading in radians.

  • params (spot.MobilityParams) – Spot specific parameters for mobility commands. If not set, this will be constructed using other args.

  • body_height – Height, meters, relative to a nominal stand height.

  • locomotion_hint – Locomotion hint to use for the velocity command.

  • frame_name – Name of the frame to use.

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and gripper_command from this incoming RobotCommand will be added to the returned RobotCommand.

Returns:

RobotCommand, which can be issued to the robot command service.

static synchro_stand_command(params=None, body_height=0.0, footprint_R_body=<bosdyn.geometry.EulerZXY object>, build_on_command=None)[source]

Command robot to stand. If the robot is sitting, it will stand up. If the robot is moving, it will come to a stop. Params can specify a trajectory for the body to follow while standing. In the simplest case, this can be a specific position+orientation which the body will hold at. The arguments body_height and footprint_R_body are ignored if params argument is passed.

Parameters:
  • params (spot.MobilityParams) – Spot specific parameters for mobility commands. If not set, this will be constructed using other args.

  • body_height (float) – Height, meters, to stand at relative to a nominal stand height.

  • footprint_R_body (EulerZXY) – The orientation of the body frame with respect to the footprint frame (gravity aligned framed with yaw computed from the stance feet)

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and gripper_command from this incoming RobotCommand will be added to the returned RobotCommand.

Returns:

RobotCommand, which can be issued to the robot command service.

static synchro_sit_command(params=None, build_on_command=None)[source]

Command the robot to sit.

Parameters:
  • params (spot.MobilityParams) – Spot specific parameters for mobility commands.

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and gripper_command from this incoming RobotCommand will be added to the returned RobotCommand.

Returns:

RobotCommand, which can be issued to the robot command service.

static stance_command(se2_frame_name, pos_fl_rt_frame, pos_fr_rt_frame, pos_hl_rt_frame, pos_hr_rt_frame, accuracy=0.05, params=None, body_height=0.0, footprint_R_body=<bosdyn.geometry.EulerZXY object>, build_on_command=None)[source]

Command robot to stance with the feet at specified positions. This will cause the robot to reposition its feet. This is not intended to be a mobility command and will reject commands where the foot position is out of reach without locomoting. To stance at a far location, try using SE2TrajectoryCommand to safely put the robot at the correct location first.

Params can specify a trajectory for the body to follow while stancing. In the simplest case, this can be a specific position+orientation which the body will hold at. The arguments body_height and footprint_R_body are ignored if params argument is passed.

Parameters:
  • se2_frame_name (string) – The frame name which the desired foot_positions are described in.

  • pos_fl_rt_frame (Vec2) – Position of front left foot in specified frame.

  • pos_fr_rt_frame (Vec2) – Position of front right foot in specified frame.

  • pos_hl_rt_frame (Vec2) – Position of rear left foot in specified frame.

  • pos_hr_rt_frame (Vec2) – Position of rear right foot in specified frame.

  • accuracy (float) – Required foot positional accuracy in meters

  • params (spot.MobilityParams) – Spot specific parameters for mobility commands. If not set, this will be constructed using other args.

  • body_height (float) – Height, meters, to stand at relative to a nominal stand height.

  • footprint_R_body (EulerZXY) – The orientation of the body frame with respect to the footprint frame (gravity aligned framed with yaw computed from the stance feet)

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and gripper_command from this incoming RobotCommand will be added to the returned RobotCommand.

Returns:

RobotCommand, which can be issued to the robot command service.

static follow_arm_command()[source]

Command robot’s body to follow the arm around.

Parameters:

params (spot.MobilityParams) – Spot specific parameters for mobility commands.

Returns:

RobotCommand, which can be issued to the robot command service.

static arm_stow_command(build_on_command=None)[source]
static arm_ready_command(build_on_command=None)[source]
static arm_carry_command(build_on_command=None)[source]
static arm_gaze_command(x, y, z, frame_name, build_on_command=None, frame2_tform_desired_hand=None, frame2_name=None, max_linear_vel=None, max_angular_vel=None, max_accel=None)[source]

Builds a Vec3Trajectory to tell the robot arm to gaze at a point in 3D space. :returns: RobotCommand, which can be issued to the robot command service

static arm_pose_command_from_pose(hand_pose, frame_name, seconds=5, build_on_command=None)[source]

Builds an SE3Trajectory Point to tell robot arm to move to a pose in space relative to the frame specified. Wraps it in SynchronizedCommand.

Parameters:
  • hand_pose (geometry_pb2.SE3Pose) – Protobuf message specifying the desired pose of the hand.

  • frame_name (string) – Name of the frame relative to which hand_pose is expressed.

  • seconds (float) – Requested duration of the arm move.

  • build_on_command (robot_command_pb2.RobotCommand) – Optional RobotCommand (not containing a full_body_command). A mobility_command and gripper_command from build_on_command will be added to the RobotCommand returned by this function.

Returns:

RobotCommand, which can be issued to the robot command service.

static arm_pose_command(x, y, z, qw, qx, qy, qz, frame_name, seconds=5, build_on_command=None)[source]

Builds an SE3Trajectory Point to tell robot arm to move to a pose in space relative to the frame specified. Wraps it in SynchronizedCommand.

Returns:

RobotCommand, which can be issued to the robot command service.

static arm_wrench_command(force_x, force_y, force_z, torque_x, torque_y, torque_z, frame_name, seconds=5, build_on_command=None)[source]
Builds a command to tell robot arm to exhibit a wrench.

Wraps it in a SynchronizedCommand.

Returns:

RobotCommand, which can be issued to the robot command service.

static claw_gripper_open_command(build_on_command=None, max_acc=None, max_vel=None)[source]

Builds a command to open the gripper. Wraps it in SynchronizedCommand.

Parameters:
  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and mobility_command from this incoming RobotCommand will be added to the returned RobotCommand.

  • max_acc – Optional maximum allowable gripper acceleration. Not setting this will lead to the robot using a relatively safe low default. If the user is sure their gripper trajectory is safe and achievable, this can be set to a large value so it doesn’t get in the way.

  • max_vel – Optional maximum allowable gripper velocity. Same thing about defaults as max_acc.

Returns:

robot_command_pb2.RobotCommand with a claw_gripper_command filled out.

static claw_gripper_close_command(build_on_command=None, max_acc=None, max_vel=None, disable_force_on_contact=False, max_torque=None)[source]

Builds a command to close the gripper. Wraps it in SynchronizedCommand.

Parameters:
  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and mobility_command from this incoming RobotCommand will be added to the returned RobotCommand.

  • max_acc – Optional maximum allowable gripper acceleration. Not setting this will lead to the robot using a relatively safe low default. If the user is sure their gripper trajectory is safe and achievable, this can be set to a large value so it doesn’t get in the way.

  • max_vel – Optional maximum allowable gripper velocity. Same thing about defaults as max_acc.

  • disable_force_on_contact – Whether to switch the gripper to force control on contact detection.

  • max_torque – Optional Maximum torque applied if contact detected closing the gripper. If unspecified, a default value of 5.5 (Nm) will be used.

Returns:

robot_command_pb2.RobotCommand with a claw_gripper_command filled out.

static claw_gripper_open_fraction_command(open_fraction, build_on_command=None, max_acc=None, max_vel=None, disable_force_on_contact=False, max_torque=None)[source]

Builds a command to set the gripper using a fractional input. Wraps it in SynchronizedCommand.

Parameters:
  • open_fraction – Percentage [0, 1] to open the gripper. 0 fully closed, 1 fully open.

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and mobility_command from this incoming RobotCommand will be added to the returned RobotCommand.

  • max_acc – Optional maximum allowable gripper acceleration. Not setting this will lead to the robot using a relatively safe low default. If the user is sure their gripper trajectory is safe and achievable, this can be set to a large value so it doesn’t get in the way.

  • max_vel – Optional maximum allowable gripper velocity. Same thing about defaults as max_acc.

  • disable_force_on_contact – Whether to switch the gripper to force control on contact detection.

  • max_torque – Optional Maximum torque applied if contact detected closing the gripper. If unspecified, a default value of 5.5 (Nm) will be used.

Returns:

robot_command_pb2.RobotCommand with a claw_gripper_command filled out.

static claw_gripper_open_angle_command(gripper_q, build_on_command=None, max_acc=None, max_vel=None, disable_force_on_contact=False, max_torque=None)[source]

Builds a command to set the gripper open angle. Wraps it in SynchronizedCommand.

Parameters:
  • gripper_q – [-1.5708, 0] where -1.5708 is fully open and 0 is fully closed.

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and mobility_command from this incoming RobotCommand will be added to the returned RobotCommand.

  • max_acc – Optional maximum allowable gripper acceleration. Not setting this will lead to the robot using a relatively safe low default. If the user is sure their gripper trajectory is safe and achievable, this can be set to a large value so it doesn’t get in the way.

  • max_vel – Optional maximum allowable gripper velocity. Same thing about defaults as max_acc.

  • disable_force_on_contact – Whether to switch the gripper to force control on contact detection.

  • max_torque – Optional Maximum torque applied if contact detected closing the gripper. If unspecified, a default value of 5.5 (Nm) will be used.

Returns:

robot_command_pb2.RobotCommand with a claw_gripper_command filled out.

static create_arm_joint_trajectory_point(sh0, sh1, el0, el1, wr0, wr1, time_since_reference_secs=None)[source]
static arm_joint_command(sh0, sh1, el0, el1, wr0, wr1, max_vel=None, max_accel=None, build_on_command=None)[source]
static arm_joint_move_helper(joint_positions, times, joint_velocities=None, ref_time=None, max_acc=None, max_vel=None, build_on_command=None)[source]

Given a set of joint positions, times, and optional velocity, create a synchro command.

Parameters:
  • joint_positions – A list of length N with joint positions at each knot point in our trajectory. Each knot joint position is represented as a list of length 6, representing the 6 joint angles [sh0, sh1, el0, el1, wr0, wr1]

  • times – A list of length N with the corresponding time_since_reference for each of our knots

  • joint_velocities – Optional joint velocities at each knot. Same structure as joint_positions

  • ref_time – Optional robot reference time. If unset, we’ll use the current synchronized robot time. Setting this is useful for getting a consistent trajectory over a long period of time when many ArmJointMoveRequest commands are chained together.

  • max_acc – Optional maximum allowable joint acceleration. Not setting this will lead to the robot using a relatively safe low default. If the user is sure their joint trajectory is safe and achievable, this can be set to a large value so it doesn’t get in the way.

  • max_vel – Optional maximum allowable joint velocity. Same thing about defaults as max_acc

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). A mobility_command and gripper_command from this incoming RobotCommand will be added to the returned RobotCommand.

Returns:

robot_command_pb2.RobotCommand with an arm_joint_move_command filled out.

static arm_cartesian_move_helper(se3_poses, times, root_frame_name, wrist_tform_tool=None, root_tform_task=None, se3_velocities=None, ref_time=None, max_acc=None, max_linear_vel=None, max_angular_vel=None, build_on_command=None)[source]
Given a set of SE3Poses, times, and optional velocities, create a synchro command

containing an arm_cartesian_command.

Parameters:
  • se3_poses (geometry_pb2.SE3Pose) – A list of length N with SE3 transforms at each knot point in our trajectory.

  • times – A list of length N with the corresponding time_since_reference for each of our knots.

  • root_frame_name – The name of the root frame. It must be a valid frame name in the frame_tree.

  • wrist_tform_tool (geometry_pb2.SE3Pose) – The optional tool pose to use during the move. If unset, defaults to a pose slightly in front of the gripper’s palm plate aligned with the wrist’s orientation.

  • root_tform_task (geometry_pb2.SE3Pose) – The SE3 transform between the root and the task frame. If unset, it will treat the root frame as the task frame.

  • se3_velocities (geometry_pb2.SE3Velocity) – An optional list of length N with SE3 velocities at each knot point in our trajectory.

  • ref_time – Optional reference time for the trajectory gotten from the computer. If unset, we’ll use the current robot-synchronized time

  • max_acc – Optional maximum allowable linear acceleration (m/s^2).

  • max_linear_vel – Optional maximum allowable linear velocity (m/s).

  • max_angular_vel – Optional maximum allowable angular velocity (rad/s).

  • build_on_command – Option to input a RobotCommand for synchronous commands.

Returns:

robot_command_pb2.RobotCommand with an arm_cartesian_command filled out.

static claw_gripper_command_helper(gripper_positions, times, gripper_velocities=None, ref_time=None, max_acc=None, max_vel=None, disable_force_on_contact=False, build_on_command=None, max_torque=None)[source]

Given a set of gripper positions, times, and optional velocities, create a synchro command.

Parameters:
  • gripper_positions – A list of length N with joint positions at each knot point in our trajectory.

  • times – A list of length N with the corresponding time_since_reference for each of our knots

  • gripper_velocities – Optional joint velocities at each knot. Same structure as gripper_positions.

  • ref_time – Optional robot reference time. If unset, we’ll use the current synchronized robot time. Setting this is useful for getting a consistent trajectory over a long period of time when many ClawGripperCommandRequest commands are chained together.

  • max_acc – Optional maximum allowable gripper acceleration. Not setting this will lead to the robot using a relatively safe low default. If the user is sure their gripper trajectory is safe and achievable, this can be set to a large value so it doesn’t get in the way.

  • max_vel – Optional maximum allowable gripper velocity. Same thing about defaults as max_acc.

  • disable_force_on_contact – Whether to switch the gripper to force control on contact detection.

  • build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and mobility_command from this incoming RobotCommand will be added to the returned RobotCommand.

  • max_torque – Optional Maximum torque applied if contact detected closing the gripper. If unspecified, a default value of 5.5 (Nm) will be used.

Returns:

robot_command_pb2.RobotCommand with a claw_gripper_command filled out.

static arm_joint_freeze_command(build_on_command=None)[source]

Returns a RobotCommand with an ArmCommand that will freeze the arm’s joints in place.

Parameters:

build_on_command – Option to input a RobotCommand (not containing a full_body_command). An arm_command and mobility_command from this incoming RobotCommand will be added to the returned RobotCommand.

Returns:

robot_command_pb2.RobotCommand

static mobility_params(body_height=0.0, footprint_R_body=<bosdyn.geometry.EulerZXY object>, locomotion_hint=1, stair_hint=False, external_force_params=None, stairs_mode=None)[source]

Helper to create Mobility params for spot mobility commands. This function is designed to help get started issuing commands, but lots of options are not exposed via this interface. See spot.robot_command_pb2 for more details. If unset, good defaults will be chosen by the robot.

Parameters:
  • body_height – Height, meters, relative to a nominal stand height.

  • footprint_R_body (EulerZXY) – The orientation of the body frame with respect to the footprint frame (gravity aligned framed with yaw computed from the stance feet)

  • locomotion_hint – Locomotion hint to use for the command.

  • stair_hint – Boolean to specify if stair mode should be used. Deprecated in favor of stairs_mode and ignored if stairs_mode set.

  • external_force_params (spot.BodyExternalForceParams) – Robot body external force parameters.

  • stairs_mode – StairsMode enum specifying stairs mode as On, Auto, or Off.

Returns:

spot.MobilityParams, params for spot mobility commands.

static body_pose(frame_name, body_pose)[source]

Helper to create a BodyControlParams.BodyPose from a single desired body_pose relative to frame_name.

Parameters:
  • frame_name (string) – Name of the frame relative to which body_pose is expressed.

  • body_pose (geometry_pb2.SE3Pose) – Protobuf message specifying the desired pose of the body.

Returns:

spot.BodyControlParams.BodyPose, specifies the desired body pose for a StandCommand

static build_body_external_forces(external_force_indicator=0, override_external_force_vec=None)[source]

Helper to create Mobility params.

This function allows the user to enable an external force estimator, or set a vector of forces (in the body frame) which override the estimator with constant external forces.

Parameters:
  • external_force_indicator – Indicates if the external force estimator should be enabled/disabled or an override force should be used. Can be specified as one of three values: spot_command_pb2.BodyExternalForceParams.{ EXTERNAL_FORCE_NONE, EXTERNAL_FORCE_USE_ESTIMATE, EXTERNAL_FORCE_USE_OVERRIDE }

  • override_external_force_vec – x/y/z list of forces in the body frame. Only used when the indicator specifies EXTERNAL_FORCE_USE_OVERRIDE

Returns:

spot.MobilityParams, params for spot mobility commands.

static build_synchro_command(*args)[source]

Combines multiple commands into one command. There’s no intelligence here on duplicate commands.

Parameters:

commands (RobotCommand containing only either mobility commands or synchro) –

Returns:

RobotCommand containing a synchro command

bosdyn.client.robot_command.blocking_command(command_client, command, check_status_fn, end_time_secs=None, timeout_sec=10, update_frequency=1.0)[source]

Helper function which uses the RobotCommandService to execute the given command.

Blocks until check_status_fn return true, or raises an exception if the command times out or fails. This helper checks the main full_body/synchronized command status (RobotCommandFeedbackStatus), but the caller should check the status of the specific commands (stand, stow, selfright, etc.) in the callback.

Parameters:
  • command_client – RobotCommand client.

  • command – The robot command to issue to the robot.

  • check_status_fn – A callback that accepts RobotCommandFeedbackResponse and returns True when the correct statuses are achieved for the specific requested command and throws CommandFailedErrorWithFeedback if an error state occurs.

  • end_time_sec – The local end time of the command (will be converted to robot time)

  • timeout_sec – Timeout for the rpc in seconds.

  • update_frequency – Update frequency for the command in Hz.

Raises:
bosdyn.client.robot_command.blocking_stand(command_client, timeout_sec=10, update_frequency=1.0, params=None)[source]

Helper function which uses the RobotCommandService to stand.

Blocks until robot is standing, or raises an exception if the command times out or fails.

Parameters:
  • command_client – RobotCommand client.

  • timeout_sec – Timeout for the command in seconds.

  • update_frequency – Update frequency for the command in Hz.

  • params (spot.MobilityParams) – Spot specific parameters for mobility commands to optionally set say body_height

Raises:
bosdyn.client.robot_command.blocking_sit(command_client, timeout_sec=10, update_frequency=1.0)[source]

Helper function which uses the RobotCommandService to sit.

Blocks until robot is sitting, or raises an exception if the command times out or fails.

Parameters:
  • command_client – RobotCommand client.

  • timeout_sec – Timeout for the command in seconds.

  • update_frequency – Update frequency for the command in Hz.

Raises:
bosdyn.client.robot_command.blocking_selfright(command_client, timeout_sec=30, update_frequency=1.0)[source]

Helper function which uses the RobotCommandService to self-right.

Blocks until self-right has completed, or raises an exception if the command times out or fails.

Parameters:
  • command_client – RobotCommand client.

  • timeout_sec – Timeout for the command in seconds.

  • update_frequency – Update frequency for the command in Hz.

Raises:
bosdyn.client.robot_command.block_until_arm_arrives(command_client, cmd_id, timeout_sec=None)[source]

Helper that blocks until the arm achieves a finishing state for the specific arm command.

This helper will block and check the feedback for ArmCartesianCommand, GazeCommand, ArmJointMoveCommand, NamedArmPositionsCommand, and ArmImpedanceCommand.

Parameters:
  • command_client – robot command client, used to request feedback

  • cmd_id – command ID returned by the robot when the arm movement command was sent.

  • timeout_sec – optional number of seconds after which we’ll return no matter what the robot’s state is.

Return values:

True if successfully got to the end of the trajectory, False if the arm stalled or the move was canceled (the arm failed to reach the goal). See the proto definitions in arm_command.proto for more information about why a trajectory would succeed or fail.

bosdyn.client.robot_command.block_for_trajectory_cmd(command_client, cmd_id, trajectory_end_statuses=(1,), body_movement_statuses=None, feedback_interval_secs=0.1, timeout_sec=None, logger=None)[source]

Helper that blocks until a trajectory command reaches a desired goal state or a timeout is reached.

Parameters:
  • command_client (RobotCommandClient) – the client used to request feedback

  • cmd_id (int) – command ID returned by the robot when the trajectory command was sent

  • trajectory_end_statuses (set of SE2TrajectoryCommand.Feedback.Status) – the feedback must have a status which is included in this set of statuses to be considered successfully complete. By default, this includes only the “STATUS_STOPPED” end condition.

  • body_movement_statuses (set of SE2TrajectoryCommand.Feedback.BodyMovementStatus) – the body movement status must be one of these statuses to be considered successfully complete. By default, this is “None”, which means any body movement status will be accepted.

  • feedback_interval_secs (float) – The time (in seconds) to wait before each feedback request checking if the trajectory is complete. Defaults to checking at 10 Hz (requests every 0.1 seconds).

  • timeout_sec (float) – optional number of seconds after which we’ll return no matter what the robot’s state is.

  • logger (logging.Logger) – The logger print debug statements with. If none, no debug printouts will be sent.

Return values:

True if reaches STATUS_STOPPED, False otherwise.