diff --git a/README.md b/README.md index f2620f3fe..a7dca83da 100644 --- a/README.md +++ b/README.md @@ -22,7 +22,7 @@ The SDK consists of: - [Spot API protocol definition](protos/bosdyn/api/README.md). This reference guide covers the details of the protocol applications used to communicate to Spot. Application developers who wish to use a language other than Python can implement clients that speak the protocol. - [Spot SDK Repository](https://github.com/boston-dynamics/spot-sdk). The GitHub repo where all of the Spot SDK code is hosted. -This is version 4.0.1 of the SDK. Please review the [Release Notes](docs/release_notes.md) to see what has changed. +This is version 4.0.2 of the SDK. Please review the [Release Notes](docs/release_notes.md) to see what has changed. ## Contents diff --git a/VERSION b/VERSION index 1454f6ed4..4d54daddb 100644 --- a/VERSION +++ b/VERSION @@ -1 +1 @@ -4.0.1 +4.0.2 diff --git a/docs/concepts/README.md b/docs/concepts/README.md index 6ddf4a219..17d3605e9 100644 --- a/docs/concepts/README.md +++ b/docs/concepts/README.md @@ -46,5 +46,6 @@ Similar to the Spot API, client applications can be written in many languages an - [Faults](faults.md) - [Autonomy services](autonomy/README.md) - [Choreography](choreography/README.md) +- [Joint Control API](joint_control/README.md) - [Spot Arm](arm/README.md) - [Spot Data](data.md) diff --git a/docs/concepts/joint_control/README.md b/docs/concepts/joint_control/README.md new file mode 100644 index 000000000..9504f4349 --- /dev/null +++ b/docs/concepts/joint_control/README.md @@ -0,0 +1,84 @@ + + +# Joint Control API (Beta) + +The Joint Control API provides developers with low-level control of the robot through high-rate, low-latency RPC streams. This controlled-access API requires a special-permissions license and is compatible with the Boston Dynamics SDK, available in either C++ or Python. + +## Contents + +Information regarding joint ordering, maximum torques, and robot morphology. + +- [Supplemental Robot Information](supplemental_data.md) + +## Components + +- [Streaming Robot State Messages](../../../protos/bosdyn/api/robot_state.proto#robotstatestreamresponse): Structure for receiving lightweight robot state messages. +- [Streaming Robot Command Messages](../../../protos/bosdyn/api/basic_command.proto#jointcommand-updaterequest): Structure for sending joint commands, gains, and leg contact advice. +- [Streaming State Client](../../../python/bosdyn-client/src/bosdyn/client/robot_state.py#bosdyn.client.robot_state.RobotStateStreamingClient): Python client for receiving lightweight robot state. +- [Streaming Command Client](../../../python/bosdyn-client/src/bosdyn/client/robot_command.py#bosdyn.client.robot_command.RobotCommandStreamingClient) Python client for streaming robot commands. + +## Usage + +To utilize the Joint Control API: + +- Install the Boston Dynamics SDK. +- Connect to a licensed robot supporting joint control. +- Enable joint control initially via [JointCommand.Request](../../../protos/bosdyn/api/basic_command.proto#jointcommand-request) RPC with the [Command Client](../../../python/bosdyn-client/src/bosdyn/client/robot_command.py#bosdyn.client.robot_command.RobotCommandClient) +- Start streaming [JointCommand.UpdateRequest](../../../protos/bosdyn/api/basic_command.proto#jointcommand-updaterequest) with the [Streaming Command Client](../../../python/bosdyn-client/src/bosdyn/client/robot_command.py#bosdyn.client.robot_command.RobotCommandStreamingClient) + +## Robot Command Stream + +The robot command streaming service allows a user to move the robot with simple commands for each of the robot's joints. The interface provided is very similar to the one that Boston Dynamics' internal developers use to compose complex walking and manipulation behaviors. + +We expose for each joint proportional-derivative + feed-forward (PDFF) control parameters outlined below. + +- **position**: Repeated desired position in radians for each of the robot's joints. +- **velocity**: Repeated desired angular velocity in radians/s for each of the robot's joints. +- **load**: Repeated desired load in Newton-meters for each of the robot's joints. +- **gains**: Repeated gains for each joint. Gains are required to be sent to initialize control, but may be omitted on subsequent commands to save bandwidth if they are unchanged. Each gain contains two parameters: **k_q_p** proportional position error gain in Newton-meters / radian and **k_qd_p** proportional velocity error gain in Newton-meter-second / radian. + +Furthermore, there are shared message fields outlined below. + +- **end_time**: The timestamp (in robot time) when the command will stop executing. This is a required field and used to prevent runaway commands. +- **reference_time**: (Optional) joint trajectory reference time. See **extrapolation_duration** for detailed explanation. If unspecified, this will default to the time the command is received. If the time is in the future, no extrapolation will be performed until that time (extrapolation never goes backwards in time.) +- **extrapolation_duration**: (Optional) joint trajectory extrapolation time. If specified, the robot will extrapolate desired position based on desired **velocity**, starting at **reference_time** for at most **extrapolation_duration** (or until **end_time**, whichever is sooner.) +- **user_command_key**: (Optional) Key that can be used for tracking when commands take effect on the robot and calculating loop latencies. Avoid using 0. +- **velocity_safety_limit**: (Optional) Joint velocity safety limit in radians/s. Possibly useful during initial development or gain tuning. If the magnitude of any joint velocity passes the threshold the robot will trigger a behavior fault and go into a safety state. Client must power down the robot or clear the behavior fault via the Robot Command Service. Values less than or equal to 0 will be considered invalid and must be sent in every **UpdateRequest** for use. + +Clients are encouraged to stream new commands at a suitably high frequency (100-333 Hz) to achieve more complex behaviors such as following higher fidelity trajectories or deploying trained machine learning policies. + +#### Note on Closed-Loop Joint Behavior + +- As outlined above, the Joint Control API provides the means to specify PDFF control parameters for each of the joints. At the servo level we utilize the desired positions/velocities/loads to calculate a total desired torque which is tracked in firmware as follows: + +**
load_servo = k_q_p \* (position_desired - position_measured) + k_qd_p \* (velocity_desired - velocity_measured) + load_desired
** + +- A pure proportional-derivative control may be achieved by setting the load commands to zero. Likewise, pure torque control may be achieved by setting the **k_q_p** and **k_qd_p** gains to zero and commanding zero **position** and **velocity**. +- Desired positions and loads are saturated with respect to the robot's kinematic and load limits. See notes below on limits. + +## Robot State Stream + +The robot state streaming service provides a minimal version of robot state suitable for high-rate communications with the robot. Usage note: a user may still find it necessary to request full robot state at a lower rate from the [RobotStateService](../../../docs/concepts/robot_services.md#robot-state), e.g. to gain access to fault information or battery state of charge. + +The morphology of the robot, represented by links and joints, is described through a URDF which can be requested through the [RobotStateService](../../../docs/concepts/robot_services.md#robot-state). This configuration representation is fully expressive of the robot's joint states relative to each other and can be used for visualization, dynamics, or forward kinematics of the robot model. A URDF model with some additional information regarding max joint torques and collision geometries of the robot with an arm can also be found [here](../../../files/spot_with_arm_urdf.zip). + +The streaming robot state includes information about joints, Inertial Measurement Unit (IMU) information, foot contact states, and the kinematic state of the robot. The `GetRobotStateStream` RPC can provide a stream that will pipe data at 333 Hz from the robot. + +- **joint_states**: Measured joint position, velocity, and load of each of the robot's joints. Positions are expressed in radians, velocities in radians/s, and load in Newton-meters. See [here](supplemental_data.md#joint-order) for supplemental information regarding joint order. +- **inertial_state**: Full-rate IMU information including accelerations and angular velocities. For IMU rotation see **kinematic_state.** +- **kinematic_state**: [Provides](../../../protos/bosdyn/api/robot_state.proto#robotstatestreamresponse-kinematicstate) the robot's estimated SE3Pose in both the "odom" and "vision" frames, along with base robot SE3Velocities. For a primer on "odom" and "vision" frames, refer to this [document](../../../docs/concepts/geometry_and_frames.md). These estimates result from the fusion of joint state, IMU data, and perception data on the robot. While every effort has been made to ensure the general accuracy of these estimates, their precision may vary depending on specific robot usage scenarios. Instances where the robot's contact forces are not through its foot, such as sliding on the ground or resting on the knees, may particularly affect the accuracy. +- **contact_states**: Repeated for each foot indicating if the robot thinks that foot is in contact with the ground. +- **last_command**: For loop-timing calculations, the robot echoes back the last user_command_key received from the streaming robot command service. + +## Example Code + +A few simple [examples](../../../python/examples/docs/joint_control_examples.md) illustrating use are shown in: + +- [Robot Squat](../../../python/examples/joint_control/README.md#armless-robot-squat) +- [Wiggle Arm](../../../python/examples/joint_control/README.md#arm-wiggle) diff --git a/docs/concepts/joint_control/knee_torque_limits.md b/docs/concepts/joint_control/knee_torque_limits.md new file mode 100644 index 000000000..e4de06fc6 --- /dev/null +++ b/docs/concepts/joint_control/knee_torque_limits.md @@ -0,0 +1,113 @@ + + +# Knee Torque Limits + +| Knee Angle (rad) | Transmission Ratio (In/Out) | Max Output Torque (N\*m) | +| ---------------- | --------------------------- | ------------------------ | +| -2.792900 | -24.776718 | 37.165077 | +| -2.767442 | -26.290108 | 39.435162 | +| -2.741984 | -27.793369 | 41.690054 | +| -2.716526 | -29.285997 | 43.928996 | +| -2.691068 | -30.767536 | 46.151304 | +| -2.665610 | -32.237423 | 48.356134 | +| -2.640152 | -33.695168 | 50.542751 | +| -2.614694 | -35.140221 | 52.710331 | +| -2.589236 | -36.572052 | 54.858078 | +| -2.563778 | -37.990086 | 56.985128 | +| -2.538320 | -39.393730 | 59.090595 | +| -2.512862 | -40.782406 | 61.173609 | +| -2.487404 | -42.155487 | 63.233231 | +| -2.461946 | -43.512371 | 65.268557 | +| -2.436488 | -44.852371 | 67.278557 | +| -2.411030 | -46.174873 | 69.262310 | +| -2.385572 | -47.479156 | 71.218735 | +| -2.360114 | -48.764549 | 73.146824 | +| -2.334656 | -50.030334 | 75.045502 | +| -2.309198 | -51.275761 | 76.913641 | +| -2.283740 | -52.500103 | 78.750154 | +| -2.258282 | -53.702587 | 80.553881 | +| -2.232824 | -54.882442 | 82.323664 | +| -2.207366 | -56.038860 | 84.058290 | +| -2.181908 | -57.171028 | 85.756542 | +| -2.156450 | -58.278133 | 87.417200 | +| -2.130992 | -59.359314 | 89.038971 | +| -2.105534 | -60.413738 | 90.620607 | +| -2.080076 | -61.440529 | 92.160793 | +| -2.054618 | -62.438812 | 93.658218 | +| -2.029160 | -63.407692 | 95.111538 | +| -2.003702 | -64.346268 | 96.519402 | +| -1.978244 | -65.253670 | 97.880505 | +| -1.952786 | -66.128944 | 99.193417 | +| -1.927328 | -66.971176 | 100.456764 | +| -1.901870 | -67.779457 | 101.669186 | +| -1.876412 | -68.552864 | 102.829296 | +| -1.850954 | -69.290451 | 103.935677 | +| -1.825496 | -69.991325 | 104.986988 | +| -1.800038 | -70.654541 | 105.981812 | +| -1.774580 | -71.279190 | 106.918785 | +| -1.749122 | -71.864319 | 107.796478 | +| -1.723664 | -72.409088 | 108.613632 | +| -1.698206 | -72.912567 | 109.368851 | +| -1.672748 | -73.373871 | 110.060806 | +| -1.647290 | -73.792130 | 110.688194 | +| -1.621832 | -74.166512 | 111.249767 | +| -1.596374 | -74.496147 | 111.744221 | +| -1.570916 | -74.780251 | 112.170376 | +| -1.545458 | -75.017998 | 112.526997 | +| -1.520000 | -75.208656 | 112.812984 | +| -1.494542 | -75.351448 | 113.027172 | +| -1.469084 | -75.445686 | 113.168530 | +| -1.443626 | -75.490677 | 113.236015 | +| -1.418168 | -75.485771 | 113.228657 | +| -1.392710 | -75.430344 | 113.145515 | +| -1.367252 | -75.323830 | 112.985744 | +| -1.341794 | -75.165688 | 112.748531 | +| -1.316336 | -74.955406 | 112.433109 | +| -1.290878 | -74.692551 | 112.038826 | +| -1.265420 | -74.376694 | 111.565041 | +| -1.239962 | -74.007477 | 111.011215 | +| -1.214504 | -73.584579 | 110.376869 | +| -1.189046 | -73.107742 | 109.661613 | +| -1.163588 | -72.576752 | 108.865128 | +| -1.138130 | -71.991455 | 107.987183 | +| -1.112672 | -71.351707 | 107.027561 | +| -1.087214 | -70.657486 | 105.986229 | +| -1.061756 | -69.908813 | 104.863220 | +| -1.036298 | -69.105721 | 103.658581 | +| -1.010840 | -68.248337 | 102.372505 | +| -0.985382 | -67.336861 | 101.005291 | +| -0.959924 | -66.371513 | 99.557270 | +| -0.934466 | -65.352615 | 98.028923 | +| -0.909008 | -64.280533 | 96.420799 | +| -0.883550 | -63.155693 | 94.733540 | +| -0.858092 | -61.978588 | 92.967882 | +| -0.832634 | -60.749775 | 91.124662 | +| -0.807176 | -59.469845 | 89.204767 | +| -0.781718 | -58.139503 | 87.209255 | +| -0.756260 | -56.759487 | 85.139231 | +| -0.730802 | -55.330616 | 82.995924 | +| -0.705344 | -53.853729 | 80.780594 | +| -0.679886 | -52.329796 | 78.494694 | +| -0.654428 | -50.759762 | 76.139643 | +| -0.628970 | -49.144699 | 73.717049 | +| -0.603512 | -47.485737 | 71.228605 | +| -0.578054 | -45.784004 | 68.676006 | +| -0.552596 | -44.040764 | 66.061146 | +| -0.527138 | -42.257267 | 63.385900 | +| -0.501680 | -40.434883 | 60.652325 | +| -0.476222 | -38.574947 | 57.862421 | +| -0.450764 | -36.678982 | 55.018473 | +| -0.425306 | -34.748432 | 52.122648 | +| -0.399848 | -32.784836 | 49.177254 | +| -0.374390 | -30.789810 | 46.184715 | +| -0.348932 | -28.764952 | 43.147428 | +| -0.323474 | -26.711969 | 40.067954 | +| -0.298016 | -24.632576 | 36.948864 | +| -0.272558 | -22.528547 | 33.792821 | +| -0.247100 | -20.401667 | 30.602500 | diff --git a/docs/concepts/joint_control/spot_with_arm.png b/docs/concepts/joint_control/spot_with_arm.png new file mode 100644 index 000000000..50b3abbf9 Binary files /dev/null and b/docs/concepts/joint_control/spot_with_arm.png differ diff --git a/docs/concepts/joint_control/supplemental_data.md b/docs/concepts/joint_control/supplemental_data.md new file mode 100644 index 000000000..5cae89a54 --- /dev/null +++ b/docs/concepts/joint_control/supplemental_data.md @@ -0,0 +1,61 @@ + + +# Supplemental Data + +Contains additional simulation data for the development of control algorithms for the Spot robot and simulations. +![Spot URDF](spot_with_arm.png) + +## Contents + +Table for the variable max knee torque due to the knee linkage. + +- [Knee Torque Limits](knee_torque_limits.md) + +## Joint Order + +All repeated fields for commands and state are in a consistent order as outlined in [spot_constants.proto](../../../protos/bosdyn/api/spot/spot_constants.proto). + +## Robot Morphology + +Robot structure can be found by inspecting the full URDF located [here](../../../files/spot_with_arm_urdf.zip). **Note:** This URDF contains additional information compared to what is available through the [RobotStateService](../../../docs/concepts/robot_services.md#robot-state) and the URDF for an armless robot located [here](../../../files/spot_base_urdf.zip). + +## Joint Transmission Details + +### Joint Gear Ratios and Max Motor Torque + +Most joints are simply actuated with a constant gear ratio. + +| Joint | Gear Ratio | Max motor torque | +| ----- | ---------- | ---------------- | +| HX | 51 | 0.88 | +| HY | 51 | 0.88 | +| KN | variable | 1.50 | +| SH0 | 101 | 0.89 | +| SH1 | coupled | 0.89 | +| EL0 | coupled | 0.89 | +| EL1 | 101 | 0.23 | +| WR0 | 101 | 0.23 | +| WR1 | 101 | 0.23 | +| F1X | 56.55 | 0.20 | + +### Knee Joints + +The Spot robot knee is actuated using a ball-screw and push-rod mechanism connected to the lower leg. Due to the push-rod's geometry, the maximum torque achievable varies depending on the configuration. The knee exhibits its greatest strength at the midpoint of its range and its weakest when fully flexed or extended. For details on the variable transmission ratio, refer to the file available [here](knee_torque_limits.md). This transmission ratio describes the motor input to knee angle output relationship as: + +``` +Tr(q_kn) = qd_motor / qd_kn +``` + +### Coupled SH1/EL0 Joints + +The SH1/EL0 joints are driven by a coupled set of input actuators. The 2x2 Jacobian describing the output velocities is: + +``` +[qd_sh1; qd_el0] = (1/101) * [1 0; -1 1] * [qd_motor0; qd_motor1] +``` diff --git a/docs/html/.buildinfo b/docs/html/.buildinfo index f6c7bacac..e30de2690 100644 --- a/docs/html/.buildinfo +++ b/docs/html/.buildinfo @@ -1,4 +1,4 @@ # Sphinx build info version 1 # This file hashes the configuration used when building these files. When it is not found, a full rebuild will be done. -config: 4c97b22c7a4ac743f2b4785d9887c8d6 +config: 77cafe9d9e3c606cba14ec4e439e933a tags: 645f666f9bcd5a90fca523b33c5a78b7 diff --git a/docs/html/README.html b/docs/html/README.html index 99878623c..35aad6fe9 100644 --- a/docs/html/README.html +++ b/docs/html/README.html @@ -4,7 +4,7 @@ -