Skip to content

Commit e34b68d

Browse files
committed
WIP
Signed-off-by: Michel Hidalgo <[email protected]>
1 parent e4c1ba6 commit e34b68d

File tree

5 files changed

+66
-24
lines changed

5 files changed

+66
-24
lines changed

spot_driver/include/spot_driver/lease/lease_service.hpp renamed to spot_driver/include/spot_driver/lease/lease_manager.hpp

Lines changed: 16 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,9 @@
1414
namespace spot_ros2::lease {
1515

1616
using spot_msgs::srv::AcquireLease;
17-
using spot_msgs::srv::ReleaseLease;
17+
using spot_msgs::srv::ReturnLease;
1818

19-
class LeaseService {
19+
class LeaseManager {
2020
public:
2121
/**
2222
* This middleware handle is used to register a service and assign to it a
@@ -25,13 +25,16 @@ class LeaseService {
2525
*/
2626
class MiddlewareHandle {
2727
public:
28-
virtual void createAcquireService(std::string service_name,
29-
std::function<void(const std::shared_ptr<AcquireLease::Request>,
30-
std::shared_ptr<AcquireLease::Response>)> callback) = 0;
28+
virtual void createAcquireLeaseService(const std::string& service_name,
29+
std::function<void(const std::shared_ptr<AcquireLease::Request>,
30+
std::shared_ptr<AcquireLease::Response>)> callback) = 0;
3131

32-
virtual void createReleaseService(std::string service_name,
33-
std::function<void(const std::shared_ptr<ReleaseLease::Request>,
34-
std::shared_ptr<ReleaseLease::Response>)> callback) = 0;
32+
virtual void createReturnLeaseService(const std::string& service_name,
33+
std::function<void(const std::shared_ptr<ReturnLease::Request>,
34+
std::shared_ptr<ReturnLease::Response>)> callback) = 0;
35+
virtual void createBond(const std::string& node_name) = 0;
36+
37+
virtual void destroyBond(const std::string& node_name) = 0;
3538

3639
virtual ~MiddlewareHandle() = default;
3740
};
@@ -42,7 +45,7 @@ class LeaseService {
4245
* @param kinematic_api The Api to interact with the Spot SDK.
4346
* @param logger Logging interface.
4447
*/
45-
explicit LeaseService(std::shared_ptr<LeaseApi> lease_api,
48+
explicit LeaseManager(std::shared_ptr<LeaseApi> lease_api,
4649
std::shared_ptr<LoggerInterfaceBase> logger,
4750
std::unique_ptr<MiddlewareHandle> middleware_handle);
4851

@@ -57,8 +60,8 @@ class LeaseService {
5760
void acquireLease(const std::shared_ptr<AcquireLease::Request> request,
5861
std::shared_ptr<AcquireLease::Response> response);
5962

60-
void releaseLease(const std::shared_ptr<ReleaseLease::Request> request,
61-
std::shared_ptr<ReleaseLease::Response> response);
63+
void returnLease(const std::shared_ptr<ReleaseLease::Request> request,
64+
std::shared_ptr<ReleaseLease::Response> response);
6265

6366
private:
6467
// The API to interact with Spot SDK.
@@ -69,5 +72,7 @@ class LeaseService {
6972

7073
// The service provider.
7174
std::unique_ptr<MiddlewareHandle> middleware_handle_;
75+
76+
std::unordered_map<std::string, std::string>
7277
};
7378
} // namespace spot_ros2::lease
Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
// Copyright (c) 2025 Boston Dynamics AI Institute LLC. All rights reserved.
2+
3+
#include <spot_driver/api/default_lease_api.hpp>
4+
5+
namespace spot_ros2 {
6+
DefaultLeaseClient::DefaultLeaseClient(bosdyn::client::LeaseClient* lease_client)
7+
: lease_client_{lease_client} {}
8+
9+
tl::expected<InverseKinematicsResponse, std::string> DefaultKinematicApi::getSolutions(
10+
InverseKinematicsRequest& request) {
11+
try {
12+
auto result = kinematic_client_->InverseKinematics(request);
13+
if (result) {
14+
return result.response;
15+
}
16+
17+
const auto error_code = result.status.code().value();
18+
const auto error_message = result.status.message();
19+
return tl::make_unexpected("The InverseKinematics service returned with error code " + std::to_string(error_code) +
20+
": " + error_message);
21+
} catch (const std::exception& ex) {
22+
return tl::make_unexpected("Failed to query the InverseKinematics service: " + std::string{ex.what()});
23+
}
24+
}
25+
26+
} // namespace spot_ros2

spot_driver/src/lease/lease_service.cpp renamed to spot_driver/src/lease/lease_manager.cpp

Lines changed: 14 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -11,32 +11,32 @@ constexpr auto kReleaseServiceName = "release_lease";
1111
}
1212

1313
namespace spot_ros2::lease {
14-
LeaseService::LeaseService(std::shared_ptr<LeaseApi> kinematic_api,
15-
std::shared_ptr<LoggerInterfaceBase> logger,
16-
std::unique_ptr<MiddlewareHandle> middleware_handle)
14+
LeaseManager::LeaseManager(std::shared_ptr<LeaseClientInterface> lease_client_interface,
15+
std::shared_ptr<LoggerInterfaceBase> logger,
16+
std::unique_ptr<MiddlewareHandle> middleware_handle)
1717
: lease_api_{lease_api}, logger_{std::move(logger)}, middleware_handle_{std::move(middleware_handle)} {}
1818

19-
void LeaseService::initialize() {
20-
middleware_handle_->createAcquireService(kAcquireServiceName,
19+
void LeaseManager::initialize() {
20+
middleware_handle_->createAcquireLeaseService(kAcquireLeaseServiceName,
2121
[this](const std::shared_ptr<AcquireLease::Request> request,
2222
std::shared_ptr<AcquireLease::Response> response) {
2323
this->acquireLease(request, response);
2424
});
25-
middleware_handle_->createReleaseService(kReleaseServiceName,
26-
[this](const std::shared_ptr<ReleaseLease::Request> request,
27-
std::shared_ptr<ReleaseLease::Response> response) {
28-
this->releaseLease(request, response);
25+
middleware_handle_->createReturnLeaseService(kReleaseLeaseServiceName,
26+
[this](const std::shared_ptr<ReturnLease::Request> request,
27+
std::shared_ptr<ReturnLease::Response> response) {
28+
this->returnLease(request, response);
2929
});
3030
}
3131

32-
void LeaseService::acquireLease(const std::shared_ptr<AcquireLease::Request> request,
32+
void LeaseManager::acquireLease(const std::shared_ptr<AcquireLease::Request> request,
3333
std::shared_ptr<AcquireLease::Response> response) {
3434
auto ros_request = request->request;
3535

3636
bosdyn::api::spot::InverseLeasesRequest proto_request;
3737
convertToProto(ros_request, proto_request);
3838

39-
auto expected = kinematic_api_->getSolutions(proto_request);
39+
auto expected = default__api_->getSolutions(proto_request);
4040
if (!expected) {
4141
logger_->logError(std::string{"Error querying the Inverse Leases service: "}.append(expected.error()));
4242
response->response.status.value = bosdyn_spot_api_msgs::msg::InverseLeasesResponseStatus::STATUS_UNKNOWN;
@@ -45,8 +45,9 @@ void LeaseService::acquireLease(const std::shared_ptr<AcquireLease::Request> req
4545
}
4646
}
4747

48-
void LeaseService::releaseLease(const std::shared_ptr<ReleaseLease::Request> request,
49-
std::shared_ptr<ReleaseLease::Response> response) {
48+
void LeaseManager::returnLease(const std::shared_ptr<ReturnLease::Request> request,
49+
std::shared_ptr<ReturnLease::Response> response) {
5050

5151
}
52+
5253
} // namespace spot_ros2::lease

spot_msgs/srv/AcquireLease.srv

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
string client_name
2+
string resource_name
3+
---
4+
bool success
5+
string message
6+
bosdyn_api_msgs/Lease lease

spot_msgs/srv/ReturnLease.srv

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
bosdyn_api_msgs/Lease lease
2+
---
3+
bool success
4+
string message

0 commit comments

Comments
 (0)