Skip to content
Merged
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 4.1.0 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed.
This is version 4.1.1 of the C++ SDK. Please review the [Release Notes](docs/cpp_release_notes.md) to see what has changed.

## Contents

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 4.1.0)
project (bosdyn VERSION 4.1.1)

# Dependencies:
find_package(Protobuf REQUIRED)
Expand Down
21 changes: 12 additions & 9 deletions cpp/bosdyn/client/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,19 +8,22 @@ Development Kit License (20191101-BDSDK-SL).

# Client Classes

The bosdyn/client folder contains client interfaces for interacting with the Boston Dynamics Spot
API. The client interfaces implement the Remote Procedure Calls (RPCs) in the
The bosdyn/client folder contains client interfaces for interacting with the Boston Dynamics Spot
API. The client interfaces implement the Remote Procedure Calls (RPCs) in the
[API protobuf definitions](https://dev.bostondynamics.com/protos/bosdyn/api/readme).

## Main Classes

The main classes contained in this folder are ClientSdk and Robot.
* **ClientSdk**: Class for settings typically common to a single developer and/or robot fleet.
* **Robot**: Class for settings common to one user's access to one robot. This is the main point
of access to all client functionality.

For example, to list the robot image sources using the Image client, simply create an Sdk object,
create a Robot object, authenticate, create the client and call the
- **ClientSdk**: Class for settings typically common to a single developer and/or robot fleet.
- **Robot**: Class for settings common to one user's access to one robot. This is the main point
of access to all client functionality.

For example, to list the robot image sources using the Image client, simply create an Sdk object,
create a Robot object, authenticate, create the client and call the
corresponding method, as shown below. It is that simple!

```
auto client_sdk = ::bosdyn::client::CreateStandardSDK("hello_spot");
auto robot = client_sdk->CreateRobot("10.0.0.3").move();
Expand All @@ -29,5 +32,5 @@ auto image_client = robot->EnsureServiceClient<::bosdyn::client::ImageClient>().
auto result = image_client->ListImageSources().move();
```

Clients that trigger robot movement also need to set up the TimeSync, Lease and E-Stop clients. Our
[Python examples](https://github.com/boston-dynamics/spot-sdk/tree/master/python/examples) repository contains many tutorials on how to use the clients. The API for the Spot Python SDK is very similar to the API for the Spot C++ SDK, and most Python examples can be used as reference on how to implement C++ applications. The Spot C++ SDK contains examples as well, listed [here](../../examples/README.md).
Clients that trigger robot movement also need to set up the TimeSync, Lease and E-Stop clients. Our
[Python examples](https://github.com/boston-dynamics/spot-sdk/tree/master/python/examples) repository contains many tutorials on how to use the clients. The API for the Spot Python SDK is very similar to the API for the Spot C++ SDK, and most Python examples can be used as reference on how to implement C++ applications. The Spot C++ SDK contains examples as well, listed [here](../../examples/README.md).
2 changes: 1 addition & 1 deletion cpp/bosdyn/client/directory/directory_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@

#include "directory_helpers.h"

#include "bosdyn/client/sdk/client_sdk.h"
#include "bosdyn/client/error_codes/directory_helper_error_code.h"
#include "bosdyn/client/sdk/client_sdk.h"

namespace bosdyn {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@
#include <thread>

#include "directory_registration_client.h"
#include "bosdyn/client/service_client/common_result_types.h"
#include "bosdyn/client/fault/fault_client.h"
#include "bosdyn/client/service_client/common_result_types.h"

#include <bosdyn/api/directory.pb.h>

Expand Down
2 changes: 1 addition & 1 deletion cpp/bosdyn/client/error_codes/error_type_condition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@

#include <iostream>

#include "bosdyn/client/error_codes/error_type_condition.h"
#include "bosdyn/client/error_codes/rpc_error_code.h"
#include "bosdyn/client/error_codes/sdk_error_code.h"
#include "bosdyn/client/error_codes/error_type_condition.h"

namespace { // anonymous namespace

Expand Down
25 changes: 15 additions & 10 deletions cpp/bosdyn/client/error_codes/time_sync_helper_error_code.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@


#include "bosdyn/client/error_codes/time_sync_helper_error_code.h"
#include "bosdyn/client/error_codes/sdk_error_code.h"
#include "bosdyn/client/error_codes/error_type_condition.h"
#include "bosdyn/client/error_codes/sdk_error_code.h"
#include "bosdyn/common/success_condition.h"

namespace bosdyn {
Expand All @@ -25,13 +25,15 @@ struct TimeSyncHelperErrorCodeCategory : std::error_category {
};

bool TimeSyncHelperErrorCodeCategory::equivalent(int valcode,
const std::error_condition& cond) const noexcept {
const std::error_condition& cond) const noexcept {
if (cond == SuccessCondition::Success) return (valcode == 0);
if (cond == ErrorTypeCondition::SDKError) return true;
return false;
}

const char* TimeSyncHelperErrorCodeCategory::name() const noexcept { return "TimeSyncHelperErrorCode"; }
const char* TimeSyncHelperErrorCodeCategory::name() const noexcept {
return "TimeSyncHelperErrorCode";
}

std::string TimeSyncHelperErrorCodeCategory::message(int value) const {
switch (static_cast<TimeSyncHelperErrorCode>(value)) {
Expand All @@ -43,21 +45,22 @@ std::string TimeSyncHelperErrorCodeCategory::message(int value) const {

const TimeSyncHelperErrorCodeCategory TimeSyncHelperErrorCodeCategory_category{};


struct EstablishTimeSyncErrorCodeCategory : std::error_category {
const char* name() const noexcept override;
std::string message(int ev) const override;
bool equivalent(int valcode, const std::error_condition& cond) const noexcept override;
};

bool EstablishTimeSyncErrorCodeCategory::equivalent(int valcode,
const std::error_condition& cond) const noexcept {
bool EstablishTimeSyncErrorCodeCategory::equivalent(
int valcode, const std::error_condition& cond) const noexcept {
if (cond == SuccessCondition::Success) return (valcode == 0);
if (cond == ErrorTypeCondition::SDKError) return true;
return false;
}

const char* EstablishTimeSyncErrorCodeCategory::name() const noexcept { return "EstablishTimeSyncErrorCode"; }
const char* EstablishTimeSyncErrorCodeCategory::name() const noexcept {
return "EstablishTimeSyncErrorCode";
}

std::string EstablishTimeSyncErrorCodeCategory::message(int value) const {
switch (static_cast<EstablishTimeSyncErrorCode>(value)) {
Expand All @@ -76,13 +79,15 @@ struct RobotTimeSyncErrorCodeCategory : std::error_category {
};

bool RobotTimeSyncErrorCodeCategory::equivalent(int valcode,
const std::error_condition& cond) const noexcept {
const std::error_condition& cond) const noexcept {
if (cond == SuccessCondition::Success) return (valcode == 0);
if (cond == ErrorTypeCondition::SDKError) return true;
return false;
}

const char* RobotTimeSyncErrorCodeCategory::name() const noexcept { return "RobotTimeSyncErrorCode"; }
const char* RobotTimeSyncErrorCodeCategory::name() const noexcept {
return "RobotTimeSyncErrorCode";
}

std::string RobotTimeSyncErrorCodeCategory::message(int value) const {
switch (static_cast<RobotTimeSyncErrorCode>(value)) {
Expand All @@ -94,7 +99,7 @@ std::string RobotTimeSyncErrorCodeCategory::message(int value) const {

const RobotTimeSyncErrorCodeCategory RobotTimeSyncErrorCodeCategory_category{};

} // anonymous namespace
} // anonymous namespace

std::error_code make_error_code(RobotTimeSyncErrorCode value) {
return {static_cast<int>(value), RobotTimeSyncErrorCodeCategory_category};
Expand Down
4 changes: 2 additions & 2 deletions cpp/bosdyn/client/error_codes/time_sync_helper_error_code.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ std::error_code make_error_code(TimeSyncHelperErrorCode);
std::error_code make_error_code(EstablishTimeSyncErrorCode);
std::error_code make_error_code(RobotTimeSyncErrorCode);

} // client namespace
} // bosdyn namespace
} // namespace client
} // namespace bosdyn

namespace std {
template <>
Expand Down
2 changes: 1 addition & 1 deletion cpp/bosdyn/client/estop/estop_keepalive.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@

#include <bosdyn/api/estop.pb.h>

#include "bosdyn/common/status.h"
#include "bosdyn/client/estop/estop_client.h"
#include "bosdyn/client/estop/estop_endpoint.h"
#include "bosdyn/common/status.h"

namespace bosdyn {

Expand Down
2 changes: 1 addition & 1 deletion cpp/bosdyn/client/processors/common_response_processor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@


#include "common_response_processor.h"
#include "bosdyn/client/error_codes/sdk_error_code.h"
#include "bosdyn/client/error_codes/header_error_code.h"
#include "bosdyn/client/error_codes/sdk_error_code.h"

namespace bosdyn {

Expand Down
15 changes: 8 additions & 7 deletions cpp/bosdyn/client/robot/robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ Result<std::shared_ptr<grpc::ChannelInterface>> Robot::EnsureChannel(

authority_iter = m_authorities_by_name.find(service_name);
if (authority_iter == m_authorities_by_name.end()) {
return {::bosdyn::common::Status(SDKErrorCode::GenericSDKError,
return {::bosdyn::common::Status(ClientCreationErrorCode::UnregisteredService,
"Could not find authority for " + service_name),
nullptr};
}
Expand All @@ -218,6 +218,12 @@ Result<std::shared_ptr<grpc::ChannelInterface>> Robot::EnsureChannel(
return EnsureSecureChannel((*authority_iter).second);
}

std::shared_ptr<grpc::ChannelInterface> Robot::CreateSecureChannel(const std::string& authority) {
std::shared_ptr<grpc::ChannelCredentials> creds =
Channel::CreateSecureChannelCreds(m_cert, std::bind(&Robot::GetUserToken, this));
return Channel::CreateSecureChannel(m_network_address, m_secure_channel_port, creds, authority);
}

Result<std::shared_ptr<grpc::ChannelInterface>> Robot::EnsureSecureChannel(
const std::string& authority) {
std::map<std::string, std::shared_ptr<grpc::ChannelInterface>>::iterator iter =
Expand All @@ -227,12 +233,7 @@ Result<std::shared_ptr<grpc::ChannelInterface>> Robot::EnsureSecureChannel(
}

// Secure Channel doesn't exist, so create it.
std::shared_ptr<grpc::ChannelCredentials> creds =
Channel::CreateSecureChannelCreds(m_cert, std::bind(&Robot::GetUserToken, this));

std::shared_ptr<grpc::ChannelInterface> channel =
Channel::CreateSecureChannel(m_network_address, m_secure_channel_port, creds, authority);

std::shared_ptr<grpc::ChannelInterface> channel = CreateSecureChannel(authority);
m_channels[authority] = channel;
return {::bosdyn::common::Status(SDKErrorCode::Success), channel};
}
Expand Down
3 changes: 3 additions & 0 deletions cpp/bosdyn/client/robot/robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -235,6 +235,9 @@ class Robot {
*/
void SetRPCParameters(const RPCParameters& parameters);

// Create a new GRPC channel.
std::shared_ptr<grpc::ChannelInterface> CreateSecureChannel(const std::string& authority);


Result<::bosdyn::api::RobotIdResponse> GetId(
const std::string& id_service_name =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,6 @@
*/


#include <bosdyn/api/spot_cam/logging.pb.h>
#include <bosdyn/api/spot_cam/camera.pb.h>
#include <bosdyn/api/spot_cam/logging.pb.h>
#include "bosdyn/client/error_codes/proto_enum_to_stderror_macro.h"
8 changes: 4 additions & 4 deletions cpp/examples/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ Boston Dynamics recommends completing the [QuickStart guide](../../docs/cpp/quic

## Contents

* [Hello Spot Example](hello_spot/README.md)
* [Basic Robot Command Example](basic_robot_command/README.md)
* [Get Image Example](get_image/README.md)
* [SpotCAM PTZ Example](spot_cam/README.md)
- [Hello Spot Example](hello_spot/README.md)
- [Basic Robot Command Example](basic_robot_command/README.md)
- [Get Image Example](get_image/README.md)
- [SpotCAM PTZ Example](spot_cam/README.md)
7 changes: 5 additions & 2 deletions cpp/examples/hello_spot/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,16 @@ Development Kit License (20191101-BDSDK-SL).

# Hello Spot

This example program is the introductory programming example for Spot. It demonstrates how to initialize the SDK to talk to robot and how to get information from the robot services, such as robot id, robot state, list of services running on the robot, and the list of registered payloads. It also logs data to the DataBuffer service.
This example program is the introductory programming example for Spot. It demonstrates how to initialize the SDK to talk to robot and how to get information from the robot services, such as robot id, robot state, list of services running on the robot, and the list of registered payloads. It also logs data to the DataBuffer service.

## Understanding Spot Programming
For your best learning experience, please use the [Quickstart Guide](../../../docs/cpp/quickstart.md) found in the SDK's docs/cpp directory. That will help you get your C++ programming environment set up properly. Then, specifically for Hello Spot, you should look at the [Understanding Spot Programming](../../../docs/python/understanding_spot_programming.md) file. This document walks you through all the commands found in this example!

For your best learning experience, please use the [Quickstart Guide](../../../docs/cpp/quickstart.md) found in the SDK's docs/cpp directory. That will help you get your C++ programming environment set up properly. Then, specifically for Hello Spot, you should look at the [Understanding Spot Programming](../../../docs/python/understanding_spot_programming.md) file. This document walks you through all the commands found in this example!

## Run the Example

To run the example, set BOSDYN_CLIENT_USERNAME and BOSDYN_CLIENT_PASSWORD environment variables with the robot credentials and then run:

```
./hello_spot {ROBOT_IP}
```
21 changes: 15 additions & 6 deletions docs/cpp/cpp_sdk_differences.md
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,11 @@ Development Kit License (20191101-BDSDK-SL).
This document describes the key differences between the Spot C++ SDK and the Spot Python SDK.

<!--ts-->
* [RPC method return types](#rpc-method-return-types)
* [Error checking](#error-checking)
* [Object ownership](#object-ownership)
* [Client-Server asynchronous communication](#client-service-asynchronous-communication)

- [RPC method return types](#rpc-method-return-types)
- [Error checking](#error-checking)
- [Object ownership](#object-ownership)
- [Client-Server asynchronous communication](#client-service-asynchronous-communication)
<!--te-->

## RPC method return types
Expand All @@ -23,9 +24,10 @@ This document describes the key differences between the Spot C++ SDK and the Spo

The C++ client classes do not throw exceptions for any errors detected during the gRPC communication or internal errors. Instead, methods return `Status` objects that include successful and failure return types. The `Status` class is described in the section below.

### Status class and error codes
### Status class and error codes

The `Status` class is used in the Spot C++ SDK as the return type for methods that need to return a success condition with additional error information. It contains an `std::error_code` field and a string message. The string message field contains a human-readable message to be used for logging and additional details for failure returns. The `std::error_code` field specifies a code for success or failures. There are two types of `std::error_code` defined in the C++ SDK:

- Manually defined: These are `std::error_code` definitions that do not depend on protobuf definitions in the Spot API. Examples of this type of `std::error_code` in the SDK are: `RPCErrorCode` used for gRPC return types, `LeaseWalletErrorCode` used for lease wallet return types, and many more.
- Auto-generated from protobuf Status enumerations. These are all associated in the `ResponseError` condition described below.

Expand All @@ -48,6 +50,7 @@ SDK methods that need to return a `Status` value as well as an object do so by r
The `Result` and `Status` objects defined in the section above contain an overloaded bool operator. So, developers can easily check for successful returns by the SDK methods:

`Result` return example that creates a `Robot` object from a `ClientSDK` object:

```
Result<std::unique_ptr<Robot>> robot_result = client_sdk->CreateRobot("spot_robot");
if (!robot_result) {
Expand All @@ -58,6 +61,7 @@ std::unique_ptr<Robot> robot = robot_result.move();
```

`Status` return example that authenticates the `Robot` object created in the code above:

```
Status status = robot->Authenticate("username", "password");
if (!status) {
Expand All @@ -67,12 +71,13 @@ if (!status) {
```

The hierarchy of error handling in the C++ SDK is as follows:

- `Result` bool operator simply returns the `Status` field in it, calling the `Status` bool operator.
- `Status` bool operator returns the value of `m_code == SuccessCondition::Success`, comparing its `std::error_code` to the `Success` `std::error_condition` described in the section [above](#status-class-and-error-codes).
- All `std::error_code` defined in the C++ SDK implement the `equivalent` method that returns success for the right enumeration value(s) that represent the success criteria. This process is described in more details below.


The `RPCErrorCode` defined for handling gRPC error codes contains this implementation of the `equivalent` method:

```
bool RPCErrorCodeCategory::equivalent(int valcode,
const std::error_condition& cond) const noexcept {
Expand Down Expand Up @@ -100,22 +105,26 @@ There are two main object ownership levels in the Spot C++ SDK:
- The `ClientSDK` class is at the highest level, and it is used to generate one or many instances of the `Robot` class, with each representing a connection to a specific robot. The `ClientSDK` instance can be discarded after the `Robot` instances are created.

- The `Robot` class provides functionality to communicate with a specific robot. It is used to create client instances that communicate with specific gRPC services registered in the robot system. The recommended way to create a `Robot` instance in an application is to use the static method in the `ClientSDK` class:

```
Result<std::unique_ptr<::bosdyn::client::Robot>> CreateRobot(
const std::string& network_address,
const ProxyUseType& proxy_use = AUTO_DETERMINE,
::bosdyn::common::Duration timeout = kRPCTimeoutNotSpecified,
std::shared_ptr<MessagePump> message_pump = nullptr);
```

That method returns a std::unique_ptr, so the application owns the `Robot` instance. This instance cannot go out-of-scope in the application while the service clients described below are still needed.

- The `ServiceClient` classes provide functionality to communicate with a specific service registered on a specific robot. The Spot C++ SDK contains a client implementation class derived from `ServiceClient` for each service defined in the Spot API. Each `ServiceClient` derived class implements the RPC methods corresponding to that service type. The recommended way to create `ServiceClient` instances in an application is to use the `EnsureServiceClient` methods in the `Robot` class:

```
Result<T*> EnsureServiceClient(
const std::string& service_name,
std::shared_ptr<grpc::ChannelInterface> channel = nullptr,
std::shared_ptr<MessagePump> message_pump = nullptr);
```

For example, to create a `RobotIdClient` object in the application in order to communicate with the `RobotId` service running on the robot, simply call:
`Result<RobotIdClient*> robot_id_client_result = robot->EnsureServiceClient<::bosdyn::client::RobotIdClient>();`

Expand Down
2 changes: 1 addition & 1 deletion docs/cpp/quickstart.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ This guide will help you set up your programming environment to successfully com

The Boston Dynamics Spot C++ SDK works with most operating systems including:

- Linux Ubuntu 18.04 LTS
- Linux Ubuntu 22.04 LTS
- gcc version 7+
- Windows 10
- Microsoft Visual Studio 2017+
Expand Down
Loading