Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
2 changes: 2 additions & 0 deletions cpp/bosdyn/client/data_acquisition/data_acquisition_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<DataAcquisitionLiveDataResultType> GetLiveDataAsync(
::bosdyn::api::LiveDataRequest& request, const RPCParameters& parameters = RPCParameters());
Expand Down Expand Up @@ -120,6 +121,7 @@ class DataAcquisitionClient : public ServiceClient {
::bosdyn::api::LiveDataResponse&& response, const grpc::Status& status,
std::promise<DataAcquisitionLiveDataResultType> promise);


std::unique_ptr<::bosdyn::api::DataAcquisitionService::StubInterface> m_stub;

// Default service name for the Data Acquisition service.
Expand Down
8 changes: 8 additions & 0 deletions docs/cpp_release_notes.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
9 changes: 8 additions & 1 deletion protos/bosdyn/api/basic_command.proto
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
56 changes: 56 additions & 0 deletions protos/bosdyn/api/mission/nodes.proto
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
5 changes: 4 additions & 1 deletion protos/bosdyn/api/mobility_command.proto
Original file line number Diff line number Diff line change
Expand Up @@ -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;

}

Expand Down Expand Up @@ -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;
Expand Down
22 changes: 22 additions & 0 deletions protos/bosdyn/api/power.proto
Original file line number Diff line number Diff line change
Expand Up @@ -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<string, FanInformation> fan_information = 2;
}
3 changes: 3 additions & 0 deletions protos/bosdyn/api/power_service.proto
Original file line number Diff line number Diff line change
Expand Up @@ -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) {}
}
5 changes: 5 additions & 0 deletions protos/bosdyn/api/robot_state.proto
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down