Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[SW-1998] Add lease manager node #584

Merged
merged 2 commits into from
Feb 20, 2025
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
33 changes: 33 additions & 0 deletions spot_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ if(CCACHE_PROGRAM)
endif()

set(THIS_PACKAGE_INCLUDE_ROS_DEPENDS
bondcpp
bosdyn_api_msgs
bosdyn_cmake_module
bosdyn_spot_api_msgs
Expand Down Expand Up @@ -50,6 +51,7 @@ find_package(OpenCV 4 REQUIRED)
add_library(spot_api
src/api/default_kinematic_api.cpp
src/api/default_image_client.cpp
src/api/default_lease_client.cpp
src/api/default_spot_api.cpp
src/api/default_state_client.cpp
src/api/default_time_sync_api.cpp
Expand All @@ -71,6 +73,9 @@ add_library(spot_api
src/interfaces/rclcpp_tf_broadcaster_interface.cpp
src/interfaces/rclcpp_tf_listener_interface.cpp
src/interfaces/rclcpp_wall_timer_interface.cpp
src/lease/lease_manager.cpp
src/lease/lease_manager_node.cpp
src/lease/lease_middleware_handle.cpp
src/kinematic/kinematic_node.cpp
src/kinematic/kinematic_service.cpp
src/kinematic/kinematic_middleware_handle.cpp
Expand Down Expand Up @@ -145,6 +150,34 @@ rclcpp_components_register_node(
PLUGIN "spot_ros2::StatePublisherNode"
EXECUTABLE state_publisher_node_component)

###
# Spot lease manager
###

# Create executable to allow running LeaseManagerNode directly as a ROS 2 node
add_executable(lease_manager_node src/lease/lease_manager_node_main.cpp)
target_link_libraries(lease_manager_node PUBLIC spot_api)
target_include_directories(lease_manager_node
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)

# Register a composable node to allow loading StatePublisherNode in a component container
add_library(lease_manager_component SHARED src/lease/lease_manager_component.cpp)
target_include_directories(lease_manager_component
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)
target_link_libraries(lease_manager_component PUBLIC spot_api)
ament_target_dependencies(lease_manager_component PUBLIC rclcpp_components)

rclcpp_components_register_node(
lease_manager_component
PLUGIN "spot_ros2::LeaseManagerNode"
EXECUTABLE lease_manager_node_component)

###
# Spot IK
###
Expand Down
41 changes: 41 additions & 0 deletions spot_driver/include/spot_driver/api/default_lease_client.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// Copyright (c) 2025 Boston Dynamics AI Institute LLC. All rights reserved.

#pragma once

#include <bosdyn/client/lease/lease.h>
#include <bosdyn/client/lease/lease_client.h>
#include <bosdyn/client/lease/lease_keepalive.h>
#include <bosdyn/client/lease/lease_wallet.h>
#include <bosdyn/client/sdk/client_sdk.h>
#include <spot_driver/api/lease_client_interface.hpp>

#include <memory>
#include <string>
#include <unordered_map>

namespace spot_ros2 {
/**
* @brief Implements LeaseClientInterface.
*/
class DefaultLeaseClient : public LeaseClientInterface {
public:
explicit DefaultLeaseClient(::bosdyn::client::LeaseClient* lease_client);

[[nodiscard]] tl::expected<::bosdyn::client::Lease, std::string> acquireLease(
const std::string& resource_name, LeaseUseCallback retention_failure_callback) override;

[[nodiscard]] tl::expected<::bosdyn::client::Lease, std::string> takeLease(
const std::string& resource_name, LeaseUseCallback retention_failure_callback) override;

[[nodiscard]] tl::expected<bool, std::string> returnLease(const ::bosdyn::client::Lease& lease) override;

[[nodiscard]] std::shared_ptr<::bosdyn::client::LeaseWallet> getLeaseWallet() const override;

[[nodiscard]] const ::bosdyn::client::ResourceHierarchy& getResourceHierarchy() const override;

private:
::bosdyn::client::LeaseClient* lease_client_;
std::unordered_map<std::string, std::unique_ptr<::bosdyn::client::LeaseKeepAlive>> keepalives_;
std::mutex keepalives_mutex_;
};
} // namespace spot_ros2
3 changes: 3 additions & 0 deletions spot_driver/include/spot_driver/api/default_spot_api.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include <bosdyn/client/robot/robot.h>
#include <bosdyn/client/sdk/client_sdk.h>

#include <spot_driver/api/lease_client_interface.hpp>
#include <spot_driver/api/state_client_interface.hpp>
#include <spot_driver/api/time_sync_api.hpp>
#include <spot_driver/api/world_object_client_interface.hpp>
Expand All @@ -32,6 +33,7 @@ class DefaultSpotApi : public SpotApi {
[[nodiscard]] std::shared_ptr<KinematicApi> kinematicInterface() const override;
[[nodiscard]] std::shared_ptr<ImageClientInterface> image_client_interface() const override;
[[nodiscard]] std::shared_ptr<StateClientInterface> stateClientInterface() const override;
[[nodiscard]] std::shared_ptr<LeaseClientInterface> leaseClientInterface() const override;
[[nodiscard]] std::shared_ptr<TimeSyncApi> timeSyncInterface() const override;
[[nodiscard]] std::shared_ptr<WorldObjectClientInterface> worldObjectClientInterface() const override;

Expand All @@ -41,6 +43,7 @@ class DefaultSpotApi : public SpotApi {
std::shared_ptr<KinematicApi> kinematic_interface_;
std::shared_ptr<ImageClientInterface> image_client_interface_;
std::shared_ptr<StateClientInterface> state_client_interface_;
std::shared_ptr<LeaseClientInterface> lease_client_interface_;
std::shared_ptr<TimeSyncApi> time_sync_api_;
std::shared_ptr<WorldObjectClientInterface> world_object_client_interface_;
std::string robot_name_;
Expand Down
70 changes: 70 additions & 0 deletions spot_driver/include/spot_driver/api/lease_client_interface.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
// Copyright (c) 2025 Boston Dynamics AI Institute LLC. All rights reserved.

#pragma once

#include <functional>
#include <memory>
#include <string>

#include <tl_expected/expected.hpp>

#include <bosdyn/api/lease.pb.h>
#include <bosdyn/client/lease/lease.h>
#include <bosdyn/client/lease/lease_wallet.h>

namespace spot_ros2 {
/**
* @brief Interface class to interact with Spot SDK's lease client.
*/
class LeaseClientInterface {
public:
using LeaseUseCallback = std::function<void(const bosdyn::api::LeaseUseResult&)>;

// LeaseClientInterface is move-only
LeaseClientInterface() = default;
LeaseClientInterface(LeaseClientInterface&& other) = default;
LeaseClientInterface(const LeaseClientInterface&) = delete;
LeaseClientInterface& operator=(LeaseClientInterface&& other) = default;
LeaseClientInterface& operator=(const LeaseClientInterface&) = delete;

virtual ~LeaseClientInterface() = default;

/**
* @brief Acquire the lease for a given resource.
* @param resource_name Name of the resource.
* @param retention_failure_callback Callback on lease retention failure, invoked by the underlying lease keepalive.
* @return Returns an expected bearing the Lease if the lease was acquired. Otherwise, it will carry an error message
* describing the failure.
*/
virtual tl::expected<::bosdyn::client::Lease, std::string> acquireLease(
const std::string& resource_name, LeaseUseCallback retention_failure_callback) = 0;

/**
* @brief Take (forcefully) the lease for a given resource.
* @param resource_name Name of the resource.
* @param retention_failure_callback Callback on lease retention failure, invoked by the underlying lease keepalive.
* @return Returns an expected bearing the Lease if the lease was taken. Otherwise, it will carry an error message
* describing the failure.
*/
virtual tl::expected<::bosdyn::client::Lease, std::string> takeLease(const std::string& resource_name,
LeaseUseCallback retention_failure_callback) = 0;

/**
* @brief Return a given lease.
* @param lease Lease to be returned.
* @return Returns an expected bearing true if the lease was returned.
* Otherwise, it will carry an error message describing the failure.
*/
virtual tl::expected<bool, std::string> returnLease(const ::bosdyn::client::Lease& lease) = 0;

/**
* @return The underlying lease wallet.
*/
virtual std::shared_ptr<::bosdyn::client::LeaseWallet> getLeaseWallet() const = 0;

/**
* @return The resource hierarchy describing the robot hardware.
*/
virtual const ::bosdyn::client::ResourceHierarchy& getResourceHierarchy() const = 0;
};
} // namespace spot_ros2
2 changes: 2 additions & 0 deletions spot_driver/include/spot_driver/api/spot_api.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#pragma once

#include <spot_driver/api/kinematic_api.hpp>
#include <spot_driver/api/lease_client_interface.hpp>
#include <spot_driver/api/state_client_interface.hpp>
#include <spot_driver/api/time_sync_api.hpp>
#include <spot_driver/api/world_object_client_interface.hpp>
Expand Down Expand Up @@ -44,6 +45,7 @@ class SpotApi {
* @return A shared_ptr to an instance of StateClientInterface which is owned by this object.
*/
virtual std::shared_ptr<StateClientInterface> stateClientInterface() const = 0;
[[nodiscard]] virtual std::shared_ptr<LeaseClientInterface> leaseClientInterface() const = 0;
virtual std::shared_ptr<TimeSyncApi> timeSyncInterface() const = 0;
[[nodiscard]] virtual std::shared_ptr<WorldObjectClientInterface> worldObjectClientInterface() const = 0;
};
Expand Down
120 changes: 120 additions & 0 deletions spot_driver/include/spot_driver/lease/lease_manager.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
// Copyright (c) 2025 Boston Dynamics AI Institute LLC. All rights reserved.

#pragma once

#include <spot_driver/api/lease_client_interface.hpp>
#include <spot_driver/interfaces/logger_interface_base.hpp>

#include <spot_msgs/srv/acquire_lease.hpp>
#include <spot_msgs/srv/return_lease.hpp>

#include <memory>
#include <mutex>
#include <string>
#include <unordered_map>

namespace spot_ros2::lease {

using spot_msgs::srv::AcquireLease;
using spot_msgs::srv::ReturnLease;

/**
* Lease management for a ROS 2 graph.
*
* This manager acts as a proxy for leasing, allowing multiple
* ROS 2 nodes to cooperate without losing ownership over robot
* hardware.
*/
class LeaseManager {
public:
/**
* This middleware handle is used to register services and instantiate
* node bonds. In testing, it can be mocked to avoid using the ROS
* infrastructure.
*/
class MiddlewareHandle {
public:
class Bond {
public:
virtual ~Bond() = default;
};

virtual void createAcquireLeaseService(
const std::string& service_name,
std::function<void(const std::shared_ptr<AcquireLease::Request>, std::shared_ptr<AcquireLease::Response>)>
callback) = 0;

virtual void createReturnLeaseService(
const std::string& service_name,
std::function<void(const std::shared_ptr<ReturnLease::Request>, std::shared_ptr<ReturnLease::Response>)>
callback) = 0;

virtual std::shared_ptr<Bond> createBond(const std::string& node_name, std::function<void()> break_callback) = 0;

virtual ~MiddlewareHandle() = default;
};

/**
* Instantiate the lease manager.
* @param lease_client The ROS node.
* @param logger Logging interface.
* @param middleware_handle
*/
explicit LeaseManager(std::shared_ptr<LeaseClientInterface> lease_client, std::shared_ptr<LoggerInterfaceBase> logger,
std::unique_ptr<MiddlewareHandle> middleware_handle);

/** Initialize the service. */
void initialize();

/**
* Acquire lease on request.
*
* Typically used to implement the associated service.
*
* @param request The ROS request.
* @param response A ROS response to be filled.
*/
void acquireLease(const std::shared_ptr<AcquireLease::Request> request,
std::shared_ptr<AcquireLease::Response> response);

/**
* Return lease on request.
*
* Typically used to implement the associated service.
*
* @param request The ROS request.
* @param response A ROS response to be filled.
*/
void returnLease(const std::shared_ptr<ReturnLease::Request> request,
std::shared_ptr<ReturnLease::Response> response);

private:
/**
* Handle lease retention failure.
*
* Typically hooked up to the underlying lease keepalive.
*
* @param result The lease use result returned on lease retention failure.
*/
void onLeaseRetentionFailure(const bosdyn::api::LeaseUseResult& result);

// An interface to the lease API.
std::shared_ptr<LeaseClientInterface> lease_client_;

// An interface to logging API.
std::shared_ptr<LoggerInterfaceBase> logger_;

// An interface to the middleware provider.
std::unique_ptr<MiddlewareHandle> middleware_handle_;

struct ManagedSublease {
bosdyn::client::Lease lease; // Actual SDK sublease.
std::shared_ptr<MiddlewareHandle::Bond> bond; // ROS layer keepalive.
};
// Storage for active subleases (and associated keepalives).
std::unordered_map<std::string, ManagedSublease> subleases_;

// Synchronization primitive for sublease storage.
std::recursive_mutex subleases_mutex_;
};
} // namespace spot_ros2::lease
45 changes: 45 additions & 0 deletions spot_driver/include/spot_driver/lease/lease_manager_node.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
// Copyright (c) 2025 Boston Dynamics AI Institute LLC. All rights reserved.

#pragma once

#include <spot_driver/lease/lease_manager.hpp>

#include <spot_driver/api/spot_api.hpp>
#include <spot_driver/interfaces/logger_interface_base.hpp>
#include <spot_driver/interfaces/parameter_interface_base.hpp>

#include <rclcpp/node.hpp>
#include <rclcpp/node_interfaces/node_base_interface.hpp>
#include <rclcpp/node_options.hpp>

#include <memory>

namespace spot_ros2::lease {
class LeaseManagerNode {
public:
explicit LeaseManagerNode(std::shared_ptr<rclcpp::Node> node, std::unique_ptr<SpotApi> spot_api,
std::shared_ptr<ParameterInterfaceBase> parameter_interface,
std::shared_ptr<LoggerInterfaceBase> logger_interface);

explicit LeaseManagerNode(const rclcpp::NodeOptions& node_options = rclcpp::NodeOptions{});

/**
* @brief Returns the NodeBaseInterface of this class's node.
* @details This function exists to allow spinning the class's node as if it were derived from rclcpp::Node.
* This allows loading this class as a component node in a composable node container without requiring that it inherit
* from rclcpp::Node.
*
* @return A shared_ptr to the NodeBaseInterface of the node stored as a private member of this class.
*/
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> get_node_base_interface();

private:
std::shared_ptr<rclcpp::Node> node_;
std::unique_ptr<SpotApi> spot_api_;
std::unique_ptr<LeaseManager> internal_;

void initialize(std::shared_ptr<rclcpp::Node> node, std::unique_ptr<SpotApi> spot_api,
std::shared_ptr<ParameterInterfaceBase> parameter_interface,
const std::shared_ptr<LoggerInterfaceBase> logger_interface);
};
} // namespace spot_ros2::lease
Loading
Loading