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 3583ed3..2e5622a 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) @@ -250,6 +250,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 9de6d01..f644c0b 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";