Skip to content

Commit 6d8255c

Browse files
Release v5.0.0 of Boston Dynamics Spot SDK (#14)
Co-authored-by: Boston Dynamics SDK Publisher <[email protected]>
1 parent 1214794 commit 6d8255c

File tree

159 files changed

+1364
-218
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

159 files changed

+1364
-218
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ The official Spot SDK documentation also contains information relevant to the C+
2121
- [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.
2222
- [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.
2323

24-
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.
24+
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.
2525

2626
## Contents
2727

cpp/CMakeLists.txt

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@
77
# This file is autogenerated.
88

99
cmake_minimum_required (VERSION 3.10.2)
10-
project (bosdyn VERSION 4.1.1)
10+
project (bosdyn VERSION 5.0.0)
1111

1212
# Dependencies:
1313
find_package(Protobuf REQUIRED)
@@ -250,6 +250,7 @@ target_include_directories(inverse_kinematics_reachability PUBLIC
250250
)
251251
target_link_libraries(inverse_kinematics_reachability PUBLIC bosdyn_client_static)
252252
install(TARGETS inverse_kinematics_reachability DESTINATION ${CMAKE_INSTALL_BINDIR})
253+
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/examples/joint_control)
253254
add_executable(spot_cam ${CMAKE_CURRENT_SOURCE_DIR}/examples/spot_cam/ptz_example.cpp)
254255
target_compile_features(spot_cam PUBLIC cxx_std_17)
255256
target_include_directories(spot_cam PUBLIC

cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.cpp

Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,43 @@ GripperCameraParamClient::GetGripperCameraParamsAsync(const RPCParameters& param
8080
return future;
8181
}
8282

83+
SetGripperCameraCalibResponseType GripperCameraParamClient::SetGripperCameraCalib(
84+
::bosdyn::api::SetGripperCameraCalibrationRequest& request, const RPCParameters& parameters) {
85+
return SetGripperCameraCalibAsync(request, parameters).get();
86+
}
87+
88+
std::shared_future<SetGripperCameraCalibResponseType>
89+
GripperCameraParamClient::SetGripperCameraCalibAsync(
90+
::bosdyn::api::SetGripperCameraCalibrationRequest& request, const RPCParameters& parameters) {
91+
std::promise<SetGripperCameraCalibResponseType> response;
92+
std::shared_future<SetGripperCameraCalibResponseType> future = response.get_future();
93+
BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!");
94+
95+
MessagePumpCallBase* one_time =
96+
InitiateAsyncCall<::bosdyn::api::SetGripperCameraCalibrationRequest,
97+
::bosdyn::api::SetGripperCameraCalibrationResponse,
98+
::bosdyn::api::SetGripperCameraCalibrationResponse>(
99+
request,
100+
std::bind(&::bosdyn::api::GripperCameraParamService::StubInterface::AsyncSetCamCalib,
101+
m_stub.get(), _1, _2, _3),
102+
std::bind(&GripperCameraParamClient::OnSetGripperCameraCalibComplete, this, _1, _2, _3,
103+
_4, _5),
104+
std::move(response), parameters);
105+
106+
return future;
107+
}
108+
109+
void GripperCameraParamClient::OnSetGripperCameraCalibComplete(
110+
MessagePumpCallBase* call, const ::bosdyn::api::SetGripperCameraCalibrationRequest& request,
111+
::bosdyn::api::SetGripperCameraCalibrationResponse&& response, const grpc::Status& status,
112+
std::promise<SetGripperCameraCalibResponseType> promise) {
113+
::bosdyn::common::Status ret_status =
114+
ProcessResponseAndGetFinalStatus<::bosdyn::api::SetGripperCameraCalibrationResponse>(
115+
status, response, SDKErrorCode::Success);
116+
117+
promise.set_value({ret_status, std::move(response)});
118+
}
119+
83120
void GripperCameraParamClient::OnGetGripperCameraParamsComplete(
84121
MessagePumpCallBase* call, const ::bosdyn::api::GripperCameraGetParamRequest& request,
85122
::bosdyn::api::GripperCameraGetParamResponse&& response, const grpc::Status& status,
@@ -91,6 +128,44 @@ void GripperCameraParamClient::OnGetGripperCameraParamsComplete(
91128
promise.set_value({ret_status, std::move(response)});
92129
}
93130

131+
GetGripperCameraCalibrationResponseType GripperCameraParamClient::GetGripperCameraCalib(
132+
const RPCParameters& parameters) {
133+
return GetGripperCameraCalibAsync(parameters).get();
134+
}
135+
136+
std::shared_future<GetGripperCameraCalibrationResponseType>
137+
GripperCameraParamClient::GetGripperCameraCalibAsync(const RPCParameters& parameters) {
138+
std::promise<GetGripperCameraCalibrationResponseType> response;
139+
std::shared_future<GetGripperCameraCalibrationResponseType> future = response.get_future();
140+
BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!");
141+
142+
::bosdyn::api::GetGripperCameraCalibrationRequest request;
143+
144+
MessagePumpCallBase* one_time =
145+
InitiateAsyncCall<::bosdyn::api::GetGripperCameraCalibrationRequest,
146+
::bosdyn::api::GetGripperCameraCalibrationResponse,
147+
::bosdyn::api::GetGripperCameraCalibrationResponse>(
148+
request,
149+
std::bind(&::bosdyn::api::GripperCameraParamService::StubInterface::AsyncGetCamCalib,
150+
m_stub.get(), _1, _2, _3),
151+
std::bind(&GripperCameraParamClient::OnGetGripperCameraCalibComplete, this, _1, _2, _3,
152+
_4, _5),
153+
std::move(response), parameters);
154+
155+
return future;
156+
}
157+
158+
void GripperCameraParamClient::OnGetGripperCameraCalibComplete(
159+
MessagePumpCallBase* call, const ::bosdyn::api::GetGripperCameraCalibrationRequest& request,
160+
::bosdyn::api::GetGripperCameraCalibrationResponse&& response, const grpc::Status& status,
161+
std::promise<GetGripperCameraCalibrationResponseType> promise) {
162+
::bosdyn::common::Status ret_status =
163+
ProcessResponseAndGetFinalStatus<::bosdyn::api::GetGripperCameraCalibrationResponse>(
164+
status, response, SDKErrorCode::Success);
165+
166+
promise.set_value({ret_status, std::move(response)});
167+
}
168+
94169
// Start of ServiceClient overrides.
95170
ServiceClient::QualityOfService GripperCameraParamClient::GetQualityOfService() const {
96171
return QualityOfService::NORMAL;

cpp/bosdyn/client/gripper_camera_param/gripper_camera_param_client.h

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,10 @@ namespace client {
2222

2323
typedef Result<::bosdyn::api::GripperCameraParamResponse> GripperCameraSetParamResponseType;
2424
typedef Result<::bosdyn::api::GripperCameraGetParamResponse> GripperCameraGetParamResponseType;
25+
typedef Result<::bosdyn::api::SetGripperCameraCalibrationResponse>
26+
SetGripperCameraCalibResponseType;
27+
typedef Result<::bosdyn::api::GetGripperCameraCalibrationResponse>
28+
GetGripperCameraCalibrationResponseType;
2529

2630
// GripperCameraParamClient is the GRPC client for the gripper camera parameter service defined in
2731
// gripper_camera_param_service.proto.
@@ -49,6 +53,24 @@ class GripperCameraParamClient : public ServiceClient {
4953
std::shared_future<GripperCameraGetParamResponseType> GetGripperCameraParamsAsync(
5054
const RPCParameters& parameters = RPCParameters());
5155

56+
// Synchronous method to request to set gripper camera calibration.
57+
SetGripperCameraCalibResponseType SetGripperCameraCalib(
58+
::bosdyn::api::SetGripperCameraCalibrationRequest& request,
59+
const RPCParameters& parameters = RPCParameters());
60+
61+
// Asynchronous method to request to set gripper camera calibration.
62+
std::shared_future<SetGripperCameraCalibResponseType> SetGripperCameraCalibAsync(
63+
::bosdyn::api::SetGripperCameraCalibrationRequest& request,
64+
const RPCParameters& parameters = RPCParameters());
65+
66+
// Synchronous method to request to get gripper camera calibration.
67+
GetGripperCameraCalibrationResponseType GetGripperCameraCalib(
68+
const RPCParameters& parameters = RPCParameters());
69+
70+
// Asynchronous method to request to get gripper camera calibration.
71+
std::shared_future<GetGripperCameraCalibrationResponseType> GetGripperCameraCalibAsync(
72+
const RPCParameters& parameters = RPCParameters());
73+
5274
// Start of ServiceClient overrides.
5375
QualityOfService GetQualityOfService() const override;
5476
void SetComms(const std::shared_ptr<grpc::ChannelInterface>& channel) override;
@@ -86,6 +108,20 @@ class GripperCameraParamClient : public ServiceClient {
86108
::bosdyn::api::GripperCameraGetParamResponse&& response, const grpc::Status& status,
87109
std::promise<GripperCameraGetParamResponseType> promise);
88110

111+
// Callback that will return SetGripperCameraCalibrationResponse message after
112+
// SetGripperCameraCalib rpc returns to the client.
113+
void OnSetGripperCameraCalibComplete(
114+
MessagePumpCallBase* call, const ::bosdyn::api::SetGripperCameraCalibrationRequest& request,
115+
::bosdyn::api::SetGripperCameraCalibrationResponse&& response, const grpc::Status& status,
116+
std::promise<SetGripperCameraCalibResponseType> promise);
117+
118+
// Callback that will return GetGripperCameraCalibrationResponse message after
119+
// GetGripperCameraCalib rpc returns to the client.
120+
void OnGetGripperCameraCalibComplete(
121+
MessagePumpCallBase* call, const ::bosdyn::api::GetGripperCameraCalibrationRequest& request,
122+
::bosdyn::api::GetGripperCameraCalibrationResponse&& response, const grpc::Status& status,
123+
std::promise<GetGripperCameraCalibrationResponseType> promise);
124+
89125
std::unique_ptr<::bosdyn::api::GripperCameraParamService::StubInterface> m_stub;
90126

91127
// Lease wallet for commands.
Lines changed: 102 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,102 @@
1+
/**
2+
* Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved.
3+
*
4+
* Downloading, reproducing, distributing or otherwise using the SDK Software
5+
* is subject to the terms and conditions of the Boston Dynamics Software
6+
* Development Kit License (20191101-BDSDK-SL).
7+
*/
8+
9+
10+
#include "network_compute_bridge_client.h"
11+
12+
using namespace std::placeholders;
13+
14+
namespace bosdyn {
15+
16+
namespace client {
17+
18+
const char* NetworkComputeBridgeClient::s_default_service_name = "network-compute-bridge";
19+
20+
const char* NetworkComputeBridgeClient::s_service_type = "bosdyn.api.NetworkComputeBridge";
21+
22+
std::shared_future<NetworkComputeResultType> NetworkComputeBridgeClient::NetworkComputeAsync(
23+
::bosdyn::api::NetworkComputeRequest& request, const RPCParameters& parameters) {
24+
std::promise<NetworkComputeResultType> response;
25+
std::shared_future<NetworkComputeResultType> future = response.get_future();
26+
BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!");
27+
28+
MessagePumpCallBase* one_time = InitiateAsyncCall<::bosdyn::api::NetworkComputeRequest,
29+
::bosdyn::api::NetworkComputeResponse,
30+
::bosdyn::api::NetworkComputeResponse>(
31+
request,
32+
std::bind(&::bosdyn::api::NetworkComputeBridge::StubInterface::AsyncNetworkCompute,
33+
m_stub.get(), _1, _2, _3),
34+
std::bind(&NetworkComputeBridgeClient::OnNetworkComputeComplete, this, _1, _2, _3, _4, _5),
35+
std::move(response), parameters);
36+
return future;
37+
}
38+
39+
void NetworkComputeBridgeClient::OnNetworkComputeComplete(
40+
MessagePumpCallBase* call, const ::bosdyn::api::NetworkComputeRequest& request,
41+
::bosdyn::api::NetworkComputeResponse&& response, const grpc::Status& status,
42+
std::promise<NetworkComputeResultType> promise) {
43+
std::cout << "On network compute complete\n";
44+
::bosdyn::common::Status ret_status =
45+
ProcessResponseAndGetFinalStatus<::bosdyn::api::NetworkComputeResponse>(status, response,
46+
response.status());
47+
std::cout << "Ret status: " << ret_status.DebugString() << std::endl;
48+
promise.set_value({ret_status, std::move(response)});
49+
}
50+
51+
NetworkComputeResultType NetworkComputeBridgeClient::NetworkCompute(
52+
::bosdyn::api::NetworkComputeRequest& request, const RPCParameters& parameters) {
53+
return NetworkComputeAsync(request, parameters).get();
54+
}
55+
56+
std::shared_future<ListAvailableModelsResultType>
57+
NetworkComputeBridgeClient::ListAvailableModelsAsync(
58+
::bosdyn::api::ListAvailableModelsRequest& request, const RPCParameters& parameters) {
59+
std::promise<ListAvailableModelsResultType> response;
60+
std::shared_future<ListAvailableModelsResultType> future = response.get_future();
61+
BOSDYN_ASSERT_PRECONDITION(m_stub != nullptr, "Stub for service is unset!");
62+
63+
MessagePumpCallBase* one_time = InitiateAsyncCall<::bosdyn::api::ListAvailableModelsRequest,
64+
::bosdyn::api::ListAvailableModelsResponse,
65+
::bosdyn::api::ListAvailableModelsResponse>(
66+
request,
67+
std::bind(&::bosdyn::api::NetworkComputeBridge::StubInterface::AsyncListAvailableModels,
68+
m_stub.get(), _1, _2, _3),
69+
std::bind(&NetworkComputeBridgeClient::OnListAvailableModelsComplete, this, _1, _2, _3, _4,
70+
_5),
71+
std::move(response), parameters);
72+
return future;
73+
};
74+
75+
void NetworkComputeBridgeClient::OnListAvailableModelsComplete(
76+
MessagePumpCallBase* call, const ::bosdyn::api::ListAvailableModelsRequest& request,
77+
::bosdyn::api::ListAvailableModelsResponse&& response, const grpc::Status& status,
78+
std::promise<ListAvailableModelsResultType> promise) {
79+
std::cout << "On list available models complete\n";
80+
::bosdyn::common::Status ret_status =
81+
ProcessResponseAndGetFinalStatus<::bosdyn::api::ListAvailableModelsResponse>(
82+
status, response, response.status());
83+
std::cout << "Ret status: " << ret_status.DebugString() << std::endl;
84+
promise.set_value({ret_status, std::move(response)});
85+
}
86+
87+
ListAvailableModelsResultType NetworkComputeBridgeClient::ListAvailableModels(
88+
::bosdyn::api::ListAvailableModelsRequest& request, const RPCParameters& parameters) {
89+
return ListAvailableModelsAsync(request, parameters).get();
90+
}
91+
92+
ServiceClient::QualityOfService NetworkComputeBridgeClient::GetQualityOfService() const {
93+
return QualityOfService::NORMAL;
94+
}
95+
96+
void NetworkComputeBridgeClient::SetComms(const std::shared_ptr<grpc::ChannelInterface>& channel) {
97+
m_stub.reset(new ::bosdyn::api::NetworkComputeBridge::Stub(channel));
98+
}
99+
100+
} // namespace client
101+
102+
} // namespace bosdyn
Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
/**
2+
* Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved.
3+
*
4+
* Downloading, reproducing, distributing or otherwise using the SDK Software
5+
* is subject to the terms and conditions of the Boston Dynamics Software
6+
* Development Kit License (20191101-BDSDK-SL).
7+
*/
8+
9+
10+
#pragma once
11+
12+
#include <bosdyn/api/network_compute_bridge.pb.h>
13+
#include <bosdyn/api/network_compute_bridge_service.grpc.pb.h>
14+
15+
#include <future>
16+
17+
#include "network_compute_bridge_error_codes.h"
18+
#include "bosdyn/client/service_client/service_client.h"
19+
20+
namespace bosdyn {
21+
22+
namespace client {
23+
24+
// Defining result types for each RPC featuring the RPC call's status and the response message
25+
// the RPC was returning from the robot
26+
typedef Result<::bosdyn::api::NetworkComputeResponse> NetworkComputeResultType;
27+
typedef Result<::bosdyn::api::ListAvailableModelsResponse> ListAvailableModelsResultType;
28+
29+
// Client which communicates with the NetworkComputeBridgeWorker service
30+
class NetworkComputeBridgeClient : public ServiceClient {
31+
public:
32+
NetworkComputeBridgeClient() = default;
33+
~NetworkComputeBridgeClient() = default;
34+
35+
// Asynchronous method to request a response to a (now deprecated) NetworkComputeRequest
36+
std::shared_future<NetworkComputeResultType> NetworkComputeAsync(
37+
::bosdyn::api::NetworkComputeRequest& request,
38+
const RPCParameters& parameters = RPCParameters());
39+
40+
// Synchronous method to request a response to a NetworkComputeRequest
41+
NetworkComputeResultType NetworkCompute(::bosdyn::api::NetworkComputeRequest& request,
42+
const RPCParameters& parameters = RPCParameters());
43+
44+
// Asynchronous method to request a list of available NCB models on the robot
45+
std::shared_future<ListAvailableModelsResultType> ListAvailableModelsAsync(
46+
::bosdyn::api::ListAvailableModelsRequest& request,
47+
const RPCParameters& parameters = RPCParameters());
48+
49+
// Synchronous method to request a list of available NCB models on the robot
50+
ListAvailableModelsResultType ListAvailableModels(
51+
::bosdyn::api::ListAvailableModelsRequest& request,
52+
const RPCParameters& parameters = RPCParameters());
53+
54+
// Start of ServiceClient overrides.
55+
// Sets the QualityOfService enum for the network compute bridge worker client to be used for
56+
// network selection optimization.
57+
QualityOfService GetQualityOfService() const override;
58+
59+
// Set the communication details of the network compute bridge worker service, including the
60+
// stub and request/response processors
61+
void SetComms(const std::shared_ptr<grpc::ChannelInterface>& channel) override;
62+
63+
// End of ServiceClient overrides.
64+
65+
// Get the default service name the network compute bridge worker service will be registered in
66+
// the directory with.
67+
static std::string GetDefaultServiceName() { return s_default_service_name; }
68+
69+
// Get the default service type for the network compute bridge worker service that will be
70+
// registered in the directory.
71+
static std::string GetServiceType() { return s_service_type; }
72+
73+
private:
74+
// Callback function for asynchronous NetworkCompute RPC calls to return a result
75+
void OnNetworkComputeComplete(MessagePumpCallBase* call,
76+
const ::bosdyn::api::NetworkComputeRequest& request,
77+
::bosdyn::api::NetworkComputeResponse&& response,
78+
const grpc::Status& status,
79+
std::promise<NetworkComputeResultType> promise);
80+
81+
// Callback function for asynchronous ListAvailableModels RPC calls to return a result
82+
void OnListAvailableModelsComplete(MessagePumpCallBase* call,
83+
const ::bosdyn::api::ListAvailableModelsRequest& request,
84+
::bosdyn::api::ListAvailableModelsResponse&& response,
85+
const grpc::Status& status,
86+
std::promise<ListAvailableModelsResultType> promise);
87+
88+
std::unique_ptr<::bosdyn::api::NetworkComputeBridge::StubInterface> m_stub;
89+
90+
// Default service name for the network compute bridge worker service.
91+
static const char* s_default_service_name;
92+
93+
// Default service type for the network compute bridge worker service.
94+
static const char* s_service_type;
95+
};
96+
97+
} // namespace client
98+
99+
} // namespace bosdyn
Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**
2+
* Copyright (c) 2023 Boston Dynamics, Inc. All rights reserved.
3+
*
4+
* Downloading, reproducing, distributing or otherwise using the SDK Software
5+
* is subject to the terms and conditions of the Boston Dynamics Software
6+
* Development Kit License (20191101-BDSDK-SL).
7+
*/
8+
9+
10+
#include "bosdyn/client/network_compute_bridge//network_compute_bridge_error_codes.h"
11+
#include "bosdyn/client/error_codes/proto_enum_to_stderror_macro_source.h"
12+
13+
DEFINE_PROTO_ENUM_ERRORCODE_IMPL_API(NetworkComputeStatus, valcode == 1)
14+
DEFINE_PROTO_ENUM_ERRORCODE_IMPL_API(ListAvailableModelsStatus, valcode == 1)

0 commit comments

Comments
 (0)