From d6df815ee586407dcd67b613f7037cdf16d3587e Mon Sep 17 00:00:00 2001 From: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Date: Tue, 17 Dec 2024 20:49:40 -0500 Subject: [PATCH 01/15] Release v4.1.1 of Boston Dynamics Spot SDK --- README.md | 2 +- cpp/CMakeLists.txt | 2 +- cpp/bosdyn/client/README.md | 21 ++++++++------- .../client/directory/directory_helpers.cpp | 2 +- .../directory_registration_helpers.h | 2 +- .../error_codes/error_type_condition.cpp | 2 +- .../time_sync_helper_error_code.cpp | 25 +++++++++++------- .../error_codes/time_sync_helper_error_code.h | 4 +-- cpp/bosdyn/client/estop/estop_keepalive.h | 2 +- .../processors/common_response_processor.cpp | 2 +- cpp/bosdyn/client/robot/robot.cpp | 15 ++++++----- cpp/bosdyn/client/robot/robot.h | 3 +++ .../media_log/media_log_error_codes.h | 2 +- cpp/examples/README.md | 8 +++--- cpp/examples/hello_spot/README.md | 7 +++-- docs/cpp/cpp_sdk_differences.md | 21 ++++++++++----- docs/cpp/quickstart.md | 2 +- docs/cpp_release_notes.md | 18 +++++++++++++ protos/bosdyn/api/basic_command.proto | 8 +++--- protos/bosdyn/api/data_acquisition.proto | 2 +- protos/bosdyn/api/directory.proto | 2 +- protos/bosdyn/api/estop.proto | 3 +-- protos/bosdyn/api/license_service.proto | 4 +-- .../api/metrics_logging/signed_proto.proto | 4 +-- protos/bosdyn/api/mission/nodes.proto | 26 ++++++++++++------- .../api/network_compute_bridge_service.proto | 2 +- protos/bosdyn/api/service_customization.proto | 8 ++++++ protos/bosdyn/api/spot/robot_command.proto | 4 +++ protos/bosdyn/api/spot_cam/LED.proto | 1 + protos/bosdyn/api/spot_cam/audio.proto | 1 + protos/bosdyn/api/spot_cam/camera.proto | 3 ++- protos/bosdyn/api/spot_cam/compositor.proto | 1 + protos/bosdyn/api/spot_cam/health.proto | 1 + protos/bosdyn/api/spot_cam/logging.proto | 1 + protos/bosdyn/api/spot_cam/network.proto | 3 ++- protos/bosdyn/api/spot_cam/power.proto | 1 + protos/bosdyn/api/spot_cam/ptz.proto | 1 + protos/bosdyn/api/spot_cam/service.proto | 2 ++ .../bosdyn/api/spot_cam/streamquality.proto | 1 + protos/bosdyn/api/spot_cam/version.proto | 1 + 40 files changed, 146 insertions(+), 74 deletions(-) diff --git a/README.md b/README.md index b620c52..c209cf8 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+ - [Payload developer documentation](https://dev.bostondynamics.com/docs/payload/readme). Payloads add additional sensing, communication, and control capabilities beyond what the base platform provides. The Payload ICD covers the mechanical, electrical, and software interfaces that Spot supports. - [Spot API protocol definition](https://dev.bostondynamics.com/docs/protos/readme). 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. -This is version 4.1.0 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. +This is version 4.1.1 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. ## Contents diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index 2b5ae17..11e21c7 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -7,7 +7,7 @@ # This file is autogenerated. cmake_minimum_required (VERSION 3.10.2) -project (bosdyn VERSION 4.0.3) +project (bosdyn VERSION 4.1.1) # Dependencies: find_package(protobuf REQUIRED) diff --git a/cpp/bosdyn/client/README.md b/cpp/bosdyn/client/README.md index 6eb51a4..8914803 100644 --- a/cpp/bosdyn/client/README.md +++ b/cpp/bosdyn/client/README.md @@ -8,19 +8,22 @@ Development Kit License (20191101-BDSDK-SL). # Client Classes -The bosdyn/client folder contains client interfaces for interacting with the Boston Dynamics Spot -API. The client interfaces implement the Remote Procedure Calls (RPCs) in the +The bosdyn/client folder contains client interfaces for interacting with the Boston Dynamics Spot +API. The client interfaces implement the Remote Procedure Calls (RPCs) in the [API protobuf definitions](https://dev.bostondynamics.com/protos/bosdyn/api/readme). ## Main Classes + The main classes contained in this folder are ClientSdk and Robot. -* **ClientSdk**: Class for settings typically common to a single developer and/or robot fleet. -* **Robot**: Class for settings common to one user's access to one robot. This is the main point -of access to all client functionality. -For example, to list the robot image sources using the Image client, simply create an Sdk object, -create a Robot object, authenticate, create the client and call the +- **ClientSdk**: Class for settings typically common to a single developer and/or robot fleet. +- **Robot**: Class for settings common to one user's access to one robot. This is the main point + of access to all client functionality. + +For example, to list the robot image sources using the Image client, simply create an Sdk object, +create a Robot object, authenticate, create the client and call the corresponding method, as shown below. It is that simple! + ``` auto client_sdk = ::bosdyn::client::CreateStandardSDK("hello_spot"); auto robot = client_sdk->CreateRobot("10.0.0.3").move(); @@ -29,5 +32,5 @@ auto image_client = robot->EnsureServiceClient<::bosdyn::client::ImageClient>(). auto result = image_client->ListImageSources().move(); ``` -Clients that trigger robot movement also need to set up the TimeSync, Lease and E-Stop clients. Our -[Python examples](https://github.com/boston-dynamics/spot-sdk/tree/master/python/examples) repository contains many tutorials on how to use the clients. The API for the Spot Python SDK is very similar to the API for the Spot C++ SDK, and most Python examples can be used as reference on how to implement C++ applications. The Spot C++ SDK contains examples as well, listed [here](../../examples/README.md). \ No newline at end of file +Clients that trigger robot movement also need to set up the TimeSync, Lease and E-Stop clients. Our +[Python examples](https://github.com/boston-dynamics/spot-sdk/tree/master/python/examples) repository contains many tutorials on how to use the clients. The API for the Spot Python SDK is very similar to the API for the Spot C++ SDK, and most Python examples can be used as reference on how to implement C++ applications. The Spot C++ SDK contains examples as well, listed [here](../../examples/README.md). diff --git a/cpp/bosdyn/client/directory/directory_helpers.cpp b/cpp/bosdyn/client/directory/directory_helpers.cpp index 596771e..4e854d7 100644 --- a/cpp/bosdyn/client/directory/directory_helpers.cpp +++ b/cpp/bosdyn/client/directory/directory_helpers.cpp @@ -9,8 +9,8 @@ #include "directory_helpers.h" -#include "bosdyn/client/sdk/client_sdk.h" #include "bosdyn/client/error_codes/directory_helper_error_code.h" +#include "bosdyn/client/sdk/client_sdk.h" namespace bosdyn { diff --git a/cpp/bosdyn/client/directory_registration/directory_registration_helpers.h b/cpp/bosdyn/client/directory_registration/directory_registration_helpers.h index 6a99a26..fa4ef2e 100644 --- a/cpp/bosdyn/client/directory_registration/directory_registration_helpers.h +++ b/cpp/bosdyn/client/directory_registration/directory_registration_helpers.h @@ -13,8 +13,8 @@ #include #include "directory_registration_client.h" -#include "bosdyn/client/service_client/common_result_types.h" #include "bosdyn/client/fault/fault_client.h" +#include "bosdyn/client/service_client/common_result_types.h" #include diff --git a/cpp/bosdyn/client/error_codes/error_type_condition.cpp b/cpp/bosdyn/client/error_codes/error_type_condition.cpp index f211996..ace9e4f 100644 --- a/cpp/bosdyn/client/error_codes/error_type_condition.cpp +++ b/cpp/bosdyn/client/error_codes/error_type_condition.cpp @@ -9,9 +9,9 @@ #include +#include "bosdyn/client/error_codes/error_type_condition.h" #include "bosdyn/client/error_codes/rpc_error_code.h" #include "bosdyn/client/error_codes/sdk_error_code.h" -#include "bosdyn/client/error_codes/error_type_condition.h" namespace { // anonymous namespace diff --git a/cpp/bosdyn/client/error_codes/time_sync_helper_error_code.cpp b/cpp/bosdyn/client/error_codes/time_sync_helper_error_code.cpp index b334e57..9b328d8 100644 --- a/cpp/bosdyn/client/error_codes/time_sync_helper_error_code.cpp +++ b/cpp/bosdyn/client/error_codes/time_sync_helper_error_code.cpp @@ -8,8 +8,8 @@ #include "bosdyn/client/error_codes/time_sync_helper_error_code.h" -#include "bosdyn/client/error_codes/sdk_error_code.h" #include "bosdyn/client/error_codes/error_type_condition.h" +#include "bosdyn/client/error_codes/sdk_error_code.h" #include "bosdyn/common/success_condition.h" namespace bosdyn { @@ -25,13 +25,15 @@ struct TimeSyncHelperErrorCodeCategory : std::error_category { }; bool TimeSyncHelperErrorCodeCategory::equivalent(int valcode, - const std::error_condition& cond) const noexcept { + const std::error_condition& cond) const noexcept { if (cond == SuccessCondition::Success) return (valcode == 0); if (cond == ErrorTypeCondition::SDKError) return true; return false; } -const char* TimeSyncHelperErrorCodeCategory::name() const noexcept { return "TimeSyncHelperErrorCode"; } +const char* TimeSyncHelperErrorCodeCategory::name() const noexcept { + return "TimeSyncHelperErrorCode"; +} std::string TimeSyncHelperErrorCodeCategory::message(int value) const { switch (static_cast(value)) { @@ -43,21 +45,22 @@ std::string TimeSyncHelperErrorCodeCategory::message(int value) const { const TimeSyncHelperErrorCodeCategory TimeSyncHelperErrorCodeCategory_category{}; - struct EstablishTimeSyncErrorCodeCategory : std::error_category { const char* name() const noexcept override; std::string message(int ev) const override; bool equivalent(int valcode, const std::error_condition& cond) const noexcept override; }; -bool EstablishTimeSyncErrorCodeCategory::equivalent(int valcode, - const std::error_condition& cond) const noexcept { +bool EstablishTimeSyncErrorCodeCategory::equivalent( + int valcode, const std::error_condition& cond) const noexcept { if (cond == SuccessCondition::Success) return (valcode == 0); if (cond == ErrorTypeCondition::SDKError) return true; return false; } -const char* EstablishTimeSyncErrorCodeCategory::name() const noexcept { return "EstablishTimeSyncErrorCode"; } +const char* EstablishTimeSyncErrorCodeCategory::name() const noexcept { + return "EstablishTimeSyncErrorCode"; +} std::string EstablishTimeSyncErrorCodeCategory::message(int value) const { switch (static_cast(value)) { @@ -76,13 +79,15 @@ struct RobotTimeSyncErrorCodeCategory : std::error_category { }; bool RobotTimeSyncErrorCodeCategory::equivalent(int valcode, - const std::error_condition& cond) const noexcept { + const std::error_condition& cond) const noexcept { if (cond == SuccessCondition::Success) return (valcode == 0); if (cond == ErrorTypeCondition::SDKError) return true; return false; } -const char* RobotTimeSyncErrorCodeCategory::name() const noexcept { return "RobotTimeSyncErrorCode"; } +const char* RobotTimeSyncErrorCodeCategory::name() const noexcept { + return "RobotTimeSyncErrorCode"; +} std::string RobotTimeSyncErrorCodeCategory::message(int value) const { switch (static_cast(value)) { @@ -94,7 +99,7 @@ std::string RobotTimeSyncErrorCodeCategory::message(int value) const { const RobotTimeSyncErrorCodeCategory RobotTimeSyncErrorCodeCategory_category{}; -} // anonymous namespace +} // anonymous namespace std::error_code make_error_code(RobotTimeSyncErrorCode value) { return {static_cast(value), RobotTimeSyncErrorCodeCategory_category}; diff --git a/cpp/bosdyn/client/error_codes/time_sync_helper_error_code.h b/cpp/bosdyn/client/error_codes/time_sync_helper_error_code.h index 0232835..3988580 100644 --- a/cpp/bosdyn/client/error_codes/time_sync_helper_error_code.h +++ b/cpp/bosdyn/client/error_codes/time_sync_helper_error_code.h @@ -31,8 +31,8 @@ std::error_code make_error_code(TimeSyncHelperErrorCode); std::error_code make_error_code(EstablishTimeSyncErrorCode); std::error_code make_error_code(RobotTimeSyncErrorCode); -} // client namespace -} // bosdyn namespace +} // namespace client +} // namespace bosdyn namespace std { template <> diff --git a/cpp/bosdyn/client/estop/estop_keepalive.h b/cpp/bosdyn/client/estop/estop_keepalive.h index 52d6d79..42f006c 100644 --- a/cpp/bosdyn/client/estop/estop_keepalive.h +++ b/cpp/bosdyn/client/estop/estop_keepalive.h @@ -18,9 +18,9 @@ #include -#include "bosdyn/common/status.h" #include "bosdyn/client/estop/estop_client.h" #include "bosdyn/client/estop/estop_endpoint.h" +#include "bosdyn/common/status.h" namespace bosdyn { diff --git a/cpp/bosdyn/client/processors/common_response_processor.cpp b/cpp/bosdyn/client/processors/common_response_processor.cpp index e0e2d4e..75bc427 100644 --- a/cpp/bosdyn/client/processors/common_response_processor.cpp +++ b/cpp/bosdyn/client/processors/common_response_processor.cpp @@ -8,8 +8,8 @@ #include "common_response_processor.h" -#include "bosdyn/client/error_codes/sdk_error_code.h" #include "bosdyn/client/error_codes/header_error_code.h" +#include "bosdyn/client/error_codes/sdk_error_code.h" namespace bosdyn { diff --git a/cpp/bosdyn/client/robot/robot.cpp b/cpp/bosdyn/client/robot/robot.cpp index 3a9c7c5..4ef1178 100644 --- a/cpp/bosdyn/client/robot/robot.cpp +++ b/cpp/bosdyn/client/robot/robot.cpp @@ -209,7 +209,7 @@ Result> Robot::EnsureChannel( authority_iter = m_authorities_by_name.find(service_name); if (authority_iter == m_authorities_by_name.end()) { - return {::bosdyn::common::Status(SDKErrorCode::GenericSDKError, + return {::bosdyn::common::Status(ClientCreationErrorCode::UnregisteredService, "Could not find authority for " + service_name), nullptr}; } @@ -218,6 +218,12 @@ Result> Robot::EnsureChannel( return EnsureSecureChannel((*authority_iter).second); } +std::shared_ptr Robot::CreateSecureChannel(const std::string& authority) { + std::shared_ptr creds = + Channel::CreateSecureChannelCreds(m_cert, std::bind(&Robot::GetUserToken, this)); + return Channel::CreateSecureChannel(m_network_address, m_secure_channel_port, creds, authority); +} + Result> Robot::EnsureSecureChannel( const std::string& authority) { std::map>::iterator iter = @@ -227,12 +233,7 @@ Result> Robot::EnsureSecureChannel( } // Secure Channel doesn't exist, so create it. - std::shared_ptr creds = - Channel::CreateSecureChannelCreds(m_cert, std::bind(&Robot::GetUserToken, this)); - - std::shared_ptr channel = - Channel::CreateSecureChannel(m_network_address, m_secure_channel_port, creds, authority); - + std::shared_ptr channel = CreateSecureChannel(authority); m_channels[authority] = channel; return {::bosdyn::common::Status(SDKErrorCode::Success), channel}; } diff --git a/cpp/bosdyn/client/robot/robot.h b/cpp/bosdyn/client/robot/robot.h index 5857982..68cc58a 100644 --- a/cpp/bosdyn/client/robot/robot.h +++ b/cpp/bosdyn/client/robot/robot.h @@ -235,6 +235,9 @@ class Robot { */ void SetRPCParameters(const RPCParameters& parameters); + // Create a new GRPC channel. + std::shared_ptr CreateSecureChannel(const std::string& authority); + Result<::bosdyn::api::RobotIdResponse> GetId( const std::string& id_service_name = diff --git a/cpp/bosdyn/client/spot_cam/media_log/media_log_error_codes.h b/cpp/bosdyn/client/spot_cam/media_log/media_log_error_codes.h index c9f7bdf..2a0d1b7 100644 --- a/cpp/bosdyn/client/spot_cam/media_log/media_log_error_codes.h +++ b/cpp/bosdyn/client/spot_cam/media_log/media_log_error_codes.h @@ -7,6 +7,6 @@ */ -#include #include +#include #include "bosdyn/client/error_codes/proto_enum_to_stderror_macro.h" diff --git a/cpp/examples/README.md b/cpp/examples/README.md index 36947ff..b605bc7 100644 --- a/cpp/examples/README.md +++ b/cpp/examples/README.md @@ -14,7 +14,7 @@ Boston Dynamics recommends completing the [QuickStart guide](../../docs/cpp/quic ## Contents -* [Hello Spot Example](hello_spot/README.md) -* [Basic Robot Command Example](basic_robot_command/README.md) -* [Get Image Example](get_image/README.md) -* [SpotCAM PTZ Example](spot_cam/README.md) +- [Hello Spot Example](hello_spot/README.md) +- [Basic Robot Command Example](basic_robot_command/README.md) +- [Get Image Example](get_image/README.md) +- [SpotCAM PTZ Example](spot_cam/README.md) diff --git a/cpp/examples/hello_spot/README.md b/cpp/examples/hello_spot/README.md index 5d5ca57..b5ab97b 100644 --- a/cpp/examples/hello_spot/README.md +++ b/cpp/examples/hello_spot/README.md @@ -8,13 +8,16 @@ Development Kit License (20191101-BDSDK-SL). # Hello Spot -This example program is the introductory programming example for Spot. It demonstrates how to initialize the SDK to talk to robot and how to get information from the robot services, such as robot id, robot state, list of services running on the robot, and the list of registered payloads. It also logs data to the DataBuffer service. +This example program is the introductory programming example for Spot. It demonstrates how to initialize the SDK to talk to robot and how to get information from the robot services, such as robot id, robot state, list of services running on the robot, and the list of registered payloads. It also logs data to the DataBuffer service. ## Understanding Spot Programming -For your best learning experience, please use the [Quickstart Guide](../../../docs/cpp/quickstart.md) found in the SDK's docs/cpp directory. That will help you get your C++ programming environment set up properly. Then, specifically for Hello Spot, you should look at the [Understanding Spot Programming](../../../docs/python/understanding_spot_programming.md) file. This document walks you through all the commands found in this example! + +For your best learning experience, please use the [Quickstart Guide](../../../docs/cpp/quickstart.md) found in the SDK's docs/cpp directory. That will help you get your C++ programming environment set up properly. Then, specifically for Hello Spot, you should look at the [Understanding Spot Programming](../../../docs/python/understanding_spot_programming.md) file. This document walks you through all the commands found in this example! ## Run the Example + To run the example, set BOSDYN_CLIENT_USERNAME and BOSDYN_CLIENT_PASSWORD environment variables with the robot credentials and then run: + ``` ./hello_spot {ROBOT_IP} ``` diff --git a/docs/cpp/cpp_sdk_differences.md b/docs/cpp/cpp_sdk_differences.md index d91c473..fd7f1e0 100644 --- a/docs/cpp/cpp_sdk_differences.md +++ b/docs/cpp/cpp_sdk_differences.md @@ -11,10 +11,11 @@ Development Kit License (20191101-BDSDK-SL). This document describes the key differences between the Spot C++ SDK and the Spot Python SDK. - * [RPC method return types](#rpc-method-return-types) - * [Error checking](#error-checking) - * [Object ownership](#object-ownership) - * [Client-Server asynchronous communication](#client-service-asynchronous-communication) + +- [RPC method return types](#rpc-method-return-types) +- [Error checking](#error-checking) +- [Object ownership](#object-ownership) +- [Client-Server asynchronous communication](#client-service-asynchronous-communication) ## RPC method return types @@ -23,9 +24,10 @@ This document describes the key differences between the Spot C++ SDK and the Spo The C++ client classes do not throw exceptions for any errors detected during the gRPC communication or internal errors. Instead, methods return `Status` objects that include successful and failure return types. The `Status` class is described in the section below. -### Status class and error codes +### Status class and error codes The `Status` class is used in the Spot C++ SDK as the return type for methods that need to return a success condition with additional error information. It contains an `std::error_code` field and a string message. The string message field contains a human-readable message to be used for logging and additional details for failure returns. The `std::error_code` field specifies a code for success or failures. There are two types of `std::error_code` defined in the C++ SDK: + - Manually defined: These are `std::error_code` definitions that do not depend on protobuf definitions in the Spot API. Examples of this type of `std::error_code` in the SDK are: `RPCErrorCode` used for gRPC return types, `LeaseWalletErrorCode` used for lease wallet return types, and many more. - Auto-generated from protobuf Status enumerations. These are all associated in the `ResponseError` condition described below. @@ -48,6 +50,7 @@ SDK methods that need to return a `Status` value as well as an object do so by r The `Result` and `Status` objects defined in the section above contain an overloaded bool operator. So, developers can easily check for successful returns by the SDK methods: `Result` return example that creates a `Robot` object from a `ClientSDK` object: + ``` Result> robot_result = client_sdk->CreateRobot("spot_robot"); if (!robot_result) { @@ -58,6 +61,7 @@ std::unique_ptr robot = robot_result.move(); ``` `Status` return example that authenticates the `Robot` object created in the code above: + ``` Status status = robot->Authenticate("username", "password"); if (!status) { @@ -67,12 +71,13 @@ if (!status) { ``` The hierarchy of error handling in the C++ SDK is as follows: + - `Result` bool operator simply returns the `Status` field in it, calling the `Status` bool operator. - `Status` bool operator returns the value of `m_code == SuccessCondition::Success`, comparing its `std::error_code` to the `Success` `std::error_condition` described in the section [above](#status-class-and-error-codes). - All `std::error_code` defined in the C++ SDK implement the `equivalent` method that returns success for the right enumeration value(s) that represent the success criteria. This process is described in more details below. - The `RPCErrorCode` defined for handling gRPC error codes contains this implementation of the `equivalent` method: + ``` bool RPCErrorCodeCategory::equivalent(int valcode, const std::error_condition& cond) const noexcept { @@ -100,6 +105,7 @@ There are two main object ownership levels in the Spot C++ SDK: - The `ClientSDK` class is at the highest level, and it is used to generate one or many instances of the `Robot` class, with each representing a connection to a specific robot. The `ClientSDK` instance can be discarded after the `Robot` instances are created. - The `Robot` class provides functionality to communicate with a specific robot. It is used to create client instances that communicate with specific gRPC services registered in the robot system. The recommended way to create a `Robot` instance in an application is to use the static method in the `ClientSDK` class: + ``` Result> CreateRobot( const std::string& network_address, @@ -107,15 +113,18 @@ Result> CreateRobot( ::bosdyn::common::Duration timeout = kRPCTimeoutNotSpecified, std::shared_ptr message_pump = nullptr); ``` + That method returns a std::unique_ptr, so the application owns the `Robot` instance. This instance cannot go out-of-scope in the application while the service clients described below are still needed. - The `ServiceClient` classes provide functionality to communicate with a specific service registered on a specific robot. The Spot C++ SDK contains a client implementation class derived from `ServiceClient` for each service defined in the Spot API. Each `ServiceClient` derived class implements the RPC methods corresponding to that service type. The recommended way to create `ServiceClient` instances in an application is to use the `EnsureServiceClient` methods in the `Robot` class: + ``` Result EnsureServiceClient( const std::string& service_name, std::shared_ptr channel = nullptr, std::shared_ptr message_pump = nullptr); ``` + For example, to create a `RobotIdClient` object in the application in order to communicate with the `RobotId` service running on the robot, simply call: `Result robot_id_client_result = robot->EnsureServiceClient<::bosdyn::client::RobotIdClient>();` diff --git a/docs/cpp/quickstart.md b/docs/cpp/quickstart.md index 82fc654..1010163 100644 --- a/docs/cpp/quickstart.md +++ b/docs/cpp/quickstart.md @@ -35,7 +35,7 @@ This guide will help you set up your programming environment to successfully com The Boston Dynamics Spot C++ SDK works with most operating systems including: -- Linux Ubuntu 18.04 LTS +- Linux Ubuntu 22.04 LTS - gcc version 7+ - Windows 10 - Microsoft Visual Studio 2017+ diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index fa49516..e1c6f4f 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,24 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 4.1.1 BETA + +### Compatibility + +The recommended Ubuntu version is now Linux Ubuntu 22.04 LTS (formerly 18.04 LTS). Please see the [quickstart](cpp/quickstart.md#system-requirements) for more information. + +### Bug Fixes and Improvements + +#### API + +Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API changes included in release 4.1.1. + +#### SDK + +### Deprecations + +Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API deprecations included in release 4.1.1. + ## Spot C++ SDK version 4.1.0 BETA ### New Features diff --git a/protos/bosdyn/api/basic_command.proto b/protos/bosdyn/api/basic_command.proto index 8c73e78..3ac626d 100644 --- a/protos/bosdyn/api/basic_command.proto +++ b/protos/bosdyn/api/basic_command.proto @@ -155,7 +155,7 @@ message SE2TrajectoryCommand { // 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. + // and the trajectory command will not be executed. string se2_frame_name = 3; // The trajectory that the robot should follow, expressed in the frame @@ -567,7 +567,7 @@ message ConstrainedManipulationCommand { message JointCommand { message Request { - // Empty message, no paramaters required to activate. + // Empty message, no parameters required to activate. } message Feedback { @@ -642,8 +642,8 @@ message JointCommand { // ADVICE_NOT_IN_CONTACT: leg will enter CONTACT_LOST state on receipt. // If a leg is not on the ground (CONTACT_LOST): // ADVICE_NONE: leg will enter CONTACT_MADE if any collision is detected on the foot. - // ADVICE_IN_CONTACT: leg will enter CONTACT_MADE if any collision is deteced on the foot. - // ADVICE_NOT_IN_CONTACT: no change + // ADVICE_IN_CONTACT: leg will enter CONTACT_MADE if any collision is detected on the + // foot. ADVICE_NOT_IN_CONTACT: no change // Contact states may be used by the robot to improve state estimation. enum Advice { // ADVICE_UNKNOWN should not be used. diff --git a/protos/bosdyn/api/data_acquisition.proto b/protos/bosdyn/api/data_acquisition.proto index 317e9d5..0ebfa9b 100644 --- a/protos/bosdyn/api/data_acquisition.proto +++ b/protos/bosdyn/api/data_acquisition.proto @@ -332,7 +332,7 @@ message AcquirePluginDataRequest { // storing the data in the DataBuffer. repeated DataIdentifier data_id = 2; - // Metadata specified by the requestor. + // Metadata specified by the requester. Metadata metadata = 3; // Id to be associated with all the data buffered for this request. It will be stored diff --git a/protos/bosdyn/api/directory.proto b/protos/bosdyn/api/directory.proto index 5736c69..f627c76 100644 --- a/protos/bosdyn/api/directory.proto +++ b/protos/bosdyn/api/directory.proto @@ -109,7 +109,7 @@ message ListServiceEntriesRequest { } // The ListServiceEntries response message returns all known services at the time the request -// was recieved. +// was received. message ListServiceEntriesResponse { // Common response header. ResponseHeader header = 1; diff --git a/protos/bosdyn/api/estop.proto b/protos/bosdyn/api/estop.proto index b91bbe4..ab853eb 100644 --- a/protos/bosdyn/api/estop.proto +++ b/protos/bosdyn/api/estop.proto @@ -89,7 +89,6 @@ message EstopSystemStatus { string stop_level_details = 5; } - // Client request for setting/maintaining an E-Stop system level. // After the first CheckIn, must include response to previous challenge. message EstopCheckInRequest { @@ -203,7 +202,7 @@ message DeregisterEstopEndpointRequest { // Response to E-Stop endpoint deregistration request. message DeregisterEstopEndpointResponse { - // Common resonse header. + // Common response header. ResponseHeader header = 1; // Copy of the initial request. diff --git a/protos/bosdyn/api/license_service.proto b/protos/bosdyn/api/license_service.proto index 91b0aa1..8b9a067 100644 --- a/protos/bosdyn/api/license_service.proto +++ b/protos/bosdyn/api/license_service.proto @@ -18,7 +18,7 @@ service LicenseService { // currently uploaded on the robot. rpc GetLicenseInfo(GetLicenseInfoRequest) returns (GetLicenseInfoResponse) {} - // Check if specific features (identified by string names) are enabled under the currently loaded - // license for this robot. + // Check if specific features (identified by string names) are enabled under the currently + // loaded license for this robot. rpc GetFeatureEnabled(GetFeatureEnabledRequest) returns (GetFeatureEnabledResponse) {} } diff --git a/protos/bosdyn/api/metrics_logging/signed_proto.proto b/protos/bosdyn/api/metrics_logging/signed_proto.proto index 2da7445..7969ad7 100644 --- a/protos/bosdyn/api/metrics_logging/signed_proto.proto +++ b/protos/bosdyn/api/metrics_logging/signed_proto.proto @@ -18,14 +18,14 @@ option java_outer_classname = "SignedProtoProto"; * 512 bytes signature * X bytes data. * - * header -> When this format changes, we'll use the header to delminate which + * header -> When this format changes, we'll use the header to deliminate which * format was used to generate this data. * * fingerprint -> The fingerprint of public key corresponding to the private key * that was used to generate the signature. As keys rotate, this will allow * the signature verifier to know what key to use to verify the signature. * - * signature -> singnature of the data field. + * signature -> signature of the data field. * * data -> Contents specified by parent container. Usually contains a serialized * protobuf. diff --git a/protos/bosdyn/api/mission/nodes.proto b/protos/bosdyn/api/mission/nodes.proto index 224c41f..1d6cf1f 100644 --- a/protos/bosdyn/api/mission/nodes.proto +++ b/protos/bosdyn/api/mission/nodes.proto @@ -593,16 +593,22 @@ message Prompt { // See the Question message for details. bool for_autonomous_processing = 6; - // Severity for this prompt. Used to determine what sort of alerting - // this prompt will trigger. - // Here are guidelines for severity as it pertains to missions: - // INFO: Normal operation. For example, waiting for charge; waiting on the dock for logs to - // download. WARN: Something went wrong, but the mission will try to recover autonomously. - // ERROR: Something went wrong, and the mission can't recover without human intervention. - // Intervention is not time sensitive and can be resolved when convenient. - // CRITICAL: Something went wrong, and the mission can't recover without human intervention. - // Human needs to rescue the robot before battery runs out because it's not charging. - AlertData.SeverityLevel severity = 7; + oneof severity_spec { + // Severity for this prompt. Used to determine what sort of alerting + // this prompt will trigger. + // Here are guidelines for severity as it pertains to missions: + // INFO: Normal operation. For example, waiting for charge; waiting on the dock for logs to + // download. WARN: Something went wrong, but the mission will try to recover autonomously. + // ERROR: Something went wrong, and the mission can't recover without human intervention. + // Intervention is not time sensitive and can be resolved when convenient. + // CRITICAL: Something went wrong, and the mission can't recover without human intervention. + // Human needs to rescue the robot before battery runs out because it's not charging. + AlertData.SeverityLevel severity = 7; + + // If specified, this node will read the severity out of the blackboard at + // the specified location. + string severity_in_blackboard = 12; + } // If specified, this node will write its current question (bosdyn.api.mission.Question proto) // to the blackboard while it is being ticked. diff --git a/protos/bosdyn/api/network_compute_bridge_service.proto b/protos/bosdyn/api/network_compute_bridge_service.proto index c790d04..3af5aa5 100644 --- a/protos/bosdyn/api/network_compute_bridge_service.proto +++ b/protos/bosdyn/api/network_compute_bridge_service.proto @@ -16,7 +16,7 @@ service NetworkComputeBridge { rpc ListAvailableModels(ListAvailableModelsRequest) returns (ListAvailableModelsResponse) {} } -// Set of RPCs for workers of the network compute bridge. This is seperate from the RPCs for the +// Set of RPCs for workers of the network compute bridge. This is separate from the RPCs for the // on-robot network compute bridge so that if they need to diverge in the future it is possible // to do so. service NetworkComputeBridgeWorker { diff --git a/protos/bosdyn/api/service_customization.proto b/protos/bosdyn/api/service_customization.proto index 0a19845..c9139c1 100644 --- a/protos/bosdyn/api/service_customization.proto +++ b/protos/bosdyn/api/service_customization.proto @@ -193,6 +193,7 @@ message Int64Param { // ERROR: It is an error to specify a min_value larger than the max_value. google.protobuf.Int64Value min_value = 4; google.protobuf.Int64Value max_value = 5; + } // Value should be provided in the same units as defined by the spec. @@ -217,6 +218,7 @@ message DoubleParam { // ERROR: It is an error to specify a min_value larger than the max_value. google.protobuf.DoubleValue min_value = 4; google.protobuf.DoubleValue max_value = 5; + } // Value should be provided in the same units as defined by the spec. @@ -227,6 +229,7 @@ message DoubleParam { // Wraps specification-related messages, and contains fields for the value sent by a client. message StringParam { message Spec { + // A value sent by the client must be equal to one of these. repeated string options = 1; @@ -239,6 +242,10 @@ message StringParam { // Default value. If empty, UIs can pick their own default OR force user to make a // selection. string default_value = 3; + + + // A hint to the UI to use a textarea / multiline EditText. + bool is_multiline = 5; } // The value sent by a client. @@ -251,6 +258,7 @@ message BoolParam { // Default value. If unset, UIs can pick their own default OR force user to make a // selection. google.protobuf.BoolValue default_value = 1; + } // The value sent by a client. diff --git a/protos/bosdyn/api/spot/robot_command.proto b/protos/bosdyn/api/spot/robot_command.proto index 9804f10..2634b11 100644 --- a/protos/bosdyn/api/spot/robot_command.proto +++ b/protos/bosdyn/api/spot/robot_command.proto @@ -118,6 +118,10 @@ message MobilityParams { // Disable the secondary nearmap-based cliff avoidance that runs while on stairs. bool disable_nearmap_cliff_avoidance = 12; + // When true, allows the robot to traverse large areas with no stereo data. When false, these + // regions of missing data are assumed to be cliffs which the robot avoids. + bool disable_missing_data_cliffs = 21; + // Semantic hazard detection can detect and classify objects or regions in the world as // obstacles or areas to avoid that would not normally be classified as such. Obstacle avoidance // still needs to be on for the robot to avoid these additional hazards. A CORE I/O is necessary diff --git a/protos/bosdyn/api/spot_cam/LED.proto b/protos/bosdyn/api/spot_cam/LED.proto index c85d08d..d8f1954 100644 --- a/protos/bosdyn/api/spot_cam/LED.proto +++ b/protos/bosdyn/api/spot_cam/LED.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/LED"; option java_outer_classname = "LightingProto"; diff --git a/protos/bosdyn/api/spot_cam/audio.proto b/protos/bosdyn/api/spot_cam/audio.proto index 133ecfc..38963eb 100644 --- a/protos/bosdyn/api/spot_cam/audio.proto +++ b/protos/bosdyn/api/spot_cam/audio.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/audio"; option java_outer_classname = "AudioProto"; diff --git a/protos/bosdyn/api/spot_cam/camera.proto b/protos/bosdyn/api/spot_cam/camera.proto index 0e96b94..740d10c 100644 --- a/protos/bosdyn/api/spot_cam/camera.proto +++ b/protos/bosdyn/api/spot_cam/camera.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/camera"; option java_outer_classname = "CameraProto"; @@ -36,7 +37,7 @@ message Camera { bosdyn.api.Vec2 focal_length = 1; // Center point in pixels bosdyn.api.Vec2 center_point = 2; - // The following 4 parameters are radial distortion coefficeints to 4 orders. + // The following 4 parameters are radial distortion coefficients to 4 orders. // See: https://en.wikipedia.org/wiki/Distortion_(optics)#Software_correction // If all 4 of these values are 0, do not apply any correction. float k1 = 3; diff --git a/protos/bosdyn/api/spot_cam/compositor.proto b/protos/bosdyn/api/spot_cam/compositor.proto index 237c9b5..314cc4e 100644 --- a/protos/bosdyn/api/spot_cam/compositor.proto +++ b/protos/bosdyn/api/spot_cam/compositor.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/compositor"; option java_outer_classname = "CompositorProto"; diff --git a/protos/bosdyn/api/spot_cam/health.proto b/protos/bosdyn/api/spot_cam/health.proto index ec1e917..1b9eca1 100644 --- a/protos/bosdyn/api/spot_cam/health.proto +++ b/protos/bosdyn/api/spot_cam/health.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/health"; option java_outer_classname = "HealthProto"; diff --git a/protos/bosdyn/api/spot_cam/logging.proto b/protos/bosdyn/api/spot_cam/logging.proto index ddb4877..0f9b407 100644 --- a/protos/bosdyn/api/spot_cam/logging.proto +++ b/protos/bosdyn/api/spot_cam/logging.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/logging"; option java_outer_classname = "LoggingProto"; diff --git a/protos/bosdyn/api/spot_cam/network.proto b/protos/bosdyn/api/spot_cam/network.proto index afbe94d..a6c8969 100644 --- a/protos/bosdyn/api/spot_cam/network.proto +++ b/protos/bosdyn/api/spot_cam/network.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/network"; option java_outer_classname = "NetworkProto"; @@ -109,7 +110,7 @@ message GetICEConfigurationResponse { // Modify the ICE configuration. // Note: this configuration replaces any configuration currently present. -// It is *not* appended. +// It is *not* appended. This may also cause existing connections to close. message SetICEConfigurationRequest { // Common request header. bosdyn.api.RequestHeader header = 1; diff --git a/protos/bosdyn/api/spot_cam/power.proto b/protos/bosdyn/api/spot_cam/power.proto index bbf446b..584e1e1 100644 --- a/protos/bosdyn/api/spot_cam/power.proto +++ b/protos/bosdyn/api/spot_cam/power.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/power"; option java_outer_classname = "PowerProto"; diff --git a/protos/bosdyn/api/spot_cam/ptz.proto b/protos/bosdyn/api/spot_cam/ptz.proto index a115961..85f2a40 100644 --- a/protos/bosdyn/api/spot_cam/ptz.proto +++ b/protos/bosdyn/api/spot_cam/ptz.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/ptz"; option java_outer_classname = "PtzProto"; diff --git a/protos/bosdyn/api/spot_cam/service.proto b/protos/bosdyn/api/spot_cam/service.proto index e358ffb..60ee9cd 100644 --- a/protos/bosdyn/api/spot_cam/service.proto +++ b/protos/bosdyn/api/spot_cam/service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/service"; option java_outer_classname = "ServiceProto"; @@ -171,3 +172,4 @@ service NetworkService { service VersionService { rpc GetSoftwareVersion(GetSoftwareVersionRequest) returns (GetSoftwareVersionResponse); } + diff --git a/protos/bosdyn/api/spot_cam/streamquality.proto b/protos/bosdyn/api/spot_cam/streamquality.proto index 1dfa58a..ab07d6b 100644 --- a/protos/bosdyn/api/spot_cam/streamquality.proto +++ b/protos/bosdyn/api/spot_cam/streamquality.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/streamquality"; option java_outer_classname = "StreamQualityProto"; diff --git a/protos/bosdyn/api/spot_cam/version.proto b/protos/bosdyn/api/spot_cam/version.proto index 9bd3cd6..df02478 100644 --- a/protos/bosdyn/api/spot_cam/version.proto +++ b/protos/bosdyn/api/spot_cam/version.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot_cam; +option go_package = "bosdyn/api/spot_cam/version"; option java_outer_classname = "VersionProto"; From 0e3b1c0042b872c3620263f2729e08b32bdda7a7 Mon Sep 17 00:00:00 2001 From: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Date: Mon, 12 May 2025 22:11:41 -0400 Subject: [PATCH 02/15] Release v5.0.0 of Boston Dynamics Spot SDK --- README.md | 2 +- cpp/CMakeLists.txt | 3 +- .../gripper_camera_param_client.cpp | 75 +++++++++ .../gripper_camera_param_client.h | 36 ++++ .../network_compute_bridge_client.cpp | 102 ++++++++++++ .../network_compute_bridge_client.h | 99 +++++++++++ .../network_compute_bridge_error_codes.cpp | 14 ++ .../network_compute_bridge_error_codes.h | 14 ++ .../client/point_cloud/point_cloud_client.cpp | 1 + .../client/point_cloud/point_cloud_client.h | 1 + .../client/sdk/client_sdk_include_clients.cpp | 2 + cpp/bosdyn/common/compiler_definitions.h | 4 +- cpp/bosdyn/common/proto_file.cpp | 88 ++++++++-- cpp/bosdyn/common/proto_file.h | 34 ++++ cpp/bosdyn/common/time.cpp | 4 + cpp/bosdyn/common/time.h | 6 +- cpp/bosdyn/math/proto_math.cpp | 11 ++ cpp/bosdyn/math/proto_math.h | 2 + cpp/examples/joint_control/CMakeLists.txt | 32 ++++ .../joint_control/joint_api_helper.hpp | 10 +- cpp/examples/query_autowalk_status/README.md | 2 +- docs/cpp/quickstart.md | 8 +- docs/cpp_release_notes.md | 51 +++++- protos/bosdyn/api/alerts.proto | 1 + protos/bosdyn/api/arm_command.proto | 1 + protos/bosdyn/api/arm_surface_contact.proto | 1 + .../api/arm_surface_contact_service.proto | 1 + protos/bosdyn/api/auth.proto | 1 + protos/bosdyn/api/auth_service.proto | 1 + .../bosdyn/api/auto_return/auto_return.proto | 1 + .../api/auto_return/auto_return_service.proto | 1 + protos/bosdyn/api/autowalk/autowalk.proto | 11 +- .../api/autowalk/autowalk_service.proto | 1 + protos/bosdyn/api/autowalk/walks.proto | 26 ++- protos/bosdyn/api/basic_command.proto | 1 + protos/bosdyn/api/bddf.proto | 1 + protos/bosdyn/api/data_acquisition.proto | 1 + .../api/data_acquisition_plugin_service.proto | 1 + .../bosdyn/api/data_acquisition_service.proto | 1 + .../bosdyn/api/data_acquisition_store.proto | 1 + .../api/data_acquisition_store_service.proto | 1 + protos/bosdyn/api/data_buffer.proto | 5 +- protos/bosdyn/api/data_buffer_service.proto | 1 + protos/bosdyn/api/data_chunk.proto | 1 + protos/bosdyn/api/data_index.proto | 1 + protos/bosdyn/api/data_service.proto | 1 + protos/bosdyn/api/directory.proto | 1 + .../bosdyn/api/directory_registration.proto | 1 + .../api/directory_registration_service.proto | 1 + protos/bosdyn/api/directory_service.proto | 1 + protos/bosdyn/api/docking/docking.proto | 1 + .../bosdyn/api/docking/docking_service.proto | 1 + protos/bosdyn/api/estop.proto | 1 + protos/bosdyn/api/estop_service.proto | 1 + protos/bosdyn/api/fault_service.proto | 1 + protos/bosdyn/api/full_body_command.proto | 1 + protos/bosdyn/api/geometry.proto | 3 +- protos/bosdyn/api/gps/aggregator.proto | 1 + .../bosdyn/api/gps/aggregator_service.proto | 1 + protos/bosdyn/api/gps/gps.proto | 1 + protos/bosdyn/api/gps/registration.proto | 17 ++ .../bosdyn/api/gps/registration_service.proto | 1 + .../bosdyn/api/graph_nav/area_callback.proto | 1 + .../api/graph_nav/area_callback_data.proto | 1 + .../api/graph_nav/area_callback_service.proto | 1 + protos/bosdyn/api/graph_nav/gps.proto | 1 + protos/bosdyn/api/graph_nav/graph_nav.proto | 24 ++- .../api/graph_nav/graph_nav_service.proto | 1 + .../bosdyn/api/graph_nav/lost_detection.proto | 1 + protos/bosdyn/api/graph_nav/map.proto | 2 +- .../bosdyn/api/graph_nav/map_processing.proto | 1 + .../graph_nav/map_processing_service.proto | 1 + protos/bosdyn/api/graph_nav/nav.proto | 1 + protos/bosdyn/api/graph_nav/recording.proto | 1 + .../api/graph_nav/recording_service.proto | 1 + .../api/graph_nav/visual_features.proto | 154 ------------------ protos/bosdyn/api/gripper_camera_param.proto | 81 +++++++++ .../api/gripper_camera_param_service.proto | 5 + protos/bosdyn/api/gripper_command.proto | 1 + protos/bosdyn/api/header.proto | 2 +- protos/bosdyn/api/image.proto | 6 + protos/bosdyn/api/image_geometry.proto | 20 ++- protos/bosdyn/api/image_service.proto | 1 + protos/bosdyn/api/ir_enable_disable.proto | 1 + .../api/ir_enable_disable_service.proto | 1 + protos/bosdyn/api/keepalive/keepalive.proto | 1 + .../api/keepalive/keepalive_service.proto | 1 + protos/bosdyn/api/lease.proto | 1 + protos/bosdyn/api/lease_service.proto | 1 + protos/bosdyn/api/license.proto | 1 + protos/bosdyn/api/license_service.proto | 1 + protos/bosdyn/api/local_grid.proto | 1 + protos/bosdyn/api/local_grid_service.proto | 1 + protos/bosdyn/api/log_status/log_status.proto | 2 + .../api/log_status/log_status_service.proto | 2 + protos/bosdyn/api/manipulation_api.proto | 1 + .../bosdyn/api/manipulation_api_service.proto | 1 + .../metrics_logging/absolute_metrics.proto | 1 + .../metrics_logging_robot.proto | 1 + .../metrics_logging_robot_service.proto | 1 + .../api/metrics_logging/signed_proto.proto | 1 + protos/bosdyn/api/mission/mission.proto | 1 + .../bosdyn/api/mission/mission_service.proto | 1 + protos/bosdyn/api/mission/nodes.proto | 51 ++++++ protos/bosdyn/api/mission/remote.proto | 1 + .../bosdyn/api/mission/remote_service.proto | 1 + protos/bosdyn/api/mission/util.proto | 18 ++ protos/bosdyn/api/mobility_command.proto | 1 + .../bosdyn/api/network_compute_bridge.proto | 1 + .../api/network_compute_bridge_service.proto | 1 + protos/bosdyn/api/network_stats.proto | 1 + protos/bosdyn/api/parameter.proto | 2 +- protos/bosdyn/api/payload.proto | 3 + protos/bosdyn/api/payload_estimation.proto | 1 + protos/bosdyn/api/payload_registration.proto | 1 + .../api/payload_registration_service.proto | 1 + protos/bosdyn/api/payload_service.proto | 1 + .../bosdyn/api/payload_software_update.proto | 62 +++++++ .../payload_software_update_initiation.proto | 22 +++ ...d_software_update_initiation_service.proto | 24 +++ .../api/payload_software_update_service.proto | 30 ++++ protos/bosdyn/api/point_cloud.proto | 82 +++++++++- protos/bosdyn/api/point_cloud_service.proto | 2 + protos/bosdyn/api/power.proto | 1 + protos/bosdyn/api/power_service.proto | 1 + protos/bosdyn/api/ray_cast.proto | 1 + protos/bosdyn/api/ray_cast_service.proto | 1 + protos/bosdyn/api/robot_command.proto | 1 + protos/bosdyn/api/robot_command_service.proto | 1 + protos/bosdyn/api/robot_id.proto | 2 +- protos/bosdyn/api/robot_id_service.proto | 1 + protos/bosdyn/api/robot_state.proto | 25 ++- protos/bosdyn/api/robot_state_service.proto | 1 + protos/bosdyn/api/service_customization.proto | 14 +- protos/bosdyn/api/service_fault.proto | 1 + protos/bosdyn/api/signals.proto | 1 + protos/bosdyn/api/software_package.proto | 111 +++++++++++++ protos/bosdyn/api/sparse_features.proto | 1 + .../bosdyn/api/spot/choreography_params.proto | 1 + .../api/spot/choreography_sequence.proto | 57 +++++++ .../api/spot/choreography_service.proto | 8 + protos/bosdyn/api/spot/door.proto | 1 + .../bosdyn/api/spot/door_area_callback.proto | 1 + protos/bosdyn/api/spot/door_service.proto | 1 + .../bosdyn/api/spot/inverse_kinematics.proto | 1 + .../api/spot/inverse_kinematics_service.proto | 1 + protos/bosdyn/api/spot/robot_command.proto | 1 + protos/bosdyn/api/spot/spot_check.proto | 1 + .../bosdyn/api/spot/spot_check_service.proto | 1 + protos/bosdyn/api/spot/spot_constants.proto | 1 + protos/bosdyn/api/stairs.proto | 1 + protos/bosdyn/api/synchronized_command.proto | 1 + protos/bosdyn/api/time_range.proto | 1 + protos/bosdyn/api/time_sync.proto | 1 + protos/bosdyn/api/time_sync_service.proto | 1 + protos/bosdyn/api/trajectory.proto | 1 + protos/bosdyn/api/units.proto | 4 +- protos/bosdyn/api/world_object.proto | 1 + protos/bosdyn/api/world_object_service.proto | 1 + 159 files changed, 1364 insertions(+), 218 deletions(-) create mode 100644 cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.cpp create mode 100644 cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.h create mode 100644 cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_error_codes.cpp create mode 100644 cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_error_codes.h create mode 100644 cpp/examples/joint_control/CMakeLists.txt delete mode 100644 protos/bosdyn/api/graph_nav/visual_features.proto create mode 100644 protos/bosdyn/api/payload_software_update.proto create mode 100644 protos/bosdyn/api/payload_software_update_initiation.proto create mode 100644 protos/bosdyn/api/payload_software_update_initiation_service.proto create mode 100644 protos/bosdyn/api/payload_software_update_service.proto create mode 100644 protos/bosdyn/api/software_package.proto diff --git a/README.md b/README.md index c209cf8..8646be9 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+ - [Payload developer documentation](https://dev.bostondynamics.com/docs/payload/readme). Payloads add additional sensing, communication, and control capabilities beyond what the base platform provides. The Payload ICD covers the mechanical, electrical, and software interfaces that Spot supports. - [Spot API protocol definition](https://dev.bostondynamics.com/docs/protos/readme). 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. -This is version 4.1.1 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. +This is version 5.0.0 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. ## Contents diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index 11e21c7..d4efbc8 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -7,7 +7,7 @@ # This file is autogenerated. cmake_minimum_required (VERSION 3.10.2) -project (bosdyn VERSION 4.1.1) +project (bosdyn VERSION 5.0.0) # Dependencies: find_package(protobuf REQUIRED) @@ -245,6 +245,7 @@ target_include_directories(inverse_kinematics_reachability PUBLIC ) target_link_libraries(inverse_kinematics_reachability PUBLIC bosdyn_client_static) install(TARGETS inverse_kinematics_reachability DESTINATION ${CMAKE_INSTALL_BINDIR}) +add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/examples/joint_control) add_executable(spot_cam ${CMAKE_CURRENT_SOURCE_DIR}/examples/spot_cam/ptz_example.cpp) target_compile_features(spot_cam PUBLIC cxx_std_17) target_include_directories(spot_cam PUBLIC diff --git a/cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.cpp b/cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.cpp index 2a9b1d0..4b7f393 100644 --- a/cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.cpp +++ b/cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.cpp @@ -80,6 +80,43 @@ GripperCameraParamClient::GetGripperCameraParamsAsync(const RPCParameters& param return future; } +SetGripperCameraCalibResponseType GripperCameraParamClient::SetGripperCameraCalib( + ::bosdyn::api::SetGripperCameraCalibrationRequest& request, const RPCParameters& parameters) { + return SetGripperCameraCalibAsync(request, parameters).get(); +} + +std::shared_future +GripperCameraParamClient::SetGripperCameraCalibAsync( + ::bosdyn::api::SetGripperCameraCalibrationRequest& request, const RPCParameters& parameters) { + std::promise response; + std::shared_future future = response.get_future(); + BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!"); + + MessagePumpCallBase* one_time = + InitiateAsyncCall<::bosdyn::api::SetGripperCameraCalibrationRequest, + ::bosdyn::api::SetGripperCameraCalibrationResponse, + ::bosdyn::api::SetGripperCameraCalibrationResponse>( + request, + std::bind(&::bosdyn::api::GripperCameraParamService::StubInterface::AsyncSetCamCalib, + m_stub.get(), _1, _2, _3), + std::bind(&GripperCameraParamClient::OnSetGripperCameraCalibComplete, this, _1, _2, _3, + _4, _5), + std::move(response), parameters); + + return future; +} + +void GripperCameraParamClient::OnSetGripperCameraCalibComplete( + MessagePumpCallBase* call, const ::bosdyn::api::SetGripperCameraCalibrationRequest& request, + ::bosdyn::api::SetGripperCameraCalibrationResponse&& response, const grpc::Status& status, + std::promise promise) { + ::bosdyn::common::Status ret_status = + ProcessResponseAndGetFinalStatus<::bosdyn::api::SetGripperCameraCalibrationResponse>( + status, response, SDKErrorCode::Success); + + promise.set_value({ret_status, std::move(response)}); +} + void GripperCameraParamClient::OnGetGripperCameraParamsComplete( MessagePumpCallBase* call, const ::bosdyn::api::GripperCameraGetParamRequest& request, ::bosdyn::api::GripperCameraGetParamResponse&& response, const grpc::Status& status, @@ -91,6 +128,44 @@ void GripperCameraParamClient::OnGetGripperCameraParamsComplete( promise.set_value({ret_status, std::move(response)}); } +GetGripperCameraCalibrationResponseType GripperCameraParamClient::GetGripperCameraCalib( + const RPCParameters& parameters) { + return GetGripperCameraCalibAsync(parameters).get(); +} + +std::shared_future +GripperCameraParamClient::GetGripperCameraCalibAsync(const RPCParameters& parameters) { + std::promise response; + std::shared_future future = response.get_future(); + BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!"); + + ::bosdyn::api::GetGripperCameraCalibrationRequest request; + + MessagePumpCallBase* one_time = + InitiateAsyncCall<::bosdyn::api::GetGripperCameraCalibrationRequest, + ::bosdyn::api::GetGripperCameraCalibrationResponse, + ::bosdyn::api::GetGripperCameraCalibrationResponse>( + request, + std::bind(&::bosdyn::api::GripperCameraParamService::StubInterface::AsyncGetCamCalib, + m_stub.get(), _1, _2, _3), + std::bind(&GripperCameraParamClient::OnGetGripperCameraCalibComplete, this, _1, _2, _3, + _4, _5), + std::move(response), parameters); + + return future; +} + +void GripperCameraParamClient::OnGetGripperCameraCalibComplete( + MessagePumpCallBase* call, const ::bosdyn::api::GetGripperCameraCalibrationRequest& request, + ::bosdyn::api::GetGripperCameraCalibrationResponse&& response, const grpc::Status& status, + std::promise promise) { + ::bosdyn::common::Status ret_status = + ProcessResponseAndGetFinalStatus<::bosdyn::api::GetGripperCameraCalibrationResponse>( + status, response, SDKErrorCode::Success); + + promise.set_value({ret_status, std::move(response)}); +} + // Start of ServiceClient overrides. ServiceClient::QualityOfService GripperCameraParamClient::GetQualityOfService() const { return QualityOfService::NORMAL; diff --git a/cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.h b/cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.h index 52c55ed..822ff57 100644 --- a/cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.h +++ b/cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.h @@ -22,6 +22,10 @@ namespace client { typedef Result<::bosdyn::api::GripperCameraParamResponse> GripperCameraSetParamResponseType; typedef Result<::bosdyn::api::GripperCameraGetParamResponse> GripperCameraGetParamResponseType; +typedef Result<::bosdyn::api::SetGripperCameraCalibrationResponse> + SetGripperCameraCalibResponseType; +typedef Result<::bosdyn::api::GetGripperCameraCalibrationResponse> + GetGripperCameraCalibrationResponseType; // GripperCameraParamClient is the GRPC client for the gripper camera parameter service defined in // gripper_camera_param_service.proto. @@ -49,6 +53,24 @@ class GripperCameraParamClient : public ServiceClient { std::shared_future GetGripperCameraParamsAsync( const RPCParameters& parameters = RPCParameters()); + // Synchronous method to request to set gripper camera calibration. + SetGripperCameraCalibResponseType SetGripperCameraCalib( + ::bosdyn::api::SetGripperCameraCalibrationRequest& request, + const RPCParameters& parameters = RPCParameters()); + + // Asynchronous method to request to set gripper camera calibration. + std::shared_future SetGripperCameraCalibAsync( + ::bosdyn::api::SetGripperCameraCalibrationRequest& request, + const RPCParameters& parameters = RPCParameters()); + + // Synchronous method to request to get gripper camera calibration. + GetGripperCameraCalibrationResponseType GetGripperCameraCalib( + const RPCParameters& parameters = RPCParameters()); + + // Asynchronous method to request to get gripper camera calibration. + std::shared_future GetGripperCameraCalibAsync( + const RPCParameters& parameters = RPCParameters()); + // Start of ServiceClient overrides. QualityOfService GetQualityOfService() const override; void SetComms(const std::shared_ptr& channel) override; @@ -86,6 +108,20 @@ class GripperCameraParamClient : public ServiceClient { ::bosdyn::api::GripperCameraGetParamResponse&& response, const grpc::Status& status, std::promise promise); + // Callback that will return SetGripperCameraCalibrationResponse message after + // SetGripperCameraCalib rpc returns to the client. + void OnSetGripperCameraCalibComplete( + MessagePumpCallBase* call, const ::bosdyn::api::SetGripperCameraCalibrationRequest& request, + ::bosdyn::api::SetGripperCameraCalibrationResponse&& response, const grpc::Status& status, + std::promise promise); + + // Callback that will return GetGripperCameraCalibrationResponse message after + // GetGripperCameraCalib rpc returns to the client. + void OnGetGripperCameraCalibComplete( + MessagePumpCallBase* call, const ::bosdyn::api::GetGripperCameraCalibrationRequest& request, + ::bosdyn::api::GetGripperCameraCalibrationResponse&& response, const grpc::Status& status, + std::promise promise); + std::unique_ptr<::bosdyn::api::GripperCameraParamService::StubInterface> m_stub; // Lease wallet for commands. diff --git a/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.cpp b/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.cpp new file mode 100644 index 0000000..66edc96 --- /dev/null +++ b/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.cpp @@ -0,0 +1,102 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#include "network_compute_bridge_client.h" + +using namespace std::placeholders; + +namespace bosdyn { + +namespace client { + +const char* NetworkComputeBridgeClient::s_default_service_name = "network-compute-bridge"; + +const char* NetworkComputeBridgeClient::s_service_type = "bosdyn.api.NetworkComputeBridge"; + +std::shared_future NetworkComputeBridgeClient::NetworkComputeAsync( + ::bosdyn::api::NetworkComputeRequest& request, const RPCParameters& parameters) { + std::promise response; + std::shared_future future = response.get_future(); + BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!"); + + MessagePumpCallBase* one_time = InitiateAsyncCall<::bosdyn::api::NetworkComputeRequest, + ::bosdyn::api::NetworkComputeResponse, + ::bosdyn::api::NetworkComputeResponse>( + request, + std::bind(&::bosdyn::api::NetworkComputeBridge::StubInterface::AsyncNetworkCompute, + m_stub.get(), _1, _2, _3), + std::bind(&NetworkComputeBridgeClient::OnNetworkComputeComplete, this, _1, _2, _3, _4, _5), + std::move(response), parameters); + return future; +} + +void NetworkComputeBridgeClient::OnNetworkComputeComplete( + MessagePumpCallBase* call, const ::bosdyn::api::NetworkComputeRequest& request, + ::bosdyn::api::NetworkComputeResponse&& response, const grpc::Status& status, + std::promise promise) { + std::cout << "On network compute complete\n"; + ::bosdyn::common::Status ret_status = + ProcessResponseAndGetFinalStatus<::bosdyn::api::NetworkComputeResponse>(status, response, + response.status()); + std::cout << "Ret status: " << ret_status.DebugString() << std::endl; + promise.set_value({ret_status, std::move(response)}); +} + +NetworkComputeResultType NetworkComputeBridgeClient::NetworkCompute( + ::bosdyn::api::NetworkComputeRequest& request, const RPCParameters& parameters) { + return NetworkComputeAsync(request, parameters).get(); +} + +std::shared_future +NetworkComputeBridgeClient::ListAvailableModelsAsync( + ::bosdyn::api::ListAvailableModelsRequest& request, const RPCParameters& parameters) { + std::promise response; + std::shared_future future = response.get_future(); + BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!"); + + MessagePumpCallBase* one_time = InitiateAsyncCall<::bosdyn::api::ListAvailableModelsRequest, + ::bosdyn::api::ListAvailableModelsResponse, + ::bosdyn::api::ListAvailableModelsResponse>( + request, + std::bind(&::bosdyn::api::NetworkComputeBridge::StubInterface::AsyncListAvailableModels, + m_stub.get(), _1, _2, _3), + std::bind(&NetworkComputeBridgeClient::OnListAvailableModelsComplete, this, _1, _2, _3, _4, + _5), + std::move(response), parameters); + return future; +}; + +void NetworkComputeBridgeClient::OnListAvailableModelsComplete( + MessagePumpCallBase* call, const ::bosdyn::api::ListAvailableModelsRequest& request, + ::bosdyn::api::ListAvailableModelsResponse&& response, const grpc::Status& status, + std::promise promise) { + std::cout << "On list available models complete\n"; + ::bosdyn::common::Status ret_status = + ProcessResponseAndGetFinalStatus<::bosdyn::api::ListAvailableModelsResponse>( + status, response, response.status()); + std::cout << "Ret status: " << ret_status.DebugString() << std::endl; + promise.set_value({ret_status, std::move(response)}); +} + +ListAvailableModelsResultType NetworkComputeBridgeClient::ListAvailableModels( + ::bosdyn::api::ListAvailableModelsRequest& request, const RPCParameters& parameters) { + return ListAvailableModelsAsync(request, parameters).get(); +} + +ServiceClient::QualityOfService NetworkComputeBridgeClient::GetQualityOfService() const { + return QualityOfService::NORMAL; +} + +void NetworkComputeBridgeClient::SetComms(const std::shared_ptr& channel) { + m_stub.reset(new ::bosdyn::api::NetworkComputeBridge::Stub(channel)); +} + +} // namespace client + +} // namespace bosdyn diff --git a/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.h b/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.h new file mode 100644 index 0000000..e7515b8 --- /dev/null +++ b/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.h @@ -0,0 +1,99 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#pragma once + +#include +#include + +#include + +#include "network_compute_bridge_error_codes.h" +#include "bosdyn/client/service_client/service_client.h" + +namespace bosdyn { + +namespace client { + +// Defining result types for each RPC featuring the RPC call's status and the response message +// the RPC was returning from the robot +typedef Result<::bosdyn::api::NetworkComputeResponse> NetworkComputeResultType; +typedef Result<::bosdyn::api::ListAvailableModelsResponse> ListAvailableModelsResultType; + +// Client which communicates with the NetworkComputeBridgeWorker service +class NetworkComputeBridgeClient : public ServiceClient { + public: + NetworkComputeBridgeClient() = default; + ~NetworkComputeBridgeClient() = default; + + // Asynchronous method to request a response to a (now deprecated) NetworkComputeRequest + std::shared_future NetworkComputeAsync( + ::bosdyn::api::NetworkComputeRequest& request, + const RPCParameters& parameters = RPCParameters()); + + // Synchronous method to request a response to a NetworkComputeRequest + NetworkComputeResultType NetworkCompute(::bosdyn::api::NetworkComputeRequest& request, + const RPCParameters& parameters = RPCParameters()); + + // Asynchronous method to request a list of available NCB models on the robot + std::shared_future ListAvailableModelsAsync( + ::bosdyn::api::ListAvailableModelsRequest& request, + const RPCParameters& parameters = RPCParameters()); + + // Synchronous method to request a list of available NCB models on the robot + ListAvailableModelsResultType ListAvailableModels( + ::bosdyn::api::ListAvailableModelsRequest& request, + const RPCParameters& parameters = RPCParameters()); + + // Start of ServiceClient overrides. + // Sets the QualityOfService enum for the network compute bridge worker client to be used for + // network selection optimization. + QualityOfService GetQualityOfService() const override; + + // Set the communication details of the network compute bridge worker service, including the + // stub and request/response processors + void SetComms(const std::shared_ptr& channel) override; + + // End of ServiceClient overrides. + + // Get the default service name the network compute bridge worker service will be registered in + // the directory with. + static std::string GetDefaultServiceName() { return s_default_service_name; } + + // Get the default service type for the network compute bridge worker service that will be + // registered in the directory. + static std::string GetServiceType() { return s_service_type; } + + private: + // Callback function for asynchronous NetworkCompute RPC calls to return a result + void OnNetworkComputeComplete(MessagePumpCallBase* call, + const ::bosdyn::api::NetworkComputeRequest& request, + ::bosdyn::api::NetworkComputeResponse&& response, + const grpc::Status& status, + std::promise promise); + + // Callback function for asynchronous ListAvailableModels RPC calls to return a result + void OnListAvailableModelsComplete(MessagePumpCallBase* call, + const ::bosdyn::api::ListAvailableModelsRequest& request, + ::bosdyn::api::ListAvailableModelsResponse&& response, + const grpc::Status& status, + std::promise promise); + + std::unique_ptr<::bosdyn::api::NetworkComputeBridge::StubInterface> m_stub; + + // Default service name for the network compute bridge worker service. + static const char* s_default_service_name; + + // Default service type for the network compute bridge worker service. + static const char* s_service_type; +}; + +} // namespace client + +} // namespace bosdyn diff --git a/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_error_codes.cpp b/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_error_codes.cpp new file mode 100644 index 0000000..bfd2c14 --- /dev/null +++ b/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_error_codes.cpp @@ -0,0 +1,14 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#include "bosdyn/client/network_compute_bridge//network_compute_bridge_error_codes.h" +#include "bosdyn/client/error_codes/proto_enum_to_stderror_macro_source.h" + +DEFINE_PROTO_ENUM_ERRORCODE_IMPL_API(NetworkComputeStatus, valcode == 1) +DEFINE_PROTO_ENUM_ERRORCODE_IMPL_API(ListAvailableModelsStatus, valcode == 1) diff --git a/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_error_codes.h b/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_error_codes.h new file mode 100644 index 0000000..f2d71b1 --- /dev/null +++ b/cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_error_codes.h @@ -0,0 +1,14 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#include +#include "bosdyn/client/error_codes/proto_enum_to_stderror_macro.h" + +DEFINE_PROTO_ENUM_ERRORCODE_HEADER_API(NetworkComputeStatus) +DEFINE_PROTO_ENUM_ERRORCODE_HEADER_API(ListAvailableModelsStatus) diff --git a/cpp/bosdyn/client/point_cloud/point_cloud_client.cpp b/cpp/bosdyn/client/point_cloud/point_cloud_client.cpp index 5a5e8bc..b590139 100644 --- a/cpp/bosdyn/client/point_cloud/point_cloud_client.cpp +++ b/cpp/bosdyn/client/point_cloud/point_cloud_client.cpp @@ -131,6 +131,7 @@ void PointCloudClient::OnGetPointCloudComplete(MessagePumpCallBase*, promise.set_value({ret_status, std::move(response)}); } + void PointCloudClient::BuildPointCloudRequest(const std::string& point_cloud_source_name, ::bosdyn::api::PointCloudRequest* request) { request->set_point_cloud_source_name(point_cloud_source_name); diff --git a/cpp/bosdyn/client/point_cloud/point_cloud_client.h b/cpp/bosdyn/client/point_cloud/point_cloud_client.h index c979257..25b70d8 100644 --- a/cpp/bosdyn/client/point_cloud/point_cloud_client.h +++ b/cpp/bosdyn/client/point_cloud/point_cloud_client.h @@ -60,6 +60,7 @@ class PointCloudClient : public ServiceClient { GetPointCloudResultType GetPointCloud(::bosdyn::api::GetPointCloudRequest& request, const RPCParameters& parameters = RPCParameters()); + // Start of ServiceClient overrides. QualityOfService GetQualityOfService() const override; void SetComms(const std::shared_ptr& channel) override; diff --git a/cpp/bosdyn/client/sdk/client_sdk_include_clients.cpp b/cpp/bosdyn/client/sdk/client_sdk_include_clients.cpp index 2a27914..01c05d1 100644 --- a/cpp/bosdyn/client/sdk/client_sdk_include_clients.cpp +++ b/cpp/bosdyn/client/sdk/client_sdk_include_clients.cpp @@ -7,6 +7,8 @@ */ +// Boston Dynamics, Inc. Confidential Information. +// Copyright 2025. All Rights Reserved. #include "bosdyn/client/auth/auth_client.h" #include "bosdyn/client/auto_return/auto_return_client.h" #include "bosdyn/client/data_acquisition/data_acquisition_client.h" diff --git a/cpp/bosdyn/common/compiler_definitions.h b/cpp/bosdyn/common/compiler_definitions.h index 7ea6e57..e1d8f12 100644 --- a/cpp/bosdyn/common/compiler_definitions.h +++ b/cpp/bosdyn/common/compiler_definitions.h @@ -15,7 +15,7 @@ # define BOSDYN_UNUSED #endif -#if defined(__GNUC__) && (__GNUC__ > 2) || ((__GNUC__ == 2) && (__GNUC_MINOR__ > 4)) || \ +#if defined(__GNUC__) && ((__GNUC__ > 2) || ((__GNUC__ == 2) && (__GNUC_MINOR__ > 4))) || \ defined(__clang__) # define BOSDYN_CHECK_PRINTF_FORMAT(X) __attribute__((format(printf, (X), 1 + (X)))) #else @@ -23,7 +23,7 @@ # define BOSDYN_CHECK_PRINTF_FORMAT(X) #endif -#if defined(__GNUC__) && (__GNUC__ > 3) || ((__GNUC__ == 3) && (__GNUC_MINOR__ > 2)) || \ +#if defined(__GNUC__) && ((__GNUC__ > 3) || ((__GNUC__ == 3) && (__GNUC_MINOR__ > 2))) || \ defined(__clang__) # define BOSDYN_NONNULL(...) __attribute__((nonnull __VA_ARGS__)) #else diff --git a/cpp/bosdyn/common/proto_file.cpp b/cpp/bosdyn/common/proto_file.cpp index 4ad3e19..fc3d4dd 100644 --- a/cpp/bosdyn/common/proto_file.cpp +++ b/cpp/bosdyn/common/proto_file.cpp @@ -30,7 +30,7 @@ class unique_fd { unique_fd(const unique_fd& other) = delete; // non-copyable. unique_fd(unique_fd&& other) { std::swap(m_fd, other.m_fd); } ~unique_fd() { - if (fd()) close(); + if (*this) close(); } inline int fd() { return m_fd; } operator bool() { return m_fd >= 0; } @@ -48,19 +48,75 @@ class unique_fd { private: int m_fd = -1; }; + +struct ReadErrorCategory : public std::error_category { + const char* name() const noexcept override { return "bosdyn::common::ReadError"; } + std::string message(int ev) const override { + switch (static_cast(ev)) { + case bosdyn::common::ReadError::kSuccess: + return "Success"; + case bosdyn::common::ReadError::kParseError: + return "Failed to parse the message."; + case bosdyn::common::ReadError::kEmptyFile: + return "File was empty."; + } + return "Unknown error"; + } + // bool equivalent(int valcode, const std::error_condition& cond) const noexcept override { + // return false;} +}; +struct WriteErrorCategory : public std::error_category { + const char* name() const noexcept override { return "bosdyn::common::WriteError"; } + std::string message(int ev) const override { + switch (static_cast(ev)) { + case bosdyn::common::WriteError::kSuccess: + return "Success"; + case bosdyn::common::WriteError::kSerializationError: + return "Failed to serialize the message."; + } + return "Unknown error"; + } + // bool equivalent(int valcode, const std::error_condition& cond) const noexcept override { + // return false;} +}; + +const ReadErrorCategory ReadErrorCategory_category{}; +const WriteErrorCategory WriteErrorCategory_category{}; + } // namespace namespace bosdyn::common { bool ParseMessageFromFile(const std::string& filename, google::protobuf::Message* message, ParseOptions options) { + // error_code is true if there is an error. + return !ParseMessageFromFileWithError(filename, message, options); +} + +bool WriteMessageToFile(const std::string& filename, const google::protobuf::Message& message, + WriteOptions options) { + // error_code is true if there is an error. + return !WriteMessageToFileWithError(filename, message, options); +} + +std::error_code make_error_code(ReadError value) { + return {static_cast(value), ReadErrorCategory_category}; +} +std::error_code make_error_code(WriteError value) { + return {static_cast(value), WriteErrorCategory_category}; +} +std::error_code ParseMessageFromFileWithError(const std::string& filename, + google::protobuf::Message* message, + ParseOptions options) { int mode = options.update_access_time ? O_RDWR : O_RDONLY; unique_fd fd(open(filename.c_str(), mode)); if (!fd) { - if (!((mode | O_RDWR) && (errno == EACCES || errno == EROFS))) return false; + if (!((mode | O_RDWR) && (errno == EACCES || errno == EROFS))) + return std::make_error_code(std::errc(errno)); // Try again, falling back to not updating access time. fd = unique_fd(open(filename.c_str(), O_RDONLY)); - if (!fd) return false; + if (!fd) return std::make_error_code(std::errc(errno)); + ; options.update_access_time = false; } #ifdef IS_LINUX @@ -73,17 +129,25 @@ bool ParseMessageFromFile(const std::string& filename, google::protobuf::Message if (options.ensure_non_empty) { struct stat stat_buf; fstat(fd.fd(), &stat_buf); - if (stat_buf.st_size == 0) return false; + if (stat_buf.st_size == 0) return ReadError::kEmptyFile; + } + if (message->ParseFromFileDescriptor(fd.fd())) { + return ReadError::kSuccess; + } else { + return ReadError::kParseError; } - return message->ParseFromFileDescriptor(fd.fd()); } - -bool WriteMessageToFile(const std::string& filename, const google::protobuf::Message& message, - WriteOptions options) { +std::error_code WriteMessageToFileWithError(const std::string& filename, + const google::protobuf::Message& message, + WriteOptions options) { unique_fd fd(open(filename.c_str(), O_CREAT | O_TRUNC | O_WRONLY, 0666)); - if (!fd) return false; - if (!message.SerializeToFileDescriptor(fd.fd())) return false; - if (options.fsync_file && fsync(fd.fd()) != 0) return false; - return fd.close(); // Will return false if closing fails. + if (!fd) return std::make_error_code(std::errc(errno)); + if (!message.SerializeToFileDescriptor(fd.fd())) return WriteError::kSerializationError; + if (options.fsync_file && fsync(fd.fd()) != 0) return std::make_error_code(std::errc(errno)); + if (fd.close()) { // Will return false if closing fails. + return WriteError::kSuccess; + } else { + return std::make_error_code(std::errc(errno)); + } } } // namespace bosdyn::common diff --git a/cpp/bosdyn/common/proto_file.h b/cpp/bosdyn/common/proto_file.h index e14bae9..329edd0 100644 --- a/cpp/bosdyn/common/proto_file.h +++ b/cpp/bosdyn/common/proto_file.h @@ -10,6 +10,7 @@ #pragma once #include +#include #include @@ -40,4 +41,37 @@ bool ParseMessageFromFile(const std::string& filename, google::protobuf::Message bool WriteMessageToFile(const std::string& filename, const google::protobuf::Message& message, WriteOptions options = WriteOptions()); +enum class ReadError { + kSuccess = 0, + kParseError, // Message failed to parse. + kEmptyFile, // File was empty. +}; + +// Parse a file into the provided message. Returns an error_code of what went wrong. +// The error code will either be a std::errc or a ReadError. +std::error_code ParseMessageFromFileWithError(const std::string& filename, + google::protobuf::Message* message, + ParseOptions options = ParseOptions()); + +enum class WriteError { + kSuccess = 0, + kSerializationError, // Message failed to serialize. +}; + +// Serialize a message to disk. Returns an error_code of what went wrong. +// The error code will either be a std::errc or a WriteError. +std::error_code WriteMessageToFileWithError(const std::string& filename, + const google::protobuf::Message& message, + WriteOptions options = WriteOptions()); + +std::error_code make_error_code(ReadError e); +std::error_code make_error_code(WriteError e); + } // namespace bosdyn::common + +namespace std { +template <> +struct is_error_code_enum : true_type {}; +template <> +struct is_error_code_enum : true_type {}; +} // namespace std diff --git a/cpp/bosdyn/common/time.cpp b/cpp/bosdyn/common/time.cpp index a98ff83..d7c11fb 100644 --- a/cpp/bosdyn/common/time.cpp +++ b/cpp/bosdyn/common/time.cpp @@ -119,6 +119,10 @@ ::google::protobuf::Duration SecToDuration(double seconds) { return google::protobuf::util::TimeUtil::NanosecondsToDuration(seconds * 1e9); } +::google::protobuf::Duration NSecToDuration(int64_t nanos) { + return google::protobuf::util::TimeUtil::NanosecondsToDuration(nanos); +} + bool DurationIsLessThan(const ::google::protobuf::Duration& d1, const ::google::protobuf::Duration& d2) { if (d1.seconds() < d2.seconds()) { diff --git a/cpp/bosdyn/common/time.h b/cpp/bosdyn/common/time.h index 8f76f67..d0df82b 100644 --- a/cpp/bosdyn/common/time.h +++ b/cpp/bosdyn/common/time.h @@ -86,14 +86,16 @@ void SetDuration(int64_t nsec, ::google::protobuf::Duration* duration); void SetDurationSinceTimestamp(const ::google::protobuf::Timestamp& timestamp, ::google::protobuf::Duration* duration); -/// Convert a duration to nanoseconds.. +/// Convert a duration to nanoseconds. int64_t DurationToNsec(const ::google::protobuf::Duration& duration); /// Convert a duration to seconds. double DurationToSec(const ::google::protobuf::Duration& duration); -// Convert seconds to a duration +// Convert seconds to a duration. ::google::protobuf::Duration SecToDuration(double seconds); +// Convert nanoseconds to a duration. +::google::protobuf::Duration NSecToDuration(int64_t nanos); /// Returns whether d1 < d2. bool DurationIsLessThan(const ::google::protobuf::Duration& d1, diff --git a/cpp/bosdyn/math/proto_math.cpp b/cpp/bosdyn/math/proto_math.cpp index e290625..ba305aa 100644 --- a/cpp/bosdyn/math/proto_math.cpp +++ b/cpp/bosdyn/math/proto_math.cpp @@ -263,6 +263,10 @@ ::bosdyn::api::Quaternion EigenToApiProto(const Eigen::Quaterniond& q) { return make_quat(q.w(), q.x(), q.y(), q.z()); } +::bosdyn::api::Quaternion EigenToApiProto(const Eigen::Quaternionf& q) { + return make_quat(q.w(), q.x(), q.y(), q.z()); +} + ::bosdyn::api::Vec3 operator*(const ::bosdyn::api::Quaternion& q, const ::bosdyn::api::Vec3& p) { ::bosdyn::api::Quaternion q2 = make_quat(0, p.x(), p.y(), p.z()); q2 = q2 * ~q; @@ -600,6 +604,13 @@ ::bosdyn::api::SE3Covariance IdentityCovMatrix() { return out; } +::bosdyn::api::Vec2 CreateVec2(double x, double y) { + ::bosdyn::api::Vec2 v; + v.set_x(x); + v.set_y(y); + return v; +} + ::bosdyn::api::Vec3 CreateVec3(double x, double y, double z) { ::bosdyn::api::Vec3 v; v.set_x(x); diff --git a/cpp/bosdyn/math/proto_math.h b/cpp/bosdyn/math/proto_math.h index 53e0812..4910da9 100644 --- a/cpp/bosdyn/math/proto_math.h +++ b/cpp/bosdyn/math/proto_math.h @@ -67,6 +67,7 @@ bool ToMatrix(const ::bosdyn::api::Quaternion& q, Eigen::Matrix* r Eigen::Matrix ToMatrix(const double& angle); Eigen::Quaterniond EigenFromApiProto(const ::bosdyn::api::Quaternion& q); ::bosdyn::api::Quaternion EigenToApiProto(const Eigen::Quaterniond& q); +::bosdyn::api::Quaternion EigenToApiProto(const Eigen::Quaternionf& q); // SE3Pose Operators ::bosdyn::api::Vec3 operator*(const ::bosdyn::api::SE3Pose& a_T_b, const ::bosdyn::api::Vec3& p); @@ -148,6 +149,7 @@ double DotProduct(const ::bosdyn::api::Vec3& a, const ::bosdyn::api::Vec3& b); double DotProduct(const ::bosdyn::api::Quaternion& a, const ::bosdyn::api::Quaternion& b); ::bosdyn::api::Quaternion Normalize(const ::bosdyn::api::Quaternion& q); +::bosdyn::api::Vec2 CreateVec2(double x = 0, double y = 0); ::bosdyn::api::Vec3 CreateVec3(double x = 0, double y = 0, double z = 0); ::bosdyn::api::Quaternion CreateQuaternion(double w = 1, double x = 0, double y = 0, double z = 0); ::bosdyn::api::Quaternion CreateRotationX(double angle); diff --git a/cpp/examples/joint_control/CMakeLists.txt b/cpp/examples/joint_control/CMakeLists.txt new file mode 100644 index 0000000..48a39f8 --- /dev/null +++ b/cpp/examples/joint_control/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required (VERSION 3.10.2) +project (joint_control) + +# no arm squat example +add_executable(noarm_squat + ${CMAKE_CURRENT_SOURCE_DIR}/noarm_squat.cpp + ${CMAKE_CURRENT_SOURCE_DIR}/joint_api_helper.cpp +) +# wiggle arm example +add_executable(wiggle_arm + ${CMAKE_CURRENT_SOURCE_DIR}/wiggle_arm_example.cpp + ${CMAKE_CURRENT_SOURCE_DIR}/joint_api_helper.cpp +) + +target_compile_features(noarm_squat PUBLIC cxx_std_17) +target_compile_features(wiggle_arm PUBLIC cxx_std_17) + +target_include_directories(noarm_squat PUBLIC + ${CMAKE_CURRENT_SOURCE_DIR} + ${PROTOBUF_INCLUDE_DIR} +) + +target_include_directories(wiggle_arm PUBLIC + ${CMAKE_CURRENT_SOURCE_DIR} + ${PROTOBUF_INCLUDE_DIR} +) + +target_link_libraries(noarm_squat PUBLIC bosdyn_client_static) +target_link_libraries(wiggle_arm PUBLIC bosdyn_client_static) + +install(TARGETS noarm_squat DESTINATION ${CMAKE_INSTALL_BINDIR}) +install(TARGETS wiggle_arm DESTINATION ${CMAKE_INSTALL_BINDIR}) \ No newline at end of file diff --git a/cpp/examples/joint_control/joint_api_helper.hpp b/cpp/examples/joint_control/joint_api_helper.hpp index 299e601..30910e2 100644 --- a/cpp/examples/joint_control/joint_api_helper.hpp +++ b/cpp/examples/joint_control/joint_api_helper.hpp @@ -37,17 +37,19 @@ class LinearInterpolator { } struct Return { + Return() = delete; + Return(float _pos_des, float _vel_des) : pos_des(_pos_des), vel_des(_vel_des) {} + float pos_des = 0.0f; float vel_des = 0.0f; - - Return() = delete; }; + Return calculate_command(int64_t time) { float pos = m_init_pos + (m_target_pos - m_init_pos) * static_cast(time) / static_cast(m_duration); float vel = (m_target_pos - m_init_pos) / m_duration; - return Return{pos, vel}; + return Return(pos, vel); } private: @@ -124,4 +126,4 @@ class JointAPIInterface { // checking round trip time of command. bool m_started_streaming = false; JointsState m_joints_state; -}; \ No newline at end of file +}; diff --git a/cpp/examples/query_autowalk_status/README.md b/cpp/examples/query_autowalk_status/README.md index 4db12f9..e5e2d87 100644 --- a/cpp/examples/query_autowalk_status/README.md +++ b/cpp/examples/query_autowalk_status/README.md @@ -18,7 +18,7 @@ To run the example, set BOSDYN_CLIENT_USERNAME and BOSDYN_CLIENT_PASSWORD enviro ./query_autowalk_status {ROBOT_IP} --autowalk_mission={Path to Autowalk Mission Folder} ``` -To see a list a full command line arguements run: +To see a list a full command line arguments run: ``` ./query_autowalk_status --help diff --git a/docs/cpp/quickstart.md b/docs/cpp/quickstart.md index 1010163..73f156b 100644 --- a/docs/cpp/quickstart.md +++ b/docs/cpp/quickstart.md @@ -149,7 +149,13 @@ The `cmake` command can also overwrite the following variables by passing them t Build the SDK using the `make` command below. ``` -make -j6 install +make -j6 +``` + +To additionally install the SDK, use the command below. + +``` +make -j6 install package ``` The `make` command generates a lot of deprecation warnings during the compiling of the classes generated from the protobuf definitions. This is expected as the protobuf definitions contain `deprecated` flags for fields that will not be supported in future versions of the SDK. diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index e1c6f4f..3e151e8 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,47 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 5.0.0 BETA + +### Bug Fixes and Improvements + +#### API + +Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API changes included in release 5.0.0. + +#### SDK + +**Clients** + +- Added [NetworkComputeBridgeClient](../cpp/bosdyn/client/network_compute_bridge/network_compute_bridge_client.cpp) client to support preexisting proto definitions. + +- Added `SetGripperCameraCalib`, `SetGripperCameraCalibAsync`, `GetGripperCameraCalib`, and `GetGripperCameraCalibAsync` methods to [GripperCameraParamClient](../cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.cpp). + +**Helper Functions** + +- Added a helper function, `NSecToDuration`, to [time.cpp](../cpp/bosdyn/common/time.cpp) that simplifies the creation of `::google::protobuf::Duration` objects from nanosecond inputs. + +- Added two helper functions, `EigenToApiProto` and `CreateVec2`, [proto_math.cpp](../cpp/bosdyn/math/proto_math.cpp) to streamline the creation of API-compatible math messages. + + - `EigenToApiProto` converts the input `Eigen::Quaternion` object to a `::bosdyn::api::Quaternion` object. + - `CreateVec2` returns a `::bosdyn::api::Vec2` object based upon the input `x` and `y`. + +- Added two file helper functions, `ParseMessageFromFileWithError` and `WriteMessageToFileWithError`, in [proto_file.cpp](../cpp/bosdyn/common/proto_file.cpp) that return an error code to provide specific details about read/write failures, supplementing the existing boolean success indicators. Use the new functions for more granular error handling. + +**Miscellaneous** + +- The preprocessor directive responsible for verifying the GNU Compiler Collection (GCC) version now handles environments where `__GNUC__` is undefined. + +### Spot Sample Code + +#### Updated + +- The joint control example now includes a [CMakeLists.txt](../cpp/examples/joint_control/CMakeLists.txt) file, enabling its compilation using the CMake build system for improved ease and correctness. + +### Deprecations + +Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API deprecations included in release 5.0.0. + ## Spot C++ SDK version 4.1.1 BETA ### Compatibility @@ -20,8 +61,6 @@ The recommended Ubuntu version is now Linux Ubuntu 22.04 LTS (formerly 18.04 LTS Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API changes included in release 4.1.1. -#### SDK - ### Deprecations Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API deprecations included in release 4.1.1. @@ -258,12 +297,6 @@ Added `EigenFromApiProto/EigenToApiProto`, `FromRoll/ToRoll`, `FromPitch/ToPitch Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API deprecations included in release 3.3.0. -### Breaking Changes - -### Dependencies - -### Known Issues - ### Sample Code #### New @@ -305,7 +338,7 @@ Enables API clients to specify high level autonomous behaviors for Spot using an #### Graph Nav – Area Callbacks Enables users to register a callback that is called in certain areas of the map during navigation. These “Area Callbacks” can instruct the robot to wait until the area is safe to cross (such as a crosswalk), take control of the robot and perform an action (such as opening a door), or perform a background action while in a certain area of the map (such as flashing lights or playing sounds). -This enables integration with the [Graph Nav](concepts/autonomy/graphnav_service.md) navigation system to extend its capabilities in terms of safety and new actions while navigating. See the [Area Callback](concepts/autonomy/area_callbacks.md) documentation for more details. +This enables integration with the [Graph Nav](concepts/autonomy/graphnav_service.md) navigation system to extend its capabilities in terms of safety and new actions while navigating. See the [Area Callback](concepts/autonomy/graphnav_area_callbacks.md) documentation for more details. ### Bug Fixes and Improvements diff --git a/protos/bosdyn/api/alerts.proto b/protos/bosdyn/api/alerts.proto index bb5a01d..e57ea28 100644 --- a/protos/bosdyn/api/alerts.proto +++ b/protos/bosdyn/api/alerts.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/alerts"; option java_outer_classname = "AlertsProto"; diff --git a/protos/bosdyn/api/arm_command.proto b/protos/bosdyn/api/arm_command.proto index 573a113..f1747fa 100644 --- a/protos/bosdyn/api/arm_command.proto +++ b/protos/bosdyn/api/arm_command.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/arm_command"; option java_outer_classname = "ArmCommandProto"; import "bosdyn/api/basic_command.proto"; diff --git a/protos/bosdyn/api/arm_surface_contact.proto b/protos/bosdyn/api/arm_surface_contact.proto index fdd46f3..932da3b 100644 --- a/protos/bosdyn/api/arm_surface_contact.proto +++ b/protos/bosdyn/api/arm_surface_contact.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/arm_surface_contact"; option java_outer_classname = "ArmSurfaceContactProto"; import "bosdyn/api/geometry.proto"; diff --git a/protos/bosdyn/api/arm_surface_contact_service.proto b/protos/bosdyn/api/arm_surface_contact_service.proto index aad02c5..9584c2f 100644 --- a/protos/bosdyn/api/arm_surface_contact_service.proto +++ b/protos/bosdyn/api/arm_surface_contact_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/arm_surface_contact_service"; option java_outer_classname = "ArmSurfaceContactServiceProto"; diff --git a/protos/bosdyn/api/auth.proto b/protos/bosdyn/api/auth.proto index 4a27527..600e867 100644 --- a/protos/bosdyn/api/auth.proto +++ b/protos/bosdyn/api/auth.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/auth"; option java_outer_classname = "AuthProto"; diff --git a/protos/bosdyn/api/auth_service.proto b/protos/bosdyn/api/auth_service.proto index 8627dd6..d646a76 100644 --- a/protos/bosdyn/api/auth_service.proto +++ b/protos/bosdyn/api/auth_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/auth_service"; option java_outer_classname = "AuthServiceProto"; diff --git a/protos/bosdyn/api/auto_return/auto_return.proto b/protos/bosdyn/api/auto_return/auto_return.proto index 687695c..b867a21 100644 --- a/protos/bosdyn/api/auto_return/auto_return.proto +++ b/protos/bosdyn/api/auto_return/auto_return.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.auto_return; +option go_package = "bosdyn/api/auto_return/auto_return"; option java_outer_classname = "AutoReturnProto"; import "google/protobuf/any.proto"; diff --git a/protos/bosdyn/api/auto_return/auto_return_service.proto b/protos/bosdyn/api/auto_return/auto_return_service.proto index fede290..6c779d9 100644 --- a/protos/bosdyn/api/auto_return/auto_return_service.proto +++ b/protos/bosdyn/api/auto_return/auto_return_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.auto_return; +option go_package = "bosdyn/api/auto_return/auto_return_service"; option java_outer_classname = "AutoReturnServiceProto"; diff --git a/protos/bosdyn/api/autowalk/autowalk.proto b/protos/bosdyn/api/autowalk/autowalk.proto index 62b4f76..01e0d90 100644 --- a/protos/bosdyn/api/autowalk/autowalk.proto +++ b/protos/bosdyn/api/autowalk/autowalk.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.autowalk; +option go_package = "bosdyn/api/autowalk/autowalk"; option java_outer_classname = "AutowalkProto"; @@ -86,7 +87,10 @@ message CompileAutowalkResponse { // There will be one ElementIdentifier for each Element in the input Walk. // The index of each ElementIdentifier corresponds to the index of the Element in the input // Walk. Skipped elements will have default values for id's. (0 and empty string) - repeated ElementIdentifiers element_identifiers = 5; + // Deprecated as of 5.0. The active_mission_text field in the mission service's State proto will + // indicate when the robot is undocking, navigating, performing an action, or docking at mission + // runtime. + repeated ElementIdentifiers element_identifiers = 5 [deprecated = true]; // If certain elements failed compilation, they will be reported back in this field. // The map correlates the index of the Element in the input Walk to the FailedElement. @@ -151,7 +155,10 @@ message LoadAutowalkResponse { // There will be one ElementIdentifier for each Element in the input Walk. // The index of each ElementIdentifier corresponds to the index of the Element in the input // Walk. Skipped elements will have default values for id's. (0 and empty string) - repeated ElementIdentifiers element_identifiers = 7; + // Deprecated as of 5.0. The active_mission_text field in the mission service's State proto will + // indicate when the robot is undocking, navigating, performing an action, or docking at mission + // runtime. + repeated ElementIdentifiers element_identifiers = 7 [deprecated = true]; // If certain elements failed compilation, they will be reported back in this field. // The map correlates the index of the Element in the input Walk to the FailedElement. diff --git a/protos/bosdyn/api/autowalk/autowalk_service.proto b/protos/bosdyn/api/autowalk/autowalk_service.proto index 7298d8d..0049971 100644 --- a/protos/bosdyn/api/autowalk/autowalk_service.proto +++ b/protos/bosdyn/api/autowalk/autowalk_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.autowalk; +option go_package = "bosdyn/api/autowalk/autowalk_service"; option java_outer_classname = "AutowalkServiceProto"; diff --git a/protos/bosdyn/api/autowalk/walks.proto b/protos/bosdyn/api/autowalk/walks.proto index bb71fcc..8677ff5 100644 --- a/protos/bosdyn/api/autowalk/walks.proto +++ b/protos/bosdyn/api/autowalk/walks.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.autowalk; +option go_package = "bosdyn/api/autowalk/walks"; option java_outer_classname = "WalksProto"; @@ -263,6 +264,11 @@ message Target { // example, the user may decide how close to the destination waypoint // the robot needs to be in order to declare success. bosdyn.api.graph_nav.TravelParams travel_params = 3; + + // Passed through to graph_nav. See comment in graph_nav.proto. + SE2Pose destination_waypoint_tform_body_goal = 4; + + reserved 2; } // Tell the robot to follow a route to a waypoint. @@ -276,6 +282,9 @@ message Target { // example, the user may decide how close to the destination waypoint // the robot needs to be in order to declare success. bosdyn.api.graph_nav.TravelParams travel_params = 2; + + // Passed through to graph_nav. See comment in graph_nav.proto. + SE2Pose destination_waypoint_tform_body_goal = 3; } oneof target { @@ -430,18 +439,28 @@ message ActionWrapper { bosdyn.api.spot_cam.PtzPosition ptz_position = 1; } - // Align SpotCam to a waypoint. Cannot be used with SpotCamPtz or RobotBodyPose + // Align the SpotCam to given reference image(s). The robot will initially point the camera in + // the direction specified by target_tform_sensor. Then, the robot will align the SpotCam by + // computing the homography between the live image(s) from the camera and the supplied reference + // image(s). Cannot be used with SpotCamPtz or RobotBodyPose message SpotCamAlignment { message Alignment { // Camera zoom parameter float zoom = 1; - // Sensor to use for alignment + // Sensor to use for alignment. The sensor must be registered with the sensor pointing + // service. The sensor_id is the name of the sensor given by the sensor pointing + // service's ListSensors RPC. string sensor_id = 2; // Image to use for alignment oneof reference { + // Points at a world object in the waypoint snapshot corresponding to the waypoint + // of this action. The world object should contain the reference image. string scene_object_id = 3; + + // Reference image to use for alignment and the camera source of the image. + ImageCaptureAndSource reference_image = 6; } // If true, this alignment will be skipped during playback @@ -454,7 +473,8 @@ message ActionWrapper { // List of alignments to perform repeated Alignment alignments = 2; - // Desired transform from the sensor to the target + // Desired transform from the sensor to the waypoint. This is used to initially point the + // camera in the correct direction before refining the alignment using reference images. bosdyn.api.SE3Pose target_tform_sensor = 3; // Final zoom the camera should be after all alignments have finished diff --git a/protos/bosdyn/api/basic_command.proto b/protos/bosdyn/api/basic_command.proto index 3ac626d..5d64443 100644 --- a/protos/bosdyn/api/basic_command.proto +++ b/protos/bosdyn/api/basic_command.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/basic_command"; option java_outer_classname = "BasicCommandProto"; diff --git a/protos/bosdyn/api/bddf.proto b/protos/bosdyn/api/bddf.proto index b3f4326..662b66d 100644 --- a/protos/bosdyn/api/bddf.proto +++ b/protos/bosdyn/api/bddf.proto @@ -9,6 +9,7 @@ syntax = "proto3"; import "google/protobuf/timestamp.proto"; package bosdyn.api; +option go_package = "bosdyn/api/bddf"; // The file format consists of 3 kinds of blocks with simple framing: // - Serialized DescriptorBlock protos, describing either the main file, diff --git a/protos/bosdyn/api/data_acquisition.proto b/protos/bosdyn/api/data_acquisition.proto index 0ebfa9b..306bf02 100644 --- a/protos/bosdyn/api/data_acquisition.proto +++ b/protos/bosdyn/api/data_acquisition.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_acquisition"; option java_outer_classname = "DataAcquisitionProto"; diff --git a/protos/bosdyn/api/data_acquisition_plugin_service.proto b/protos/bosdyn/api/data_acquisition_plugin_service.proto index 4c70d0a..626b6d2 100644 --- a/protos/bosdyn/api/data_acquisition_plugin_service.proto +++ b/protos/bosdyn/api/data_acquisition_plugin_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_acquisition_plugin_service"; option java_outer_classname = "DataAcquisitionPluginServiceProto"; diff --git a/protos/bosdyn/api/data_acquisition_service.proto b/protos/bosdyn/api/data_acquisition_service.proto index 93e57e0..a248afe 100644 --- a/protos/bosdyn/api/data_acquisition_service.proto +++ b/protos/bosdyn/api/data_acquisition_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_acquisition_service"; option java_outer_classname = "DataAcquisitionServiceProto"; diff --git a/protos/bosdyn/api/data_acquisition_store.proto b/protos/bosdyn/api/data_acquisition_store.proto index 286c602..d1bb628 100644 --- a/protos/bosdyn/api/data_acquisition_store.proto +++ b/protos/bosdyn/api/data_acquisition_store.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_acquisition_store"; option java_outer_classname = "DataAcquisitionStoreProto"; diff --git a/protos/bosdyn/api/data_acquisition_store_service.proto b/protos/bosdyn/api/data_acquisition_store_service.proto index 734facb..0372b02 100644 --- a/protos/bosdyn/api/data_acquisition_store_service.proto +++ b/protos/bosdyn/api/data_acquisition_store_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_acquisition_store_service"; option java_outer_classname = "DataAcquisitionStoreServiceProto"; diff --git a/protos/bosdyn/api/data_buffer.proto b/protos/bosdyn/api/data_buffer.proto index dc3b220..1d626fc 100644 --- a/protos/bosdyn/api/data_buffer.proto +++ b/protos/bosdyn/api/data_buffer.proto @@ -6,6 +6,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_buffer"; option java_outer_classname = "DataBufferProto"; @@ -157,7 +158,8 @@ message SignalSchema { Type type = 2; // Zero or one variable in 'vars' may be specified as a time variable. - // A time variable must have type TYPE_FLOAT64. + // A time variable must have type TYPE_INT64 and should be stored as nanoseconds + // since the UNIX epoch in the robot clock. bool is_time = 3; } @@ -290,6 +292,7 @@ message Event { // Optionally request that the robot try to preserve data near this time for a service log. LogPreserveHint log_preserve_hint = 9; + } message RecordTextMessagesResponse { diff --git a/protos/bosdyn/api/data_buffer_service.proto b/protos/bosdyn/api/data_buffer_service.proto index fcef656..d5635b2 100644 --- a/protos/bosdyn/api/data_buffer_service.proto +++ b/protos/bosdyn/api/data_buffer_service.proto @@ -8,6 +8,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_buffer_service"; option java_outer_classname = "DataBufferServiceProto"; diff --git a/protos/bosdyn/api/data_chunk.proto b/protos/bosdyn/api/data_chunk.proto index 6213b7a..0729658 100644 --- a/protos/bosdyn/api/data_chunk.proto +++ b/protos/bosdyn/api/data_chunk.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_chunk"; option java_outer_classname = "DataChunkProto"; diff --git a/protos/bosdyn/api/data_index.proto b/protos/bosdyn/api/data_index.proto index ae44b8c..7d6e617 100644 --- a/protos/bosdyn/api/data_index.proto +++ b/protos/bosdyn/api/data_index.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_index"; option java_outer_classname = "DataIndexProto"; diff --git a/protos/bosdyn/api/data_service.proto b/protos/bosdyn/api/data_service.proto index f799727..03616f4 100644 --- a/protos/bosdyn/api/data_service.proto +++ b/protos/bosdyn/api/data_service.proto @@ -8,6 +8,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/data_service"; option java_outer_classname = "DataServiceProto"; diff --git a/protos/bosdyn/api/directory.proto b/protos/bosdyn/api/directory.proto index f627c76..64d28fd 100644 --- a/protos/bosdyn/api/directory.proto +++ b/protos/bosdyn/api/directory.proto @@ -12,6 +12,7 @@ import "bosdyn/api/header.proto"; import "google/protobuf/timestamp.proto"; package bosdyn.api; +option go_package = "bosdyn/api/directory"; // A message representing a discoverable service. By definition, all services // discoverable by this system are expected to be grpc "services" provided by diff --git a/protos/bosdyn/api/directory_registration.proto b/protos/bosdyn/api/directory_registration.proto index 82a5e68..72c7a84 100644 --- a/protos/bosdyn/api/directory_registration.proto +++ b/protos/bosdyn/api/directory_registration.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/directory_registration"; option java_outer_classname = "DirectoryRegistrationProto"; diff --git a/protos/bosdyn/api/directory_registration_service.proto b/protos/bosdyn/api/directory_registration_service.proto index d9fd11c..25d02a8 100644 --- a/protos/bosdyn/api/directory_registration_service.proto +++ b/protos/bosdyn/api/directory_registration_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/directory_registration_service"; option java_outer_classname = "DirectoryRegistrationServiceProto"; diff --git a/protos/bosdyn/api/directory_service.proto b/protos/bosdyn/api/directory_service.proto index b5595c0..cbe175a 100644 --- a/protos/bosdyn/api/directory_service.proto +++ b/protos/bosdyn/api/directory_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/directory_service"; option java_outer_classname = "DirectoryServiceProto"; diff --git a/protos/bosdyn/api/docking/docking.proto b/protos/bosdyn/api/docking/docking.proto index 1acbc2e..4b26f5b 100644 --- a/protos/bosdyn/api/docking/docking.proto +++ b/protos/bosdyn/api/docking/docking.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.docking; +option go_package = "bosdyn/api/docking/docking"; option java_outer_classname = "DockingProto"; diff --git a/protos/bosdyn/api/docking/docking_service.proto b/protos/bosdyn/api/docking/docking_service.proto index 87dcf2b..beda3e7 100644 --- a/protos/bosdyn/api/docking/docking_service.proto +++ b/protos/bosdyn/api/docking/docking_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.docking; +option go_package = "bosdyn/api/docking/docking_service"; option java_outer_classname = "DockingServiceProto"; diff --git a/protos/bosdyn/api/estop.proto b/protos/bosdyn/api/estop.proto index ab853eb..808fb4d 100644 --- a/protos/bosdyn/api/estop.proto +++ b/protos/bosdyn/api/estop.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/estop"; option java_outer_classname = "EstopProto"; diff --git a/protos/bosdyn/api/estop_service.proto b/protos/bosdyn/api/estop_service.proto index d0398d7..3291fec 100644 --- a/protos/bosdyn/api/estop_service.proto +++ b/protos/bosdyn/api/estop_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/estop_service"; option java_outer_classname = "EstopServiceProto"; diff --git a/protos/bosdyn/api/fault_service.proto b/protos/bosdyn/api/fault_service.proto index f2b5971..87ef4ad 100644 --- a/protos/bosdyn/api/fault_service.proto +++ b/protos/bosdyn/api/fault_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/fault_service"; option java_outer_classname = "FaultServiceProto"; diff --git a/protos/bosdyn/api/full_body_command.proto b/protos/bosdyn/api/full_body_command.proto index 5f8e186..193d24d 100644 --- a/protos/bosdyn/api/full_body_command.proto +++ b/protos/bosdyn/api/full_body_command.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/full_body_command"; option java_outer_classname = "FullBodyCommandProto"; diff --git a/protos/bosdyn/api/geometry.proto b/protos/bosdyn/api/geometry.proto index 576b724..a5f7735 100644 --- a/protos/bosdyn/api/geometry.proto +++ b/protos/bosdyn/api/geometry.proto @@ -7,10 +7,10 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/geometry"; import "google/protobuf/wrappers.proto"; -option go_package = "bosdyn/api"; option java_outer_classname = "GeometryProto"; // Two dimensional vector primitive. @@ -280,7 +280,6 @@ Matrix matrix = 1; // Variance of the yaw component of the SE3 Pose. // Warning: DEPRECATED as of 2.1. This should equal cov_rzrz, inside `matrix`. Will be removed // in a future release. -// FIXME(sberard): https://bostondynamics.atlassian.net/browse/SPOT-12523 double yaw_variance = 2 [deprecated = true]; // Warning: DEPRECATED as of 2.1. Use 'matrix.' Will be removed in a future release. double cov_xx = 3 [deprecated = true]; diff --git a/protos/bosdyn/api/gps/aggregator.proto b/protos/bosdyn/api/gps/aggregator.proto index d4347a0..b90eba7 100644 --- a/protos/bosdyn/api/gps/aggregator.proto +++ b/protos/bosdyn/api/gps/aggregator.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.gps; +option go_package = "bosdyn/api/gps/aggregator"; option java_outer_classname = "AggregatorProto"; diff --git a/protos/bosdyn/api/gps/aggregator_service.proto b/protos/bosdyn/api/gps/aggregator_service.proto index 4f3a730..7f9dda6 100644 --- a/protos/bosdyn/api/gps/aggregator_service.proto +++ b/protos/bosdyn/api/gps/aggregator_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.gps; +option go_package = "bosdyn/api/gps/aggregator_service"; option java_outer_classname = "AggregatorServiceProto"; diff --git a/protos/bosdyn/api/gps/gps.proto b/protos/bosdyn/api/gps/gps.proto index 79db778..e3a6b3f 100644 --- a/protos/bosdyn/api/gps/gps.proto +++ b/protos/bosdyn/api/gps/gps.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.gps; +option go_package = "bosdyn/api/gps/gps"; option java_outer_classname = "LocationProto"; diff --git a/protos/bosdyn/api/gps/registration.proto b/protos/bosdyn/api/gps/registration.proto index 02bd397..3967d1a 100644 --- a/protos/bosdyn/api/gps/registration.proto +++ b/protos/bosdyn/api/gps/registration.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.gps; +option go_package = "bosdyn/api/gps/registration"; option java_outer_classname = "RegistrationProto"; @@ -39,6 +40,7 @@ message Registration { STATUS_NEED_DATA = 2; // No data has been reported to perform registration. STATUS_NEED_MORE_DATA = 3; // Data has been reported, but not enough to get a fix. STATUS_STALE = 4; // We have a registration, but it is based on old data. + STATUS_HIGH_ERROR = 5; // If the registration is poor, signal high error. } Status status = 1; @@ -59,6 +61,21 @@ message Registration { // won't exactly match robot_body_location, because robot_body_location is // filtered, and the GPS might have some offset relative to the robot's body. repeated GpsState gps_states = 7; + + // Information about the quality of the registration. + message Quality { + // The number of points being used in the registration. + int32 num_points = 1; + // The 3D position covariance 3x3 matrix calculated from the registration and measured with + // respect to the "odom" frame. + Matrix covariance = 2; + // The residuals of the computed registration. + Matrix residuals = 3; + // The mean of the residuals of the registration. + double mean_residual = 4; + } + Quality quality = 8; + } message GetLocationRequest { diff --git a/protos/bosdyn/api/gps/registration_service.proto b/protos/bosdyn/api/gps/registration_service.proto index d7a4ecc..f7c2150 100644 --- a/protos/bosdyn/api/gps/registration_service.proto +++ b/protos/bosdyn/api/gps/registration_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.gps; +option go_package = "bosdyn/api/gps/registration_service"; option java_outer_classname = "RegistrationServiceProto"; diff --git a/protos/bosdyn/api/graph_nav/area_callback.proto b/protos/bosdyn/api/graph_nav/area_callback.proto index 3c920c8..f25925f 100644 --- a/protos/bosdyn/api/graph_nav/area_callback.proto +++ b/protos/bosdyn/api/graph_nav/area_callback.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/area_callback"; option java_outer_classname = "AreaCallbackProto"; import "google/protobuf/any.proto"; diff --git a/protos/bosdyn/api/graph_nav/area_callback_data.proto b/protos/bosdyn/api/graph_nav/area_callback_data.proto index cbc2e1b..b671d79 100644 --- a/protos/bosdyn/api/graph_nav/area_callback_data.proto +++ b/protos/bosdyn/api/graph_nav/area_callback_data.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/area_callback_data"; option java_outer_classname = "AreaCallbackDataProto"; import "google/protobuf/any.proto"; diff --git a/protos/bosdyn/api/graph_nav/area_callback_service.proto b/protos/bosdyn/api/graph_nav/area_callback_service.proto index a468e99..f5519df 100644 --- a/protos/bosdyn/api/graph_nav/area_callback_service.proto +++ b/protos/bosdyn/api/graph_nav/area_callback_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/area_callback_service"; option java_outer_classname = "AreaCallbackServiceProto"; import "bosdyn/api/graph_nav/area_callback.proto"; diff --git a/protos/bosdyn/api/graph_nav/gps.proto b/protos/bosdyn/api/graph_nav/gps.proto index 9f03597..4a75583 100644 --- a/protos/bosdyn/api/graph_nav/gps.proto +++ b/protos/bosdyn/api/graph_nav/gps.proto @@ -6,6 +6,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/gps"; option java_outer_classname = "GraphNavGPSProto"; import "bosdyn/api/geometry.proto"; diff --git a/protos/bosdyn/api/graph_nav/graph_nav.proto b/protos/bosdyn/api/graph_nav/graph_nav.proto index faed096..dba6f43 100644 --- a/protos/bosdyn/api/graph_nav/graph_nav.proto +++ b/protos/bosdyn/api/graph_nav/graph_nav.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/graph_nav"; option java_outer_classname = "GraphNavProto"; @@ -105,6 +106,7 @@ message SetLocalizationRequest { // Improve localization based on images from body cameras VisualRefinementOptions refine_with_visual_features = 12; } + } // Info on whether the robot's current sensor setup is compatible with the recorded data @@ -114,6 +116,10 @@ message SensorCompatibilityStatus { bool map_has_lidar_data = 1; // If true, the robot is currently configured to use LIDAR data. bool robot_configured_for_lidar = 2; + // If true, the loaded map has GPS data in it. + bool map_has_gps_data = 3; + // If true, the robot is currently configured to use GPS data. + bool robot_configured_for_gps = 4; } // The SetLocalization response message contains the resulting localization to the map. @@ -137,8 +143,8 @@ message SetLocalizationResponse { STATUS_UNKNOWN_WAYPOINT = 3; // Localization was aborted, likely because of a new request. STATUS_ABORTED = 4; - // Failed to localize for some other reason; see the error_report for details. - // This is often because the initial guess was incorrect. + // Failed to localize for some other reason. This is often because the initial guess was + // incorrect. STATUS_FAILED = 5; // Failed to localize because the fiducial requested by 'use_fiducial_id' was too far away // from the robot. @@ -168,7 +174,7 @@ message SetLocalizationResponse { Status status = 3; // If set, describes the reason the status is not OK. - string error_report = 4; + string error_report = 4 [deprecated = true]; // Result of localization. Localization localization = 5; @@ -303,6 +309,9 @@ message TravelParams { // around large obstacles that were not present during mission recording. // NOTE: Alternate route-finding waypoints are disabled when using the long range planner. PLANNER_MODE_LONG_RANGE = 3; + + // Use long range planner with live data only. + PLANNER_MODE_LONG_RANGE_LIVE_ONLY = 4; }; PathPlannerMode planner_mode = 17; } @@ -353,6 +362,9 @@ message NavigateToRequest { // 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. + // + // Also note that the waypoint frame will be flattened before this transform is applied. + // This is relevant in cases where the destination_waypoint is not gravity alligned. SE2Pose destination_waypoint_tform_body_goal = 8; // Unique identifier for the command. If 0, this is a new command, otherwise it is a @@ -362,6 +374,7 @@ message NavigateToRequest { // Defines robot behavior when route is blocked. Defaults to reroute when route is blocked. RouteFollowingParams.RouteBlockedBehavior route_blocked_behavior = 10; + } // Response to a NavigateToRequest. This is returned immediately after the request is processed. A @@ -685,6 +698,9 @@ message NavigateToAnchorRequest { // Identifier provided by the time sync service to verify time sync between robot and client. string clock_identifier = 9; + // Defines robot behavior when route is blocked. Defaults to reroute when route is blocked. + RouteFollowingParams.RouteBlockedBehavior route_blocked_behavior = 12; + // 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. @@ -1030,6 +1046,8 @@ message LostDetectorState { Localization last_accepted_localization = 6; // This is the most recent localization that the lost detector rejected. Localization last_rejected_localization = 7; + // This is the most recent localization that would have been accepted with strict parameters. + Localization last_accepted_strict_localization = 10; // The number of edges the LostDetector believes the robot has crossed without first getting an // accepted localization. int32 num_consecutive_bad_edges = 8; diff --git a/protos/bosdyn/api/graph_nav/graph_nav_service.proto b/protos/bosdyn/api/graph_nav/graph_nav_service.proto index c440481..f2abb1d 100644 --- a/protos/bosdyn/api/graph_nav/graph_nav_service.proto +++ b/protos/bosdyn/api/graph_nav/graph_nav_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/graph_nav_service"; option java_outer_classname = "GraphNavServiceProto"; diff --git a/protos/bosdyn/api/graph_nav/lost_detection.proto b/protos/bosdyn/api/graph_nav/lost_detection.proto index b7d3f5f..31de1fe 100644 --- a/protos/bosdyn/api/graph_nav/lost_detection.proto +++ b/protos/bosdyn/api/graph_nav/lost_detection.proto @@ -6,6 +6,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/lost_detection"; option java_outer_classname = "LostDetectionProto"; // Determines how "strict" the lost detector is about declaring lost. diff --git a/protos/bosdyn/api/graph_nav/map.proto b/protos/bosdyn/api/graph_nav/map.proto index 8a8379d..a84f159 100644 --- a/protos/bosdyn/api/graph_nav/map.proto +++ b/protos/bosdyn/api/graph_nav/map.proto @@ -7,10 +7,10 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/map"; option java_outer_classname = "MapProto"; import "bosdyn/api/graph_nav/lost_detection.proto"; -import "bosdyn/api/graph_nav/visual_features.proto"; import "bosdyn/api/geometry.proto"; import "bosdyn/api/graph_nav/area_callback_data.proto"; import "bosdyn/api/image.proto"; diff --git a/protos/bosdyn/api/graph_nav/map_processing.proto b/protos/bosdyn/api/graph_nav/map_processing.proto index 80b6f4c..a886d17 100644 --- a/protos/bosdyn/api/graph_nav/map_processing.proto +++ b/protos/bosdyn/api/graph_nav/map_processing.proto @@ -13,6 +13,7 @@ import "bosdyn/api/header.proto"; import "bosdyn/api/graph_nav/map.proto"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/map_processing"; // Processes a GraphNav map by creating additional edges. After processing, // a new subgraph is created containing additional edges to add to the map. diff --git a/protos/bosdyn/api/graph_nav/map_processing_service.proto b/protos/bosdyn/api/graph_nav/map_processing_service.proto index 96b30ae..6ca924b 100644 --- a/protos/bosdyn/api/graph_nav/map_processing_service.proto +++ b/protos/bosdyn/api/graph_nav/map_processing_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/map_processing_service"; option java_outer_classname = "MapProcessingServiceProto"; diff --git a/protos/bosdyn/api/graph_nav/nav.proto b/protos/bosdyn/api/graph_nav/nav.proto index d6e9ca9..6ff6530 100644 --- a/protos/bosdyn/api/graph_nav/nav.proto +++ b/protos/bosdyn/api/graph_nav/nav.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/nav"; option java_outer_classname = "NavProto"; import "bosdyn/api/graph_nav/map.proto"; diff --git a/protos/bosdyn/api/graph_nav/recording.proto b/protos/bosdyn/api/graph_nav/recording.proto index 004b841..83ab647 100644 --- a/protos/bosdyn/api/graph_nav/recording.proto +++ b/protos/bosdyn/api/graph_nav/recording.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/recording"; import "google/protobuf/timestamp.proto"; diff --git a/protos/bosdyn/api/graph_nav/recording_service.proto b/protos/bosdyn/api/graph_nav/recording_service.proto index 9a8cd0e..dcd336a 100644 --- a/protos/bosdyn/api/graph_nav/recording_service.proto +++ b/protos/bosdyn/api/graph_nav/recording_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.graph_nav; +option go_package = "bosdyn/api/graph_nav/recording_service"; import "bosdyn/api/graph_nav/recording.proto"; diff --git a/protos/bosdyn/api/graph_nav/visual_features.proto b/protos/bosdyn/api/graph_nav/visual_features.proto deleted file mode 100644 index aeae49a..0000000 --- a/protos/bosdyn/api/graph_nav/visual_features.proto +++ /dev/null @@ -1,154 +0,0 @@ -// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. -// -// Downloading, reproducing, distributing or otherwise using the SDK Software -// is subject to the terms and conditions of the Boston Dynamics Software -// Development Kit License (20191101-BDSDK-SL). - -syntax = "proto3"; - -package bosdyn.api.graph_nav; -option java_outer_classname = "VisualFeaturesProto"; - -import "bosdyn/api/geometry.proto"; -import "bosdyn/api/image.proto"; -import "google/protobuf/timestamp.proto"; -import "google/protobuf/wrappers.proto"; - -// Generic sparse visual descriptor with a byte blob and a descriptor name. -message GenericDescriptor { - // Name of the descriptor which identifies how it is to be interpreted. - string name = 1; - // Binary blob representing the descriptor. - bytes data = 2; -} -// Represents a visual descriptor of a feature, usually a sparse visual feature. -message VisualDescriptor { - oneof visual_descriptor { - // Oriented Brief (ORB) sparse visual feature. - bytes orb = 1; - // Place to put other descriptors not explicitly captured above. - GenericDescriptor other = 100; - } -} - -// Represents a 2d (pixel-based) detection of a feature in an image. -message VisualKeypoint { - // The descriptor of the sparse feature, used to match it to other features. - VisualDescriptor visual_descriptor = 1; - // Position (pixels) in the image. - bosdyn.api.Vec2 position = 2; - // Size of the feature in pixels. If the feature is circular, this is the radius of the circle. - // If the feature is square, this is the side length of the square. - float size_pixels = 3; - // Orientation of the feature in the image plane, radians. Counterclockwise. - float orientation = 4; - // The depth (in meters) from the camera if it exists, or empty otherwise. - google.protobuf.DoubleValue depth_measurement = 5; - // 2x2 Covariance matrix of the position measurement's uncertainty. - bosdyn.api.Matrixf position_covariance = 6; - // Expected variance of the depth measurement, if it exists. - google.protobuf.DoubleValue depth_variance = 7; -} - -// Represents a set of visual features collected at a particular time from a particular camera -// source. Associates an image geometry + pixel data with visual features extracted there. -message VisualKeyFrame { - // The visual features extracted at the camera image. - repeated VisualKeypoint keypoints = 1; - // Contains the actual data in the image capture (may be compressed), and information - // about the source. Note that the raw data may be omitted if visual features are already - // extracted. - ImageCaptureAndSource image_capture_and_source = 2; - // Transformation from a bundle frame to the image. Depending on the context, - // the bundle frame may be the body, odometry, etc. - bosdyn.api.SE3Pose bundle_tform_image = 3; -} - -// Represents a bundle of visual KeyFrames taken around the same time. For example, if the robot has -// many cameras, this represents all of the cameras captured at around the same time/location. -message VisualKeyFrameBundle { - // A number of key frames, possibly from different sources. - repeated VisualKeyFrame key_frames = 1; - // Reference frame that the keyframes' poses are expressed in. - string bundle_frame_name = 2; - // Frame tree snapshot mapping common poses at record time (odom, body, etc.) to each other and - // the bundle frame. - bosdyn.api.FrameTreeSnapshot frame_tree_snapshot = 3; -} - -// A 3D position with a covariance estimate. -message PositionWithCovariance { - // The vector is to be interpreted as a 3D position in a frame. - bosdyn.api.Vec3 position = 1; - // 3x3 covariance matrix representing uncertainty in the position. - bosdyn.api.Matrixf covariance = 2; -} - -// A 3D direction with a covariance estimate. -message DirectionWithCovariance { - // The vector is to be interpreted as a 3D normalized direction in a frame. - bosdyn.api.Vec3 direction = 1; - // 2x2 covariance matrix representing uncertainty in the direction (in a local tangent frame). - bosdyn.api.Matrixf covariance = 2; -} - -// Indexes an observation of a landmark at a particular bundle, keyframe and keypoint. -// Waypoint snapshots have bundles of keyframes, each keyframe has a number of extracted keypoints. -// Observations are structured as: -// bundle_0 ... -// bundle_1 -// .... keyframe_0 -// .... keyframe_1 -// ........ keypoint_0 -// ........ keypoint_1 -// ........ ... -// ........ keypoint_J -// .... ... -// .... keyframe_K -// ... -// bundle_N -message LandmarkObservationIndex { - // The bundle from within the waypoint snapshot that this - // landmark observation came from. - int32 bundle_id = 1; - // The keyframe from within the bundle that this observation came from. - int32 keyframe_id = 2; - // The keypoint within the keyframe that this observation came from. - int32 keypoint_id = 3; - // Time of the camera image which observed this landmark. - google.protobuf.Timestamp timestamp = 4; -} - -// Represents a 3D landmark that has some visual descriptor attached to it. -message VisualLandmark { - // Unique ID of the landmark. Ids of landmarks are unique only in a particular instance of a - // graph nav map. Ids of landmarks may change as maps update. - int64 id = 1; - // The landmark may either be a full 3D landmark (in which case it is a point), or an - // orientation-only landmark (in which case it is a normalized direction). The frame of the - // landmark is left ambiguous here; generally the container of the landmark will specify which - // frame it is in. Note that landmarks may have *both* position and direction. A 3D position - // with covariance. - PositionWithCovariance position_with_covariance = 2; - // The vector is to be interpreted as a normalized 3D direction in the landmark frame. This - // represents the direction "into" the landmark from where it was first observed. - DirectionWithCovariance direction_with_covariance = 3; - // The canonical descriptor associated with this landmark. If a landmark looks different from - // different angles, then multiple landmarks are likely to be created for it. This will be set - // whenever the first observation is made of a landmark to create it. - VisualDescriptor visual_descriptor = 4; - // Indices of the observations that support this landmark. - repeated LandmarkObservationIndex landmark_observations = 5; -} - -// A group of 3D landmarks. These landmarks may be associated with a single waypoint, or with groups -// of waypoints. -message VisualLandmarks { - // Unorganized 3d landmark cloud. - repeated VisualLandmark landmarks = 1; - // Name of the reference frame that the landmarks are in. - string landmark_frame = 2; - // The frame tree must contain, at minimum, the landmark_frame and some other frame that the - // waypoint or current robot body knows about (for example, "odom" or "vision"). - FrameTreeSnapshot frame_tree_snapshot = 3; -} diff --git a/protos/bosdyn/api/gripper_camera_param.proto b/protos/bosdyn/api/gripper_camera_param.proto index c630316..86c444d 100644 --- a/protos/bosdyn/api/gripper_camera_param.proto +++ b/protos/bosdyn/api/gripper_camera_param.proto @@ -7,10 +7,12 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/gripper_camera_param"; option java_outer_classname = "GripperCameraParamProto"; import "bosdyn/api/header.proto"; import "bosdyn/api/geometry.proto"; +import "bosdyn/api/image.proto"; import "google/protobuf/wrappers.proto"; // The GripperCameraParam request message sets new gripper sensor parameters. Gripper sensor @@ -201,3 +203,82 @@ message RoiParameters { // Size of the region of interest. RoiWindowSize window_size = 2; } + +// Depth camera calibration parameters +message GripperDepthCameraCalibrationParams { + // The sensor frame uses the convention of z along the optical axis, x along the column + // and y along the row (from top left.) + SE3Pose wr1_tform_sensor = 1; + + message DepthCameraIntrinsics { + oneof camera_models { + // Rectilinear camera model. + ImageSource.PinholeModel pinhole = 1; + // The pinhole camera model with the 4 parameter brown conrady distortion model. + ImageSource.PinholeBrownConrady pinhole_brown_conrady = 2; + // The kannala brandt camera model for modeling fisheye lenses. + ImageSource.KannalaBrandtModel kannala_brandt = 3; + } + } + + // Depth camera intrinsics. + // The depth camera in the gripper does not have and adjustable lens, so only one set of + // intrinsics is needed. + DepthCameraIntrinsics intrinsics = 2; +} + +// Color camera calibration parameters +// Distortion for color camera is not supported. +message GripperColorCameraCalibrationParams { + // The sensor frame uses the convention of z along the optical axis, x along the column + // and y along the row (from top left.) + SE3Pose wr1_tform_sensor = 1; + + message ColorCameraIntrinsics { + // Rectilinear camera model. + ImageSource.PinholeModel pinhole = 1; + + // Camera mode having the resolution of image. + GripperCameraParams.CameraMode camera_mode = 2; + + // The RGB camera in the gripper has an adjustable lens position. This value ranges from 0 + // to 1 inclusive and does not directly translate into focal length. If it’s not set (for + // example, in auto-focus mode), the system assumes that calibration needs to be based on + // the current focus value (focus_absolute from GripperCameraParams). + google.protobuf.DoubleValue focus_absolute = 3; + } + + // Color camera intrinsics. + // We support to calibrate color camera in the gripper at a number of focus value. + repeated ColorCameraIntrinsics intrinsics = 2; +} + +message GripperCameraCalibrationProto { + GripperDepthCameraCalibrationParams depth = 1; + GripperColorCameraCalibrationParams color = 2; +} + +// Request to set the gripper camera calibration parameters. To reset the calibration, send the +// request with empty gripper_cam_cal. +message SetGripperCameraCalibrationRequest { + RequestHeader header = 1; + GripperCameraCalibrationProto gripper_cam_cal = 2; +} + +message SetGripperCameraCalibrationResponse { + // Common response header. + ResponseHeader header = 1; +} + +// Request to get the gripper camera calibration parameters. +message GetGripperCameraCalibrationRequest { + // Common request header. + RequestHeader header = 1; +} + +message GetGripperCameraCalibrationResponse { + // Common request header. + ResponseHeader header = 1; + + GripperCameraCalibrationProto gripper_cam_cal = 2; +} \ No newline at end of file diff --git a/protos/bosdyn/api/gripper_camera_param_service.proto b/protos/bosdyn/api/gripper_camera_param_service.proto index f850913..2ec8e4d 100644 --- a/protos/bosdyn/api/gripper_camera_param_service.proto +++ b/protos/bosdyn/api/gripper_camera_param_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/gripper_camera_param_service"; option java_outer_classname = "GripperCameraParamServiceProto"; @@ -15,4 +16,8 @@ import "bosdyn/api/gripper_camera_param.proto"; service GripperCameraParamService { rpc SetParams(GripperCameraParamRequest) returns (GripperCameraParamResponse) {} rpc GetParams(GripperCameraGetParamRequest) returns (GripperCameraGetParamResponse) {} + rpc SetCamCalib(SetGripperCameraCalibrationRequest) + returns (SetGripperCameraCalibrationResponse) {} + rpc GetCamCalib(GetGripperCameraCalibrationRequest) + returns (GetGripperCameraCalibrationResponse) {} } diff --git a/protos/bosdyn/api/gripper_command.proto b/protos/bosdyn/api/gripper_command.proto index b487d51..a42e7f5 100644 --- a/protos/bosdyn/api/gripper_command.proto +++ b/protos/bosdyn/api/gripper_command.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/gripper_command"; option java_outer_classname = "GripperCommandProto"; import "bosdyn/api/basic_command.proto"; diff --git a/protos/bosdyn/api/header.proto b/protos/bosdyn/api/header.proto index 77b21a2..2c3959a 100644 --- a/protos/bosdyn/api/header.proto +++ b/protos/bosdyn/api/header.proto @@ -7,11 +7,11 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/header"; import "google/protobuf/any.proto"; import "google/protobuf/timestamp.proto"; -option go_package = "bosdyn/api"; option java_outer_classname = "HeaderProto"; // Standard header attached to all GRPC requests to services. diff --git a/protos/bosdyn/api/image.proto b/protos/bosdyn/api/image.proto index 341449e..8a94844 100644 --- a/protos/bosdyn/api/image.proto +++ b/protos/bosdyn/api/image.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/image"; option java_outer_classname = "ImageProto"; import "bosdyn/api/header.proto"; @@ -225,6 +226,11 @@ message ListImageSourcesResponse { // 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). repeated ImageSource image_sources = 2; + + // A tree-based collection of transformations, which will include the transformations to each + // image sources sensors in addition to transformations to the common frames ("vision", "body", + // "odom"). All transforms within the snapshot are at the time of the request. + FrameTreeSnapshot transforms_snapshot = 3; } // The image request specifying the image source and data format desired. diff --git a/protos/bosdyn/api/image_geometry.proto b/protos/bosdyn/api/image_geometry.proto index f62f600..4f78d1d 100644 --- a/protos/bosdyn/api/image_geometry.proto +++ b/protos/bosdyn/api/image_geometry.proto @@ -7,8 +7,8 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/image_geometry"; -option go_package = "bosdyn/api"; option java_outer_classname = "ImageGeometryProto"; // geometry.proto is standardized to use double fields. There are some primitives already specified @@ -29,9 +29,23 @@ message RectangleI { reserved 1, 2, 3, 4; } -// Represents an area in the XY plane, with integer indices +// Represents a point in the XY plane, with integer indices. +message Vec2I { + int32 x = 1; + int32 y = 2; +} + +// Represents a polygon in the XY plane, with integer indices. +// This can be convex or concave, and clockwise or counter-clockwise, but +// must not self-intersect. +message PolygonI { + repeated Vec2I vertices = 1; +} + +// Represents an area in the XY plane, with integer indices. message AreaI { oneof geometry { RectangleI rectangle = 1; + PolygonI polygon = 2; } -} \ No newline at end of file +} diff --git a/protos/bosdyn/api/image_service.proto b/protos/bosdyn/api/image_service.proto index 362353d..cb4d62e 100644 --- a/protos/bosdyn/api/image_service.proto +++ b/protos/bosdyn/api/image_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/image_service"; option java_outer_classname = "ImageServiceProto"; diff --git a/protos/bosdyn/api/ir_enable_disable.proto b/protos/bosdyn/api/ir_enable_disable.proto index 67c4256..41c18be 100644 --- a/protos/bosdyn/api/ir_enable_disable.proto +++ b/protos/bosdyn/api/ir_enable_disable.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/ir_enable_disable"; option java_outer_classname = "IREnableDisableProto"; import "bosdyn/api/header.proto"; diff --git a/protos/bosdyn/api/ir_enable_disable_service.proto b/protos/bosdyn/api/ir_enable_disable_service.proto index b8ce8d0..981e5f2 100644 --- a/protos/bosdyn/api/ir_enable_disable_service.proto +++ b/protos/bosdyn/api/ir_enable_disable_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/ir_enable_disable_service"; option java_outer_classname = "IREnableDisableServiceProto"; diff --git a/protos/bosdyn/api/keepalive/keepalive.proto b/protos/bosdyn/api/keepalive/keepalive.proto index 405c2b3..b069ad1 100644 --- a/protos/bosdyn/api/keepalive/keepalive.proto +++ b/protos/bosdyn/api/keepalive/keepalive.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.keepalive; +option go_package = "bosdyn/api/keepalive/keepalive"; option java_outer_classname = "KeepaliveProto"; diff --git a/protos/bosdyn/api/keepalive/keepalive_service.proto b/protos/bosdyn/api/keepalive/keepalive_service.proto index ff59258..19ea44c 100644 --- a/protos/bosdyn/api/keepalive/keepalive_service.proto +++ b/protos/bosdyn/api/keepalive/keepalive_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.keepalive; +option go_package = "bosdyn/api/keepalive/keepalive_service"; option java_outer_classname = "KeepaliveServiceProto"; diff --git a/protos/bosdyn/api/lease.proto b/protos/bosdyn/api/lease.proto index c0eb511..bbd30f8 100644 --- a/protos/bosdyn/api/lease.proto +++ b/protos/bosdyn/api/lease.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/lease"; option java_outer_classname = "LeaseProto"; import "bosdyn/api/header.proto"; diff --git a/protos/bosdyn/api/lease_service.proto b/protos/bosdyn/api/lease_service.proto index d6a9ad6..1d1436b 100644 --- a/protos/bosdyn/api/lease_service.proto +++ b/protos/bosdyn/api/lease_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/lease_service"; option java_outer_classname = "LeaseServiceProto"; diff --git a/protos/bosdyn/api/license.proto b/protos/bosdyn/api/license.proto index a0593fb..c5acacc 100644 --- a/protos/bosdyn/api/license.proto +++ b/protos/bosdyn/api/license.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/license"; option java_outer_classname = "LicenseProto"; diff --git a/protos/bosdyn/api/license_service.proto b/protos/bosdyn/api/license_service.proto index 8b9a067..9f54d36 100644 --- a/protos/bosdyn/api/license_service.proto +++ b/protos/bosdyn/api/license_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/license_service"; option java_outer_classname = "LicenseServiceProto"; diff --git a/protos/bosdyn/api/local_grid.proto b/protos/bosdyn/api/local_grid.proto index f1f6c38..61890ed 100644 --- a/protos/bosdyn/api/local_grid.proto +++ b/protos/bosdyn/api/local_grid.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/local_grid"; option java_outer_classname = "LocalGridProto"; import "bosdyn/api/geometry.proto"; diff --git a/protos/bosdyn/api/local_grid_service.proto b/protos/bosdyn/api/local_grid_service.proto index 543055d..37fbd13 100644 --- a/protos/bosdyn/api/local_grid_service.proto +++ b/protos/bosdyn/api/local_grid_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/local_grid_service"; option java_outer_classname = "LocalGridServiceProto"; diff --git a/protos/bosdyn/api/log_status/log_status.proto b/protos/bosdyn/api/log_status/log_status.proto index 8b12be9..6927070 100644 --- a/protos/bosdyn/api/log_status/log_status.proto +++ b/protos/bosdyn/api/log_status/log_status.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.log_status; +option go_package = "bosdyn/api/log_status/log_status"; import "bosdyn/api/header.proto"; import "google/protobuf/duration.proto"; @@ -203,3 +204,4 @@ message TerminateLogResponse { // Status of terminated log. LogStatus log_status = 3; } + diff --git a/protos/bosdyn/api/log_status/log_status_service.proto b/protos/bosdyn/api/log_status/log_status_service.proto index 64443e2..4fc0e00 100644 --- a/protos/bosdyn/api/log_status/log_status_service.proto +++ b/protos/bosdyn/api/log_status/log_status_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.log_status; +option go_package = "bosdyn/api/log_status/log_status_service"; import "bosdyn/api/log_status/log_status.proto"; @@ -43,4 +44,5 @@ service LogStatusService { // Terminate Log before it is complete. rpc TerminateLog(TerminateLogRequest) returns (TerminateLogResponse); + } diff --git a/protos/bosdyn/api/manipulation_api.proto b/protos/bosdyn/api/manipulation_api.proto index 87692d1..7fef1de 100644 --- a/protos/bosdyn/api/manipulation_api.proto +++ b/protos/bosdyn/api/manipulation_api.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/manipulation_api"; option java_outer_classname = "ManipulationApiProto"; diff --git a/protos/bosdyn/api/manipulation_api_service.proto b/protos/bosdyn/api/manipulation_api_service.proto index e53f1cd..58b7012 100644 --- a/protos/bosdyn/api/manipulation_api_service.proto +++ b/protos/bosdyn/api/manipulation_api_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/manipulation_api_service"; import "bosdyn/api/manipulation_api.proto"; diff --git a/protos/bosdyn/api/metrics_logging/absolute_metrics.proto b/protos/bosdyn/api/metrics_logging/absolute_metrics.proto index c86fd57..cf5a4aa 100644 --- a/protos/bosdyn/api/metrics_logging/absolute_metrics.proto +++ b/protos/bosdyn/api/metrics_logging/absolute_metrics.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.metrics_logging; +option go_package = "bosdyn/api/metrics_logging/absolute_metrics"; import "bosdyn/api/data_buffer.proto"; import "bosdyn/api/parameter.proto"; diff --git a/protos/bosdyn/api/metrics_logging/metrics_logging_robot.proto b/protos/bosdyn/api/metrics_logging/metrics_logging_robot.proto index 7763a43..4d8fc46 100644 --- a/protos/bosdyn/api/metrics_logging/metrics_logging_robot.proto +++ b/protos/bosdyn/api/metrics_logging/metrics_logging_robot.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.metrics_logging; +option go_package = "bosdyn/api/metrics_logging/metrics_logging_robot"; import "bosdyn/api/data_buffer.proto"; import "bosdyn/api/header.proto"; diff --git a/protos/bosdyn/api/metrics_logging/metrics_logging_robot_service.proto b/protos/bosdyn/api/metrics_logging/metrics_logging_robot_service.proto index 88173f3..852c3a7 100644 --- a/protos/bosdyn/api/metrics_logging/metrics_logging_robot_service.proto +++ b/protos/bosdyn/api/metrics_logging/metrics_logging_robot_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.metrics_logging; +option go_package = "bosdyn/api/metrics_logging/metrics_logging_robot_service"; import "bosdyn/api/metrics_logging/metrics_logging_robot.proto"; diff --git a/protos/bosdyn/api/metrics_logging/signed_proto.proto b/protos/bosdyn/api/metrics_logging/signed_proto.proto index 7969ad7..c7be614 100644 --- a/protos/bosdyn/api/metrics_logging/signed_proto.proto +++ b/protos/bosdyn/api/metrics_logging/signed_proto.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.metrics_logging; +option go_package = "bosdyn/api/metrics_logging/signed_proto"; option java_outer_classname = "SignedProtoProto"; diff --git a/protos/bosdyn/api/mission/mission.proto b/protos/bosdyn/api/mission/mission.proto index 8bf6ce1..dd3ad2d 100644 --- a/protos/bosdyn/api/mission/mission.proto +++ b/protos/bosdyn/api/mission/mission.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.mission; +option go_package = "bosdyn/api/mission/mission"; option java_outer_classname = "MissionProto"; diff --git a/protos/bosdyn/api/mission/mission_service.proto b/protos/bosdyn/api/mission/mission_service.proto index 825bdd1..40ad66f 100644 --- a/protos/bosdyn/api/mission/mission_service.proto +++ b/protos/bosdyn/api/mission/mission_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.mission; +option go_package = "bosdyn/api/mission/mission_service"; option java_outer_classname = "MissionServiceProto"; diff --git a/protos/bosdyn/api/mission/nodes.proto b/protos/bosdyn/api/mission/nodes.proto index 1d6cf1f..a910117 100644 --- a/protos/bosdyn/api/mission/nodes.proto +++ b/protos/bosdyn/api/mission/nodes.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.mission; +option go_package = "bosdyn/api/mission/nodes"; option java_outer_classname = "NodesProto"; @@ -18,6 +19,7 @@ import "bosdyn/api/alerts.proto"; import "bosdyn/api/docking/docking.proto"; import "bosdyn/api/geometry.proto"; import "bosdyn/api/gripper_camera_param.proto"; +import "bosdyn/api/image.proto"; import "bosdyn/api/spot/choreography_sequence.proto"; import "bosdyn/api/spot_cam/camera.proto"; import "bosdyn/api/spot_cam/logging.proto"; @@ -82,6 +84,7 @@ message Node { SpotCamLed spot_cam_led = 37; SpotCamFocusState spot_cam_focus_state = 58; SpotCamResetAutofocus spot_cam_reset_autofocus = 38; + SpotCamNamedPosition spot_cam_named_position = 63; StoreMetadata store_metadata = 39; Switch switch = 40; DataAcquisition data_acquisition = 41; @@ -372,10 +375,41 @@ message BosdynNavigateTo { // a blackboard variable with this name. string navigate_to_response_blackboard_key = 7; + // If provided, parameters from this request will be merged with the other parameters defined in + // the node and be used in the NavigateTo RPC. + string navigate_to_request_blackboard_key = 9; + // Defines robot behavior when route is blocked. Defaults to reroute when route is blocked. bosdyn.api.graph_nav.RouteFollowingParams.RouteBlockedBehavior route_blocked_behavior = 8; } +// Tell the robot to navigate to a pose in the seed frame +message BosdynNavigateToAnchor { + // Name of the service to use. + string service_name = 1; + // Host machine the service is running on. + string host = 2; + + // Desired goal pose in seed frame. + bosdyn.api.SE3Pose seed_tform_goal = 3; + + // Preferences on how to pick the route. + bosdyn.api.graph_nav.RouteGenParams route_gen_params = 4; + // Parameters that define how to traverse and end the route. + bosdyn.api.graph_nav.TravelParams travel_params = 5; + + // If provided, this will write the last NavigationFeedbackResponse message + // to a blackboard variable with this name. + string navigation_feedback_response_blackboard_key = 6; + // If provided, this will write the last NavigateToResponse message to + // a blackboard variable with this name. + string navigate_to_anchor_response_blackboard_key = 7; + + // If provided, parameters from this request will be merged with the other parameters defined in + // the node and be used in the NavigateToAnchor RPC. + string navigate_to_anchor_request_blackboard_key = 8; +} + // Tell the robot to navigate a route. message BosdynNavigateRoute { // Name of the service to use. @@ -687,6 +721,23 @@ message SpotCamPtz { AdjustParameters adjust_parameters = 4; } +// Point the PTZ to a specified named configuraiton. +message SpotCamNamedPosition { + // Name of the service to use. + string service_name = 1; + + // Host machine of the directory server that the Spot CAM registered with. + string host = 2; + + // Name of the ptz to be pointed. + string ptz_name = 3; + + // Named position to move the PTZ to. + // Currently, the only supported named position is "stow". + // Stow points the camera forward, parallel to the robot body's +x axis. + string named_position = 4; +} + // Store media using the Spot CAM. message SpotCamStoreMedia { // Name of the service to use. diff --git a/protos/bosdyn/api/mission/remote.proto b/protos/bosdyn/api/mission/remote.proto index ba018fe..dda989b 100644 --- a/protos/bosdyn/api/mission/remote.proto +++ b/protos/bosdyn/api/mission/remote.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.mission; +option go_package = "bosdyn/api/mission/remote"; option java_outer_classname = "RemoteProto"; diff --git a/protos/bosdyn/api/mission/remote_service.proto b/protos/bosdyn/api/mission/remote_service.proto index 40f4c4f..7141432 100644 --- a/protos/bosdyn/api/mission/remote_service.proto +++ b/protos/bosdyn/api/mission/remote_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.mission; +option go_package = "bosdyn/api/mission/remote_service"; option java_outer_classname = "RemoteServiceProto"; diff --git a/protos/bosdyn/api/mission/util.proto b/protos/bosdyn/api/mission/util.proto index 0f817fd..b03d287 100644 --- a/protos/bosdyn/api/mission/util.proto +++ b/protos/bosdyn/api/mission/util.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.mission; +option go_package = "bosdyn/api/mission/util"; option java_outer_classname = "UtilProto"; @@ -41,19 +42,36 @@ message VariableDeclaration { TYPE_INT = 3; TYPE_BOOL = 4; TYPE_MESSAGE = 5; + TYPE_LIST = 6; + TYPE_DICT = 7; } + // Subtype of the variable if it is a list or dict type. This would be type of the elements of + // that collection + message SubType { + Type type = 1; + SubType sub_type = 2; + } + SubType sub_type = 3; // Type that this variable is expected to have. Used to verify assignments and comparisons. Type type = 2; } // A constant value. Corresponds to the VariableDeclaration Type enum. message ConstantValue { + message ListValue { + repeated ConstantValue values = 1; + } + message DictValue { + map values = 1; + } oneof value { double float_value = 1; string string_value = 2; int64 int_value = 3; bool bool_value = 4; google.protobuf.Any msg_value = 5; + ListValue list_value = 6; + DictValue dict_value = 7; } } diff --git a/protos/bosdyn/api/mobility_command.proto b/protos/bosdyn/api/mobility_command.proto index 9422530..0ea60a7 100644 --- a/protos/bosdyn/api/mobility_command.proto +++ b/protos/bosdyn/api/mobility_command.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/mobility_command"; option java_outer_classname = "MobilityCommandProto"; diff --git a/protos/bosdyn/api/network_compute_bridge.proto b/protos/bosdyn/api/network_compute_bridge.proto index 92ad71d..198206a 100644 --- a/protos/bosdyn/api/network_compute_bridge.proto +++ b/protos/bosdyn/api/network_compute_bridge.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/network_compute_bridge"; option java_outer_classname = "NetworkComputeBridgeProto"; import "bosdyn/api/alerts.proto"; diff --git a/protos/bosdyn/api/network_compute_bridge_service.proto b/protos/bosdyn/api/network_compute_bridge_service.proto index 3af5aa5..5e2c8b3 100644 --- a/protos/bosdyn/api/network_compute_bridge_service.proto +++ b/protos/bosdyn/api/network_compute_bridge_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/network_compute_bridge_service"; import "bosdyn/api/network_compute_bridge.proto"; diff --git a/protos/bosdyn/api/network_stats.proto b/protos/bosdyn/api/network_stats.proto index a02b8ee..5dd5cf4 100644 --- a/protos/bosdyn/api/network_stats.proto +++ b/protos/bosdyn/api/network_stats.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/network_stats"; import "google/protobuf/duration.proto"; diff --git a/protos/bosdyn/api/parameter.proto b/protos/bosdyn/api/parameter.proto index a2e757c..d7df7ab 100644 --- a/protos/bosdyn/api/parameter.proto +++ b/protos/bosdyn/api/parameter.proto @@ -7,11 +7,11 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/parameter"; import "google/protobuf/duration.proto"; import "google/protobuf/timestamp.proto"; -option go_package = "bosdyn/api"; option java_outer_classname = "ParameterProto"; // A generic parameter message used by the robot state service to describe different, diff --git a/protos/bosdyn/api/payload.proto b/protos/bosdyn/api/payload.proto index 1e09e43..64c14f9 100644 --- a/protos/bosdyn/api/payload.proto +++ b/protos/bosdyn/api/payload.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/payload"; option java_outer_classname = "PayloadProto"; import "bosdyn/api/geometry.proto"; @@ -25,6 +26,8 @@ message Payload { // A human-readable description string providing more context as to the // function of this payload. It is displayed in UIs. string description = 3; + // A unique traceable per-payload serial number. + string serial_number = 18; // A list of labels used to indicate what type of payload this is. repeated string label_prefix = 9; // Set true once the payload is authorized by the administrator in the payload webpage. diff --git a/protos/bosdyn/api/payload_estimation.proto b/protos/bosdyn/api/payload_estimation.proto index 751dec8..552d3b5 100644 --- a/protos/bosdyn/api/payload_estimation.proto +++ b/protos/bosdyn/api/payload_estimation.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/payload_estimation"; option java_outer_classname = "PayloadEstimationProto"; diff --git a/protos/bosdyn/api/payload_registration.proto b/protos/bosdyn/api/payload_registration.proto index 88022fc..95dbf54 100644 --- a/protos/bosdyn/api/payload_registration.proto +++ b/protos/bosdyn/api/payload_registration.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/payload_registration"; option java_outer_classname = "PayloadRegistrationProto"; import "bosdyn/api/payload.proto"; diff --git a/protos/bosdyn/api/payload_registration_service.proto b/protos/bosdyn/api/payload_registration_service.proto index ad44470..3db4721 100644 --- a/protos/bosdyn/api/payload_registration_service.proto +++ b/protos/bosdyn/api/payload_registration_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/payload_registration_service"; option java_outer_classname = "PayloadRegistrationServiceProto"; diff --git a/protos/bosdyn/api/payload_service.proto b/protos/bosdyn/api/payload_service.proto index 0760ae0..d785683 100644 --- a/protos/bosdyn/api/payload_service.proto +++ b/protos/bosdyn/api/payload_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/payload_service"; option java_outer_classname = "PayloadAccessServiceProto"; diff --git a/protos/bosdyn/api/payload_software_update.proto b/protos/bosdyn/api/payload_software_update.proto new file mode 100644 index 0000000..c3ccae8 --- /dev/null +++ b/protos/bosdyn/api/payload_software_update.proto @@ -0,0 +1,62 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/payload_software_update"; +option java_outer_classname = "PayloadSoftwareUpdateProto"; + +import "bosdyn/api/header.proto"; +import "bosdyn/api/software_package.proto"; + +// Send payload's current software version to the robot software updater. +message SendCurrentVersionInfoRequest { + // Common request header. + RequestHeader header = 1; + + SoftwarePackageVersion package_version = 2; +} + +message SendCurrentVersionInfoResponse { + // Common response header. + ResponseHeader header = 1; +} + +// Request version information for staged packages matching the supplied package names. Typically +// this is a single package name representing the payload, but if the payload hosts additional +// installable components, these may also be queried. +message GetAvailableSoftwareUpdatesRequest { + // Common request header. + RequestHeader header = 1; + + // Unique strings identifying units of payload software. + repeated string package_names = 2; +} + +// Software updater returns information about the staged software packages matching the supplied +// package names in the request. +message GetAvailableSoftwareUpdatesResponse { + // Common response header. + ResponseHeader header = 1; + + // Information about staged software updates matching the requested package names. + repeated StagedSoftwarePackage staged_packages = 2; +} + +// Send the status of an update process to the robot. +message SendSoftwareUpdateStatusRequest { + // Common request header. + RequestHeader header = 1; + + // Current status of the software update process for this payload. + SoftwareUpdateStatus update_status = 2; +} + +message SendSoftwareUpdateStatusResponse { + // Common response header. + ResponseHeader header = 1; +} diff --git a/protos/bosdyn/api/payload_software_update_initiation.proto b/protos/bosdyn/api/payload_software_update_initiation.proto new file mode 100644 index 0000000..c934108 --- /dev/null +++ b/protos/bosdyn/api/payload_software_update_initiation.proto @@ -0,0 +1,22 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/payload_software_update_initiation"; +option java_outer_classname = "PayloadSoftwareUpdateInitiationProto"; + +// Event instructing the payload to send its current software version information +// via a trusted channel. +message TriggerSendPayloadSoftwareInfoRequest {} + +message TriggerSendPayloadSoftwareInfoResponse {} + +// Event instructing the payload to initiate its software update process. +message TriggerInitiateUpdateRequest {} + +message TriggerInitiateUpdateResponse {} diff --git a/protos/bosdyn/api/payload_software_update_initiation_service.proto b/protos/bosdyn/api/payload_software_update_initiation_service.proto new file mode 100644 index 0000000..1825734 --- /dev/null +++ b/protos/bosdyn/api/payload_software_update_initiation_service.proto @@ -0,0 +1,24 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/payload_software_update_initiation_service"; +option java_outer_classname = "PayloadSoftwareUpdateInitiationServiceProto"; + +import "bosdyn/api/payload_software_update_initiation.proto"; + +// This service is hosted by a payload and is used by Spot to tell it to perform +// certain actions related to payload software update. These RPCs support events only; +// no data exchange takes place. +service PayloadSoftwareUpdateInitiationService { + // Tell the payload to send information about its current software version. + rpc TriggerSendPayloadSoftwareInfo(TriggerSendPayloadSoftwareInfoRequest) + returns (TriggerSendPayloadSoftwareInfoResponse); + // Tell the payload to initiate its software update operation. + rpc TriggerInitiateUpdate(TriggerInitiateUpdateRequest) returns (TriggerInitiateUpdateResponse); +} diff --git a/protos/bosdyn/api/payload_software_update_service.proto b/protos/bosdyn/api/payload_software_update_service.proto new file mode 100644 index 0000000..3eaff7e --- /dev/null +++ b/protos/bosdyn/api/payload_software_update_service.proto @@ -0,0 +1,30 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/payload_software_update_service"; +option java_outer_classname = "PayloadSoftwareUpdateServiceProto"; + +import "bosdyn/api/payload_software_update.proto"; + +// The PayloadSoftwareUpdateService is hosted by a robot and coordinates software updates of the +// various payloads attached to the robot. Each payload connects to this service to communicate +// its current version, obtain information about available updates, and provide status of the +// update process. +service PayloadSoftwareUpdateService { + // Send the payload's current software version information to the service. + rpc SendCurrentVersionInfo(SendCurrentVersionInfoRequest) + returns (SendCurrentVersionInfoResponse); + // Query the payload software update service for available software updates for the payload + // and any updateable components hosted by the payload. + rpc GetAvailableSoftwareUpdates(GetAvailableSoftwareUpdatesRequest) + returns (GetAvailableSoftwareUpdatesResponse); + // Set the status of the payload software update in process. + rpc SendSoftwareUpdateStatus(SendSoftwareUpdateStatusRequest) + returns (SendSoftwareUpdateStatusResponse); +} diff --git a/protos/bosdyn/api/point_cloud.proto b/protos/bosdyn/api/point_cloud.proto index d5bab0b..746e54e 100644 --- a/protos/bosdyn/api/point_cloud.proto +++ b/protos/bosdyn/api/point_cloud.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/point_cloud"; option java_outer_classname = "PointCloudProto"; import "bosdyn/api/header.proto"; @@ -30,6 +31,9 @@ message PointCloudSource { // to the point cloud data frame and the point cloud sensor frame. FrameTreeSnapshot transforms_snapshot = 31; + // If non-empty, the cloud types that can be returned by this service. + repeated PointCloudRequest.PointCloudType supported_cloud_types = 4; + reserved 2; } @@ -113,6 +117,42 @@ message PointCloud { reserved 8, 9; } +// A structured point cloud obtained from a series of scans from a LIDAR. +message LidarPointCloud { + // Information to track where the LIDAR was over time. + message LidarPoseSample { + // Position of the lidar in the vision world frame at acquisition_time. + Vec3 lidar_pos_in_vision = 1; + + // Robot time of this pose sample. + google.protobuf.Timestamp acquisition_time = 2; + + // Which scan in point_cloud corresponds to this pose sample. + int32 scan_number = 3; + } + + // The point cloud data, where the points are stored in row-major order + // as num_beams x num_scans, and a point is three floats XYZ. + // # rows == num_beams and # columns == num_scans + // Each row corresponds to a beam from the LIDAR. + // Each column corresponds to a scan from the LIDAR. + // Beams will be ordered from lowest to highest. + // Scans will be order from oldest to newest. + // Missing data will be returned as all-zeros (0.0, 0.0, 0.0). + PointCloud point_cloud = 1; + + // Number of beams produced by the LIDAR. + int32 num_beams = 2; + + // Number of scans included in the cloud. + int32 num_scans = 3; + + // Subsampled trajectory of the lidar position over time. + // Will always include the first & last scan poses. + repeated LidarPoseSample lidar_pose_history = 4; +} + + message ListPointCloudSourcesRequest { // Common request header. RequestHeader header = 1; @@ -134,6 +174,28 @@ message PointCloudRequest { // Name of the point cloud source to request from. string point_cloud_source_name = 1; + // How to format the returned point cloud. + // Not all services may support every format, in + // which case they will treat the requet as CLOUD_TYPE_POINTS. + enum PointCloudType { + // No specified type, treated same as CLOUD_TYPE_POINTS. + CLOUD_TYPE_UNKNOWN = 0; + + // Request point cloud as unstructured list of points. + // This will not include entries for missing returns. + CLOUD_TYPE_POINTS = 1; + + // Request data as a structured tensor retaining scan & beam information. + // This will include entries for missing returns. + CLOUD_TYPE_LIDAR = 2; + } + + PointCloudType cloud_type = 2; + + // Skip every downsample_rate-1 scans, if supported by the service. + // Has no effect if less than or equal to 1. + int32 downsample_rate = 3; + } // The GetPointCloud request message to ask a specific point cloud service for data. @@ -161,14 +223,28 @@ message PointCloudResponse { // There was a problem with the point cloud data. Only the PointCloudSource is filled out. STATUS_POINT_CLOUD_DATA_ERROR = 3; - // Provided point cloud source was not found. One + // Provided point cloud source was not found. STATUS_UNKNOWN_SOURCE = 4; + + // Service does not support the requested cloud type. + STATUS_UNSUPPORTED_CLOUD_TYPE = 5; } // Return status for the request. Status status = 1; - // The current point cloud from the service. - PointCloud point_cloud = 2; + // The current point cloud from the service. Currently lidar_cloud is set if CLOUD_TYPE_LIDAR + // was requested, otherwise point_cloud is set. + oneof cloud_data { + PointCloud point_cloud = 2; + LidarPointCloud lidar_cloud = 3; + } + + // True if the client already received the latest cloud from the service. + // In this case, cloud_data will be empty. + bool no_update = 4; + + // If positive, the expected nanoseconds until new cloud data will be ready. + int32 expected_time_to_next_update = 5; } message GetPointCloudResponse { diff --git a/protos/bosdyn/api/point_cloud_service.proto b/protos/bosdyn/api/point_cloud_service.proto index bb1d4ba..6306240 100644 --- a/protos/bosdyn/api/point_cloud_service.proto +++ b/protos/bosdyn/api/point_cloud_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/point_cloud_service"; option java_outer_classname = "PointCloudServiceProto"; @@ -24,4 +25,5 @@ service PointCloudService { // Request point clouds by source name. rpc GetPointCloud(GetPointCloudRequest) returns (GetPointCloudResponse) {} + } diff --git a/protos/bosdyn/api/power.proto b/protos/bosdyn/api/power.proto index f617c0b..e1fa363 100644 --- a/protos/bosdyn/api/power.proto +++ b/protos/bosdyn/api/power.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/power"; option java_outer_classname = "PowerProto"; diff --git a/protos/bosdyn/api/power_service.proto b/protos/bosdyn/api/power_service.proto index 741b26f..44aa657 100644 --- a/protos/bosdyn/api/power_service.proto +++ b/protos/bosdyn/api/power_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/power_service"; option java_outer_classname = "PowerServiceProto"; diff --git a/protos/bosdyn/api/ray_cast.proto b/protos/bosdyn/api/ray_cast.proto index 678e475..37e5665 100644 --- a/protos/bosdyn/api/ray_cast.proto +++ b/protos/bosdyn/api/ray_cast.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/ray_cast"; option java_outer_classname = "RayCastProto"; diff --git a/protos/bosdyn/api/ray_cast_service.proto b/protos/bosdyn/api/ray_cast_service.proto index 930064c..62b8d7d 100644 --- a/protos/bosdyn/api/ray_cast_service.proto +++ b/protos/bosdyn/api/ray_cast_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/ray_cast_service"; option java_outer_classname = "RayCastServiceProto"; diff --git a/protos/bosdyn/api/robot_command.proto b/protos/bosdyn/api/robot_command.proto index 617b8c6..1aec76c 100644 --- a/protos/bosdyn/api/robot_command.proto +++ b/protos/bosdyn/api/robot_command.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/robot_command"; option java_outer_classname = "RobotCommandProto"; diff --git a/protos/bosdyn/api/robot_command_service.proto b/protos/bosdyn/api/robot_command_service.proto index 54ffc8d..617b172 100644 --- a/protos/bosdyn/api/robot_command_service.proto +++ b/protos/bosdyn/api/robot_command_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/robot_command_service"; option java_outer_classname = "RobotCommandServiceProto"; import "bosdyn/api/robot_command.proto"; diff --git a/protos/bosdyn/api/robot_id.proto b/protos/bosdyn/api/robot_id.proto index aeb050b..2f841a0 100644 --- a/protos/bosdyn/api/robot_id.proto +++ b/protos/bosdyn/api/robot_id.proto @@ -7,12 +7,12 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/robot_id"; import "bosdyn/api/header.proto"; import "bosdyn/api/parameter.proto"; import "google/protobuf/timestamp.proto"; -option go_package = "bosdyn/api"; option java_outer_classname = "RobotIdProto"; // Robot identity information, which should be static while robot is powered-on. diff --git a/protos/bosdyn/api/robot_id_service.proto b/protos/bosdyn/api/robot_id_service.proto index 213330a..2ac921f 100644 --- a/protos/bosdyn/api/robot_id_service.proto +++ b/protos/bosdyn/api/robot_id_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/robot_id_service"; option java_outer_classname = "RobotIdServiceProto"; diff --git a/protos/bosdyn/api/robot_state.proto b/protos/bosdyn/api/robot_state.proto index c859fa9..5b76b21 100644 --- a/protos/bosdyn/api/robot_state.proto +++ b/protos/bosdyn/api/robot_state.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/robot_state"; option java_outer_classname = "RobotStateProto"; import "bosdyn/api/geometry.proto"; @@ -142,8 +143,12 @@ message PowerState { // The motor power state of the robot. MotorPowerState motor_power_state = 2; + // Human-readable error description. Not for programmatic analysis. + string motor_power_error_message = 10; + + // State describing if robot is connected to shore (wall) power. Robot can't be powered on - // while on shore power + // while on shore power. enum ShorePowerState { option allow_alias = true; @@ -257,8 +262,11 @@ message SystemFault { // robot. int32 code = 4; - // Fault UID - uint64 uid = 8; + // Fault UID. Deprecated in favor of string based uuid. + uint64 uid = 8 [deprecated = true]; + + // Fault universal unique identifier (UUID). + string uuid = 9; // User visible description of the fault (and possibly remedies.) string error_message = 5; @@ -296,6 +304,7 @@ message SystemFault { // SEVERITY_CRITICAL likely means the robot is going to shutdown // immediately. Severity severity = 7; + } // The robot's current E-Stop states and endpoints. @@ -385,6 +394,7 @@ message BatteryState { message SystemState { // Temperature of the robot motors. repeated MotorTemperature motor_temperatures = 1; + } // The kinematic state of the robot describes the current estimated positions of the robot body and @@ -617,7 +627,11 @@ message ManipulatorState { bool is_gripper_holding_item = 6; // The estimated force on the end-effector expressed in the hand frame. - Vec3 estimated_end_effector_force_in_hand = 13; + // Deprecated in favor of the estimated_end_effector_wrench_in_end_effector + Vec3 estimated_end_effector_force_in_hand = 13 [deprecated = true]; + + // The estimated wrench on the end-effector expressed in the end_effector (hand) frame. + Wrench estimated_end_effector_wrench_in_end_effector = 17; enum StowState { STOWSTATE_UNKNOWN = 0; @@ -679,6 +693,7 @@ message TerrainState { bool is_unsafe_to_sit = 1; } + // The RobotState request message to get the current state of the robot. message RobotStateRequest { // Common request header. @@ -770,6 +785,8 @@ message RobotImpairedState { // The detector is either not present, or not working. Note that if the detector // exists but is throwing a system fault, the status will be IMPAIRED_STATUS_SYSTEM_FAULT. IMPAIRED_STATUS_ENTITY_DETECTOR_NOT_WORKING = 8; + // The robot got stuck due to a collision + IMPAIRED_STATUS_STUCK_IN_COLLISION = 9; } // If the status is ROBOT_IMPAIRED, this is specifically why the robot is impaired. ImpairedStatus impaired_status = 1; diff --git a/protos/bosdyn/api/robot_state_service.proto b/protos/bosdyn/api/robot_state_service.proto index dc0c689..c61db68 100644 --- a/protos/bosdyn/api/robot_state_service.proto +++ b/protos/bosdyn/api/robot_state_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/robot_state_service"; option java_outer_classname = "RobotStateServiceProto"; diff --git a/protos/bosdyn/api/service_customization.proto b/protos/bosdyn/api/service_customization.proto index c9139c1..0ff5772 100644 --- a/protos/bosdyn/api/service_customization.proto +++ b/protos/bosdyn/api/service_customization.proto @@ -7,12 +7,12 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/service_customization"; import "google/protobuf/wrappers.proto"; import "bosdyn/api/image_geometry.proto"; import "bosdyn/api/units.proto"; -option go_package = "bosdyn/api"; option java_outer_classname = "ServiceCustomizationProto"; // This file contains messages that can customize service APIs. @@ -285,10 +285,16 @@ message RegionOfInterestParam { // selection. AreaI default_area = 2; - // Area may eventually contain many shape primitives. In that case, services can constrain - // which primitives they accept. These will be opt in, so that adding new primitive types - // won't be automatically advertised by older services. + // Area may eventually contain many shape primitives. In that case, services can constrain + // which primitives they accept. These will be opt in, so that adding new primitive types + // won't be automatically advertised by older services. For widest compatibility, services + // should at least support rectangles. + // + // Whether or not the service accepts a rectangle. bool allows_rectangle = 3; + + // Whether or not the service accepts a polygon. + bool allows_polygon = 4; } AreaI area = 1; diff --git a/protos/bosdyn/api/service_fault.proto b/protos/bosdyn/api/service_fault.proto index 96bbfe3..64824f0 100644 --- a/protos/bosdyn/api/service_fault.proto +++ b/protos/bosdyn/api/service_fault.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/service_fault"; option java_outer_classname = "ServiceFaultProto"; import "bosdyn/api/header.proto"; diff --git a/protos/bosdyn/api/signals.proto b/protos/bosdyn/api/signals.proto index 2291a47..58da045 100644 --- a/protos/bosdyn/api/signals.proto +++ b/protos/bosdyn/api/signals.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/signals"; option java_outer_classname = "SignalsProto"; import "bosdyn/api/geometry.proto"; diff --git a/protos/bosdyn/api/software_package.proto b/protos/bosdyn/api/software_package.proto new file mode 100644 index 0000000..a6f2dc6 --- /dev/null +++ b/protos/bosdyn/api/software_package.proto @@ -0,0 +1,111 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/software_package"; +option java_outer_classname = "SoftwarePackage"; + +import "google/protobuf/timestamp.proto"; +import "bosdyn/api/robot_id.proto"; + +// Common data type for communicating version information about an installable software package +// on the robot or its payloads. +message SoftwarePackageVersion { + // Unique string identifying the unit of software, e.g., "spot" or "coreio". Package names + // identifying payload software must not conflict with other package names in use. Note that + // Spot Extensions also use their name in this field when reporting their versions as well. + string package_name = 1; + + // Version of the software package. + SoftwareVersion version = 2; + + // Release date associated with the software package. + google.protobuf.Timestamp release_date = 3; + + // Unique identifier of the build of the software package. For example, this can be a + // randomly generated UUID, a hash of some binary artifact, or a version control commit hash. + // The only requirement is that it uniquely identifies the build of the software package. + + // This is used to test whether installed software packages are equivalent to the desired + // package versions and provide a stronger guarantee than the version field and release_date. + string build_id = 4; +} + +// StagedSoftwarePackage builds upon the version information by adding details of the package's +// size on disk and the URL that robot payloads can use to retrieve the file. +message StagedSoftwarePackage { + // Information about the software package version. + SoftwarePackageVersion version_info = 1; + + // File size of the software package in bytes. + int64 file_size = 2; + + // URL of the file on the staging server. + string url = 3; +} + +// SoftwareUpdateStatus provides details on the progress of an installation of a unit of software +// on the robot. +message SoftwareUpdateStatus { + // Unique string identifying the software unit. + string package_name = 1; + + enum Status { + STATUS_UNKNOWN = 0; + // Payload is not currently executing an update. + STATUS_IDLE = 1; + // Payload is waiting for other software installations to complete. + STATUS_WAITING = 2; + // Payload is downloading the software package from the staging server. + STATUS_DOWNLOADING = 3; + // Payload is validating the downloaded package. + STATUS_VALIDATING = 4; + // Payload is installing the software package. + STATUS_INSTALLING = 5; + // Payload is rebooting to start using the new software. + STATUS_REBOOTING = 6; + // Payload has successfully been updated. + STATUS_SUCCESS = 7; + // Payload failed to install the update. + STATUS_FAILURE = 8; + } + + enum ErrorCode { + ERROR_UNINITIALIZED = 0; + // No error + ERROR_NONE = 1; + // Unknown error; not covered in any of the cases below + ERROR_UNKNOWN = 2; + // Failed to download the package from the staging area + ERROR_DOWNLOAD_FAILED = 3; + // Update rejected for some reason (staged is older than current, for example) + ERROR_UPDATE_REJECTED = 4; + // Validation by software failed + ERROR_VALIDATION_FAILED = 5; + // Inadequate disk space to accept software update + ERROR_INSUFFICIENT_STORAGE = 6; + // Failed to find a required file during the update process + ERROR_FILE_NOT_FOUND = 7; + // Package was downloaded and validated, but failed to install. + ERROR_INSTALLATION_FAILED = 8; + // The update was started, but it was interrupted before it was allowed to complete. + ERROR_INTERRUPTED = 9; + // This depends on another update, but that other update failed to install. + ERROR_DEPENDENCY_FAILED = 10; + // Payload failed to respond after a timeout; update is presumed to have failed. + ERROR_TIMEOUT = 11; + // The payload is already installing an update. + ERROR_INSTALLATION_ALREADY_IN_PROGRESS = 12; + } + + // Status of the update process for a specific software package. + Status status = 2; + + // If status == STATUS_FAILURE, this field communicates the reason for the failure. + ErrorCode error_code = 3; +} diff --git a/protos/bosdyn/api/sparse_features.proto b/protos/bosdyn/api/sparse_features.proto index f2166ad..abde99e 100644 --- a/protos/bosdyn/api/sparse_features.proto +++ b/protos/bosdyn/api/sparse_features.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/sparse_features"; option java_outer_classname = "SparseFeaturesProto"; diff --git a/protos/bosdyn/api/spot/choreography_params.proto b/protos/bosdyn/api/spot/choreography_params.proto index 02d56fc..8564bef 100644 --- a/protos/bosdyn/api/spot/choreography_params.proto +++ b/protos/bosdyn/api/spot/choreography_params.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/choreography_params"; option java_outer_classname = "ChoreographyParamsProto"; diff --git a/protos/bosdyn/api/spot/choreography_sequence.proto b/protos/bosdyn/api/spot/choreography_sequence.proto index 91effca..bdfc9b3 100644 --- a/protos/bosdyn/api/spot/choreography_sequence.proto +++ b/protos/bosdyn/api/spot/choreography_sequence.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/choreography_sequence"; option java_outer_classname = "ChoreographyProto"; @@ -1097,3 +1098,59 @@ message ChoreographyTimeAdjustResponse { // status was STATUS_OK. repeated string warnings = 3; } + +// Size and shape of a specific individual leg. +message LegSize { + // Horizontal distances from the center of the foot sphere to the edge of the collision + // geometry. Meters. + float distance_inward = 1; // Toward the front/back centerline. Baseline robot: 0.02 m + float distance_outward = 2; // Away from the front/back centerline. Baseline robot: 0.02 m + float distance_forward = 3; // Baseline robot: 0.035m + float distance_backward = 4; // Baseline robot: 0.035m +} + +// Tell the robot its legs are a non-standard size to help avoid self-collision. +// Typically used for robots that are wearing costumes. +// Configuration will be permanently stored (persisting through reboot) until cleared by sending an +// empty request. +message LegSizeConfigurationRequest { + // Common request header + RequestHeader header = 1; + + LegSize front_left_size = 2; + LegSize front_right_size = 3; + LegSize hind_left_size = 4; + LegSize hind_right_size = 5; +} + +message LegSizeConfigurationResponse { + // Common response header + ResponseHeader header = 1; + + enum Status { + // Status unknown. Do not use. + STATUS_UNKNOWN = 0; + // The new leg size configuration value was accepted and stored. + STATUS_OK = 1; + // The new leg size configuration value either contained values below 0 or above the + // maximum dimension size of .20 meters. The configuration was not stored. + STATUS_EXCEEDS_LIMITS = 2; + } + Status status = 2; +} + +// Check the state of the current leg size configuration. +message LegSizeConfigurationStateRequest { + // Common request header + RequestHeader header = 1; +} + +message LegSizeConfigurationStateResponse { + // Common response header + ResponseHeader header = 1; + + LegSize front_left_size = 2; + LegSize front_right_size = 3; + LegSize hind_left_size = 4; + LegSize hind_right_size = 5; +} diff --git a/protos/bosdyn/api/spot/choreography_service.proto b/protos/bosdyn/api/spot/choreography_service.proto index 65c7a37..aecf1ff 100644 --- a/protos/bosdyn/api/spot/choreography_service.proto +++ b/protos/bosdyn/api/spot/choreography_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/choreography_service"; option java_outer_classname = "ChoreographyServiceProto"; @@ -67,6 +68,13 @@ service ChoreographyService { // Commands intended for individual dance moves that are currently executing. rpc ChoreographyCommand(ChoreographyCommandRequest) returns (ChoreographyCommandResponse) {} + // Adjust leg size configuration, which affects self-collision avoidance regions. + rpc LegSizeConfiguration(LegSizeConfigurationRequest) returns (LegSizeConfigurationResponse) {} + + // Read the current leg size configuration from the robot. + rpc LegSizeConfigurationState(LegSizeConfigurationStateRequest) + returns (LegSizeConfigurationStateResponse) {} + // Adjust the time when a robot should start dancing within a tolerance. rpc ChoreographyTimeAdjust(ChoreographyTimeAdjustRequest) returns (ChoreographyTimeAdjustResponse) {} diff --git a/protos/bosdyn/api/spot/door.proto b/protos/bosdyn/api/spot/door.proto index 0d40de7..9246d63 100644 --- a/protos/bosdyn/api/spot/door.proto +++ b/protos/bosdyn/api/spot/door.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/door"; option java_outer_classname = "DoorCommandProto"; import "bosdyn/api/basic_command.proto"; diff --git a/protos/bosdyn/api/spot/door_area_callback.proto b/protos/bosdyn/api/spot/door_area_callback.proto index a2f9c6c..9d57ae3 100644 --- a/protos/bosdyn/api/spot/door_area_callback.proto +++ b/protos/bosdyn/api/spot/door_area_callback.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/door_area_callback"; option java_outer_classname = "DoorAreaCallbackProto"; import "bosdyn/api/spot/door.proto"; diff --git a/protos/bosdyn/api/spot/door_service.proto b/protos/bosdyn/api/spot/door_service.proto index 25a13b1..31fd14e 100644 --- a/protos/bosdyn/api/spot/door_service.proto +++ b/protos/bosdyn/api/spot/door_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/door_service"; option java_outer_classname = "DoorCommandServiceProto"; import "bosdyn/api/spot/door.proto"; diff --git a/protos/bosdyn/api/spot/inverse_kinematics.proto b/protos/bosdyn/api/spot/inverse_kinematics.proto index ed67b4f..243e1ef 100644 --- a/protos/bosdyn/api/spot/inverse_kinematics.proto +++ b/protos/bosdyn/api/spot/inverse_kinematics.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/inverse_kinematics"; option java_outer_classname = "InverseKinematicsProto"; import "bosdyn/api/arm_command.proto"; diff --git a/protos/bosdyn/api/spot/inverse_kinematics_service.proto b/protos/bosdyn/api/spot/inverse_kinematics_service.proto index 967b60e..39233d1 100644 --- a/protos/bosdyn/api/spot/inverse_kinematics_service.proto +++ b/protos/bosdyn/api/spot/inverse_kinematics_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/inverse_kinematics_service"; option java_outer_classname = "InverseKinematicsServiceProto"; diff --git a/protos/bosdyn/api/spot/robot_command.proto b/protos/bosdyn/api/spot/robot_command.proto index 2634b11..1d6a46a 100644 --- a/protos/bosdyn/api/spot/robot_command.proto +++ b/protos/bosdyn/api/spot/robot_command.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/robot_command"; option java_outer_classname = "RobotCommandProto"; diff --git a/protos/bosdyn/api/spot/spot_check.proto b/protos/bosdyn/api/spot/spot_check.proto index 86c91f3..18b9914 100644 --- a/protos/bosdyn/api/spot/spot_check.proto +++ b/protos/bosdyn/api/spot/spot_check.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/spot_check"; option java_outer_classname = "SpotCheckProto"; diff --git a/protos/bosdyn/api/spot/spot_check_service.proto b/protos/bosdyn/api/spot/spot_check_service.proto index cfde99d..de24afb 100644 --- a/protos/bosdyn/api/spot/spot_check_service.proto +++ b/protos/bosdyn/api/spot/spot_check_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/spot_check_service"; option java_outer_classname = "SpotCheckServiceProto"; diff --git a/protos/bosdyn/api/spot/spot_constants.proto b/protos/bosdyn/api/spot/spot_constants.proto index d509e26..9f71b8b 100644 --- a/protos/bosdyn/api/spot/spot_constants.proto +++ b/protos/bosdyn/api/spot/spot_constants.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api.spot; +option go_package = "bosdyn/api/spot/spot_constants"; // Joint indexing diff --git a/protos/bosdyn/api/stairs.proto b/protos/bosdyn/api/stairs.proto index be4dd10..099ee58 100644 --- a/protos/bosdyn/api/stairs.proto +++ b/protos/bosdyn/api/stairs.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/stairs"; option java_outer_classname = "StairsProto"; diff --git a/protos/bosdyn/api/synchronized_command.proto b/protos/bosdyn/api/synchronized_command.proto index d6e4018..a168fc0 100644 --- a/protos/bosdyn/api/synchronized_command.proto +++ b/protos/bosdyn/api/synchronized_command.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/synchronized_command"; option java_outer_classname = "SynchronizedCommandProto"; diff --git a/protos/bosdyn/api/time_range.proto b/protos/bosdyn/api/time_range.proto index 125f25e..171b552 100644 --- a/protos/bosdyn/api/time_range.proto +++ b/protos/bosdyn/api/time_range.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/time_range"; option java_outer_classname = "TimeRangeProto"; import "google/protobuf/timestamp.proto"; diff --git a/protos/bosdyn/api/time_sync.proto b/protos/bosdyn/api/time_sync.proto index 9a0855a..31807cd 100644 --- a/protos/bosdyn/api/time_sync.proto +++ b/protos/bosdyn/api/time_sync.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/time_sync"; option java_outer_classname = "TimeSyncProto"; diff --git a/protos/bosdyn/api/time_sync_service.proto b/protos/bosdyn/api/time_sync_service.proto index 5503935..76a21bd 100644 --- a/protos/bosdyn/api/time_sync_service.proto +++ b/protos/bosdyn/api/time_sync_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/time_sync_service"; option java_outer_classname = "TimeSyncServiceProto"; diff --git a/protos/bosdyn/api/trajectory.proto b/protos/bosdyn/api/trajectory.proto index e8f638c..8ef63ee 100644 --- a/protos/bosdyn/api/trajectory.proto +++ b/protos/bosdyn/api/trajectory.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/trajectory"; option java_outer_classname = "TrajectoryProto"; import "bosdyn/api/geometry.proto"; diff --git a/protos/bosdyn/api/units.proto b/protos/bosdyn/api/units.proto index b5032ae..97ab269 100644 --- a/protos/bosdyn/api/units.proto +++ b/protos/bosdyn/api/units.proto @@ -7,8 +7,8 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/units"; -option go_package = "bosdyn/api"; option java_outer_classname = "UnitsProto"; enum TemperatureEnum { @@ -44,4 +44,4 @@ message Units { // // NOTE: Only relevant for units with non equal zero points. bool is_relative = 4; -} \ No newline at end of file +} diff --git a/protos/bosdyn/api/world_object.proto b/protos/bosdyn/api/world_object.proto index 39e322d..37e551a 100644 --- a/protos/bosdyn/api/world_object.proto +++ b/protos/bosdyn/api/world_object.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/world_object"; option java_outer_classname = "WorldObjectProto"; diff --git a/protos/bosdyn/api/world_object_service.proto b/protos/bosdyn/api/world_object_service.proto index d725a32..5cb53da 100644 --- a/protos/bosdyn/api/world_object_service.proto +++ b/protos/bosdyn/api/world_object_service.proto @@ -7,6 +7,7 @@ syntax = "proto3"; package bosdyn.api; +option go_package = "bosdyn/api/world_object_service"; option java_outer_classname = "WorldObjectServiceProto"; From 94bd70ad32d2e3df42b376c826aff31d00984f36 Mon Sep 17 00:00:00 2001 From: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Date: Mon, 18 Aug 2025 21:31:33 -0400 Subject: [PATCH 03/15] Release v5.0.1 of Boston Dynamics Spot SDK --- README.md | 2 +- cpp/CMakeLists.txt | 2 +- cpp/bosdyn/client/directory/service_wait.cpp | 81 ++++ cpp/bosdyn/client/directory/service_wait.h | 52 +++ .../directory_registration_helpers.cpp | 76 +++- .../directory_registration_helpers.h | 22 +- .../error_callback/error_callback_result.h | 24 ++ .../payload_registration_helpers.cpp | 66 +++- .../payload_registration_helpers.h | 20 +- cpp/bosdyn/client/robot/robot.cpp | 9 + cpp/bosdyn/client/robot/robot.h | 9 + cpp/bosdyn/client/robot/token_manager.cpp | 81 +++- cpp/bosdyn/client/robot/token_manager.h | 38 +- .../client/util/periodic_thread_helper.cpp | 29 ++ .../client/util/periodic_thread_helper.h | 38 ++ docs/cpp_release_notes.md | 8 + protos/bosdyn/api/audio_visual.proto | 374 ++++++++++++++++++ protos/bosdyn/api/audio_visual_service.proto | 32 ++ protos/bosdyn/api/graph_nav/graph_nav.proto | 17 +- protos/bosdyn/api/robot_state.proto | 1 + .../bosdyn/api/spot/choreography_params.proto | 7 + 21 files changed, 921 insertions(+), 67 deletions(-) create mode 100644 cpp/bosdyn/client/directory/service_wait.cpp create mode 100644 cpp/bosdyn/client/directory/service_wait.h create mode 100644 cpp/bosdyn/client/error_callback/error_callback_result.h create mode 100644 cpp/bosdyn/client/util/periodic_thread_helper.cpp create mode 100644 cpp/bosdyn/client/util/periodic_thread_helper.h create mode 100644 protos/bosdyn/api/audio_visual.proto create mode 100644 protos/bosdyn/api/audio_visual_service.proto diff --git a/README.md b/README.md index 8646be9..04ceb2b 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+ - [Payload developer documentation](https://dev.bostondynamics.com/docs/payload/readme). Payloads add additional sensing, communication, and control capabilities beyond what the base platform provides. The Payload ICD covers the mechanical, electrical, and software interfaces that Spot supports. - [Spot API protocol definition](https://dev.bostondynamics.com/docs/protos/readme). 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. -This is version 5.0.0 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. +This is version 5.0.1 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. ## Contents diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index d4efbc8..d15f58a 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -7,7 +7,7 @@ # This file is autogenerated. cmake_minimum_required (VERSION 3.10.2) -project (bosdyn VERSION 5.0.0) +project (bosdyn VERSION 5.0.1) # Dependencies: find_package(protobuf REQUIRED) diff --git a/cpp/bosdyn/client/directory/service_wait.cpp b/cpp/bosdyn/client/directory/service_wait.cpp new file mode 100644 index 0000000..3bbff4d --- /dev/null +++ b/cpp/bosdyn/client/directory/service_wait.cpp @@ -0,0 +1,81 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#include "service_wait.h" +#include "bosdyn/common/success_condition.h" + +namespace bosdyn::directory::util { + +// Error category for WaitError. +class WaitCategory : public std::error_category { + public: + const char* name() const noexcept override { return "wait_error"; } + std::string message(int ev) const override { + switch (static_cast(ev)) { + case WaitError::kSuccess: + return "Success"; + case WaitError::kTimeout: + return "Timeout"; + } + return "Unknown"; + } + std::error_condition default_error_condition(int ev) const noexcept override { + return std::error_condition(ev, *this); + } + bool equivalent(int code, const std::error_condition& condition) const noexcept override { + if (condition == SuccessCondition::Success) { + return code == static_cast(WaitError::kSuccess); + } + return false; + } +}; + +const WaitCategory s_wait_category{}; + +std::error_code make_error_code(WaitError value) { + return {static_cast(value), s_wait_category}; +} + +WaitResult WaitForAllServices(const std::set& service_names, + bosdyn::client::Robot& robot, const bosdyn::common::Duration& timeout, + const bosdyn::common::Duration& interval) { + auto start_time = bosdyn::common::NowTimePoint(); + auto end_time = start_time + timeout; + WaitResult result; + + do { + bosdyn::client::Result> list_result = + robot.ListServices(); + if (!list_result) { + if (list_result.status.code() != RetryableRPCCondition::Retryable) { + // Return immediately if the error is not retryable. + result.status = list_result.status; + return result; + } + // Retryable error, keep trying. + } else { + result.missing_services = service_names; + for (const api::ServiceEntry& entry : list_result.response) { + result.missing_services.erase(entry.name()); + } + if (result.missing_services.empty()) { + result.status = {WaitError::kSuccess}; + return result; + } + } + std::this_thread::sleep_for(interval); + } while (bosdyn::common::NowTimePoint() < end_time); + + // Failed to find all services. Return the ones that are missing according to the latest set of + // found services. + result.status = {WaitError::kTimeout}; + return result; +} + +} // namespace bosdyn::directory::util diff --git a/cpp/bosdyn/client/directory/service_wait.h b/cpp/bosdyn/client/directory/service_wait.h new file mode 100644 index 0000000..b93629f --- /dev/null +++ b/cpp/bosdyn/client/directory/service_wait.h @@ -0,0 +1,52 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#pragma once + +#include + +#include "bosdyn/client/robot/robot.h" +#include "bosdyn/common/time.h" + +namespace bosdyn::directory::util { + +enum class WaitError { + kSuccess = 0, + kTimeout = 1, +}; + +struct WaitResult { + // Normally a WaitError, but may be an RPC failure. + bosdyn::common::Status status; + // List of any services that were missing when a timeout was hit. + std::set missing_services; +}; + +/** + * Block until all requested services are registered with the directory. Useful during startup to + * wait until the services you depend on are all running before you start creating clients. + * + * The status code will normally be a WaitError for success or timeout. If it fails with a timeout, + * the services that were not yet registered will be returned in missing_services. If the calls to + * list the services fail in an un-retryable manner, that error code will be returned in the status + * instead. + */ +WaitResult WaitForAllServices( + const std::set& service_names, bosdyn::client::Robot& robot, + const bosdyn::common::Duration& timeout, + const bosdyn::common::Duration& interval = std::chrono::milliseconds(100)); + +std::error_code make_error_code(WaitError value); + +} // namespace bosdyn::directory::util + +namespace std { +template <> +struct is_error_code_enum : true_type {}; +} // namespace std diff --git a/cpp/bosdyn/client/directory_registration/directory_registration_helpers.cpp b/cpp/bosdyn/client/directory_registration/directory_registration_helpers.cpp index c6084a2..718ce27 100644 --- a/cpp/bosdyn/client/directory_registration/directory_registration_helpers.cpp +++ b/cpp/bosdyn/client/directory_registration/directory_registration_helpers.cpp @@ -20,14 +20,20 @@ namespace client { DirectoryRegistrationKeepAlive::DirectoryRegistrationKeepAlive( DirectoryRegistrationClient* directory_registration_client, const ::bosdyn::api::ServiceEntry& service_entry, const ::bosdyn::api::Endpoint& endpoint, - ::bosdyn::common::Duration rpc_interval, FaultClient* fault_client) + ::bosdyn::common::Duration rpc_interval, FaultClient* fault_client, + std::function error_callback, + ::bosdyn::common::Duration registration_initial_retry_interval) : m_directory_registration_client(directory_registration_client), m_service_entry(service_entry), m_endpoint(endpoint), m_registration_interval(rpc_interval), + m_registration_initial_retry_interval(registration_initial_retry_interval), m_thread(), + m_periodic_thread_helper(std::make_unique()), m_thread_stopped(true), - m_fault_client(fault_client) {} + m_fault_client(fault_client), + m_error_callback(error_callback) {} + DirectoryRegistrationKeepAlive::~DirectoryRegistrationKeepAlive() { Shutdown(); @@ -35,7 +41,6 @@ DirectoryRegistrationKeepAlive::~DirectoryRegistrationKeepAlive() { } void DirectoryRegistrationKeepAlive::Start(const std::vector& fault_attributes) { - m_should_exit = false; m_thread_stopped = false; // Populate the registration fault with default values. @@ -61,8 +66,10 @@ void DirectoryRegistrationKeepAlive::Start(const std::vector& fault bool DirectoryRegistrationKeepAlive::IsAlive() const { return !m_thread_stopped; } void DirectoryRegistrationKeepAlive::Shutdown() { - m_should_exit = true; - m_thread.join(); + m_periodic_thread_helper->Stop(); + if (m_thread.joinable()) { + m_thread.join(); + } } UnregisterServiceResultType DirectoryRegistrationKeepAlive::Unregister() { @@ -70,7 +77,9 @@ UnregisterServiceResultType DirectoryRegistrationKeepAlive::Unregister() { } void DirectoryRegistrationKeepAlive::PeriodicReregisterThreadMethod() { - bool first_time = true; + + ::bosdyn::common::Duration retry_interval = m_registration_initial_retry_interval; + ::bosdyn::common::Duration wait_interval = m_registration_interval; // Set up register and update requests ::bosdyn::api::RegisterServiceRequest register_service_request; @@ -81,12 +90,7 @@ void DirectoryRegistrationKeepAlive::PeriodicReregisterThreadMethod() { update_service_request.mutable_service_entry()->CopyFrom(m_service_entry); // Continually attempt to register and update the service. - while (!m_should_exit) { - if (!first_time) { - std::this_thread::sleep_for(m_registration_interval); - } - first_time = false; - + do { // Register service. auto res_register = m_directory_registration_client->RegisterService(register_service_request); @@ -94,6 +98,7 @@ void DirectoryRegistrationKeepAlive::PeriodicReregisterThreadMethod() { // by the directory registration service. if (res_register) { m_registration_fault_active = false; + wait_interval = m_registration_interval; continue; } // If registration failed in a bad way. @@ -102,6 +107,27 @@ void DirectoryRegistrationKeepAlive::PeriodicReregisterThreadMethod() { if (m_fault_client && m_fault_client->TriggerServiceFault(m_service_fault)) { m_registration_fault_active = true; } + auto action = ErrorCallbackResult::kResumeNormalOperation; + if (m_error_callback) { + try { + action = m_error_callback(res_register.status); + } catch (const std::exception& e) { + std::cerr << "Exception thrown in error callback: " << e.what() << std::endl; + } + } + if (action == ErrorCallbackResult::kAbort) { + break; + } + if (action == ErrorCallbackResult::kRetryImmediately) { + wait_interval = std::chrono::seconds(0); + } else if (action == ErrorCallbackResult::kRetryWithExponentialBackOff) { + // Exponentially increase the retry interval. + wait_interval = retry_interval; + retry_interval = std::min(retry_interval * 2, m_registration_interval); + } else { + // Default action is to continue with the next iteration. + wait_interval = m_registration_interval; + } continue; } @@ -112,6 +138,27 @@ void DirectoryRegistrationKeepAlive::PeriodicReregisterThreadMethod() { if (m_fault_client && m_fault_client->TriggerServiceFault(m_service_fault)) { m_registration_fault_active = true; } + auto action = ErrorCallbackResult::kResumeNormalOperation; + if (m_error_callback) { + try { + action = m_error_callback(res_register.status); + } catch (const std::exception& e) { + std::cerr << "Exception thrown in error callback: " << e.what() << std::endl; + } + } + if (action == ErrorCallbackResult::kAbort) { + break; + } + if (action == ErrorCallbackResult::kRetryImmediately) { + wait_interval = std::chrono::seconds(0); + } else if (action == ErrorCallbackResult::kRetryWithExponentialBackOff) { + // Exponentially increase the retry interval. + wait_interval = retry_interval; + retry_interval = std::min(retry_interval * 2, m_registration_interval); + } else { + // Default action is to continue with the next iteration. + wait_interval = m_registration_interval; + } continue; } @@ -121,9 +168,12 @@ void DirectoryRegistrationKeepAlive::PeriodicReregisterThreadMethod() { m_registration_fault_active = false; } } - } + wait_interval = m_registration_interval; + retry_interval = m_registration_initial_retry_interval; + } while (m_periodic_thread_helper->WaitForInterval(wait_interval)); m_thread_stopped = true; + m_periodic_thread_helper->Stop(); } } // namespace client diff --git a/cpp/bosdyn/client/directory_registration/directory_registration_helpers.h b/cpp/bosdyn/client/directory_registration/directory_registration_helpers.h index fa4ef2e..4276f53 100644 --- a/cpp/bosdyn/client/directory_registration/directory_registration_helpers.h +++ b/cpp/bosdyn/client/directory_registration/directory_registration_helpers.h @@ -9,12 +9,17 @@ #pragma once -#include +#include +#include +#include #include +#include #include "directory_registration_client.h" +#include "bosdyn/client/error_callback/error_callback_result.h" #include "bosdyn/client/fault/fault_client.h" #include "bosdyn/client/service_client/common_result_types.h" +#include "bosdyn/client/util/periodic_thread_helper.h" #include @@ -32,7 +37,9 @@ class DirectoryRegistrationKeepAlive { DirectoryRegistrationClient* directory_registration_client, const ::bosdyn::api::ServiceEntry& service_entry, const ::bosdyn::api::Endpoint& endpoint, ::bosdyn::common::Duration rpc_interval = std::chrono::seconds(30), - FaultClient* fault_client = nullptr); + FaultClient* fault_client = nullptr, + std::function error_callback = {}, + ::bosdyn::common::Duration registration_initial_retry_interval = std::chrono::seconds(1)); ~DirectoryRegistrationKeepAlive(); @@ -52,6 +59,9 @@ class DirectoryRegistrationKeepAlive { // Background thread that continually registers/updates the service. void PeriodicReregisterThreadMethod(); + // Wait for the refresh interval and coordinate with the destructor on the condition variable. + bool WaitForInterval(::bosdyn::common::Duration interval); + DirectoryRegistrationClient* m_directory_registration_client = nullptr; ::bosdyn::api::ServiceEntry m_service_entry; @@ -59,11 +69,12 @@ class DirectoryRegistrationKeepAlive { // Time between registration/update calls. Should be shorter than the liveness timeout. ::bosdyn::common::Duration m_registration_interval; + ::bosdyn::common::Duration m_registration_initial_retry_interval; std::thread m_thread; - // Thread should exit. - bool m_should_exit; + // Object used to coordinate the lifecycle and timing of the periodic thread. + std::unique_ptr m_periodic_thread_helper; // Is thread stopped. bool m_thread_stopped; @@ -76,6 +87,9 @@ class DirectoryRegistrationKeepAlive { // Bool to track if there is a failure. bool m_registration_fault_active; + + // Callback to invoke in the event of a periodic reregistration failure. + std::function m_error_callback; }; } // namespace client diff --git a/cpp/bosdyn/client/error_callback/error_callback_result.h b/cpp/bosdyn/client/error_callback/error_callback_result.h new file mode 100644 index 0000000..b800b65 --- /dev/null +++ b/cpp/bosdyn/client/error_callback/error_callback_result.h @@ -0,0 +1,24 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#pragma once + +namespace bosdyn { +namespace client { + +enum class ErrorCallbackResult { + kDefaultAction, + kRetryImmediately, + kRetryWithExponentialBackOff, + kResumeNormalOperation, + kAbort, +}; + +} // namespace client +} // namespace bosdyn diff --git a/cpp/bosdyn/client/payload_registration/payload_registration_helpers.cpp b/cpp/bosdyn/client/payload_registration/payload_registration_helpers.cpp index 8ecc454..ecff2f9 100644 --- a/cpp/bosdyn/client/payload_registration/payload_registration_helpers.cpp +++ b/cpp/bosdyn/client/payload_registration/payload_registration_helpers.cpp @@ -19,10 +19,15 @@ namespace client { PayloadRegistrationKeepAlive::PayloadRegistrationKeepAlive( PayloadRegistrationClient* payload_registration_client, const ::bosdyn::api::Payload& payload, - const std::string& secret, ::bosdyn::common::Duration rpc_interval) + const std::string& secret, ::bosdyn::common::Duration rpc_interval, + std::function error_callback, + ::bosdyn::common::Duration registration_initial_retry_interval) : m_payload_registration_client(payload_registration_client), m_payload(payload), m_rpc_interval(rpc_interval), + m_periodic_thread_helper(std::make_unique()), + m_registration_initial_retry_interval(registration_initial_retry_interval), + m_error_callback(error_callback), m_should_exit(false), m_is_alive(false) { m_register_request.mutable_payload()->CopyFrom(payload); @@ -32,12 +37,13 @@ PayloadRegistrationKeepAlive::PayloadRegistrationKeepAlive( m_thread = std::thread(&PayloadRegistrationKeepAlive::PeriodicReregisterThreadMethod, this); } + PayloadRegistrationKeepAlive::~PayloadRegistrationKeepAlive() { Shutdown(); } bool PayloadRegistrationKeepAlive::IsAlive() const { return m_is_alive; } void PayloadRegistrationKeepAlive::Shutdown() { - m_should_exit = true; + m_periodic_thread_helper->Stop(); if (m_thread.joinable()) { m_thread.join(); } @@ -48,31 +54,51 @@ void PayloadRegistrationKeepAlive::PeriodicReregisterThreadMethod() { m_is_alive = true; // Continually attempt to register and update the service. - std::chrono::seconds last_request_success_time = std::chrono::seconds(0); std::chrono::seconds last_log_time = std::chrono::seconds(0); - while (!m_should_exit) { - if (::bosdyn::common::SecSinceEpoch() > last_request_success_time + m_rpc_interval) { - m_last_result = m_payload_registration_client->RegisterPayload(m_register_request); - - // If payload registration failed in an unexpected way, log the error. - if (!m_last_result && - m_last_result.status.code() != - ::bosdyn::api::RegisterPayloadResponse::STATUS_ALREADY_EXISTS) { - // Do not spam logs. - if (::bosdyn::common::SecSinceEpoch() > last_log_time + m_log_limit) { - last_log_time = ::bosdyn::common::SecSinceEpoch(); - std::cerr << m_payload.guid() - << " PayloadRegistrationKeepAlive failed registration: " - << m_last_result.status.DebugString(); + ::bosdyn::common::Duration wait_time = m_wait_time; + ::bosdyn::common::Duration retry_interval = m_registration_initial_retry_interval; + + do { + m_last_result = m_payload_registration_client->RegisterPayload(m_register_request); + + // If payload registration failed in an unexpected way, log the error. + if (!m_last_result && m_last_result.status.code() != + ::bosdyn::api::RegisterPayloadResponse::STATUS_ALREADY_EXISTS) { + ErrorCallbackResult action = ErrorCallbackResult::kResumeNormalOperation; + if (m_error_callback) { + try { + action = m_error_callback(m_last_result.status); + } catch (const std::exception& e) { + std::cerr << "Exception thrown in error callback: " << e.what() << std::endl; } + } + if (action == ErrorCallbackResult::kAbort) { + break; + } else if (action == ErrorCallbackResult::kRetryImmediately) { + wait_time = std::chrono::seconds(0); + } else if (action == ErrorCallbackResult::kRetryWithExponentialBackOff) { + wait_time = retry_interval; + retry_interval = std::min(retry_interval * 2, m_rpc_interval); } else { - last_request_success_time = ::bosdyn::common::SecSinceEpoch(); + wait_time = m_rpc_interval; + retry_interval = m_registration_initial_retry_interval; } + + // Do not spam logs. + if (::bosdyn::common::SecSinceEpoch() > last_log_time + m_log_limit) { + last_log_time = ::bosdyn::common::SecSinceEpoch(); + std::cerr << m_payload.guid() + << " PayloadRegistrationKeepAlive failed registration: " + << m_last_result.status.DebugString(); + } + } else { + wait_time = m_rpc_interval; + retry_interval = m_registration_initial_retry_interval; } - std::this_thread::sleep_for(m_wait_time); - } + } while (m_periodic_thread_helper->WaitForInterval(wait_time)); m_is_alive = false; + m_periodic_thread_helper->Stop(); } } // namespace client diff --git a/cpp/bosdyn/client/payload_registration/payload_registration_helpers.h b/cpp/bosdyn/client/payload_registration/payload_registration_helpers.h index b08c9f8..786afd5 100644 --- a/cpp/bosdyn/client/payload_registration/payload_registration_helpers.h +++ b/cpp/bosdyn/client/payload_registration/payload_registration_helpers.h @@ -9,14 +9,17 @@ #pragma once +#include #include #include #include #include "payload_registration_client.h" +#include "bosdyn/client/error_callback/error_callback_result.h" #include "bosdyn/client/robot/robot.h" #include "bosdyn/client/service_client/common_result_types.h" +#include "bosdyn/client/util/periodic_thread_helper.h" namespace bosdyn { @@ -33,12 +36,12 @@ class PayloadRegistrationKeepAlive { PayloadRegistrationKeepAlive( PayloadRegistrationClient* payload_registration_client, const ::bosdyn::api::Payload& payload, const std::string& secret, - ::bosdyn::common::Duration rpc_interval = std::chrono::seconds(30)); + ::bosdyn::common::Duration rpc_interval = std::chrono::seconds(30), + std::function error_callback = {}, + ::bosdyn::common::Duration registration_initial_retry_interval = std::chrono::seconds(1)); - ~PayloadRegistrationKeepAlive(); - // Start the thread if it is not yet running. - void Start(); + ~PayloadRegistrationKeepAlive(); // Return true if the thread is running. bool IsAlive() const; @@ -71,12 +74,21 @@ class PayloadRegistrationKeepAlive { std::thread m_thread; + // Object used to coordinate the lifecycle and timing of the periodic thread. + std::unique_ptr m_periodic_thread_helper; + // Time to wait between checking if exit has been requested. ::bosdyn::common::Duration m_wait_time = std::chrono::seconds(1); // Limit on how frequently an error should be logged. ::bosdyn::common::Duration m_log_limit = std::chrono::seconds(3); + // Initial retry interval for registration. + ::bosdyn::common::Duration m_registration_initial_retry_interval = std::chrono::seconds(1); + + // Callback to invoke in the event of a periodic reregistration failure. + std::function m_error_callback; + // Thread should exit. bool m_should_exit; diff --git a/cpp/bosdyn/client/robot/robot.cpp b/cpp/bosdyn/client/robot/robot.cpp index 4ef1178..a315b1f 100644 --- a/cpp/bosdyn/client/robot/robot.cpp +++ b/cpp/bosdyn/client/robot/robot.cpp @@ -263,6 +263,7 @@ void Robot::UpdateTokenCache(const std::string& username) { if (!m_token_manager) { TokenManager* raw_token_manager = new TokenManager(this); m_token_manager = std::unique_ptr(raw_token_manager); + m_token_manager->SetTokenRefreshErrorCallback(m_token_refresh_error_callback); } if (!username.empty()) m_current_user = username; @@ -499,6 +500,14 @@ std::string Robot::GetUserToken() { return m_user_token; } +void Robot::SetTokenRefreshErrorCallback( + std::function callback) { + m_token_refresh_error_callback = callback; + if (m_token_manager) { + m_token_manager->SetTokenRefreshErrorCallback(callback); + } +} + void Robot::SetRPCParameters(const RPCParameters& parameters) { m_RPC_parameters = parameters; diff --git a/cpp/bosdyn/client/robot/robot.h b/cpp/bosdyn/client/robot/robot.h index 68cc58a..3c80886 100644 --- a/cpp/bosdyn/client/robot/robot.h +++ b/cpp/bosdyn/client/robot/robot.h @@ -10,8 +10,11 @@ #pragma once #include +#include +#include #include #include "bosdyn/client/directory/directory_client.h" +#include "bosdyn/client/error_callback/error_callback_result.h" #include "bosdyn/client/error_codes/client_creation_error_code.h" #include "bosdyn/client/lease/lease_wallet.h" #include "bosdyn/client/processors/request_processor.h" @@ -155,6 +158,9 @@ class Robot { std::string GetUserToken(); + void SetTokenRefreshErrorCallback( + std::function callback); + // Set certificate in the robot. void SetRobotCert(const std::string& cert) { m_cert = cert; } @@ -338,6 +344,9 @@ class Robot { std::unique_ptr m_token_cache; std::string m_serial_number; + std::function + m_token_refresh_error_callback; + // Map with bootstrapped authorities for the services we need to communicate with before // getting the full list from the Directory service. Key in the map represents the service // name and value represents the authority. diff --git a/cpp/bosdyn/client/robot/token_manager.cpp b/cpp/bosdyn/client/robot/token_manager.cpp index 463fce1..13e36d8 100644 --- a/cpp/bosdyn/client/robot/token_manager.cpp +++ b/cpp/bosdyn/client/robot/token_manager.cpp @@ -14,38 +14,89 @@ namespace bosdyn { namespace client { -TokenManager::TokenManager(Robot* robot, ::bosdyn::common::Duration refresh_interval) +TokenManager::TokenManager(Robot* robot, ::bosdyn::common::Duration refresh_interval, + ::bosdyn::common::Duration initial_retry_interval) : m_robot(robot), + m_periodic_thread_helper(std::make_unique()), m_refresh_thread_is_alive(true), - m_user_token_refresh_interval(refresh_interval) { + m_user_token_refresh_interval(refresh_interval), + m_user_token_initial_retry_interval(initial_retry_interval) { m_refresh_thread = std::thread(&TokenManager::Update, this); } + TokenManager::~TokenManager() { Stop(); } +bool TokenManager::IsAlive() const { return m_refresh_thread_is_alive; } + void TokenManager::Stop() { - { - std::lock_guard lock(this->m_refresh_mutex); - m_refresh_thread_is_alive = false; + m_periodic_thread_helper->Stop(); + if (m_refresh_thread.joinable()) { + m_refresh_thread.join(); } - m_cv.notify_one(); - m_refresh_thread.join(); -} - -bool TokenManager::WaitForInterval() { - std::unique_lock lock(m_refresh_mutex); - if (!m_refresh_thread_is_alive) return false; - return !m_cv.wait_for(lock, m_user_token_refresh_interval, - [this]() { return !m_refresh_thread_is_alive; }); } void TokenManager::Update() { - while (WaitForInterval()) { + ::bosdyn::common::Duration retry_interval = m_user_token_initial_retry_interval; + ::bosdyn::common::Duration wait_interval = m_user_token_refresh_interval; + while (m_periodic_thread_helper->WaitForInterval(wait_interval)) { ::bosdyn::common::Status status = m_robot->AuthenticateWithToken(m_robot->GetUserToken()); if (!status) { fprintf(stderr, "AuthenticateWithToken failed: '%s'\n", status.DebugString().c_str()); + ErrorCallbackResult result = ErrorCallbackResult::kRetryWithExponentialBackOff; + if (status.code().value() == + ::bosdyn::api::GetAuthTokenResponse::STATUS_INVALID_TOKEN) { + std::function callback; + { + // Lock the mutex to safely access the callback. + std::lock_guard lock(m_refresh_mutex); + callback = m_token_refresh_error_callback; + } + if (callback) { + // Notify the callback that the token has expired. + try { + result = callback(status); + } catch (const std::exception& e) { + fprintf(stderr, "Exception in token refresh error callback: %s\n", + e.what()); + } + } + } + if (result == ErrorCallbackResult::kRetryWithExponentialBackOff || + result == ErrorCallbackResult::kDefaultAction) { + // Exponentially increase the retry interval. + wait_interval = retry_interval; + fprintf(stderr, "Retrying in %f seconds\n", ((double)wait_interval.count()) / 1e9); + retry_interval = std::min(retry_interval * 2, m_user_token_refresh_interval); + } else if (result == ErrorCallbackResult::kAbort) { + fprintf(stderr, "Aborting token manager thread.\n"); + break; + } else if (result == ErrorCallbackResult::kResumeNormalOperation) { + // Reset the retry interval to the initial value. + retry_interval = m_user_token_initial_retry_interval; + wait_interval = m_user_token_refresh_interval; + } else if (result == ErrorCallbackResult::kRetryImmediately) { + // Retry immediately. + wait_interval = std::chrono::milliseconds(0); + } + } else { + // Reset the retry interval on success. + retry_interval = m_user_token_initial_retry_interval; + wait_interval = m_user_token_refresh_interval; } } + // Callback result of kAbort will cause the thread to exit; mark it as down. + { + std::lock_guard lock(m_refresh_mutex); + m_refresh_thread_is_alive = false; + } + m_periodic_thread_helper->Stop(); +} + +void TokenManager::SetTokenRefreshErrorCallback( + std::function callback) { + std::lock_guard lock(m_refresh_mutex); + m_token_refresh_error_callback = callback; } } // namespace client diff --git a/cpp/bosdyn/client/robot/token_manager.h b/cpp/bosdyn/client/robot/token_manager.h index 229a574..a47a468 100644 --- a/cpp/bosdyn/client/robot/token_manager.h +++ b/cpp/bosdyn/client/robot/token_manager.h @@ -9,7 +9,14 @@ #pragma once +#include +#include +#include + +#include #include "robot.h" +#include "bosdyn/client/error_callback/error_callback_result.h" +#include "bosdyn/client/util/periodic_thread_helper.h" namespace bosdyn { @@ -19,30 +26,35 @@ class Robot; // Forward class declaration to resolve the circular dependency class TokenManager { public: - explicit TokenManager(::bosdyn::client::Robot* robot, - ::bosdyn::common::Duration refresh_interval = std::chrono::seconds(3600)); + explicit TokenManager( + ::bosdyn::client::Robot* robot, + ::bosdyn::common::Duration refresh_interval = std::chrono::seconds(3600), + ::bosdyn::common::Duration initial_retry_interval = std::chrono::seconds(1)); ~TokenManager(); + // Return true if the thread is running. + bool IsAlive() const; + void Stop(); + void SetTokenRefreshErrorCallback( + std::function callback); + private: // Refreshes the user token as needed. void Update(); - // Wait for the refresh interval and coordinate with the destructor on the condition variable. - bool WaitForInterval(); - ::bosdyn::client::Robot* m_robot; // Refresh token thread. std::thread m_refresh_thread; - // Lock for the condition variable + // Mutex to protect the token refresh callback and thread liveness boolean. std::mutex m_refresh_mutex; - // Condition Variable for checking if the thread should still be sleeping or be stopped. - std::condition_variable m_cv; + // Object used to coordinate the lifecycle and timing of the periodic thread. + std::unique_ptr m_periodic_thread_helper; // Boolean indicating it the thread is still running or if it has returned. bool m_refresh_thread_is_alive; @@ -50,6 +62,16 @@ class TokenManager { // Duration between token refreshes. This defaults to 1 hour, but can be updated by // the value passed to the constructor. ::bosdyn::common::Duration m_user_token_refresh_interval; + + // Initial duration between retries when a token refresh fails, where successive retries + // back off by a factor of two up to m_user_token_refresh_interval. This defaults to 1 second, + // but can be updated by the value passed to the constructor. + ::bosdyn::common::Duration m_user_token_initial_retry_interval; + + // Callback to be invoked when persistent token refresh operations have failed and the + // the token is expired. + std::function + m_token_refresh_error_callback; }; } // namespace client diff --git a/cpp/bosdyn/client/util/periodic_thread_helper.cpp b/cpp/bosdyn/client/util/periodic_thread_helper.cpp new file mode 100644 index 0000000..b6728a2 --- /dev/null +++ b/cpp/bosdyn/client/util/periodic_thread_helper.cpp @@ -0,0 +1,29 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#include "bosdyn/client/util/periodic_thread_helper.h" + +namespace bosdyn { +namespace client { + +void PeriodicThreadHelper::Stop() { + std::unique_lock lock(m_mutex); + m_should_exit = true; + lock.unlock(); + m_cv.notify_all(); +} + +bool PeriodicThreadHelper::WaitForInterval(::bosdyn::common::Duration interval) { + std::unique_lock lock(m_mutex); + if (m_should_exit) return false; + return !m_cv.wait_for(lock, interval, [this]() { return m_should_exit; }); +} + +} // namespace client +} // namespace bosdyn diff --git a/cpp/bosdyn/client/util/periodic_thread_helper.h b/cpp/bosdyn/client/util/periodic_thread_helper.h new file mode 100644 index 0000000..4882492 --- /dev/null +++ b/cpp/bosdyn/client/util/periodic_thread_helper.h @@ -0,0 +1,38 @@ +/** + * Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. + * + * Downloading, reproducing, distributing or otherwise using the SDK Software + * is subject to the terms and conditions of the Boston Dynamics Software + * Development Kit License (20191101-BDSDK-SL). + */ + + +#pragma once + +#include +#include + +#include "bosdyn/common/time.h" + +namespace bosdyn { +namespace client { + +class PeriodicThreadHelper { + public: + PeriodicThreadHelper() = default; + virtual ~PeriodicThreadHelper() = default; + + // Indicates that the thread should exit. + virtual void Stop(); + + // Wait for the specified interval. If thread shutdown was requested, return false. + virtual bool WaitForInterval(::bosdyn::common::Duration interval); + + private: + std::mutex m_mutex; + std::condition_variable m_cv; + bool m_should_exit = false; +}; + +} // namespace client +} // namespace bosdyn diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index 3e151e8..0bc9cef 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,14 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 5.0.1 BETA + +### Bug Fixes and Improvements + +#### SDK + +- Enhanced error handling and client notification for authentication token expiration and directory registration failures in long-running Spot API clients and services has been addressed. This was a long-standing issue that would occur if an API client was unable to refresh its authentication token for an extended period of time (due to e.g., prolonged network connectivity issues, issues with the robot's services), which would result in the token expiring without any clear indication to client code. Since most payload services are intended to run continuously, this would result in silent failures and loss of service functionality. To take advantage of this new functionality, register a error callback on the `Robot` class instance by calling `SetTokenRefreshErrorCallback` with the callback to invoke on error. For `DirectoryRegistrationKeepAlive` and `PayloadRegistrationKeepAlive`, these callbacks are supplied in the constructor. + ## Spot C++ SDK version 5.0.0 BETA ### Bug Fixes and Improvements diff --git a/protos/bosdyn/api/audio_visual.proto b/protos/bosdyn/api/audio_visual.proto new file mode 100644 index 0000000..0a3d602 --- /dev/null +++ b/protos/bosdyn/api/audio_visual.proto @@ -0,0 +1,374 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/audio_visual"; + +option java_outer_classname = "AudioVisualProto"; + +import "bosdyn/api/header.proto"; +import "google/protobuf/timestamp.proto"; +import "google/protobuf/duration.proto"; +import "google/protobuf/wrappers.proto"; +import "bosdyn/api/spot/choreography_params.proto"; + +// Defines an individual LED's color. +message Color { + // A color preset. Each preset maps to an RGB value. + enum Preset { + PRESET_UNKNOWN = 0; + PRESET_NORMAL = 1; + PRESET_WARNING = 2; + PRESET_DANGER = 3; + } + + // A specific RGB color. Each channel is from [0, 255]. + message RGB { + int32 r = 1; + int32 g = 2; + int32 b = 3; + } + + oneof color_type { + Preset preset = 1; + RGB rgb = 2; + } +} + +// A group of sequences that can be played back on the Spot AV System LEDs, SpotCam LEDs, or the +// Mood Light LEDs. +message LedSequenceGroup { + enum InterpolationMode { + INTERPOLATION_UNKNOWN = 0; + // Zero-order hold between this frame and the next. + INTERPOLATION_NONE = 1; + // Linearly interpolate the RGB channels from the color defined in this frame to + // the color defined in the next frame. If this is the last frame, the next + // frame is the frame at index 0. + INTERPOLATION_LINEAR = 2; + } + + // A sequence for an individual LED on the robot. + message LedSequence { + // A sequence of frames that create an animation. After the final frame in the sequence, the + // sequence loops back to the first frame. + message AnimationSequence { + message Frame { + // LED color. + Color color = 4; + // Duration of the frame. + google.protobuf.Duration duration = 2; + // Describes how the system should interpolate between this frame and the next. + InterpolationMode interpolation = 3; + } + repeated Frame frames = 1; + } + + // Blink this LED. + message BlinkSequence { + // LED Color. + Color color = 4; + // Blink period [0.1, 25.5] seconds. + google.protobuf.Duration period = 2; + // Duty cycle from [0, 1]. Determines what % of each period the LED should be on for. + float duty_cycle = 3; + } + + // Pulse this LED. + message PulseSequence { + // LED color. + Color color = 3; + // Pulse period [0.1, 25.5] seconds. + google.protobuf.Duration period = 2; + } + + // Special blink mode that is guaranteed to not affect robot perception. The pulse width of + // this sequence is fixed at approximately 30ms. + message SyncedBlinkSequence { + // LED color. + Color color = 3; + // Blink period [0.1, 25.5] seconds. + google.protobuf.Duration period = 2; + } + + // Set this LED to a solid color. + message SolidColorSequence { + // LED color. + Color color = 2; + } + + // Select one of the preset types. + oneof sequence_type { + AnimationSequence animation_sequence = 1; + BlinkSequence blink_sequence = 2; + PulseSequence pulse_sequence = 3; + SyncedBlinkSequence synced_blink_sequence = 4; + SolidColorSequence solid_color_sequence = 5; + } + } + + message SpotCamSequence { + message AnimationSequence { + // For Spot Cam, there are four LEDs at indices [0, 3]. The brightness for each LED may + // be set between [0.0, 1.0], where 0 is off and 1 is full brightness. + message Frame { + map brightnesses = 1; + } + + repeated Frame frames = 1; + } + + // Blink all the LEDs on Spot CAM at a certain frequency. + message BlinkSequence { + // LED brightness. + float brightness = 1; + // Blink period in seconds. + google.protobuf.Duration period = 2; + // Duty cycle from [0, 1]. Determines what % of each period the LED should be on for. + float duty_cycle = 3; + } + + // "Breathe" all the LEDs on Spot CAM at a certain frequency. + message BreatheSequence { + // LED brightness. + float brightness = 1; + // Blink period in seconds. + google.protobuf.Duration period = 2; + } + + // Set the four LEDs on spot cam at indices [0, 3] to brightnesses between [0.1, 1.0]. + message FixedBrightnessSequence { + map brightnesses = 1; + } + + oneof sequence_type { + AnimationSequence animation_sequence = 1; + BlinkSequence blink_sequence = 2; + BreatheSequence breathe_sequence = 3; + FixedBrightnessSequence fixed_brightness_sequence = 4; + } + } + + message StatusLightsSequence { + message Frame { + // Color for each of the Status Light LEDs during this frame. + Color top_left = 1; + Color upper_mid_left = 2; + Color lower_mid_left = 3; + Color bottom_left = 4; + Color top_right = 5; + Color upper_mid_right = 6; + Color lower_mid_right = 7; + Color bottom_right = 8; + // Frame duration. + google.protobuf.Duration duration = 9; + } + + repeated Frame frames = 1; + InterpolationMode interpolation = 2; + } + + // Sequences for each of the different lights in the AV System. If a sequence is not specified, + // then it defaults to "off". + LedSequence front_center = 1; + LedSequence front_left = 2; + LedSequence front_right = 3; + LedSequence hind_left = 4; + LedSequence hind_right = 5; + + // Additional sequences for Non-AV system lights. If a sequence is not specified, then it + // defaults to no operation (meaning, other systems can control these separate from the AV + // system). + SpotCamSequence spot_cam = 6; + StatusLightsSequence status_lights = 7; +} + +// A group of sequences that can be played on the Piezo buzzer. +message AudioSequenceGroup { + message BuzzerSequence { + message NoteWithDuration { + // The note specification (note name or rest) and modifiers (sharp/flat, octave). + bosdyn.api.spot.BuzzerNoteParams note = 1; + google.protobuf.Duration duration = 2; + } + repeated NoteWithDuration notes = 1; + } + + // A sequence that sets what is played on the buzzer. If a sequence is not specified, the + // buzzer defaults to not playing anything. + BuzzerSequence buzzer = 1; +} + +// Specifies a combination of sound, buzzer, and LED states. +message AudioVisualBehavior { + bool enabled = 1; + int32 priority = 2; + + // The sequences for the LEDs. + LedSequenceGroup led_sequence_group = 3; + // The sequence group for the buzzer. + AudioSequenceGroup audio_sequence_group = 4; +} + +message LiveAudioVisualBehavior { + string name = 1; + // Whether this behavior is marked permanent, and cannot be edited or deleted. + // This field will be filled out for ListBehaviors. + bool permanent = 2; + AudioVisualBehavior behavior = 3; +} + +/* RUN BEHAVIOR */ + +message RunBehaviorRequest { + RequestHeader header = 1; + + // Which behavior to run. + string name = 2; + + // The timestamp (in robot time) when this behavior will stop. + google.protobuf.Timestamp end_time = 3; + + // If this behavior is already running, setting this to true will restart the behavior's + // sequences from the beginning. If this behavior is not running, this parameter has no effect. + bool restart = 4; +} + +message RunBehaviorResponse { + enum Status { + STATUS_UNKNOWN = 0; + // The system attempted to run the specified behavior. Check run_result for more details. + STATUS_SUCCESS = 1; + // The specified behavior name does not exist in the system. + STATUS_DOES_NOT_EXIST = 2; + // The specified end_time has already expired. + STATUS_EXPIRED = 3; + } + + enum RunResult { + RESULT_UNKNOWN = 0; + // The behavior was run. + RESULT_BEHAVIOR_RUN = 1; + // The behavior was not run because the system is currently disabled. + RESULT_SYSTEM_DISABLED = 2; + // The behavior was not run because it is disabled. + RESULT_BEHAVIOR_DISABLED = 3; + // The behavior was not run because it has a lower priority than the currently active + // behavior. + RESULT_LOW_PRIORITY = 4; + // The behavior was not run, because it is already being run by a different client. + RESULT_ALREADY_RUNNING = 5; + } + + ResponseHeader header = 1; + Status status = 2; + + // The result of running this behavior. + RunResult run_result = 3; + +} + +/* STOP BEHAVIOR */ +message StopBehaviorRequest { + RequestHeader header = 1; + + // The name of the behavior to stop. + string behavior_name = 2; +} + +message StopBehaviorResponse { + enum Status { + STATUS_UNKNOWN = 0; + // StopBehavior ran successfully. Check result for more details. + STATUS_SUCCESS = 1; + // The client that issued this request is not the client that was running the behavior. + STATUS_INVALID_CLIENT = 2; + } + + ResponseHeader header = 1; + Status status = 2; +} + +/* LIST BEHAVIORS */ +message ListBehaviorsRequest { + RequestHeader header = 1; +} + +message ListBehaviorsResponse { + ResponseHeader header = 1; + + repeated LiveAudioVisualBehavior behaviors = 2; +} + +/* SYSTEM PARAMS */ +message PresetColorAssociation { + enum PredefinedColor { + PREDEFINED_UNKNOWN = 0; + PREDEFINED_GREEN = 1; + PREDEFINED_AMBER = 2; + PREDEFINED_RED = 3; + PREDEFINED_BLUE = 4; + PREDEFINED_PINK = 5; + PREDEFINED_PURPLE = 6; + PREDEFINED_WHITE = 7; + } + + oneof association { + PredefinedColor color_name = 1; + Color.RGB custom_value = 2; + } +} + +// These values will persist across robot reboots. +message AudioVisualSystemParams { + // True if the system is currently enabled. + bool enabled = 1; + + // The current max brightness [0, 1]. + float max_brightness = 2; + + // The buzzer's current max volume [0, 1]. + float buzzer_max_volume = 3; + + + PresetColorAssociation normal_color_association = 5; + PresetColorAssociation warning_color_association = 6; + PresetColorAssociation danger_color_association = 7; +} + +message GetSystemParamsRequest { + RequestHeader header = 1; +} + +message GetSystemParamsResponse { + ResponseHeader header = 1; + + AudioVisualSystemParams params = 2; +} + +message SetSystemParamsRequest { + RequestHeader header = 1; + + // True if the system is currently enabled. + google.protobuf.BoolValue enabled = 2; + + // The new max brightness value [0, 1]. + google.protobuf.FloatValue max_brightness = 3; + + // The new buzzer max volume value [0, 1]. + google.protobuf.FloatValue buzzer_max_volume = 4; + + + PresetColorAssociation normal_color_association = 6; + PresetColorAssociation warning_color_association = 7; + PresetColorAssociation danger_color_association = 8; +} + +message SetSystemParamsResponse { + ResponseHeader header = 1; +} diff --git a/protos/bosdyn/api/audio_visual_service.proto b/protos/bosdyn/api/audio_visual_service.proto new file mode 100644 index 0000000..bbf43c9 --- /dev/null +++ b/protos/bosdyn/api/audio_visual_service.proto @@ -0,0 +1,32 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/audio_visual_service"; + +option java_outer_classname = "AudioVisualServiceProto"; + +import "bosdyn/api/audio_visual.proto"; + +service AudioVisualService { + // Run an AudioVisualBehavior. + rpc RunBehavior(RunBehaviorRequest) returns (RunBehaviorResponse) {} + + // Stop an AudioVisualBehavior. + rpc StopBehavior(StopBehaviorRequest) returns (StopBehaviorResponse) {} + + + // List all AudioVisualBehaviors currently added to the AudioVisual Service. + rpc ListBehaviors(ListBehaviorsRequest) returns (ListBehaviorsResponse) {} + + // Get the current status of the system. + rpc GetSystemParams(GetSystemParamsRequest) returns (GetSystemParamsResponse) {} + + // Set the current status of the system. + rpc SetSystemParams(SetSystemParamsRequest) returns (SetSystemParamsResponse) {} +} diff --git a/protos/bosdyn/api/graph_nav/graph_nav.proto b/protos/bosdyn/api/graph_nav/graph_nav.proto index dba6f43..c7fdb4a 100644 --- a/protos/bosdyn/api/graph_nav/graph_nav.proto +++ b/protos/bosdyn/api/graph_nav/graph_nav.proto @@ -1138,7 +1138,7 @@ message ClearGraphResponse { } // Uploads a graph to the server. This graph will be appended to the graph that -// currently exists on the server. +// currently exists on the server unless replace_graph is specified. message UploadGraphRequest { // Common request header. RequestHeader header = 1; @@ -1154,6 +1154,14 @@ message UploadGraphRequest { // If true, validation warnings will be treated as errors, and STATUS_INVALID_GRAPH will be // returned. This is false by default. bool treat_validation_warnings_as_errors = 5; + + // If true, the old graph will be replaced with the uploaded graph, rather than merged + // with it. If the graph did not change the areas that Spot is currently localized to, the + // localization will be retained. When using this flag, clients should check for the + // replaced_graph flag in the UploadGraphResponse to determine if the robot acknowledged the + // flag. If it did not, the robot is running older software and the graph should be cleared + // prior to re-sending this request without this flag. + bool replace_graph = 6; } // This is a streaming version of the UploadGraph request. @@ -1275,6 +1283,13 @@ message UploadGraphResponse { // why the graph was invalid. Note that some graph validation errors are warnings and the robot // will be able to navigate on the graph even when they are present. ValidationStatus validation_status = 12; + + // If the replace_graph flag was provided in the corresponding request, this flag + // confirms that the graph has been updated in-place. Because old releases did not + // support the replace_graph request flag, clients should check for this response flag when + // using the request flag and retry with a ClearGraphRequest and resubmission without the + // request flag if this is unset. + bool replaced_graph = 13; } // The DownloadGraphRequest requests that the server send the graph (waypoints and edges) diff --git a/protos/bosdyn/api/robot_state.proto b/protos/bosdyn/api/robot_state.proto index 5b76b21..474525a 100644 --- a/protos/bosdyn/api/robot_state.proto +++ b/protos/bosdyn/api/robot_state.proto @@ -631,6 +631,7 @@ message ManipulatorState { Vec3 estimated_end_effector_force_in_hand = 13 [deprecated = true]; // The estimated wrench on the end-effector expressed in the end_effector (hand) frame. + // Only the force component of the wrench is currently set. Wrench estimated_end_effector_wrench_in_end_effector = 17; enum StowState { diff --git a/protos/bosdyn/api/spot/choreography_params.proto b/protos/bosdyn/api/spot/choreography_params.proto index 8564bef..2d510ed 100644 --- a/protos/bosdyn/api/spot/choreography_params.proto +++ b/protos/bosdyn/api/spot/choreography_params.proto @@ -683,6 +683,13 @@ message BuzzerNoteParams { NOTE_G = 5; NOTE_A = 6; NOTE_B = 7; + // This "note" corresponds to the frequencies at which peak Sound Pressure Level (SPL) + // (i.e., maximum loudness) is achieved for the buzzer. Note that sharp, flat, and octave + // are ignored for this "note". + NOTE_PEAK_SPL = 8; + // This "note" corresponds to a musical rest, i.e., no sound. Note that sharp, flat, and + // octave are ignored for this "note". + NOTE_REST = 9; } Note note = 1; From 8756dde41280601ca5001a94996f80c1624048a7 Mon Sep 17 00:00:00 2001 From: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Date: Tue, 7 Oct 2025 12:11:35 -0400 Subject: [PATCH 04/15] Release v5.0.1.1 of Boston Dynamics Spot SDK --- README.md | 2 +- cpp/CMakeLists.txt | 2 +- docs/cpp_release_notes.md | 6 ++ protos/bosdyn/api/audio_visual.proto | 58 ++++++++++++++++++++ protos/bosdyn/api/audio_visual_service.proto | 8 +++ protos/bosdyn/api/world_object.proto | 53 ++++++++++++++++++ 6 files changed, 127 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 04ceb2b..a165fa2 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+ - [Payload developer documentation](https://dev.bostondynamics.com/docs/payload/readme). Payloads add additional sensing, communication, and control capabilities beyond what the base platform provides. The Payload ICD covers the mechanical, electrical, and software interfaces that Spot supports. - [Spot API protocol definition](https://dev.bostondynamics.com/docs/protos/readme). 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. -This is version 5.0.1 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. +This is version 5.0.1.1 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. ## Contents diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index d15f58a..d5fcedd 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -7,7 +7,7 @@ # This file is autogenerated. cmake_minimum_required (VERSION 3.10.2) -project (bosdyn VERSION 5.0.1) +project (bosdyn VERSION 5.0.1.1) # Dependencies: find_package(protobuf REQUIRED) diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index 0bc9cef..f7b990f 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,12 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 5.0.1.1 BETA + +There have been no changes in the C++ SDK between 5.0.1 and this version. + +Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API changes included in this release. + ## Spot C++ SDK version 5.0.1 BETA ### Bug Fixes and Improvements diff --git a/protos/bosdyn/api/audio_visual.proto b/protos/bosdyn/api/audio_visual.proto index 0a3d602..6b38c97 100644 --- a/protos/bosdyn/api/audio_visual.proto +++ b/protos/bosdyn/api/audio_visual.proto @@ -294,6 +294,64 @@ message StopBehaviorResponse { Status status = 2; } +/* ADD BEHAVIOR */ +// Before you consider adding your own AV behaviors, please consider that +// the ‘solid lights on’ behavior can overheat the AV board if you leave +// it on for too long with certain RGB values. +message AddOrModifyBehaviorRequest { + RequestHeader header = 1; + // New behavior's name. + string name = 2; + // Behavior to add. + AudioVisualBehavior behavior = 3; +} + +message AddOrModifyBehaviorResponse { + enum Status { + STATUS_UNKNOWN = 0; + // The behavior was added successfully. + STATUS_SUCCESS = 1; + // A permanent behavior cannot be modified. + STATUS_MODIFY_PERMANENT = 2; + // The request contained an invalid field. + STATUS_INVALID = 3; + } + + ResponseHeader header = 1; + Status status = 2; + + repeated string deprecated_invalid_fields = 3 [deprecated = true]; + + // Human readable error message. Only set for STATUS_INVALID. + string error_message = 5; + + // Only for STATUS_SUCCESS, specifies the resulting LiveAudioVisualBehavior object. + LiveAudioVisualBehavior live_behavior = 4; +} + +/* DELETE BEHAVIOR */ +message DeleteBehaviorsRequest { + RequestHeader header = 1; + // Behavior names to remove. + repeated string behavior_names = 2; +} + +message DeleteBehaviorsResponse { + enum Status { + STATUS_UNKNOWN = 0; + // Behaviors were deleted successfully. + STATUS_SUCCESS = 1; + // A specified behavior name was not present in the system. + STATUS_DOES_NOT_EXIST = 2; + // A permanent behavior cannot be deleted. + STATUS_DELETE_PERMANENT = 3; + } + + ResponseHeader header = 1; + Status status = 2; + repeated LiveAudioVisualBehavior deleted_behaviors = 3; +} + /* LIST BEHAVIORS */ message ListBehaviorsRequest { RequestHeader header = 1; diff --git a/protos/bosdyn/api/audio_visual_service.proto b/protos/bosdyn/api/audio_visual_service.proto index bbf43c9..1f4b119 100644 --- a/protos/bosdyn/api/audio_visual_service.proto +++ b/protos/bosdyn/api/audio_visual_service.proto @@ -20,6 +20,14 @@ service AudioVisualService { // Stop an AudioVisualBehavior. rpc StopBehavior(StopBehaviorRequest) returns (StopBehaviorResponse) {} + // Add a new or modify an existing AudioVisualBehavior. + // Before you consider adding your own AV behaviors, please consider that + // the ‘solid lights on’ behavior can overheat the AV board if you leave + // it on for too long with certain RGB values. + rpc AddOrModifyBehavior(AddOrModifyBehaviorRequest) returns (AddOrModifyBehaviorResponse) {} + + // Delete one or more AudioVisualBehaviors. + rpc DeleteBehaviors(DeleteBehaviorsRequest) returns (DeleteBehaviorsResponse) {} // List all AudioVisualBehaviors currently added to the AudioVisual Service. rpc ListBehaviors(ListBehaviorsRequest) returns (ListBehaviorsResponse) {} diff --git a/protos/bosdyn/api/world_object.proto b/protos/bosdyn/api/world_object.proto index 37e551a..dc2258e 100644 --- a/protos/bosdyn/api/world_object.proto +++ b/protos/bosdyn/api/world_object.proto @@ -57,6 +57,8 @@ message WorldObject { repeated DrawableProperties drawable_properties = 5; // The apriltag properties describe any fiducial identifying an object. AprilTagProperties apriltag_properties = 6; + // Properties of a moving entity. + TrackedEntityProperties tracked_entity_properties = 13; // Property for a user no-go NoGoRegionProperties nogo_region_properties = 14; // The image properties describe any camera and image coordinates associated with an object. @@ -312,6 +314,57 @@ message BoundingBoxProperties { string frame = 2; } +// Represents an entity (object that possibly has a mind of its own, like a person or vehicle) that +// is being tracked by the world object service. +message TrackedEntityProperties { + // Unique ID of the entity according to the tracking system. Note that + // this does not persist between reboots, and an entity track may be lost + // and regained later, possibly with a new ID. + int32 entity_id = 1; + enum EntityType { + ENTITY_TYPE_UNKNOWN = 0; // Unset. + ENTITY_TYPE_3D_BLOB = 1; // Tracked using 3D blob detection. + ENTITY_TYPE_PERSON = 2; // Tracked using person detection. + ENTITY_TYPE_FORKLIFT = 3; + ENTITY_TYPE_SPOT = 4; + } + + // Current type of the entity. + EntityType entity_type = 2; + // The pose of the entity is expressed in this frame. + string frame = 3; + // Bounding box size expressed in the reference frame. This is the + // side length of the bounding box. + Vec3 size_in_frame = 4; + // The velocity of the object will be expressed in this frame. + string velocity_frame = 5; + // Velocity estimate expressed in the given frame. + Vec3 velocity = 6; + // Number from 0-1 indicating whether we believe this object + // exists. + double likelihood_exists = 8; + // Map from type enum (e.g., "person") to a value from 0-1 indicating + // our belief of how likely this object is the corresponding type. + map type_likelihoods = 11; + // Number of times we've observed this entity. + int32 num_observations = 10; + // The maximum length of the observed velocity vector for this entity. + double max_observed_velocity = 12; + reserved 9; + // Average velocity over a window. The size of the window varies depending on how + // old the entity is. See velocity_window_size_seconds for details. + Vec3 windowed_average_velocity = 14; + // This is the number of seconds in the window used to compute windowed_average_velocity. + double velocity_window_size_seconds = 15; + // This is the absolute magnitude of the velocity over a window -- that is: + // sum_{i in window} (||v_i||) where v_i = the velocity at that time. This is the + // same window size as "velocity_window_size_seconds". Note that this velocity is 2d, projected + // to the x/y/ plane in vision frame. + double windowed_velocity_magnitude = 16; + // Estimate of the entity's direction. + Vec3 direction_in_vision = 17; +} + // The drawing and visualization information for a world object. message DrawableProperties { From 1d527740f59b47df63cbe3431c2e6515845588dd Mon Sep 17 00:00:00 2001 From: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Date: Tue, 21 Oct 2025 21:16:39 -0400 Subject: [PATCH 05/15] Release v5.0.1.2 of Boston Dynamics Spot SDK --- README.md | 2 +- cpp/CMakeLists.txt | 2 +- docs/cpp_release_notes.md | 6 ++++++ protos/bosdyn/api/world_object.proto | 1 + 4 files changed, 9 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index a165fa2..8ed8e80 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+ - [Payload developer documentation](https://dev.bostondynamics.com/docs/payload/readme). Payloads add additional sensing, communication, and control capabilities beyond what the base platform provides. The Payload ICD covers the mechanical, electrical, and software interfaces that Spot supports. - [Spot API protocol definition](https://dev.bostondynamics.com/docs/protos/readme). 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. -This is version 5.0.1.1 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. +This is version 5.0.1.2 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. ## Contents diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index d5fcedd..c47bd08 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -7,7 +7,7 @@ # This file is autogenerated. cmake_minimum_required (VERSION 3.10.2) -project (bosdyn VERSION 5.0.1.1) +project (bosdyn VERSION 5.0.1.2) # Dependencies: find_package(protobuf REQUIRED) diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index f7b990f..35a766b 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,12 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 5.0.1.2 BETA + +There have been no changes in the C++ SDK between 5.0.1.1 and this version. + +Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API changes included in this release. + ## Spot C++ SDK version 5.0.1.1 BETA There have been no changes in the C++ SDK between 5.0.1 and this version. diff --git a/protos/bosdyn/api/world_object.proto b/protos/bosdyn/api/world_object.proto index dc2258e..c2d0d1e 100644 --- a/protos/bosdyn/api/world_object.proto +++ b/protos/bosdyn/api/world_object.proto @@ -88,6 +88,7 @@ enum WorldObjectType { WORLD_OBJECT_APRILTAG = 2; WORLD_OBJECT_IMAGE_COORDINATES = 5; WORLD_OBJECT_DOCK = 6; + WORLD_OBJECT_TRACKED_ENTITY = 7; WORLD_OBJECT_USER_NOGO = 8; WORLD_OBJECT_STAIRCASE = 9; } From 95a47ee2cd8e0b0712f078f50950d7e111339ec7 Mon Sep 17 00:00:00 2001 From: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Date: Mon, 22 Dec 2025 13:50:42 -0500 Subject: [PATCH 06/15] Release v5.1.0 of Boston Dynamics Spot SDK --- README.md | 2 +- cpp/CMakeLists.txt | 2 +- .../client/data_buffer/signal_schema_key.h | 1 + cpp/bosdyn/client/data_chunk/data_chunking.h | 8 +- .../proto_enum_to_stderror_macro.h | 122 +++++---------- .../proto_enum_to_stderror_macro_source.h | 108 ++++--------- .../client/graph_nav/graph_nav_client.cpp | 68 ++++++++ .../client/graph_nav/graph_nav_client.h | 21 +++ cpp/bosdyn/client/robot/robot.cpp | 17 +- cpp/bosdyn/client/robot/robot.h | 3 + cpp/bosdyn/common/common_header_handling.cpp | 2 +- cpp/bosdyn/common/string_util.cpp | 2 + cpp/bosdyn/common/string_util.h | 1 + cpp/bosdyn/common/strip_bytes_fields.cpp | 10 ++ cpp/bosdyn/common/strip_bytes_fields.h | 1 + cpp/bosdyn/common/time.cpp | 23 ++- cpp/bosdyn/math/proto_math.cpp | 7 + cpp/bosdyn/math/proto_math.h | 1 + docs/cpp_release_notes.md | 20 +++ protos/bosdyn/api/autowalk/walks.proto | 74 +++++++++ protos/bosdyn/api/basic_command.proto | 8 +- protos/bosdyn/api/data_acquisition.proto | 20 +++ .../bosdyn/api/data_acquisition_service.proto | 1 + protos/bosdyn/api/docking/docking.proto | 7 +- protos/bosdyn/api/fiducial_purpose.proto | 23 +++ protos/bosdyn/api/graph_nav/graph_nav.proto | 49 ++++++ .../api/graph_nav/graph_nav_service.proto | 3 + protos/bosdyn/api/graph_nav/map.proto | 7 + protos/bosdyn/api/hazard_avoidance.proto | 147 ++++++++++++++++++ .../bosdyn/api/hazard_avoidance_service.proto | 25 +++ protos/bosdyn/api/log_status/log_status.proto | 54 +++++++ .../api/log_status/log_status_service.proto | 6 + protos/bosdyn/api/mission/mission.proto | 4 + protos/bosdyn/api/mission/nodes.proto | 50 +++++- .../bosdyn/api/network_compute_bridge.proto | 1 + protos/bosdyn/api/power.proto | 2 + protos/bosdyn/api/robot_state.proto | 4 + protos/bosdyn/api/service_fault.proto | 1 + protos/bosdyn/api/signals.proto | 9 ++ protos/bosdyn/api/spot/robot_command.proto | 4 + protos/bosdyn/api/spot_cam/network.proto | 1 + protos/bosdyn/api/world_object.proto | 4 + 42 files changed, 745 insertions(+), 178 deletions(-) create mode 100644 protos/bosdyn/api/fiducial_purpose.proto create mode 100644 protos/bosdyn/api/hazard_avoidance.proto create mode 100644 protos/bosdyn/api/hazard_avoidance_service.proto diff --git a/README.md b/README.md index 8ed8e80..17774b4 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+ - [Payload developer documentation](https://dev.bostondynamics.com/docs/payload/readme). Payloads add additional sensing, communication, and control capabilities beyond what the base platform provides. The Payload ICD covers the mechanical, electrical, and software interfaces that Spot supports. - [Spot API protocol definition](https://dev.bostondynamics.com/docs/protos/readme). 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. -This is version 5.0.1.2 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. +This is version 5.1.0 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. ## Contents diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index c47bd08..177f6e5 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -7,7 +7,7 @@ # This file is autogenerated. cmake_minimum_required (VERSION 3.10.2) -project (bosdyn VERSION 5.0.1.2) +project (bosdyn VERSION 5.1.0) # Dependencies: find_package(protobuf REQUIRED) diff --git a/cpp/bosdyn/client/data_buffer/signal_schema_key.h b/cpp/bosdyn/client/data_buffer/signal_schema_key.h index bfa21cb..b7829c4 100644 --- a/cpp/bosdyn/client/data_buffer/signal_schema_key.h +++ b/cpp/bosdyn/client/data_buffer/signal_schema_key.h @@ -9,6 +9,7 @@ #pragma once +#include #include namespace bosdyn { diff --git a/cpp/bosdyn/client/data_chunk/data_chunking.h b/cpp/bosdyn/client/data_chunk/data_chunking.h index a4a8d3b..8b231c8 100644 --- a/cpp/bosdyn/client/data_chunk/data_chunking.h +++ b/cpp/bosdyn/client/data_chunk/data_chunking.h @@ -9,6 +9,8 @@ #pragma once +#include "google/protobuf/io/coded_stream.h" +#include "google/protobuf/io/zero_copy_stream_impl_lite.h" #include "bosdyn/client/error_codes/sdk_error_code.h" #include "bosdyn/client/service_client/result.h" @@ -42,8 +44,12 @@ Result MessageFromDataChunks(const std::vector // This macro goes in some helper file. -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ns, ns_def, ns_def_parenthesis) \ - namespace std { \ - template <> \ - struct is_error_code_enum : public true_type {}; \ - } \ - ns_def std::error_code make_error_code(ns::enumclass); \ - ns_def_parenthesis +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ns) \ + namespace std { \ + template <> \ + struct is_error_code_enum<::ns::enumclass> : public true_type {}; \ + } \ + namespace ns { \ + std::error_code make_error_code(::ns::enumclass); \ + } // Define wrapper for macro above for each namespace, so it is easier to call the macro -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_API(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api, \ - namespace bosdyn{namespace api{ \ - , \ - }}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_AUTO_RETURN(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::auto_return, \ - namespace bosdyn{namespace api{namespace auto_return{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_AUTOWALK(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::autowalk, \ - namespace bosdyn{namespace api{namespace autowalk{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_KEEPALIVE(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::keepalive, \ - namespace bosdyn{namespace api{namespace keepalive{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_LOG_STATUS(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::log_status, \ - namespace bosdyn{namespace api{namespace log_status{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_SPOT(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::spot, \ - namespace bosdyn{namespace api{namespace spot{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_MISSION(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::mission, \ - namespace bosdyn{namespace api{namespace mission{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_GRAPHNAV(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::graph_nav, \ - namespace bosdyn{namespace api{namespace graph_nav{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_METRICS(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::metrics_logging, \ - namespace bosdyn{namespace api{namespace metrics_logging{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_INTERNAL(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::internal, \ - namespace bosdyn{namespace api{namespace internal{ \ - , \ - }}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_LOCALNAV(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER( \ - enumclass, ::bosdyn::api::internal::localnav, \ - namespace bosdyn{namespace api{namespace internal{namespace localnav{ \ - , \ - }}}}) - -#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_DOCKING(enumclass) \ - DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, ::bosdyn::api::docking, \ - namespace bosdyn{namespace api{namespace docking{ \ - , \ - }}}) +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_API(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_AUTO_RETURN(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::auto_return) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_AUTOWALK(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::autowalk) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_KEEPALIVE(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::keepalive) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_LOG_STATUS(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::log_status) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_SPOT(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::spot) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_MISSION(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::mission) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_GRAPHNAV(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::graph_nav) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_METRICS(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::metrics_logging) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_INTERNAL(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::internal) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_LOCALNAV(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::internal::localnav) + +#define DEFINE_PROTO_ENUM_ERRORCODE_HEADER_DOCKING(enumclass) \ + DEFINE_PROTO_ENUM_ERRORCODE_HEADER(enumclass, bosdyn::api::docking) diff --git a/cpp/bosdyn/client/error_codes/proto_enum_to_stderror_macro_source.h b/cpp/bosdyn/client/error_codes/proto_enum_to_stderror_macro_source.h index 012f3ef..15c628c 100644 --- a/cpp/bosdyn/client/error_codes/proto_enum_to_stderror_macro_source.h +++ b/cpp/bosdyn/client/error_codes/proto_enum_to_stderror_macro_source.h @@ -11,8 +11,7 @@ #include "bosdyn/common/success_condition.h" // This macro goes in some helper file. -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ns, ns_def, ns_def_parenthesis, \ - equivalent_condition) \ +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ns, equivalent_condition) \ namespace { \ struct enumclass##Category : public std::error_category { \ const char* name() const noexcept override { return #enumclass; } \ @@ -32,100 +31,49 @@ } \ const enumclass##Category enumclass##Category_category{}; \ } \ - ns_def std::error_code make_error_code(enumclass value) { \ + namespace ns { \ + std::error_code make_error_code(enumclass value) { \ return {static_cast(value), enumclass##Category_category}; \ } \ - ns_def_parenthesis + } // Define wrapper for macro above for each namespace, so it is easier to call the macro #define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_API(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api, \ - namespace bosdyn{namespace api{ \ - , \ - }}, \ - equivalent_condition) + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_AUTO_RETURN(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::auto_return, \ - namespace bosdyn{namespace api{namespace auto_return{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_AUTO_RETURN(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::auto_return, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_AUTOWALK(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::autowalk, \ - namespace bosdyn{namespace api{namespace autowalk{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_AUTOWALK(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::autowalk, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_KEEPALIVE(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::keepalive, \ - namespace bosdyn{namespace api{namespace keepalive{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_KEEPALIVE(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::keepalive, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_LOG_STATUS(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::log_status, \ - namespace bosdyn{namespace api{namespace log_status{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_LOG_STATUS(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::log_status, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_SPOT(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::spot, \ - namespace bosdyn{namespace api{namespace spot{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_SPOT(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::spot, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_MISSION(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::mission, \ - namespace bosdyn{namespace api{namespace mission{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_MISSION(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::mission, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_GRAPHNAV(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::graph_nav, \ - namespace bosdyn{namespace api{namespace graph_nav{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_GRAPHNAV(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::graph_nav, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_METRICS(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::metrics_logging, \ - namespace bosdyn{namespace api{namespace metrics_logging{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_METRICS(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::metrics_logging, equivalent_condition) -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_INTERNAL(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::internal, \ - namespace bosdyn{namespace api{namespace internal{ \ - , \ - }}}, \ - equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_INTERNAL(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::internal, equivalent_condition) #define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_LOCALNAV(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL( \ - enumclass, ::bosdyn::api::internal::localnav, \ - namespace bosdyn{namespace api{namespace internal{namespace localnav{ \ - , \ - }}}}, \ - equivalent_condition) - -#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_DOCKING(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::docking, \ - namespace bosdyn{namespace api{namespace docking{ \ - , \ - }}}, \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::internal::localnav, \ equivalent_condition) +#define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_DOCKING(enumclass, equivalent_condition) \ + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::docking, equivalent_condition) + #define DEFINE_PROTO_ENUM_ERRORCODE_IMPL_LONG_RANGE_MAP(enumclass, equivalent_condition) \ - DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, ::bosdyn::api::internal, \ - namespace bosdyn{namespace api{namespace internal{ \ - , \ - }}}, \ - equivalent_condition) + DEFINE_PROTO_ENUM_ERRORCODE_IMPL(enumclass, bosdyn::api::internal, equivalent_condition) diff --git a/cpp/bosdyn/client/graph_nav/graph_nav_client.cpp b/cpp/bosdyn/client/graph_nav/graph_nav_client.cpp index 307c6a1..348b4c2 100644 --- a/cpp/bosdyn/client/graph_nav/graph_nav_client.cpp +++ b/cpp/bosdyn/client/graph_nav/graph_nav_client.cpp @@ -548,6 +548,74 @@ void GraphNavClient::OnUploadEdgeSnapshotComplete( promise.set_value({ret_status, std::move(response)}); } +std::shared_future GraphNavClient::UploadSnapshotsAsync( + ::bosdyn::api::graph_nav::UploadSnapshotsRequest::Snapshots& input_request, + const RPCParameters& parameters) { + std::promise response; + std::shared_future future = response.get_future(); + BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!"); + + std::vector<::bosdyn::api::DataChunk> chunks; + std::vector<::bosdyn::api::graph_nav::UploadSnapshotsRequest> requests; + ::bosdyn::common::Status status = + MessageToDataChunks<::bosdyn::api::graph_nav::UploadSnapshotsRequest::Snapshots>( + input_request, &chunks); + if (!status) { + response.set_value({status, {}}); + return future; + } + + for (auto& chunk : chunks) { + ::bosdyn::api::graph_nav::UploadSnapshotsRequest request; + + auto request_chunk = request.mutable_chunk(); + *request_chunk = std::move(chunk); + + // For each request, apply the lease processor to automatically include a lease. + auto lease_status = ProcessRequestWithLease(&request, m_lease_wallet.get(), + ::bosdyn::client::kBodyResource); + if (!lease_status) { + // Failed to set a lease with the lease wallet. Return early since the request will fail + // without a lease. + response.set_value({lease_status, {}}); + return future; + } + + requests.emplace_back(std::move(request)); + } + + MessagePumpCallBase* one_time = + InitiateRequestStreamAsyncCall<::bosdyn::api::graph_nav::UploadSnapshotsRequest, + ::bosdyn::api::graph_nav::UploadSnapshotsResponse, + ::bosdyn::api::graph_nav::UploadSnapshotsResponse>( + std::move(requests), + std::bind( + &::bosdyn::api::graph_nav::GraphNavService::StubInterface::AsyncUploadSnapshots, + m_stub.get(), _1, _2, _3, _4), + std::bind(&GraphNavClient::OnUploadSnapshotsComplete, this, _1, _2, _3, _4, _5), + std::move(response), parameters); + + return future; +} + +UploadSnapshotsResultType GraphNavClient::UploadSnapshots( + ::bosdyn::api::graph_nav::UploadSnapshotsRequest::Snapshots& input_request, + const RPCParameters& parameters) { + return UploadSnapshotsAsync(input_request, parameters).get(); +} + +void GraphNavClient::OnUploadSnapshotsComplete( + MessagePumpCallBase* call, + const std::vector<::bosdyn::api::graph_nav::UploadSnapshotsRequest>&& request, + ::bosdyn::api::graph_nav::UploadSnapshotsResponse&& response, const grpc::Status& status, + std::promise promise) { + ::bosdyn::common::Status ret_status = ProcessResponseWithLeaseAndGetFinalStatus< + ::bosdyn::api::graph_nav::UploadSnapshotsResponse>(status, response, SDKErrorCode::Success, + m_lease_wallet.get()); + + promise.set_value({ret_status, std::move(response)}); +} + std::shared_future GraphNavClient::DownloadWaypointSnapshotAsync( ::bosdyn::api::graph_nav::DownloadWaypointSnapshotRequest& request, diff --git a/cpp/bosdyn/client/graph_nav/graph_nav_client.h b/cpp/bosdyn/client/graph_nav/graph_nav_client.h index 3114748..f77fb0a 100644 --- a/cpp/bosdyn/client/graph_nav/graph_nav_client.h +++ b/cpp/bosdyn/client/graph_nav/graph_nav_client.h @@ -54,6 +54,9 @@ typedef Result<::bosdyn::api::graph_nav::UploadWaypointSnapshotResponse> // Return type for the UploadEdgeSnapshot method. typedef Result<::bosdyn::api::graph_nav::UploadEdgeSnapshotResponse> UploadEdgeSnapshotResultType; +// Return type for the UploadSnapshots method. +typedef Result<::bosdyn::api::graph_nav::UploadSnapshotsResponse> UploadSnapshotsResultType; + // Return type for the DownloadWaypointSnapshot method. typedef Result<::bosdyn::api::graph_nav::WaypointSnapshot> DownloadWaypointSnapshotResultType; @@ -177,6 +180,16 @@ class GraphNavClient : public ServiceClient { ::bosdyn::api::graph_nav::EdgeSnapshot& request, const RPCParameters& parameters = RPCParameters()); + // Asynchronous method to execute a UploadSnapshots request. + std::shared_future UploadSnapshotsAsync( + ::bosdyn::api::graph_nav::UploadSnapshotsRequest::Snapshots& request, + const RPCParameters& parameters = RPCParameters()); + + // Synchronous method to execute a UploadSnapshots request. + UploadSnapshotsResultType UploadSnapshots( + ::bosdyn::api::graph_nav::UploadSnapshotsRequest::Snapshots& request, + const RPCParameters& parameters = RPCParameters()); + // Asynchronous method to execute a DownloadWaypointSnapshot request. Only one response // message is returned with all the data chunks received from the service concatenated // together. @@ -335,6 +348,14 @@ class GraphNavClient : public ServiceClient { ::bosdyn::api::graph_nav::UploadEdgeSnapshotResponse&& response, const grpc::Status& status, std::promise promise); + // Callback that will return the UploadSnapshotsResponse message after UploadSnapshots rpc + // returns to the client. + void OnUploadSnapshotsComplete( + MessagePumpCallBase* call, + const std::vector<::bosdyn::api::graph_nav::UploadSnapshotsRequest>&& request, + ::bosdyn::api::graph_nav::UploadSnapshotsResponse&& response, const grpc::Status& status, + std::promise promise); + // Callback that will return the DownloadWaypointSnapshotResponse message after // DownloadWaypointSnapshot rpc returns to the client. void OnDownloadWaypointSnapshotComplete( diff --git a/cpp/bosdyn/client/robot/robot.cpp b/cpp/bosdyn/client/robot/robot.cpp index a315b1f..8860e44 100644 --- a/cpp/bosdyn/client/robot/robot.cpp +++ b/cpp/bosdyn/client/robot/robot.cpp @@ -166,14 +166,17 @@ Result> Robot::EnsureChannel( std::map::const_iterator endpoint_iter = m_bootstrap_endpoints_by_name.find(service_name); if (endpoint_iter == m_bootstrap_endpoints_by_name.end()) { + std::unique_lock lock(m_authorities_and_endpoints_mutex); endpoint_iter = m_endpoints_by_name.find(service_name); if (endpoint_iter == m_endpoints_by_name.end()) { // Sync with Directory to get the endpoints. + lock.unlock(); Result> services_result = ListServices(); if (!services_result.status) { return {services_result.status, nullptr}; } + lock.lock(); endpoint_iter = m_endpoints_by_name.find(service_name); if (endpoint_iter == m_endpoints_by_name.end()) { return {::bosdyn::common::Status(ClientCreationErrorCode::UnregisteredService, @@ -199,14 +202,17 @@ Result> Robot::EnsureChannel( std::map::const_iterator authority_iter = m_bootstrap_authorities_by_name.find(service_name); if (authority_iter == m_bootstrap_authorities_by_name.end()) { + std::unique_lock lock(m_authorities_and_endpoints_mutex); authority_iter = m_authorities_by_name.find(service_name); if (authority_iter == m_authorities_by_name.end()) { // Sync with Directory to get the authorities. + lock.unlock(); Result> services_result = ListServices(); if (!services_result.status) { return {services_result.status, nullptr}; } + lock.lock(); authority_iter = m_authorities_by_name.find(service_name); if (authority_iter == m_authorities_by_name.end()) { return {::bosdyn::common::Status(ClientCreationErrorCode::UnregisteredService, @@ -331,10 +337,13 @@ Result> Robot::UpdateInformationFromLis return {result.status, {}}; } - m_authorities_by_name.clear(); - for (const auto& entry : result.response.service_entries()) { - service_list.push_back(entry); - m_authorities_by_name[entry.name()] = entry.authority(); + { + std::lock_guard lock(m_authorities_and_endpoints_mutex); + m_authorities_by_name.clear(); + for (const auto& entry : result.response.service_entries()) { + service_list.push_back(entry); + m_authorities_by_name[entry.name()] = entry.authority(); + } } return {::bosdyn::common::Status(SDKErrorCode::Success), std::move(service_list)}; diff --git a/cpp/bosdyn/client/robot/robot.h b/cpp/bosdyn/client/robot/robot.h index 3c80886..224dc6c 100644 --- a/cpp/bosdyn/client/robot/robot.h +++ b/cpp/bosdyn/client/robot/robot.h @@ -352,6 +352,9 @@ class Robot { // name and value represents the authority. const std::map m_bootstrap_authorities_by_name; + // Protect access to the authorities and endpoints maps. + std::mutex m_authorities_and_endpoints_mutex; + // Map to store authorities for the services as received from the Directory service. Key in the // map represents the service name and value represents the authority. std::map m_authorities_by_name; diff --git a/cpp/bosdyn/common/common_header_handling.cpp b/cpp/bosdyn/common/common_header_handling.cpp index 6965feb..95eca39 100644 --- a/cpp/bosdyn/common/common_header_handling.cpp +++ b/cpp/bosdyn/common/common_header_handling.cpp @@ -37,7 +37,7 @@ void PrepareResponseHeader(const ::bosdyn::api::RequestHeader& request_header, void StripLargeByteFields(::google::protobuf::Message* proto_message) { // Operates on Request and Response messages. - const std::string message_type = proto_message->GetTypeName(); + const std::string& message_type = proto_message->GetTypeName(); const auto& whitelist_map = ::bosdyn::common::strip_messages::kWhitelistedBytesFieldsMap; auto strip_message_func = whitelist_map.find(message_type); if (strip_message_func != whitelist_map.end()) { diff --git a/cpp/bosdyn/common/string_util.cpp b/cpp/bosdyn/common/string_util.cpp index fa29b58..5d1145b 100644 --- a/cpp/bosdyn/common/string_util.cpp +++ b/cpp/bosdyn/common/string_util.cpp @@ -9,6 +9,7 @@ #include "string_util.h" +#include #include namespace bosdyn { @@ -32,6 +33,7 @@ std::string RemoveSuffix(const std::string& str, const std::string& suffix) { return EndsWith(str, suffix) ? str.substr(0, str.length() - suffix.length()) : str; } + } // namespace common } // namespace bosdyn diff --git a/cpp/bosdyn/common/string_util.h b/cpp/bosdyn/common/string_util.h index f95fba4..1646615 100644 --- a/cpp/bosdyn/common/string_util.h +++ b/cpp/bosdyn/common/string_util.h @@ -24,6 +24,7 @@ bool StartsWith(const std::string& str, const std::string& start); /// If str ends with suffix, return the part preceding, otherwise the original value of str. std::string RemoveSuffix(const std::string& str, const std::string& suffix); + } // namespace common } // namespace bosdyn diff --git a/cpp/bosdyn/common/strip_bytes_fields.cpp b/cpp/bosdyn/common/strip_bytes_fields.cpp index 1b50034..4cb0809 100644 --- a/cpp/bosdyn/common/strip_bytes_fields.cpp +++ b/cpp/bosdyn/common/strip_bytes_fields.cpp @@ -24,6 +24,7 @@ std::map kWhitelistedBytesFie {"bosdyn.api.GetPointCloudResponse", StripPointCloudResponse}, {"bosdyn.api.graph_nav.UploadWaypointSnapshotRequest", StripUploadWaypointRequest}, {"bosdyn.api.graph_nav.UploadEdgeSnapshotRequest", StripUploadEdgeRequest}, + {"bosdyn.api.graph_nav.UploadSnapshotsRequest", StripUploadSnapshotsRequest}, {"bosdyn.api.graph_nav.DownloadWaypointSnapshotResponse", StripDownloadWaypointResponse}, {"bosdyn.api.graph_nav.DownloadEdgeSnapshotResponse", StripDownloadEdgeResponse}, {"bosdyn.api.RecordDataBlobsRequest", StripRecordDataBlobsRequest}, @@ -84,6 +85,15 @@ bool StripUploadEdgeRequest(::google::protobuf::Message* proto_message) { return false; } +bool StripUploadSnapshotsRequest(::google::protobuf::Message* proto_message) { + if (auto* upload_msg = + dynamic_cast<::bosdyn::api::graph_nav::UploadSnapshotsRequest*>(proto_message)) { + upload_msg->mutable_chunk()->clear_data(); + return true; + } + return false; +} + bool StripDownloadWaypointResponse(::google::protobuf::Message* proto_message) { if (auto* download_msg = dynamic_cast<::bosdyn::api::graph_nav::DownloadWaypointSnapshotResponse*>( diff --git a/cpp/bosdyn/common/strip_bytes_fields.h b/cpp/bosdyn/common/strip_bytes_fields.h index 21a7714..c407784 100644 --- a/cpp/bosdyn/common/strip_bytes_fields.h +++ b/cpp/bosdyn/common/strip_bytes_fields.h @@ -39,6 +39,7 @@ bool StripLocalGridResponse(::google::protobuf::Message* proto_message); bool StripPointCloudResponse(::google::protobuf::Message* proto_message); bool StripUploadWaypointRequest(::google::protobuf::Message* proto_message); bool StripUploadEdgeRequest(::google::protobuf::Message* proto_message); +bool StripUploadSnapshotsRequest(::google::protobuf::Message* proto_message); bool StripDownloadWaypointResponse(::google::protobuf::Message* proto_message); bool StripDownloadEdgeResponse(::google::protobuf::Message* proto_message); bool StripRecordDataBlobsRequest(::google::protobuf::Message* proto_message); diff --git a/cpp/bosdyn/common/time.cpp b/cpp/bosdyn/common/time.cpp index d7c11fb..1675a37 100644 --- a/cpp/bosdyn/common/time.cpp +++ b/cpp/bosdyn/common/time.cpp @@ -12,7 +12,11 @@ #include +#include #include +#include +#include +#include #include #include "bosdyn/common/numbers.h" @@ -28,18 +32,29 @@ ::std::chrono::nanoseconds _default_clock_fn() { ::std::chrono::system_clock::now().time_since_epoch()); } -ClockFn _clock_fn = _default_clock_fn; +std::shared_ptr& clock_fn() { + // Using a static _local_ variable here avoids the static initialization order fiasco. + // See https://isocpp.org/wiki/faq/ctors#static-init-order-on-first-use. + static auto ret = std::make_shared(_default_clock_fn); + return ret; +} } // namespace using TimeUtil = google::protobuf::util::TimeUtil; /// Set a clock function which overrides default functionality of NowNsec. -void SetClock(const ClockFn& fn) { _clock_fn = fn; } +void SetClock(const ClockFn& fn) { + auto fn_shared = std::make_shared(fn); + std::atomic_store_explicit(&clock_fn(), fn_shared, std::memory_order_release); +} -void RestoreDefaultClock() { _clock_fn = _default_clock_fn; } +void RestoreDefaultClock() { SetClock(_default_clock_fn); } -std::chrono::nanoseconds NsecSinceEpoch() { return _clock_fn(); } +std::chrono::nanoseconds NsecSinceEpoch() { + auto fn_shared = std::atomic_load_explicit(&clock_fn(), std::memory_order_acquire); + return (*fn_shared)(); +} std::chrono::seconds SecSinceEpoch() { return ::std::chrono::duration_cast<::std::chrono::seconds>(NsecSinceEpoch()); diff --git a/cpp/bosdyn/math/proto_math.cpp b/cpp/bosdyn/math/proto_math.cpp index ba305aa..cc3567b 100644 --- a/cpp/bosdyn/math/proto_math.cpp +++ b/cpp/bosdyn/math/proto_math.cpp @@ -329,6 +329,13 @@ bool Equals(const ::bosdyn::api::SE3Pose& a_T_b, const ::bosdyn::api::SE3Pose& b return (a_eq_b || a_eq_negative_b); } +Eigen::Isometry2d EigenFromApiProto(const ::bosdyn::api::SE2Pose& a_T_b) { + Eigen::Matrix ret = Eigen::Matrix::Identity(); + ret.block<2, 2>(0, 0) = ToMatrix(a_T_b.angle()); + ret.block<2, 1>(0, 2) = EigenFromApiProto(a_T_b.position()); + return Eigen::Isometry2d(ret); +} + Eigen::Isometry3d EigenFromApiProto(const ::bosdyn::api::SE3Pose& a_T_b) { Eigen::Matrix ret = Eigen::Matrix::Identity(); ret.block<3, 3>(0, 0) = EigenFromApiProto(a_T_b.rotation()).toRotationMatrix(); diff --git a/cpp/bosdyn/math/proto_math.h b/cpp/bosdyn/math/proto_math.h index 4910da9..a98727a 100644 --- a/cpp/bosdyn/math/proto_math.h +++ b/cpp/bosdyn/math/proto_math.h @@ -84,6 +84,7 @@ ::bosdyn::api::SE2Pose operator*(const ::bosdyn::api::SE2Pose& a_T_b, const ::bosdyn::api::SE2Pose& b_T_c); bool operator==(const ::bosdyn::api::SE2Pose& a_T_b, const ::bosdyn::api::SE2Pose& b_T_c); ::bosdyn::api::Vec2 operator*(const ::bosdyn::api::SE2Pose& a_T_b, const ::bosdyn::api::Vec2& p); +Eigen::Isometry2d EigenFromApiProto(const ::bosdyn::api::SE2Pose& a_T_b); // SE(2) Velocity Helpers bool operator==(const ::bosdyn::api::SE2Velocity& vel_a, const ::bosdyn::api::SE2Velocity& vel_b); diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index 35a766b..b4605c3 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,26 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 5.1.0 BETA + +### Bug Fixes and Improvements + +#### API + +Please see the [General Release Notes](https://dev.bostondynamics.com/docs/release_notes) for a description of the API changes included in release 5.1.0. + +#### SDK + +**Clients** + +- Fixed a potential segmentation fault when calling `ListServices()` on a `Robot` instance from multiple threads. Previously, while client creation and client objects were thread-safe, the internal updates to the robot's maps of authorities and endpoints were not. This could result in a crash if two threads called `ListServices()` concurrently. + +- Added `UploadSnapshots` and `UploadSnapshotsAsync` methods to [GraphNavClient](../cpp/bosdyn/client/graph_nav/graph_nav_client.cpp). + +**Helper Functions** + +- Added `EigenFromApiProto(const ::bosdyn::api::SE2Pose&)` to [proto_math.cpp](../cpp/bosdyn/math/proto_math.cpp). This function converts a `::bosdyn::api::SE2Pose` proto message into an `Eigen::Isometry2d`, constructing the corresponding 2D transformation matrix from the proto's angle and position fields. + ## Spot C++ SDK version 5.0.1.2 BETA There have been no changes in the C++ SDK between 5.0.1.1 and this version. diff --git a/protos/bosdyn/api/autowalk/walks.proto b/protos/bosdyn/api/autowalk/walks.proto index 8677ff5..d7dd54d 100644 --- a/protos/bosdyn/api/autowalk/walks.proto +++ b/protos/bosdyn/api/autowalk/walks.proto @@ -13,6 +13,7 @@ option java_outer_classname = "WalksProto"; import "google/protobuf/duration.proto"; +import "google/protobuf/wrappers.proto"; import "bosdyn/api/mission/nodes.proto"; import "bosdyn/api/mission/util.proto"; import "bosdyn/api/data_acquisition.proto"; @@ -59,6 +60,16 @@ message Walk { // walk). ChoreographyItems choreography_items = 9; + // Interrupts can be used to interrupt the normal flow of an autowalk. + // This could be useful for: + // - Getting the robot to power off when an onboard sensor determines an + // unsafe condition. + // - Having an external system that's internet connected inform the robot + // it's going to rain, so that the robot can return to the dock early. + // - Temporarily pausing the mission to get a closer look at a detected + // anomaly. + WalkInterrupt interrupts = 10; + } // These parameters apply to the entire autowalk. @@ -313,6 +324,10 @@ message Target { TARGET_STOW_BEHAVIOR_ALWAYS = 3; } TargetStowBehavior target_stow_behavior = 5; + + // If true, the robot is allowed to continue to perform the action + // Before it comes to a complete stop. + bool success_when_goal_area_reached = 6; } // An Action is what the robot should do at a location. For example, the user @@ -333,6 +348,8 @@ message Action { // element name. AcquireDataRequest acquire_data_request = 1; bosdyn.api.mission.DataAcquisition.CompletionBehavior completion_behavior = 2; + + // Last known Data Acquisition capabilities. AcquisitionCapabilityList last_known_capabilities = 3; @@ -390,6 +407,18 @@ message Action { message ExecuteChoreography { // The name of the sequence to play. string sequence_name = 1; + + message PromptParams { + // Should the dance start time be determined before the dance plays + // at runtime from user input + bool prompt_for_start_time = 1; + + // How long will the prompt run before timing out. If unset, + // the default value of 10 minutes will be used. + google.protobuf.DoubleValue prompt_timeout = 2; + } + + PromptParams prompt_params = 2; } oneof action { @@ -488,6 +517,7 @@ message ActionWrapper { message ArmSensorPointing { // Arm Joint Move Command // The joint trajectory to execute in the initial rough pointing joint move. + // Can be unset - if it is, robot will skip this step. bosdyn.api.ArmJointTrajectory joint_trajectory = 2; // Arm Cartesian Command @@ -497,6 +527,7 @@ message ActionWrapper { bosdyn.api.SE3Pose wrist_tform_tool = 3; // A 3D pose trajectory for the tool expressed in target frame, + // Can be unset - if it is, robot will skip this step. bosdyn.api.SE3Trajectory pose_trajectory_rt_target = 4; // Robot desired stance relative to waypoint @@ -604,6 +635,49 @@ message FailureBehavior { } } +// How are multiple interruptions handled? +// - SafePowerOff can never be overridden, and can override everything. +// - ReturnToStartAndTerminate can only be overridden by SafePowerOff, +// and can override everything else. +// - Node can't override anything except an actively running element. +// If multiple interrupts with "Node" as the condition_behavior are +// triggered, the first one triggered will run. When that behavior +// completes, all signals will be revaluated, and if the other +// interrupt is still high then that behavior will be triggered. +message WalkInterrupt { + message DaqPluginSignal { + reserved 1; + DataAcquisitionCapability capability = 4; + DataCapture data_capture = 2; + + // The DataCapture will be sent as part of a LiveDataRequest + // to the data acquisition plugin service. The service will return + // a CapabilityLiveData for that data_capture, which will be embedded + // in the mission blackboard at the following name, for use + // in the condition node. + string blackboard_name = 3; + } + + message ConditionAndBehavior { + // Only used for things like the autowalk report. + string name = 1; + + // Should evaluate to true when this interrupt should occur. + oneof condition { + bosdyn.api.mission.Condition condition_node = 2; + } + + oneof behavior { + FailureBehavior.SafePowerOff safe_power_off = 3; + FailureBehavior.ReturnToStartAndTerminate return_to_start_and_terminate = 4; + bosdyn.api.mission.Node behavior_node = 5; + } + } + + repeated DaqPluginSignal signals = 1; + repeated ConditionAndBehavior conditions_and_behaviors = 2; +} + // If your mission has docks, autowalk can pause the mission to return // to the dock if the battery gets too low. Use this message to control // when this behavior happens. diff --git a/protos/bosdyn/api/basic_command.proto b/protos/bosdyn/api/basic_command.proto index 5d64443..a18938c 100644 --- a/protos/bosdyn/api/basic_command.proto +++ b/protos/bosdyn/api/basic_command.proto @@ -215,6 +215,10 @@ message SE2TrajectoryCommand { } // Flag indicating if the final requested position was achievable. FinalGoalStatus final_goal_status = 5; + + // Enables clients to monitor the commanded goal trajectory, even if not sending the + // command. + SE2TrajectoryCommand.Request request_information = 6; } } @@ -244,7 +248,8 @@ message SE2VelocityCommand { } message Feedback { - // Planar velocity commands provide no feedback. + // Enables clients to monitor the commanded goal velocity, even if not sending the command. + SE2VelocityCommand.Request request_information = 1; } } @@ -630,6 +635,7 @@ message JointCommand { // 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. google.protobuf.FloatValue velocity_safety_limit = 9; + } message ContactAdvice { diff --git a/protos/bosdyn/api/data_acquisition.proto b/protos/bosdyn/api/data_acquisition.proto index 306bf02..7a01589 100644 --- a/protos/bosdyn/api/data_acquisition.proto +++ b/protos/bosdyn/api/data_acquisition.proto @@ -44,6 +44,7 @@ message DataAcquisitionCapability { // Capability has live data available via GetLiveData RPC. bool has_live_data = 6; + } // Description of an image acquisition capability. The image acquisition capabilities will be @@ -77,6 +78,7 @@ message NetworkComputeCapability { AvailableModels models = 3; } + // 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. message AcquisitionCapabilityList { @@ -88,6 +90,7 @@ message AcquisitionCapabilityList { // List of network compute capabilities. repeated NetworkComputeCapability network_compute_sources = 5; + } // The CaptureActionId describes the entire capture action for an AcquireData request and will be @@ -167,6 +170,13 @@ message AssociatedAlertData { AlertData alert_data = 2; } +// An order for a given capture. This is used to determine the order in which captures are +// processed and saved. +message CaptureOrdering { + // The order value. Lower values indicate higher priority and will be executed first. + int32 value = 1; +} + // An individual capture which can be specified in the AcquireData request to identify a piece of // image data to be collected. message ImageSourceCapture { @@ -184,6 +194,9 @@ message ImageSourceCapture { // DEPRECATED as of 3.2.0. Use image_request instead. // Specific pixel format to capture reported by the ImageAcquisitionCapability message. Image.PixelFormat pixel_format = 3 [deprecated = true]; + + // The order in which this capture should be performed relative to the other captures. + CaptureOrdering order = 5; } // An individual capture which can be specified in the AcquireData or LiveData request to identify @@ -196,6 +209,9 @@ message DataCapture { // Values passed to the service at capture time. // See the DictParam.Spec in DataAcquisitionCapability. DictParam custom_params = 9; + + // The order in which this capture should be performed relative to the other captures. + CaptureOrdering order = 10; } message NetworkComputeCapture { @@ -208,6 +224,9 @@ message NetworkComputeCapture { // Which service to use. NetworkComputeServerConfiguration server_config = 2; + + // The order in which this capture should be performed relative to the other captures. + CaptureOrdering order = 4; } @@ -502,3 +521,4 @@ message LiveDataResponse { reserved 2; } + diff --git a/protos/bosdyn/api/data_acquisition_service.proto b/protos/bosdyn/api/data_acquisition_service.proto index a248afe..edc998d 100644 --- a/protos/bosdyn/api/data_acquisition_service.proto +++ b/protos/bosdyn/api/data_acquisition_service.proto @@ -32,4 +32,5 @@ service DataAcquisitionService { // Request live data available from DAQ plugins during teleoperation. // Please use the other RPCs for typical data acquisition. rpc GetLiveData(LiveDataRequest) returns (LiveDataResponse); + } diff --git a/protos/bosdyn/api/docking/docking.proto b/protos/bosdyn/api/docking/docking.proto index 4b26f5b..2edfa13 100644 --- a/protos/bosdyn/api/docking/docking.proto +++ b/protos/bosdyn/api/docking/docking.proto @@ -175,14 +175,13 @@ message DockingCommandFeedbackResponse { enum DockType { // Unknown type of dock DOCK_TYPE_UNKNOWN = 0; - - - // Prototype version SpotDock - DOCK_TYPE_CONTACT_PROTOTYPE = 2; // Production version SpotDock DOCK_TYPE_SPOT_DOCK = 3; // Production version SpotDock located in the dog house. DOCK_TYPE_SPOT_DOGHOUSE = 4; + + + reserved 1, 2; } // The configuration of a range of dock ID's diff --git a/protos/bosdyn/api/fiducial_purpose.proto b/protos/bosdyn/api/fiducial_purpose.proto new file mode 100644 index 0000000..7e6c341 --- /dev/null +++ b/protos/bosdyn/api/fiducial_purpose.proto @@ -0,0 +1,23 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; +package bosdyn.api; +option go_package = "bosdyn/api/FiducialPurpose"; +option java_outer_classname = "FiducialPurposeProto"; + +// A purpose of a fiducial. +enum FiducialPurpose { + UNKNOWN = 0; + // Fiducial is used for localization. (needs to be unique and static) + LOCALIZATION = 1; + // Fiducial is used as a docking target. + DOCK = 2; + // Fiducial is used interrupts + INTERRUPT = 3; + // Fiducial is used for log triggering. + LOG_TRIGGERING = 4; +} diff --git a/protos/bosdyn/api/graph_nav/graph_nav.proto b/protos/bosdyn/api/graph_nav/graph_nav.proto index c7fdb4a..c2a1971 100644 --- a/protos/bosdyn/api/graph_nav/graph_nav.proto +++ b/protos/bosdyn/api/graph_nav/graph_nav.proto @@ -227,6 +227,10 @@ message SetLocalizationResponse { message RouteGenParams { + + // When navigating after getting stuck, setting this to true will cause the robot to first + // backtrack from its stuck location to the start waypoint before starting the new route. + bool backtrack_to_start_waypoint = 2; } // Parameters describing how to travel along a route. @@ -898,6 +902,20 @@ message NavigationFeedbackResponse { // Map of Region IDs with relevant information map active_region_information = 10; + // The robot may achieve parts of the goal before the status is STATUS_REACHED_GOAL. + // This enum captures intermediate states. + enum GoalStatus { + // Unset. + GOAL_STATUS_UNKNOWN = 0; + // The robot has not yet reached the destination. + GOAL_STATUS_NOT_REACHED = 1; + // The robot is within the destination's goal specified in the TravelParams. + GOAL_STATUS_IN_GOAL_AREA = 2; + // The robot is standing at the final goal point. + GOAL_STATUS_STANDING_AT_GOAL = 3; + } + GoalStatus goal_status = 19; + // Data for a Area Callback region message ActiveRegionInformation { // human readable name for the region @@ -1388,6 +1406,37 @@ message UploadEdgeSnapshotResponse { MapStats map_stats = 3; } +// Like the individual waypoint/edge RPCs, but for N snapshots of both edges and waypoints. +// graph_nav only processes complete Snapshots so large protos are discouraged; +// any network interruption would require the data to be resent. Clients are +// encouraged to send data in batches on the order of a few MB to strike a +// balance between eliminating per-RPC overhead and recovering from errors. +message UploadSnapshotsRequest { + RequestHeader header = 1; + message Snapshots { + repeated WaypointSnapshot waypoint_snapshots = 1; + repeated EdgeSnapshot edge_snapshots = 2; + } + DataChunk chunk = 2; // This should be interpreted as a serialized Snapshots. + Lease lease = 3; +} + +message UploadSnapshotsResponse { + ResponseHeader header = 1; + LeaseUseResult lease_use_result = 2; + + // If waypoint snapshots were uploaded, sensor compatibilty is checked. + enum Status { + STATUS_UNKNOWN = 0; + STATUS_OK = 1; + STATUS_INCOMPATIBLE_SENSORS = 2; + } + Status status = 3; + SensorCompatibilityStatus sensor_status = 4; + + MapStats map_stats = 5; +} + // 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, diff --git a/protos/bosdyn/api/graph_nav/graph_nav_service.proto b/protos/bosdyn/api/graph_nav/graph_nav_service.proto index f2abb1d..2c07dfe 100644 --- a/protos/bosdyn/api/graph_nav/graph_nav_service.proto +++ b/protos/bosdyn/api/graph_nav/graph_nav_service.proto @@ -68,6 +68,9 @@ service GraphNavService { // Uploads large edge snapshot as a stream for a particular edge. rpc UploadEdgeSnapshot(stream UploadEdgeSnapshotRequest) returns (UploadEdgeSnapshotResponse) {} + // Uploads multiple waypoint+edge snapshots. + rpc UploadSnapshots(stream UploadSnapshotsRequest) returns (UploadSnapshotsResponse) {} + // Download waypoint data from the server. If the snapshot exists in disk cache, it will be // loaded. rpc DownloadWaypointSnapshot(DownloadWaypointSnapshotRequest) diff --git a/protos/bosdyn/api/graph_nav/map.proto b/protos/bosdyn/api/graph_nav/map.proto index a84f159..1a906af 100644 --- a/protos/bosdyn/api/graph_nav/map.proto +++ b/protos/bosdyn/api/graph_nav/map.proto @@ -398,6 +398,13 @@ message Edge { GROUND_CLUTTER_FROM_FOOTFALLS = 2; } GroundClutterAvoidanceMode ground_clutter_mode = 17; + + message AudioVisualSettings { + // Behavior to run while traversing this edge. + string behavior_name = 1; + } + + AudioVisualSettings audio_visual_settings = 19; } // Annotations specific to the current edge. Annotations annotations = 4; diff --git a/protos/bosdyn/api/hazard_avoidance.proto b/protos/bosdyn/api/hazard_avoidance.proto new file mode 100644 index 0000000..bf45c11 --- /dev/null +++ b/protos/bosdyn/api/hazard_avoidance.proto @@ -0,0 +1,147 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/hazard_avoidance"; + +option java_outer_classname = "HazardAvoidanceProto"; + +import "google/protobuf/timestamp.proto"; +import "google/protobuf/duration.proto"; + +import "bosdyn/api/geometry.proto"; +import "bosdyn/api/header.proto"; +import "bosdyn/api/image.proto"; +import "bosdyn/api/point_cloud.proto"; + +// Hazard data to add for tracking. +message HazardObservation { + // Proto to wrap a list of circles. + message CircleList { + repeated Circle circles = 1; + } + + // The time at which the hazard was observed. + google.protobuf.Timestamp acquisition_time = 1; + + oneof observation_data { + // A point cloud associated with this hazard. + PointCloud point_cloud = 2; + + // A segmented depth image; all positive pixels will be associated to this hazard. + // segmented_depth.shot.image must be type PIXEL_FORMAT_DEPTH_U16. + ImageCaptureAndSource segmented_depth = 3; + + // An oriented box to describe the footprint of the hazard. Must be in the vision frame. + Box2WithFrame box = 8; + + // A circle in the vision frame's XY plane to describe the footprint of the hazard. + Circle circle = 9; + + // Multiple circles in the vision frame's XY plane that describe the hazard. + CircleList circle_list = 10; + } + + enum HazardType { + // Not specified - not a valid value. + TYPE_UNKNOWN = 0; + + // Robot should avoid stepping on, with low penalty for doing so. + TYPE_PREFER_AVOID_WEAK = 1; + + // Robot should avoid stepping on, with high penalty for doing so. + TYPE_PREFER_AVOID_STRONG = 2; + + // Robot should never step on, but it can move over. + TYPE_NEVER_STEP_ON = 3; + + // Robot should never step on or move over. + TYPE_NEVER_STEP_ACROSS = 4; + + // Safe terrain - the robot should prefer stepping here. + TYPE_PREFER_STEP_ON = 5; + + // Robot should never step on, but it can move over. + // Positive margin will be treated as TYPE_PREFER_AVOID_WEAK. + // Negative margin will be unaffected. + TYPE_NEVER_STEP_ON_AVOID_MARGIN = 6; + + // Robot should never step on or move over. + // Positive margin will be treated as TYPE_PREFER_AVOID_STRONG. + // Negative margin will be unaffected. + TYPE_NEVER_STEP_ACROSS_AVOID_MARGIN = 7; + } + + // The type of hazard. + HazardType type = 4; + + // Confidence in the observation. + float likelihood = 5; + + // A label associated with the observation. + string semantic_label = 6; + + // Margin to expand (or contract if negative) the hazard by in meters. + float margin = 7; +} + +// Request to add multiple hazard observations. +message AddHazardsRequest { + RequestHeader header = 1; + repeated HazardObservation hazards = 2; + + // Body pose in VO at the time of the request. + // If not provided, will attempt to extract from the observation data. + SE3Pose vision_tform_body = 3; + + // If true, will write directly into the published map and not to the internally tracked map. + bool skip_aggregation = 4; + + // If skip_aggregation is true, max seconds for the observations to be kept around. + google.protobuf.Duration max_unaggregated_update_age = 5; + + // Identifier for the source of the observations. + string hazard_source = 6; +} + +// Result of adding a single hazard observation. +message AddHazardResult { + enum Status { + STATUS_UNKNOWN = 0; // Unset. + STATUS_HAZARDS_UPDATED = 1; // Updated the hazard map. + STATUS_IGNORED = 2; // No new hazard information was added. + STATUS_INVALID_DATA = 5; // The HazardObservation contained errors. + + reserved 3, 4; + } + + // Status of the detection. + Status status = 1; +} + +// Response for adding multiple hazard observations. +message AddHazardsResponse { + ResponseHeader header = 1; + repeated AddHazardResult add_hazard_results = 2; + + // Convenience value to check how many results returned STATUS_HAZARDS_UPDATED. + int32 num_hazards_updated = 3; +} + +// Request to get the status of the service. +message GetHazardServiceStatusRequest { + RequestHeader header = 1; +} + +// Response for getting the status of the service. +message GetHazardServiceStatusResponse { + ResponseHeader header = 1; + + // Time since last observation. Can be used to check if the extension is running. + google.protobuf.Duration time_since_last_observation = 2; +} diff --git a/protos/bosdyn/api/hazard_avoidance_service.proto b/protos/bosdyn/api/hazard_avoidance_service.proto new file mode 100644 index 0000000..ffe9795 --- /dev/null +++ b/protos/bosdyn/api/hazard_avoidance_service.proto @@ -0,0 +1,25 @@ +// Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved. +// +// Downloading, reproducing, distributing or otherwise using the SDK Software +// is subject to the terms and conditions of the Boston Dynamics Software +// Development Kit License (20191101-BDSDK-SL). + +syntax = "proto3"; + +package bosdyn.api; +option go_package = "bosdyn/api/hazard_avoidance_service"; + +option java_outer_classname = "HazardAvoidanceServiceProto"; + +import "bosdyn/api/hazard_avoidance.proto"; + +// The hazard avoidance service provides a way to aggregate and track observations of hazardous +// terrains/structures around the robot. +service HazardAvoidanceService { + // Request to add new hazard observations. + rpc AddHazards(AddHazardsRequest) returns (AddHazardsResponse) {} + + // Request to check if the extension is running. + rpc GetHazardServiceStatus(GetHazardServiceStatusRequest) + returns (GetHazardServiceStatusResponse) {} +} diff --git a/protos/bosdyn/api/log_status/log_status.proto b/protos/bosdyn/api/log_status/log_status.proto index 6927070..4ae5fce 100644 --- a/protos/bosdyn/api/log_status/log_status.proto +++ b/protos/bosdyn/api/log_status/log_status.proto @@ -9,6 +9,7 @@ syntax = "proto3"; package bosdyn.api.log_status; option go_package = "bosdyn/api/log_status/log_status"; +import "bosdyn/api/data_buffer.proto"; import "bosdyn/api/header.proto"; import "google/protobuf/duration.proto"; import "google/protobuf/timestamp.proto"; @@ -32,6 +33,9 @@ message LogStatus { TYPE_UNKNOWN = 0; TYPE_EXPERIMENT = 1; // A log into the future. TYPE_RETRO = 2; // A retroactive log. + TYPE_EVENT = 3; // A log created automatically from an event. + TYPE_DATA = 4; // A log created from a data log request. + TYPE_CONCURRENT = 5; // An experiment log that allows concurrency. } // Id of the response log. @@ -42,6 +46,16 @@ message LogStatus { // Type of log. Type type = 3; + + // Timestamp of the start of an experiment log, in robot time. + google.protobuf.Timestamp start_time = 4; + + // Timestamp of the end of an experiment log, in robot time. + google.protobuf.Timestamp end_time = 5; + + // Current duration of an experiment log, in robot time. This is not the total runtime, but + // rather how long it has run as of now. + google.protobuf.Duration run_time = 6; } message GetLogStatusRequest { @@ -90,6 +104,43 @@ message GetActiveLogStatusesResponse { repeated LogStatus log_statuses = 3; } +message StartConcurrentLogRequest { + // Common request header. + bosdyn.api.RequestHeader header = 1; + + // How long into the future should this log end? + google.protobuf.Duration keep_alive = 2; + + // How long into the past should text logs extend? (default 0) + google.protobuf.Duration past_textlog_duration = 3; + + // Specify an event for the request. The data included in the log will be defined by this event, + // if the robot has data associated with the event. + bosdyn.api.Event event = 4; +} + +message StartConcurrentLogResponse { + enum Status { + STATUS_UNKNOWN = 0; + STATUS_OK = 1; + STATUS_EXPERIMENT_LOG_RUNNING = 2; // An experiment log is already running. + STATUS_CONCURRENCY_LIMIT_REACHED = 3; // Maximum number of logs running concurrently. + STATUS_NO_DATA_FOR_EVENT = 4; // The specified event has no data associated with it + } + + // Common response header. + bosdyn.api.ResponseHeader header = 1; + + // Response status. + Status status = 2; + + // Status of the created log. + LogStatus log_status = 3; + + // Timestamp of the end of the log, in robot time. + google.protobuf.Timestamp end_time = 4; +} + message StartRetroLogRequest { // Common request header. bosdyn.api.RequestHeader header = 1; @@ -125,6 +176,9 @@ message StartExperimentLogRequest { // How long into the future should this log end? google.protobuf.Duration keep_alive = 2; + + // How long into the past should text logs extend? (default 0) + google.protobuf.Duration past_textlog_duration = 3; } message StartExperimentLogResponse { diff --git a/protos/bosdyn/api/log_status/log_status_service.proto b/protos/bosdyn/api/log_status/log_status_service.proto index 4fc0e00..a55fa90 100644 --- a/protos/bosdyn/api/log_status/log_status_service.proto +++ b/protos/bosdyn/api/log_status/log_status_service.proto @@ -37,6 +37,12 @@ service LogStatusService { // Only one experiment log can be run at a time. rpc StartExperimentLog(StartExperimentLogRequest) returns (StartExperimentLogResponse); + // Given a duration T and an event E, starts an experiment log that will include any data + // the robot associates with E, with a keepalive/watchdog timer of T. However, unlike an + // experiment log it allows for concurrency, so E must be provided to constrain the data + // included in the log. + rpc StartConcurrentLog(StartConcurrentLogRequest) returns (StartConcurrentLogResponse); + // UpdateExperimentLog(id, T) will update the keepalive/watchdog timer of // the log with the provided id if the log is active. The updated duration // of the log will be [t_rpc, t_rpc + T] where t_rpc = time of RPC reception. diff --git a/protos/bosdyn/api/mission/mission.proto b/protos/bosdyn/api/mission/mission.proto index dd3ad2d..ca0b2f6 100644 --- a/protos/bosdyn/api/mission/mission.proto +++ b/protos/bosdyn/api/mission/mission.proto @@ -158,6 +158,10 @@ message Question { // human. Clients should usually avoid generating a UI element to ask such a question. bool for_autonomous_processing = 5; + // Optional string data to help autonomous systems identify questions. + // This data will come from the Prompt asking the question. + string autonomy_key = 8; + // Severity for this question. See comment in Prompt message in nodes.proto for a better // understanding of what levels mean. AlertData.SeverityLevel severity = 6; diff --git a/protos/bosdyn/api/mission/nodes.proto b/protos/bosdyn/api/mission/nodes.proto index a910117..e266cf8 100644 --- a/protos/bosdyn/api/mission/nodes.proto +++ b/protos/bosdyn/api/mission/nodes.proto @@ -100,6 +100,7 @@ message Node { MissionUploadChoreography mission_upload_choreography = 57; CreateMissionText create_mission_text = 59; BosdynQueryStoredCaptures bosdyn_query_stored_captures = 60; + DataAcquisitionLiveData data_acquisition_live_data = 64; } // Defines parameters, used by this node or its children. @@ -301,6 +302,7 @@ message Condition { HANDLE_STALE_FAIL = 3; // return FAILURE status if stale data is read. } HandleStaleness handle_staleness = 6; + } // Get state from the robot. @@ -381,6 +383,7 @@ message BosdynNavigateTo { // Defines robot behavior when route is blocked. Defaults to reroute when route is blocked. bosdyn.api.graph_nav.RouteFollowingParams.RouteBlockedBehavior route_blocked_behavior = 8; + } // Tell the robot to navigate to a pose in the seed frame @@ -408,6 +411,7 @@ message BosdynNavigateToAnchor { // If provided, parameters from this request will be merged with the other parameters defined in // the node and be used in the NavigateToAnchor RPC. string navigate_to_anchor_request_blackboard_key = 8; + } // Tell the robot to navigate a route. @@ -437,6 +441,7 @@ message BosdynNavigateRoute { // If provided, parameters from this request will be merged with the other parameters defined in // the node and be used in the NavigateRoute RPC. string navigate_route_request_blackboard_key = 8; + } // Get GraphNav state from the robot and save it to the blackboard. @@ -560,6 +565,10 @@ message ExecuteChoreography { string host = 2; // The name of the sequence to play. string sequence_name = 3; + + // Optional Blackboard variable that can specify a start time in nanoseconds + // since epoch in the robot's clock to be used for the start time of the sequence. + string start_time_in_blackboard = 4; } // Uploads the given set of animations and choreography sequences to the robot. @@ -612,11 +621,15 @@ message Prompt { oneof answer_spec { // The set of options that can be chosen for this prompt. OptionsList options_list = 9; - // Key to an OptionsList protobuf object on the blackboard. The variable is only read when - // the node starts meaning options cannot change while the node is running. + // Key to a OptionsList protobuf object on the blackboard. Note that this variable is only + // read when the node starts, meaning that options can not change while the node is running. string options_list_in_blackboard = 11; // Custom parameter specification for the answer expected for this prompt. DictParam.Spec custom_params = 10; + // Key to a DictParam.Spec protobuf object on the blackboard. Note that this variable is + // only read when the node starts, meaning that options can not change while the node is + // running. + string custom_params_in_blackboard = 13; } // Child node, run after the prompt has been responded to. @@ -627,6 +640,10 @@ message Prompt { // See the Question message for details. bool for_autonomous_processing = 6; + // Optional string data to help autonomous systems identify questions, this will be + // copied into the Question message. + string autonomy_key = 14; + oneof severity_spec { // Severity for this prompt. Used to determine what sort of alerting // this prompt will trigger. @@ -889,6 +906,9 @@ message DataAcquisition { // This allows the robot to continue on with the mission sooner, but // it will be unaware of failures in processing or storage. COMPLETE_AFTER_ACQUIRED = 2; + // Node is complete after the AcquireData request is sent. + // Note that if the request fails, the node will not be aware of it. + COMPLETE_AFTER_REQUEST = 3; } CompletionBehavior completion_behavior = 4; @@ -933,6 +953,32 @@ message DataAcquisition { } +message DataAcquisitionLiveData { + // Service name for a data acquisition service + // NOTE: Not the plugin! Just the main service + // You pick the plugin by specifying a capture name in DataCapture + string service_name = 1; + + // Host machine of the directory server that the data acquisition service is registered with. + string host = 2; + + message DataCaptureAndBlackboardName { + // What request to send to that plugin + DataCapture data_capture = 1; + + // The DataCapture will be sent as part of a LiveDataRequest + // to the data acquisition plugin service. The plugin service will return + // a CapabilityLiveData for that data_capture, which will be embedded + // in the blackboard at the following name, for use in a child node. + string blackboard_name = 2; + } + + repeated DataCaptureAndBlackboardName data_captures = 3; + + // Child node. Children will have access to the state gathered by this node. + Node child = 4; +} + // 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. diff --git a/protos/bosdyn/api/network_compute_bridge.proto b/protos/bosdyn/api/network_compute_bridge.proto index 198206a..7309f09 100644 --- a/protos/bosdyn/api/network_compute_bridge.proto +++ b/protos/bosdyn/api/network_compute_bridge.proto @@ -65,6 +65,7 @@ message ModelData { // Per-model parameters. DictParam.Spec custom_params = 7; + } message ModelLabels { diff --git a/protos/bosdyn/api/power.proto b/protos/bosdyn/api/power.proto index e1fa363..06ca0e3 100644 --- a/protos/bosdyn/api/power.proto +++ b/protos/bosdyn/api/power.proto @@ -87,6 +87,8 @@ message PowerCommandRequest { REQUEST_ON_PAYLOAD_PORTS = 6; // Turn on power to the payload ports. REQUEST_OFF_WIFI_RADIO = 7; // Cut power to the hardware Wi-Fi radio. REQUEST_ON_WIFI_RADIO = 8; // Power on the hardware Wi-Fi radio. + REQUEST_SOFT_REBOOT_ROBOT = + 9; // Soft reboot of base robot computers. Does not cut power to payloads. } Request request = 3; diff --git a/protos/bosdyn/api/robot_state.proto b/protos/bosdyn/api/robot_state.proto index 474525a..a056565 100644 --- a/protos/bosdyn/api/robot_state.proto +++ b/protos/bosdyn/api/robot_state.proto @@ -305,6 +305,10 @@ message SystemFault { // immediately. Severity severity = 7; + + // Diagnostic Troubleshooting Code (DTC). This will directly map to the "code" field in this + // message. + string dtc = 15; } // The robot's current E-Stop states and endpoints. diff --git a/protos/bosdyn/api/service_fault.proto b/protos/bosdyn/api/service_fault.proto index 64824f0..84825e6 100644 --- a/protos/bosdyn/api/service_fault.proto +++ b/protos/bosdyn/api/service_fault.proto @@ -34,6 +34,7 @@ message ServiceFaultId { // Optional. If not set, it will be assigned to the payload associated with the // service_name. string payload_guid = 3; + } // The current service faults for services registered with the robot. diff --git a/protos/bosdyn/api/signals.proto b/protos/bosdyn/api/signals.proto index 58da045..7aa9c04 100644 --- a/protos/bosdyn/api/signals.proto +++ b/protos/bosdyn/api/signals.proto @@ -88,6 +88,15 @@ message SignalSpec { // If multiple conditions are simultaneously met, // the higher severity condition or first in the list will be the accepted alert state. repeated AlertConditionSpec alerts = 3; + // Data type of the signal. + enum DataType { + DATA_TYPE_UNKNOWN = 0; + DATA_TYPE_DOUBLE = 1; + DATA_TYPE_INT = 2; + DATA_TYPE_STRING = 3; + DATA_TYPE_BOOL = 4; + } + DataType data_type = 4; } // The recorded signal data. diff --git a/protos/bosdyn/api/spot/robot_command.proto b/protos/bosdyn/api/spot/robot_command.proto index 1d6a46a..183f8fa 100644 --- a/protos/bosdyn/api/spot/robot_command.proto +++ b/protos/bosdyn/api/spot/robot_command.proto @@ -15,6 +15,7 @@ import "bosdyn/api/geometry.proto"; import "bosdyn/api/trajectory.proto"; import "google/protobuf/wrappers.proto"; + // The locomotion hint specifying the gait of the robot. enum LocomotionHint { option allow_alias = true; @@ -62,6 +63,7 @@ enum SwingHeight { // Params common across spot movement and mobility. message MobilityParams { + // Max allowable velocity at any point in trajectory. SE2VelocityLimit vel_limit = 1; @@ -139,6 +141,7 @@ message MobilityParams { HazardDetectionMode hazard_detection_mode = 18; + } // Parameters for offsetting the body from the normal default. @@ -278,3 +281,4 @@ message BodyExternalForceParams { // Reserved for deprecated fields. reserved 2; } + diff --git a/protos/bosdyn/api/spot_cam/network.proto b/protos/bosdyn/api/spot_cam/network.proto index a6c8969..386e1e9 100644 --- a/protos/bosdyn/api/spot_cam/network.proto +++ b/protos/bosdyn/api/spot_cam/network.proto @@ -123,3 +123,4 @@ message SetICEConfigurationResponse { // Common response header. bosdyn.api.ResponseHeader header = 1; } + diff --git a/protos/bosdyn/api/world_object.proto b/protos/bosdyn/api/world_object.proto index c2d0d1e..1886db5 100644 --- a/protos/bosdyn/api/world_object.proto +++ b/protos/bosdyn/api/world_object.proto @@ -18,6 +18,7 @@ import "bosdyn/api/image.proto"; import "bosdyn/api/sparse_features.proto"; import "bosdyn/api/stairs.proto"; import "bosdyn/api/gps/registration.proto"; +import "bosdyn/api/fiducial_purpose.proto"; import "google/protobuf/duration.proto"; import "google/protobuf/timestamp.proto"; import "google/protobuf/any.proto"; @@ -294,6 +295,9 @@ message AprilTagProperties { SE3Covariance detection_covariance = 5; // The frame that the detection covariance is expressed in. string detection_covariance_reference_frame = 6; + + // Purpose of the fiducial. + FiducialPurpose purpose = 10; } message RayProperties { From a390822349cb9809f7855535d0930caa41e1d755 Mon Sep 17 00:00:00 2001 From: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Date: Thu, 5 Feb 2026 12:42:49 -0500 Subject: [PATCH 07/15] Release v5.1.1 of Boston Dynamics Spot SDK --- README.md | 2 +- cpp/CMakeLists.txt | 2 +- docs/cpp_release_notes.md | 4 ++++ 3 files changed, 6 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 17774b4..20e05e6 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+ - [Payload developer documentation](https://dev.bostondynamics.com/docs/payload/readme). Payloads add additional sensing, communication, and control capabilities beyond what the base platform provides. The Payload ICD covers the mechanical, electrical, and software interfaces that Spot supports. - [Spot API protocol definition](https://dev.bostondynamics.com/docs/protos/readme). 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. -This is version 5.1.0 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. +This is version 5.1.1 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. ## Contents diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index 177f6e5..138c3ac 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -7,7 +7,7 @@ # This file is autogenerated. cmake_minimum_required (VERSION 3.10.2) -project (bosdyn VERSION 5.1.0) +project (bosdyn VERSION 5.1.1) # Dependencies: find_package(protobuf REQUIRED) diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index b4605c3..6683af3 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,10 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 5.1.1 BETA + +- No changes from 5.1.0 + ## Spot C++ SDK version 5.1.0 BETA ### Bug Fixes and Improvements From 4aacfa4ba2ceb5eb9de291bcdbc4312cf1c5ce59 Mon Sep 17 00:00:00 2001 From: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Date: Wed, 18 Mar 2026 09:47:43 -0400 Subject: [PATCH 08/15] Release v5.1.4 of Boston Dynamics Spot SDK --- .../data_acquisition_client.cpp | 1 + .../data_acquisition_client.h | 2 ++ docs/cpp_release_notes.md | 4 ++++ protos/bosdyn/api/basic_command.proto | 9 +++++++- protos/bosdyn/api/mobility_command.proto | 5 ++++- protos/bosdyn/api/power.proto | 22 +++++++++++++++++++ protos/bosdyn/api/power_service.proto | 3 +++ protos/bosdyn/api/robot_state.proto | 5 +++++ 8 files changed, 49 insertions(+), 2 deletions(-) diff --git a/cpp/bosdyn/client/data_acquisition/data_acquisition_client.cpp b/cpp/bosdyn/client/data_acquisition/data_acquisition_client.cpp index cb7ada7..48c6dbb 100644 --- a/cpp/bosdyn/client/data_acquisition/data_acquisition_client.cpp +++ b/cpp/bosdyn/client/data_acquisition/data_acquisition_client.cpp @@ -84,6 +84,7 @@ DataAcquisitionGetStatusResultType DataAcquisitionClient::GetStatus( return GetStatusAsync(request, parameters).get(); } + void DataAcquisitionClient::OnGetStatusComplete( MessagePumpCallBase* call, const ::bosdyn::api::GetStatusRequest& request, ::bosdyn::api::GetStatusResponse&& response, const grpc::Status& status, diff --git a/cpp/bosdyn/client/data_acquisition/data_acquisition_client.h b/cpp/bosdyn/client/data_acquisition/data_acquisition_client.h index a9f41c4..96b1b4b 100644 --- a/cpp/bosdyn/client/data_acquisition/data_acquisition_client.h +++ b/cpp/bosdyn/client/data_acquisition/data_acquisition_client.h @@ -67,6 +67,7 @@ class DataAcquisitionClient : public ServiceClient { ::bosdyn::api::CancelAcquisitionRequest& request, const RPCParameters& parameters = RPCParameters()); + // Asynchronous RPC to request live data for each capability. std::shared_future GetLiveDataAsync( ::bosdyn::api::LiveDataRequest& request, const RPCParameters& parameters = RPCParameters()); @@ -120,6 +121,7 @@ class DataAcquisitionClient : public ServiceClient { ::bosdyn::api::LiveDataResponse&& response, const grpc::Status& status, std::promise promise); + std::unique_ptr<::bosdyn::api::DataAcquisitionService::StubInterface> m_stub; // Default service name for the Data Acquisition service. diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index 6683af3..6869bb6 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,10 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 5.1.4 BETA + +- No changes from 5.1.1 + ## Spot C++ SDK version 5.1.1 BETA - No changes from 5.1.0 diff --git a/protos/bosdyn/api/basic_command.proto b/protos/bosdyn/api/basic_command.proto index a18938c..5b63c1c 100644 --- a/protos/bosdyn/api/basic_command.proto +++ b/protos/bosdyn/api/basic_command.proto @@ -101,7 +101,14 @@ message StopCommand { // Freeze all joints at their current positions (no balancing control). message FreezeCommand { message Request { - // Freeze command request takes no additional arguments. + // Optional mode for freeze behavior. + enum Mode { + MODE_UNKNOWN = 0; + MODE_DEFAULT = 1; + // Freeze with higher joint gains to minimize deformation under external loads. + MODE_STIFF = 2; + } + Mode mode = 1; } message Feedback { diff --git a/protos/bosdyn/api/mobility_command.proto b/protos/bosdyn/api/mobility_command.proto index 0ea60a7..2e0f185 100644 --- a/protos/bosdyn/api/mobility_command.proto +++ b/protos/bosdyn/api/mobility_command.proto @@ -35,6 +35,9 @@ message MobilityCommand { StanceCommand.Request stance_request = 5; StopCommand.Request stop_request = 6; FollowArmCommand.Request follow_arm_request = 7; + // Mobility freeze for cases where the user wants to freeze only the lower body, leaving + // the arm free to move. + FreezeCommand.Request freeze_request = 8; } @@ -62,7 +65,7 @@ message MobilityCommand { StanceCommand.Feedback stance_feedback = 5; StopCommand.Feedback stop_feedback = 6; FollowArmCommand.Feedback follow_arm_feedback = 7; - + FreezeCommand.Feedback freeze_feedback = 8; } RobotCommandFeedbackStatus.Status status = 100; diff --git a/protos/bosdyn/api/power.proto b/protos/bosdyn/api/power.proto index 06ca0e3..e9af890 100644 --- a/protos/bosdyn/api/power.proto +++ b/protos/bosdyn/api/power.proto @@ -272,3 +272,25 @@ message ResetSafetyStopResponse { // Current feedback of specified command. Status status = 3; } + +// Request fan information from the robot. +message GetFanInformationRequest { + // Common request header. + RequestHeader header = 1; +} + +message FanInformation { + // Fan frequency in hertz. + float frequency = 1; +} + +// Response with fan information from various robot components. +message GetFanInformationResponse { + // Common response header. + ResponseHeader header = 1; + + // Map of fan name to fan information. Each robot might have a different set of fans to report. + // For example, Spot will report information for the fans "body_fan_0, body_fan_1, hips_fan_0, + // hips_fan_1". + map fan_information = 2; +} diff --git a/protos/bosdyn/api/power_service.proto b/protos/bosdyn/api/power_service.proto index 44aa657..1f928e3 100644 --- a/protos/bosdyn/api/power_service.proto +++ b/protos/bosdyn/api/power_service.proto @@ -30,6 +30,9 @@ service PowerService { rpc FanPowerCommandFeedback(FanPowerCommandFeedbackRequest) returns (FanPowerCommandFeedbackResponse) {} + // Get fan information. + rpc GetFanInformation(GetFanInformationRequest) returns (GetFanInformationResponse) {} + // Reset the safety stop bit on SRSF-configured robots. rpc ResetSafetyStop(ResetSafetyStopRequest) returns (ResetSafetyStopResponse) {} } diff --git a/protos/bosdyn/api/robot_state.proto b/protos/bosdyn/api/robot_state.proto index a056565..7892c9b 100644 --- a/protos/bosdyn/api/robot_state.proto +++ b/protos/bosdyn/api/robot_state.proto @@ -374,6 +374,11 @@ message BatteryState { // Temperatures may be measured in many locations across the battery. repeated double temperatures = 7; + // Measured battery communications loss percentage. Measured value from 0.0 to 100.0, where 0.0 + // means no communication loss and 100.0 means complete communication loss with the battery. If + // there is no battery in the robot, this value may be 0.0 or left unset. + google.protobuf.DoubleValue communications_loss_percent = 9; + enum Status { // The battery is in an unknown / unexpected state. STATUS_UNKNOWN = 0; From e363bcf4b1358f3c95dcd00b73098f4e8e1e0461 Mon Sep 17 00:00:00 2001 From: Andrew Messing Date: Fri, 23 Feb 2024 10:02:23 -0500 Subject: [PATCH 09/15] Added CD GHA --- .devcontainer/Dockerfile.amd64 | 27 ++++++++ .devcontainer/Dockerfile.arm64 | 29 ++++++++ .github/workflows/cd.yml | 121 +++++++++++++++++++++++++++++++++ cpp/CMakeLists.txt | 2 +- docs/cpp/quickstart.md | 6 ++ 5 files changed, 184 insertions(+), 1 deletion(-) create mode 100644 .devcontainer/Dockerfile.amd64 create mode 100644 .devcontainer/Dockerfile.arm64 create mode 100644 .github/workflows/cd.yml diff --git a/.devcontainer/Dockerfile.amd64 b/.devcontainer/Dockerfile.amd64 new file mode 100644 index 0000000..2fd89e0 --- /dev/null +++ b/.devcontainer/Dockerfile.amd64 @@ -0,0 +1,27 @@ +FROM ubuntu:22.04 + +RUN apt-get update --fix-missing &&\ + apt-get install -y --no-install-recommends build-essential ca-certificates git g++ pkg-config python3 curl ninja-build tar zip unzip zlib1g-dev libssl-dev wget &&\ + apt-get autoclean &&\ + apt-get autoremove &&\ + apt-get clean &&\ + rm -rf /var/lib/apt/lists/* + +RUN update-ca-certificates + +RUN wget https://github.com/Kitware/CMake/releases/download/v3.28.3/cmake-3.28.3.tar.gz &&\ + tar -xzf cmake-3.28.3.tar.gz &&\ + cd cmake-3.28.3 &&\ + ./configure &&\ + make install &&\ + cd .. &&\ + rm cmake-3.28.3.tar.gz &&\ + rm -r cmake-3.28.3 + +RUN git clone https://github.com/microsoft/vcpkg &&\ + cd vcpkg &&\ + git checkout 3b213864579b6fa686e38715508f7cd41a50900f &&\ + ./bootstrap-vcpkg.sh -disableMetrics &&\ + ./vcpkg install grpc:x64-linux &&\ + ./vcpkg install eigen3:x64-linux &&\ + ./vcpkg install cli11:x64-linux diff --git a/.devcontainer/Dockerfile.arm64 b/.devcontainer/Dockerfile.arm64 new file mode 100644 index 0000000..7f32e6e --- /dev/null +++ b/.devcontainer/Dockerfile.arm64 @@ -0,0 +1,29 @@ +FROM arm64v8/ubuntu:22.04 +SHELL ["/bin/bash", "-c"] + +RUN apt-get update --fix-missing &&\ + apt-get install -y --no-install-recommends build-essential ca-certificates cmake git g++ pkg-config python3 curl ninja-build tar zip unzip zlib1g-dev libssl-dev wget &&\ + apt-get autoclean &&\ + apt-get autoremove &&\ + apt-get clean &&\ + rm -rf /var/lib/apt/lists/* + +RUN update-ca-certificates + +RUN wget https://github.com/Kitware/CMake/releases/download/v3.28.3/cmake-3.28.3.tar.gz &&\ + tar -xzf cmake-3.28.3.tar.gz &&\ + cd cmake-3.28.3 &&\ + ./configure &&\ + make install &&\ + cd .. &&\ + rm cmake-3.28.3.tar.gz &&\ + rm -r cmake-3.28.3 + +RUN git clone https://github.com/microsoft/vcpkg &&\ + cd vcpkg &&\ + git checkout 3b213864579b6fa686e38715508f7cd41a50900f &&\ + export VCPKG_FORCE_SYSTEM_BINARIES=arm &&\ + ./bootstrap-vcpkg.sh -disableMetrics &&\ + ./vcpkg install grpc:arm64-linux &&\ + ./vcpkg install eigen3:arm64-linux &&\ + ./vcpkg install cli11:arm64-linux diff --git a/.github/workflows/cd.yml b/.github/workflows/cd.yml new file mode 100644 index 0000000..4ba2429 --- /dev/null +++ b/.github/workflows/cd.yml @@ -0,0 +1,121 @@ +# Commented out due to speed of runners. Uncomment when we get the better ones. + +# # This workflow automatically releases binaries upon tagging. +# name: spot-cpp-sdk CD + +# on: +# push: +# tags: +# - '*' + +# concurrency: +# group: ${{ github.workflow }}-${{ github.ref }} +# cancel-in-progress: true + +# env: +# REGISTRY: ghcr.io +# # github.repository as / +# IMAGE_NAME: bdaiinstitute/spot_cpp_sdk_builder + +# jobs: + # build-docker-image: + # permissions: + # contents: read + # packages: write + # # This is used to complete the identity challenge + # # with sigstore/fulcio when running outside of PRs. + # id-token: write + # strategy: + # fail-fast: false + # matrix: + # config: + # - { arch: "amd64" } + # - { arch: "arm64" } + # name: Build docker image for ${{ matrix.config.arch }} + # runs-on: ubuntu-latest + # steps: + # - name: Checkout repository + # uses: actions/checkout@v4 + + # - name: Set up QEMU # as virtualization is necessary to build container images + # uses: docker/setup-qemu-action@v3 + + # - name: Setup Docker buildx # to workaround: https://github.com/docker/build-push-action/issues/461 + # uses: docker/setup-buildx-action@79abd3f86f79a9d68a23c75a09a9a85889262adf + + # - name: Log into registry ${{ env.REGISTRY }} + # uses: docker/login-action@v3 # https://github.com/docker/login-action + # with: + # registry: ${{ env.REGISTRY }} + # username: ${{ github.actor }} + # password: ${{ secrets.GITHUB_TOKEN }} + + # # Extract metadata (tags, labels) for Docker + # # https://github.com/docker/metadata-action + # - name: Extract Docker metadata + # id: meta + # uses: docker/metadata-action@v5 + # with: + # images: ${{ env.REGISTRY }}/${{ env.IMAGE_NAME }}_${{ matrix.config.arch }} + + # - name: Build and push + # uses: docker/build-push-action@v5 # https://github.com/docker/build-push-action + # id: build + # with: + # context: . + # file: .devcontainer/Dockerfile.${{ matrix.config.arch }} + # tags: ${{ steps.meta.outputs.tags }} + # labels: ${{ steps.meta.outputs.labels }} + # cache-from: type=gha + # cache-to: type=gha,mode=max + # push: true + + # build-artifacts: + # strategy: + # fail-fast: false + # matrix: + # config: + # - { arch: "amd64" } + # - { arch: "arm64" } + # name: Build spot-cpp-sdk for ${{ matrix.config.arch }} + # # needs: build-docker-image + # runs-on: ubuntu-latest + # container: + # # env cannot be used here... + # image: ghcr.io/bdaiinstitute/spot_cpp_sdk_builder_${{ matrix.config.arch }}:latest + # steps: + # - name: Checkout repository + # uses: actions/checkout@v4 + + # - name: Build spot-sdk-cpp + # run: | + # cd spot-sdk-cpp/cpp + # mkdir build + # cd build + # cmake ../ -DCMAKE_TOOLCHAIN_FILE=/vcpkg/scripts/buildsystems/vcpkg.cmake -DCMAKE_FIND_PACKAGE_PREFER_CONFIG=TRUE -DBUILD_CHOREOGRAPHY_LIBS=ON + # make -j2 install package + + # - name: Upload ${{ matrix.config.arch }} artifact + # uses: actions/upload-artifact@v4 + # with: + # name: ${{ matrix.config.arch }}-artifact + # path: '*.deb' + # retention-days: 1 + + # bundle-debians: + # name: Release artifacts + # runs-on: ubuntu-latest + # needs: build-artifacts + # steps: + # - name: Download artifacts + # uses: actions/download-artifact@v4 + # with: + # pattern: '*-artifact' + # merge-multiple: true + + # - name: Release to GitHub + # uses: softprops/action-gh-release@v1 + # with: + # name: Release ${{ github.ref_name }} + # files: '*.deb' + \ No newline at end of file diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index 138c3ac..3b805b7 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -44,7 +44,7 @@ file(GLOB_RECURSE bosdyn_protos_files CONFIGURE_DEPENDS if (bosdyn_protos_files) add_library(bosdyn_api_obj OBJECT ${bosdyn_protos_files}) set_property(TARGET bosdyn_api_obj PROPERTY POSITION_INDEPENDENT_CODE 1) - target_link_libraries(bosdyn_api_obj PUBLIC ${PROTOBUF_LIBRARIES} gRPC::grpc gRPC::grpc++) + target_link_libraries(bosdyn_api_obj PUBLIC protobuf::libprotobuf gRPC::grpc gRPC::grpc++) target_include_directories(bosdyn_api_obj PUBLIC $ $ diff --git a/docs/cpp/quickstart.md b/docs/cpp/quickstart.md index 73f156b..f644c0b 100644 --- a/docs/cpp/quickstart.md +++ b/docs/cpp/quickstart.md @@ -160,6 +160,12 @@ make -j6 install package The `make` command generates a lot of deprecation warnings during the compiling of the classes generated from the protobuf definitions. This is expected as the protobuf definitions contain `deprecated` flags for fields that will not be supported in future versions of the SDK. +Build the SDK and generate a debian package using the `make` command below: + +``` +make -j6 install package +``` + **On Windows:** - Open the `sln` file in the build folder in Microsoft Visual Studio. From 765fd7a91cfd43acb2852f8d0d70d7b4e8d44ebb Mon Sep 17 00:00:00 2001 From: Andrew Messing <129519955+amessing-bdai@users.noreply.github.com> Date: Wed, 16 Oct 2024 09:47:00 -0400 Subject: [PATCH 10/15] Update devcontainers for building debians (#4) * Working towards depending on apt packages * Updates * Restore Spot C++ SDK builds Signed-off-by: Michel Hidalgo * Remove unused gRPC CMake module Signed-off-by: Michel Hidalgo * Restore cli11 dependency Signed-off-by: Michel Hidalgo * Remove vcpkg reference in CPack config Signed-off-by: Michel Hidalgo * Update arm version of the docker image --------- Signed-off-by: Michel Hidalgo Co-authored-by: Michel Hidalgo --- .devcontainer/Dockerfile.amd64 | 50 ++++++++++++++------------ .devcontainer/Dockerfile.amd64_vcpkg | 27 +++++++++++++++ .devcontainer/Dockerfile.arm64 | 52 +++++++++++++++------------- .devcontainer/Dockerfile.arm64_vcpkg | 29 ++++++++++++++++ .devcontainer/build.sh | 13 +++++++ .devcontainer/entrypoint.sh | 9 +++++ cpp/.gitignore | 1 + cpp/CMakeLists.txt | 49 ++++++++++++++------------ cpp/cmake/ProjectConfig.cmake.in | 6 ++-- 9 files changed, 165 insertions(+), 71 deletions(-) create mode 100644 .devcontainer/Dockerfile.amd64_vcpkg create mode 100644 .devcontainer/Dockerfile.arm64_vcpkg create mode 100755 .devcontainer/build.sh create mode 100755 .devcontainer/entrypoint.sh create mode 100644 cpp/.gitignore diff --git a/.devcontainer/Dockerfile.amd64 b/.devcontainer/Dockerfile.amd64 index 2fd89e0..1e4c0af 100644 --- a/.devcontainer/Dockerfile.amd64 +++ b/.devcontainer/Dockerfile.amd64 @@ -1,27 +1,33 @@ FROM ubuntu:22.04 -RUN apt-get update --fix-missing &&\ - apt-get install -y --no-install-recommends build-essential ca-certificates git g++ pkg-config python3 curl ninja-build tar zip unzip zlib1g-dev libssl-dev wget &&\ - apt-get autoclean &&\ - apt-get autoremove &&\ - apt-get clean &&\ - rm -rf /var/lib/apt/lists/* +RUN apt-get update --fix-missing \ + && apt-get install -y --no-install-recommends \ + build-essential \ + ca-certificates \ + cmake \ + git \ + libcli11-dev \ + libeigen3-dev \ + libgrpc++-dev \ + libprotobuf-dev \ + g++ \ + pkg-config \ + protobuf-compiler \ + protobuf-compiler-grpc \ + python3 \ + curl \ + ninja-build \ + tar \ + zip \ + unzip \ + zlib1g-dev \ + libssl-dev \ + wget \ + && apt-get autoclean \ + && apt-get autoremove \ + && apt-get clean \ + && rm -rf /var/lib/apt/lists/* RUN update-ca-certificates -RUN wget https://github.com/Kitware/CMake/releases/download/v3.28.3/cmake-3.28.3.tar.gz &&\ - tar -xzf cmake-3.28.3.tar.gz &&\ - cd cmake-3.28.3 &&\ - ./configure &&\ - make install &&\ - cd .. &&\ - rm cmake-3.28.3.tar.gz &&\ - rm -r cmake-3.28.3 - -RUN git clone https://github.com/microsoft/vcpkg &&\ - cd vcpkg &&\ - git checkout 3b213864579b6fa686e38715508f7cd41a50900f &&\ - ./bootstrap-vcpkg.sh -disableMetrics &&\ - ./vcpkg install grpc:x64-linux &&\ - ./vcpkg install eigen3:x64-linux &&\ - ./vcpkg install cli11:x64-linux +COPY entrypoint.sh . diff --git a/.devcontainer/Dockerfile.amd64_vcpkg b/.devcontainer/Dockerfile.amd64_vcpkg new file mode 100644 index 0000000..2fd89e0 --- /dev/null +++ b/.devcontainer/Dockerfile.amd64_vcpkg @@ -0,0 +1,27 @@ +FROM ubuntu:22.04 + +RUN apt-get update --fix-missing &&\ + apt-get install -y --no-install-recommends build-essential ca-certificates git g++ pkg-config python3 curl ninja-build tar zip unzip zlib1g-dev libssl-dev wget &&\ + apt-get autoclean &&\ + apt-get autoremove &&\ + apt-get clean &&\ + rm -rf /var/lib/apt/lists/* + +RUN update-ca-certificates + +RUN wget https://github.com/Kitware/CMake/releases/download/v3.28.3/cmake-3.28.3.tar.gz &&\ + tar -xzf cmake-3.28.3.tar.gz &&\ + cd cmake-3.28.3 &&\ + ./configure &&\ + make install &&\ + cd .. &&\ + rm cmake-3.28.3.tar.gz &&\ + rm -r cmake-3.28.3 + +RUN git clone https://github.com/microsoft/vcpkg &&\ + cd vcpkg &&\ + git checkout 3b213864579b6fa686e38715508f7cd41a50900f &&\ + ./bootstrap-vcpkg.sh -disableMetrics &&\ + ./vcpkg install grpc:x64-linux &&\ + ./vcpkg install eigen3:x64-linux &&\ + ./vcpkg install cli11:x64-linux diff --git a/.devcontainer/Dockerfile.arm64 b/.devcontainer/Dockerfile.arm64 index 7f32e6e..dcbfb10 100644 --- a/.devcontainer/Dockerfile.arm64 +++ b/.devcontainer/Dockerfile.arm64 @@ -1,29 +1,33 @@ FROM arm64v8/ubuntu:22.04 -SHELL ["/bin/bash", "-c"] -RUN apt-get update --fix-missing &&\ - apt-get install -y --no-install-recommends build-essential ca-certificates cmake git g++ pkg-config python3 curl ninja-build tar zip unzip zlib1g-dev libssl-dev wget &&\ - apt-get autoclean &&\ - apt-get autoremove &&\ - apt-get clean &&\ - rm -rf /var/lib/apt/lists/* +RUN apt-get update --fix-missing \ + && apt-get install -y --no-install-recommends \ + build-essential \ + ca-certificates \ + cmake \ + git \ + libcli11-dev \ + libeigen3-dev \ + libgrpc++-dev \ + libprotobuf-dev \ + g++ \ + pkg-config \ + protobuf-compiler \ + protobuf-compiler-grpc \ + python3 \ + curl \ + ninja-build \ + tar \ + zip \ + unzip \ + zlib1g-dev \ + libssl-dev \ + wget \ + && apt-get autoclean \ + && apt-get autoremove \ + && apt-get clean \ + && rm -rf /var/lib/apt/lists/* RUN update-ca-certificates -RUN wget https://github.com/Kitware/CMake/releases/download/v3.28.3/cmake-3.28.3.tar.gz &&\ - tar -xzf cmake-3.28.3.tar.gz &&\ - cd cmake-3.28.3 &&\ - ./configure &&\ - make install &&\ - cd .. &&\ - rm cmake-3.28.3.tar.gz &&\ - rm -r cmake-3.28.3 - -RUN git clone https://github.com/microsoft/vcpkg &&\ - cd vcpkg &&\ - git checkout 3b213864579b6fa686e38715508f7cd41a50900f &&\ - export VCPKG_FORCE_SYSTEM_BINARIES=arm &&\ - ./bootstrap-vcpkg.sh -disableMetrics &&\ - ./vcpkg install grpc:arm64-linux &&\ - ./vcpkg install eigen3:arm64-linux &&\ - ./vcpkg install cli11:arm64-linux +COPY entrypoint.sh . diff --git a/.devcontainer/Dockerfile.arm64_vcpkg b/.devcontainer/Dockerfile.arm64_vcpkg new file mode 100644 index 0000000..7f32e6e --- /dev/null +++ b/.devcontainer/Dockerfile.arm64_vcpkg @@ -0,0 +1,29 @@ +FROM arm64v8/ubuntu:22.04 +SHELL ["/bin/bash", "-c"] + +RUN apt-get update --fix-missing &&\ + apt-get install -y --no-install-recommends build-essential ca-certificates cmake git g++ pkg-config python3 curl ninja-build tar zip unzip zlib1g-dev libssl-dev wget &&\ + apt-get autoclean &&\ + apt-get autoremove &&\ + apt-get clean &&\ + rm -rf /var/lib/apt/lists/* + +RUN update-ca-certificates + +RUN wget https://github.com/Kitware/CMake/releases/download/v3.28.3/cmake-3.28.3.tar.gz &&\ + tar -xzf cmake-3.28.3.tar.gz &&\ + cd cmake-3.28.3 &&\ + ./configure &&\ + make install &&\ + cd .. &&\ + rm cmake-3.28.3.tar.gz &&\ + rm -r cmake-3.28.3 + +RUN git clone https://github.com/microsoft/vcpkg &&\ + cd vcpkg &&\ + git checkout 3b213864579b6fa686e38715508f7cd41a50900f &&\ + export VCPKG_FORCE_SYSTEM_BINARIES=arm &&\ + ./bootstrap-vcpkg.sh -disableMetrics &&\ + ./vcpkg install grpc:arm64-linux &&\ + ./vcpkg install eigen3:arm64-linux &&\ + ./vcpkg install cli11:arm64-linux diff --git a/.devcontainer/build.sh b/.devcontainer/build.sh new file mode 100755 index 0000000..69ee41b --- /dev/null +++ b/.devcontainer/build.sh @@ -0,0 +1,13 @@ +#!/usr/bin/env bash +ARCH=$(dpkg --print-architecture) + +if [ "$ARCH" == "amd64" ]; then + docker build -t spot_builder -f Dockerfile.amd64 . +elif [ "$ARCH" == "arm64" ]; then + docker build -t spot_builder -f Dockerfile.arm64 . +else + echo "Unknown architecture: $ARCH" > /dev/stderr + exit 1 +fi + +docker run -v ~/spot-cpp-sdk:/spot-cpp-sdk spot_builder /entrypoint.sh diff --git a/.devcontainer/entrypoint.sh b/.devcontainer/entrypoint.sh new file mode 100755 index 0000000..6dce835 --- /dev/null +++ b/.devcontainer/entrypoint.sh @@ -0,0 +1,9 @@ +#!/usr/bin/env bash +cd /spot-cpp-sdk/cpp +if [ -d build ]; then + rm -r build +fi +mkdir build +cd build +cmake .. -DCMAKE_FIND_PACKAGE_PREFER_CONFIG=TRUE -DBUILD_CHOREOGRAPHY_LIBS=ON -DBUILD_SHARED_LIBS=ON +make -j8 install package diff --git a/cpp/.gitignore b/cpp/.gitignore new file mode 100644 index 0000000..378eac2 --- /dev/null +++ b/cpp/.gitignore @@ -0,0 +1 @@ +build diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index 3b805b7..e2955bc 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -10,12 +10,16 @@ cmake_minimum_required (VERSION 3.10.2) project (bosdyn VERSION 5.1.1) # Dependencies: -find_package(protobuf REQUIRED) +find_package(Protobuf REQUIRED) find_package(Eigen3 REQUIRED) -find_package(gRPC REQUIRED) + +find_package(PkgConfig REQUIRED) +pkg_check_modules(GRPC REQUIRED grpc) +pkg_check_modules(GRPCPP REQUIRED grpc++) +find_program(GRPC_CPP_PLUGIN_LOCATION grpc_cpp_plugin REQUIRED) find_package(CLI11 REQUIRED) find_package(Threads REQUIRED) -get_target_property(grpc_cpp_plugin_location gRPC::grpc_cpp_plugin LOCATION) + include_directories(SYSTEM $) set(CMAKE_EXPORT_COMPILE_COMMANDS true) @@ -24,6 +28,7 @@ set(CMAKE_EXPORT_COMPILE_COMMANDS true) set(CMAKE_BUILD_TYPE "Release" CACHE STRING "Choose the type of build." FORCE) option(BUILD_SHARED_LIBS "Build using shared libraries" ON) option(BUILD_CHOREOGRAPHY_LIBS "Boolean to control whether choreography proto libraries are built" ON) +option(BUILD_EXAMPLES "Boolean to control whether examples are built" OFF) IF (NOT UNIX) SET(BUILD_SHARED_LIBS OFF CACHE BOOL "Build using shared libraries" FORCE) @@ -31,30 +36,27 @@ ENDIF (NOT UNIX) include(GNUInstallDirs) - ### API protos LIBRARY ### -set(API_protos_PATH ${CMAKE_CURRENT_SOURCE_DIR}/build/protos/) -# Copy protos folders to build folder so they are in a subdirectory from the cpp folder (necessary for the proto cpp files generation). -file(COPY ${CMAKE_CURRENT_SOURCE_DIR}/../protos/ DESTINATION ${API_protos_PATH}) +get_filename_component(API_protos_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../protos/ ABSOLUTE) +file(GLOB_RECURSE bosdyn_protos_files CONFIGURE_DEPENDS "${API_protos_PATH}/*.proto") set(protos_OUTPUT_DIR ${CMAKE_CURRENT_BINARY_DIR}/protos) file(MAKE_DIRECTORY ${protos_OUTPUT_DIR}) -file(GLOB_RECURSE bosdyn_protos_files CONFIGURE_DEPENDS - RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} "${API_protos_PATH}/*.proto") - if (bosdyn_protos_files) add_library(bosdyn_api_obj OBJECT ${bosdyn_protos_files}) set_property(TARGET bosdyn_api_obj PROPERTY POSITION_INDEPENDENT_CODE 1) - target_link_libraries(bosdyn_api_obj PUBLIC protobuf::libprotobuf gRPC::grpc gRPC::grpc++) + target_link_libraries(bosdyn_api_obj PUBLIC protobuf::libprotobuf ${GRPC_LINK_LIBRARIES} ${GRPCPP_LINK_LIBRARIES}) target_include_directories(bosdyn_api_obj PUBLIC + ${GRPC_INCLUDE_DIRS} ${GRPCPP_INCLUDE_DIRS} $ $ ) protobuf_generate(TARGET bosdyn_api_obj LANGUAGE cpp - IMPORT_DIRS ${API_protos_PATH} - PROTOC_OUT_DIR ${protos_OUTPUT_DIR}) + IMPORT_DIRS ${API_protos_PATH} + PROTOC_OUT_DIR ${protos_OUTPUT_DIR} + ) protobuf_generate(TARGET bosdyn_api_obj LANGUAGE grpc GENERATE_EXTENSIONS .grpc.pb.h .grpc.pb.cc - PLUGIN "protoc-gen-grpc=${grpc_cpp_plugin_location}" + PLUGIN "protoc-gen-grpc=${GRPC_CPP_PLUGIN_LOCATION}" IMPORT_DIRS ${API_protos_PATH} PROTOC_OUT_DIR ${protos_OUTPUT_DIR} ) @@ -93,13 +95,11 @@ endif() if (BUILD_CHOREOGRAPHY_LIBS) ### API choreography_protos LIBRARY ### -set(API_choreography_protos_PATH ${CMAKE_CURRENT_SOURCE_DIR}/build/choreography_protos/) -# Copy choreography_protos folders to build folder so they are in a subdirectory from the cpp folder (necessary for the proto cpp files generation). -file(COPY ${CMAKE_CURRENT_SOURCE_DIR}/../choreography_protos/ DESTINATION ${API_choreography_protos_PATH}) +get_filename_component(API_choreography_protos_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../choreography_protos/ ABSOLUTE) +file(GLOB_RECURSE bosdyn_choreography_protos_files CONFIGURE_DEPENDS "${API_choreography_protos_PATH}/*.proto") set(choreography_protos_OUTPUT_DIR ${CMAKE_CURRENT_BINARY_DIR}/choreography_protos) file(MAKE_DIRECTORY ${choreography_protos_OUTPUT_DIR}) -file(GLOB_RECURSE bosdyn_choreography_protos_files CONFIGURE_DEPENDS - RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} "${API_choreography_protos_PATH}/*.proto") +file(GLOB_RECURSE bosdyn_choreography_protos_files CONFIGURE_DEPENDS "${API_choreography_protos_PATH}/*.proto") if (bosdyn_choreography_protos_files) add_library(bosdyn_choreography_protos_obj OBJECT ${bosdyn_choreography_protos_files}) @@ -114,7 +114,7 @@ if (bosdyn_choreography_protos_files) PROTOC_OUT_DIR ${choreography_protos_OUTPUT_DIR}) protobuf_generate(TARGET bosdyn_choreography_protos_obj LANGUAGE grpc GENERATE_EXTENSIONS .grpc.pb.h .grpc.pb.cc - PLUGIN "protoc-gen-grpc=${grpc_cpp_plugin_location}" + PLUGIN "protoc-gen-grpc=${GRPC_CPP_PLUGIN_LOCATION}" IMPORT_DIRS ${API_choreography_protos_PATH} PROTOC_OUT_DIR ${choreography_protos_OUTPUT_DIR} ) @@ -193,7 +193,11 @@ install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/bosdyn ) +include(CMakePackageConfigHelpers) + ### EXAMPLE EXECUTABLES ### +if(BUILD_EXAMPLES) + link_directories( ${PROTOBUF_LIB_DIR} ) @@ -210,6 +214,7 @@ target_compile_features(arm_manipulation_api_walk_to PUBLIC cxx_std_17) target_include_directories(arm_manipulation_api_walk_to PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ${PROTOBUF_INCLUDE_DIR} + $ ) target_link_libraries(arm_manipulation_api_walk_to PUBLIC bosdyn_client_static) install(TARGETS arm_manipulation_api_walk_to DESTINATION ${CMAKE_INSTALL_BINDIR}) @@ -255,12 +260,12 @@ target_include_directories(spot_cam PUBLIC target_link_libraries(spot_cam PUBLIC bosdyn_client_static) install(TARGETS spot_cam DESTINATION ${CMAKE_INSTALL_BINDIR}) # Save a version file in the project's binary directory -include(CMakePackageConfigHelpers) set(VERSION_FILE "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake") write_basic_package_version_file("${VERSION_FILE}" VERSION ${PACKAGE_VERSION} COMPATIBILITY AnyNewerVersion ) +endif() # This defines the instructions to generate a relocatable targets file at install time set(PROJECT_CONFIG_PATH "${CMAKE_INSTALL_LIBDIR}/cmake/${PROJECT_NAME}") @@ -274,7 +279,6 @@ install( # Define Variables needed by package config file set(PACKAGE_INSTALL_PREFIX /opt/spot-cpp-sdk) -set(DEP_INSTALL_PATH ${PACKAGE_INSTALL_PREFIX}/external) #this generates a relocatable config file for install, but it gets invoked at build time, #so the output has to be saved in a way that will not conflict with the export config @@ -323,6 +327,5 @@ if (UNIX) set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_CURRENT_SOURCE_DIR}/../LICENSE") set(CPACK_RESOURCE_FILE_README "${CMAKE_CURRENT_SOURCE_DIR}/README.md") set(CPACK_PACKAGING_INSTALL_PREFIX "${PACKAGE_INSTALL_PREFIX}") - set(CPACK_INSTALLED_DIRECTORIES "${VCPKG_INSTALLED_DIR}/${VCPKG_TARGET_TRIPLET}/;${DEP_INSTALL_PATH}/") include(CPack) endif() diff --git a/cpp/cmake/ProjectConfig.cmake.in b/cpp/cmake/ProjectConfig.cmake.in index 0bc68d2..fc53629 100644 --- a/cpp/cmake/ProjectConfig.cmake.in +++ b/cpp/cmake/ProjectConfig.cmake.in @@ -7,9 +7,11 @@ list(APPEND CMAKE_PREFIX_PATH @DEP_INSTALL_PATH@) include(CMakeFindDependencyMacro) find_dependency(Protobuf CONFIG REQUIRED) find_dependency(Eigen3 CONFIG REQUIRED) -find_dependency(gRPC CONFIG REQUIRED) -find_dependency(CLI11 CONFIG REQUIRED) +find_dependency(PkgConfig CONFIG REQUIRED) +pkg_check_modules(GRPC REQUIRED grpc) +pkg_check_modules(GRPCPP REQUIRED grpc++) find_dependency(Threads REQUIRED) +find_dependency(CLI11 REQUIRED) # Pick up the auto-generated file which knows how to add the library targets # This will mean that we do not have to supply full paths for the libraries set(exports_file "${CMAKE_CURRENT_LIST_DIR}/@EXPORTS_FILE@") From 1e5f22feb63ea4b611595c8913c935b35472a67c Mon Sep 17 00:00:00 2001 From: mhidalgo-bdai <144129882+mhidalgo-bdai@users.noreply.github.com> Date: Wed, 16 Oct 2024 13:35:10 -0300 Subject: [PATCH 11/15] Add dependencies to Spot C++ SDK debians (#5) Signed-off-by: Michel Hidalgo --- .devcontainer/Dockerfile.amd64 | 1 + .devcontainer/Dockerfile.arm64 | 1 + cpp/CMakeLists.txt | 2 ++ 3 files changed, 4 insertions(+) diff --git a/.devcontainer/Dockerfile.amd64 b/.devcontainer/Dockerfile.amd64 index 1e4c0af..f9494a6 100644 --- a/.devcontainer/Dockerfile.amd64 +++ b/.devcontainer/Dockerfile.amd64 @@ -5,6 +5,7 @@ RUN apt-get update --fix-missing \ build-essential \ ca-certificates \ cmake \ + file \ git \ libcli11-dev \ libeigen3-dev \ diff --git a/.devcontainer/Dockerfile.arm64 b/.devcontainer/Dockerfile.arm64 index dcbfb10..53433bf 100644 --- a/.devcontainer/Dockerfile.arm64 +++ b/.devcontainer/Dockerfile.arm64 @@ -5,6 +5,7 @@ RUN apt-get update --fix-missing \ build-essential \ ca-certificates \ cmake \ + file \ git \ libcli11-dev \ libeigen3-dev \ diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index e2955bc..6e717aa 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -320,6 +320,8 @@ if (UNIX) set(CPACK_GENERATOR "DEB") set(CPACK_PACKAGE_NAME "spot-cpp-sdk") set(CPACK_DEBIAN_FILE_NAME DEB-DEFAULT) + set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) + set(CPACK_DEBIAN_PACKAGE_DEPENDS "libcli11-dev (>=2.1.2)") # libcli11-dev is header-only, thus it has to be listed explicitly set(CPACK_DEBIAN_PACKAGE_MAINTAINER "Boston Dynamics SDK Publisher ") set(CPACK_PACKAGE_VENDOR "Boston Dynamics") set(CPACK_PACKAGE_VERSION ${PROJECT_VERSION}) From fc570791691f0de176b8761d41cd0c5247c8205d Mon Sep 17 00:00:00 2001 From: mhidalgo-bdai <144129882+mhidalgo-bdai@users.noreply.github.com> Date: Wed, 16 Oct 2024 17:29:31 -0300 Subject: [PATCH 12/15] Add gRPC dev libraries to Spot C++ SDK debian deps (#6) Signed-off-by: Michel Hidalgo --- cpp/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index 6e717aa..fd2e4dd 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -321,7 +321,7 @@ if (UNIX) set(CPACK_PACKAGE_NAME "spot-cpp-sdk") set(CPACK_DEBIAN_FILE_NAME DEB-DEFAULT) set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) - set(CPACK_DEBIAN_PACKAGE_DEPENDS "libcli11-dev (>=2.1.2)") # libcli11-dev is header-only, thus it has to be listed explicitly + set(CPACK_DEBIAN_PACKAGE_DEPENDS "libcli11-dev (>=2.1.2), libgrpc++-dev (>=1.30.2)") # not picked up by shlibdeps, thus listed explicitly set(CPACK_DEBIAN_PACKAGE_MAINTAINER "Boston Dynamics SDK Publisher ") set(CPACK_PACKAGE_VENDOR "Boston Dynamics") set(CPACK_PACKAGE_VERSION ${PROJECT_VERSION}) From 9d54e1c10a7fa9e3670485e4b67388fc4da94088 Mon Sep 17 00:00:00 2001 From: mhidalgo-bdai <144129882+mhidalgo-bdai@users.noreply.github.com> Date: Wed, 16 Oct 2024 18:07:59 -0300 Subject: [PATCH 13/15] No CONFIG modules in Spot C++ SDK CMake config (#7) Signed-off-by: Michel Hidalgo --- cpp/cmake/ProjectConfig.cmake.in | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/cpp/cmake/ProjectConfig.cmake.in b/cpp/cmake/ProjectConfig.cmake.in index fc53629..efe5fe0 100644 --- a/cpp/cmake/ProjectConfig.cmake.in +++ b/cpp/cmake/ProjectConfig.cmake.in @@ -5,9 +5,9 @@ list(APPEND CMAKE_PREFIX_PATH @DEP_INSTALL_PATH@) # Make sure the dependencies are available first include(CMakeFindDependencyMacro) -find_dependency(Protobuf CONFIG REQUIRED) -find_dependency(Eigen3 CONFIG REQUIRED) -find_dependency(PkgConfig CONFIG REQUIRED) +find_dependency(Protobuf REQUIRED) +find_dependency(Eigen3 REQUIRED) +find_dependency(PkgConfig REQUIRED) pkg_check_modules(GRPC REQUIRED grpc) pkg_check_modules(GRPCPP REQUIRED grpc++) find_dependency(Threads REQUIRED) From 01bb1a7fcb241e0c229507eba3d81737ae1a604f Mon Sep 17 00:00:00 2001 From: mhidalgo-bdai <144129882+mhidalgo-bdai@users.noreply.github.com> Date: Thu, 17 Oct 2024 10:45:45 -0300 Subject: [PATCH 14/15] Add Protobuf dev libraries to Spot C++ SDK debian deps (#8) Signed-off-by: Michel Hidalgo --- cpp/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cpp/CMakeLists.txt b/cpp/CMakeLists.txt index fd2e4dd..f5e422d 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -321,7 +321,7 @@ if (UNIX) set(CPACK_PACKAGE_NAME "spot-cpp-sdk") set(CPACK_DEBIAN_FILE_NAME DEB-DEFAULT) set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) - set(CPACK_DEBIAN_PACKAGE_DEPENDS "libcli11-dev (>=2.1.2), libgrpc++-dev (>=1.30.2)") # not picked up by shlibdeps, thus listed explicitly + set(CPACK_DEBIAN_PACKAGE_DEPENDS "libcli11-dev (>=2.1.2), libgrpc++-dev (>=1.30.2), libprotobuf-dev (>=3.12.4)") # not picked up by shlibdeps, thus listed explicitly set(CPACK_DEBIAN_PACKAGE_MAINTAINER "Boston Dynamics SDK Publisher ") set(CPACK_PACKAGE_VENDOR "Boston Dynamics") set(CPACK_PACKAGE_VERSION ${PROJECT_VERSION}) From 831346decf8fff415e4e332717f67eb372e2deac Mon Sep 17 00:00:00 2001 From: Katie Hughes <157421702+khughes-bdai@users.noreply.github.com> Date: Thu, 15 May 2025 13:32:43 -0400 Subject: [PATCH 15/15] Release v5.0.0 of Boston Dynamics Spot SDK (#14) Co-authored-by: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Release v5.0.0 of Boston Dynamics Spot SDK (#14) Co-authored-by: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> 5.1.0 sdk update (#16) * Release v5.0.1.1 of Boston Dynamics Spot SDK * Release v5.0.1.2 of Boston Dynamics Spot SDK * Release v5.1.0 of Boston Dynamics Spot SDK --------- Co-authored-by: Boston Dynamics SDK Publisher <53276189+bd-sdk-publisher@users.noreply.github.com> Release v5.1.0 of Boston Dynamics Spot SDK --- protos/bosdyn/api/mission/nodes.proto | 56 +++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) diff --git a/protos/bosdyn/api/mission/nodes.proto b/protos/bosdyn/api/mission/nodes.proto index e266cf8..aeb8b95 100644 --- a/protos/bosdyn/api/mission/nodes.proto +++ b/protos/bosdyn/api/mission/nodes.proto @@ -414,6 +414,62 @@ message BosdynNavigateToAnchor { } +// Tell the robot to navigate to a pose in the seed frame +message BosdynNavigateToAnchor { + // Name of the service to use. + string service_name = 1; + // Host machine the service is running on. + string host = 2; + + // Desired goal pose in seed frame. + bosdyn.api.SE3Pose seed_tform_goal = 3; + + // Preferences on how to pick the route. + bosdyn.api.graph_nav.RouteGenParams route_gen_params = 4; + // Parameters that define how to traverse and end the route. + bosdyn.api.graph_nav.TravelParams travel_params = 5; + + // If provided, this will write the last NavigationFeedbackResponse message + // to a blackboard variable with this name. + string navigation_feedback_response_blackboard_key = 6; + // If provided, this will write the last NavigateToResponse message to + // a blackboard variable with this name. + string navigate_to_anchor_response_blackboard_key = 7; + + // If provided, parameters from this request will be merged with the other parameters defined in + // the node and be used in the NavigateToAnchor RPC. + string navigate_to_anchor_request_blackboard_key = 8; + +} + +// Tell the robot to navigate to a pose in the seed frame +message BosdynNavigateToAnchor { + // Name of the service to use. + string service_name = 1; + // Host machine the service is running on. + string host = 2; + + // Desired goal pose in seed frame. + bosdyn.api.SE3Pose seed_tform_goal = 3; + + // Preferences on how to pick the route. + bosdyn.api.graph_nav.RouteGenParams route_gen_params = 4; + // Parameters that define how to traverse and end the route. + bosdyn.api.graph_nav.TravelParams travel_params = 5; + + // If provided, this will write the last NavigationFeedbackResponse message + // to a blackboard variable with this name. + string navigation_feedback_response_blackboard_key = 6; + // If provided, this will write the last NavigateToResponse message to + // a blackboard variable with this name. + string navigate_to_anchor_response_blackboard_key = 7; + + // If provided, parameters from this request will be merged with the other parameters defined in + // the node and be used in the NavigateToAnchor RPC. + string navigate_to_anchor_request_blackboard_key = 8; + +} + // Tell the robot to navigate a route. message BosdynNavigateRoute { // Name of the service to use.