diff --git a/README.md b/README.md index 17774b4..c677472 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+ - [Payload developer documentation](https://dev.bostondynamics.com/docs/payload/readme). Payloads add additional sensing, communication, and control capabilities beyond what the base platform provides. The Payload ICD covers the mechanical, electrical, and software interfaces that Spot supports. - [Spot API protocol definition](https://dev.bostondynamics.com/docs/protos/readme). This reference guide covers the details of the protocol applications used to communicate to Spot. Application developers who wish to use a language other than Python can implement clients that speak the protocol. -This is version 5.1.0 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed. +This is version 5.1.4 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 3c807ce..a29da9b 100644 --- a/cpp/CMakeLists.txt +++ b/cpp/CMakeLists.txt @@ -7,7 +7,7 @@ # This file is autogenerated. cmake_minimum_required (VERSION 3.10.2) -project (bosdyn VERSION 5.1.0) +project (bosdyn VERSION 5.1.4) # Dependencies: find_package(Protobuf REQUIRED) diff --git a/cpp/bosdyn/client/data_acquisition/data_acquisition_client.cpp b/cpp/bosdyn/client/data_acquisition/data_acquisition_client.cpp index cb7ada7..48c6dbb 100644 --- a/cpp/bosdyn/client/data_acquisition/data_acquisition_client.cpp +++ b/cpp/bosdyn/client/data_acquisition/data_acquisition_client.cpp @@ -84,6 +84,7 @@ DataAcquisitionGetStatusResultType DataAcquisitionClient::GetStatus( return GetStatusAsync(request, parameters).get(); } + void DataAcquisitionClient::OnGetStatusComplete( MessagePumpCallBase* call, const ::bosdyn::api::GetStatusRequest& request, ::bosdyn::api::GetStatusResponse&& response, const grpc::Status& status, diff --git a/cpp/bosdyn/client/data_acquisition/data_acquisition_client.h b/cpp/bosdyn/client/data_acquisition/data_acquisition_client.h index a9f41c4..96b1b4b 100644 --- a/cpp/bosdyn/client/data_acquisition/data_acquisition_client.h +++ b/cpp/bosdyn/client/data_acquisition/data_acquisition_client.h @@ -67,6 +67,7 @@ class DataAcquisitionClient : public ServiceClient { ::bosdyn::api::CancelAcquisitionRequest& request, const RPCParameters& parameters = RPCParameters()); + // Asynchronous RPC to request live data for each capability. std::shared_future GetLiveDataAsync( ::bosdyn::api::LiveDataRequest& request, const RPCParameters& parameters = RPCParameters()); @@ -120,6 +121,7 @@ class DataAcquisitionClient : public ServiceClient { ::bosdyn::api::LiveDataResponse&& response, const grpc::Status& status, std::promise promise); + std::unique_ptr<::bosdyn::api::DataAcquisitionService::StubInterface> m_stub; // Default service name for the Data Acquisition service. diff --git a/docs/cpp_release_notes.md b/docs/cpp_release_notes.md index b4605c3..6869bb6 100644 --- a/docs/cpp_release_notes.md +++ b/docs/cpp_release_notes.md @@ -8,6 +8,14 @@ Development Kit License (20191101-BDSDK-SL). # Spot C++ SDK Release Notes +## Spot C++ SDK version 5.1.4 BETA + +- No changes from 5.1.1 + +## Spot C++ SDK version 5.1.1 BETA + +- No changes from 5.1.0 + ## Spot C++ SDK version 5.1.0 BETA ### Bug Fixes and Improvements diff --git a/protos/bosdyn/api/basic_command.proto b/protos/bosdyn/api/basic_command.proto index a18938c..5b63c1c 100644 --- a/protos/bosdyn/api/basic_command.proto +++ b/protos/bosdyn/api/basic_command.proto @@ -101,7 +101,14 @@ message StopCommand { // Freeze all joints at their current positions (no balancing control). message FreezeCommand { message Request { - // Freeze command request takes no additional arguments. + // Optional mode for freeze behavior. + enum Mode { + MODE_UNKNOWN = 0; + MODE_DEFAULT = 1; + // Freeze with higher joint gains to minimize deformation under external loads. + MODE_STIFF = 2; + } + Mode mode = 1; } message Feedback { diff --git a/protos/bosdyn/api/mission/nodes.proto b/protos/bosdyn/api/mission/nodes.proto index e266cf8..aeb8b95 100644 --- a/protos/bosdyn/api/mission/nodes.proto +++ b/protos/bosdyn/api/mission/nodes.proto @@ -414,6 +414,62 @@ message BosdynNavigateToAnchor { } +// Tell the robot to navigate to a pose in the seed frame +message BosdynNavigateToAnchor { + // Name of the service to use. + string service_name = 1; + // Host machine the service is running on. + string host = 2; + + // Desired goal pose in seed frame. + bosdyn.api.SE3Pose seed_tform_goal = 3; + + // Preferences on how to pick the route. + bosdyn.api.graph_nav.RouteGenParams route_gen_params = 4; + // Parameters that define how to traverse and end the route. + bosdyn.api.graph_nav.TravelParams travel_params = 5; + + // If provided, this will write the last NavigationFeedbackResponse message + // to a blackboard variable with this name. + string navigation_feedback_response_blackboard_key = 6; + // If provided, this will write the last NavigateToResponse message to + // a blackboard variable with this name. + string navigate_to_anchor_response_blackboard_key = 7; + + // If provided, parameters from this request will be merged with the other parameters defined in + // the node and be used in the NavigateToAnchor RPC. + string navigate_to_anchor_request_blackboard_key = 8; + +} + +// Tell the robot to navigate to a pose in the seed frame +message BosdynNavigateToAnchor { + // Name of the service to use. + string service_name = 1; + // Host machine the service is running on. + string host = 2; + + // Desired goal pose in seed frame. + bosdyn.api.SE3Pose seed_tform_goal = 3; + + // Preferences on how to pick the route. + bosdyn.api.graph_nav.RouteGenParams route_gen_params = 4; + // Parameters that define how to traverse and end the route. + bosdyn.api.graph_nav.TravelParams travel_params = 5; + + // If provided, this will write the last NavigationFeedbackResponse message + // to a blackboard variable with this name. + string navigation_feedback_response_blackboard_key = 6; + // If provided, this will write the last NavigateToResponse message to + // a blackboard variable with this name. + string navigate_to_anchor_response_blackboard_key = 7; + + // If provided, parameters from this request will be merged with the other parameters defined in + // the node and be used in the NavigateToAnchor RPC. + string navigate_to_anchor_request_blackboard_key = 8; + +} + // Tell the robot to navigate a route. message BosdynNavigateRoute { // Name of the service to use. diff --git a/protos/bosdyn/api/mobility_command.proto b/protos/bosdyn/api/mobility_command.proto index 0ea60a7..2e0f185 100644 --- a/protos/bosdyn/api/mobility_command.proto +++ b/protos/bosdyn/api/mobility_command.proto @@ -35,6 +35,9 @@ message MobilityCommand { StanceCommand.Request stance_request = 5; StopCommand.Request stop_request = 6; FollowArmCommand.Request follow_arm_request = 7; + // Mobility freeze for cases where the user wants to freeze only the lower body, leaving + // the arm free to move. + FreezeCommand.Request freeze_request = 8; } @@ -62,7 +65,7 @@ message MobilityCommand { StanceCommand.Feedback stance_feedback = 5; StopCommand.Feedback stop_feedback = 6; FollowArmCommand.Feedback follow_arm_feedback = 7; - + FreezeCommand.Feedback freeze_feedback = 8; } RobotCommandFeedbackStatus.Status status = 100; diff --git a/protos/bosdyn/api/power.proto b/protos/bosdyn/api/power.proto index 06ca0e3..e9af890 100644 --- a/protos/bosdyn/api/power.proto +++ b/protos/bosdyn/api/power.proto @@ -272,3 +272,25 @@ message ResetSafetyStopResponse { // Current feedback of specified command. Status status = 3; } + +// Request fan information from the robot. +message GetFanInformationRequest { + // Common request header. + RequestHeader header = 1; +} + +message FanInformation { + // Fan frequency in hertz. + float frequency = 1; +} + +// Response with fan information from various robot components. +message GetFanInformationResponse { + // Common response header. + ResponseHeader header = 1; + + // Map of fan name to fan information. Each robot might have a different set of fans to report. + // For example, Spot will report information for the fans "body_fan_0, body_fan_1, hips_fan_0, + // hips_fan_1". + map fan_information = 2; +} diff --git a/protos/bosdyn/api/power_service.proto b/protos/bosdyn/api/power_service.proto index 44aa657..1f928e3 100644 --- a/protos/bosdyn/api/power_service.proto +++ b/protos/bosdyn/api/power_service.proto @@ -30,6 +30,9 @@ service PowerService { rpc FanPowerCommandFeedback(FanPowerCommandFeedbackRequest) returns (FanPowerCommandFeedbackResponse) {} + // Get fan information. + rpc GetFanInformation(GetFanInformationRequest) returns (GetFanInformationResponse) {} + // Reset the safety stop bit on SRSF-configured robots. rpc ResetSafetyStop(ResetSafetyStopRequest) returns (ResetSafetyStopResponse) {} } diff --git a/protos/bosdyn/api/robot_state.proto b/protos/bosdyn/api/robot_state.proto index a056565..7892c9b 100644 --- a/protos/bosdyn/api/robot_state.proto +++ b/protos/bosdyn/api/robot_state.proto @@ -374,6 +374,11 @@ message BatteryState { // Temperatures may be measured in many locations across the battery. repeated double temperatures = 7; + // Measured battery communications loss percentage. Measured value from 0.0 to 100.0, where 0.0 + // means no communication loss and 100.0 means complete communication loss with the battery. If + // there is no battery in the robot, this value may be 0.0 or left unset. + google.protobuf.DoubleValue communications_loss_percent = 9; + enum Status { // The battery is in an unknown / unexpected state. STATUS_UNKNOWN = 0;