15 #ifndef NAV2_ROS_COMMON__SERVICE_CLIENT_HPP_
16 #define NAV2_ROS_COMMON__SERVICE_CLIENT_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_ros_common/node_utils.hpp"
31 template<
typename ServiceT>
35 using SharedPtr = std::shared_ptr<nav2::ServiceClient<ServiceT>>;
36 using UniquePtr = std::unique_ptr<nav2::ServiceClient<ServiceT>>;
44 template<
typename NodeT>
46 const std::string & service_name,
47 const NodeT & provided_node,
bool use_internal_executor =
false)
48 : service_name_(service_name),
49 clock_(provided_node->get_clock()),
50 logger_(provided_node->get_logger()),
51 node_base_interface_(provided_node->get_node_base_interface()),
52 use_internal_executor_(use_internal_executor)
54 if (use_internal_executor) {
55 callback_group_ = provided_node->create_callback_group(
56 rclcpp::CallbackGroupType::MutuallyExclusive,
58 callback_group_executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
59 callback_group_executor_->add_callback_group(callback_group_,
60 provided_node->get_node_base_interface());
63 client_ = rclcpp::create_client<ServiceT>(
64 provided_node->get_node_base_interface(),
65 provided_node->get_node_graph_interface(),
66 provided_node->get_node_services_interface(),
68 rclcpp::ServicesQoS(),
71 nav2::setIntrospectionMode(this->client_,
72 provided_node->get_node_parameters_interface(), clock_);
75 using RequestType =
typename ServiceT::Request;
76 using ResponseType =
typename ServiceT::Response;
84 typename ResponseType::SharedPtr
invoke(
85 typename RequestType::SharedPtr & request,
86 const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1),
87 const std::chrono::nanoseconds wait_for_service_timeout = std::chrono::seconds(10))
89 auto now = clock_->now();
90 while (!client_->wait_for_service(std::chrono::seconds(1))) {
92 throw std::runtime_error(
93 service_name_ +
" service client: interrupted while waiting for service");
96 logger_,
"%s service client: waiting for service to appear...",
97 service_name_.c_str());
99 if (clock_->now() - now > wait_for_service_timeout) {
100 throw std::runtime_error(
101 service_name_ +
" service client: timed out waiting for service");
106 logger_,
"%s service client: send async request",
107 service_name_.c_str());
108 auto future_result = client_->async_send_request(request);
111 client_->remove_pending_request(future_result);
112 throw std::runtime_error(service_name_ +
" service client: async_send_request failed");
115 return future_result.get();
125 typename RequestType::SharedPtr & request,
126 typename ResponseType::SharedPtr & response,
127 const std::chrono::nanoseconds wait_for_service_timeout = std::chrono::seconds(10))
129 auto now = clock_->now();
130 while (!client_->wait_for_service(std::chrono::seconds(1))) {
132 throw std::runtime_error(
133 service_name_ +
" service client: interrupted while waiting for service");
136 logger_,
"%s service client: waiting for service to appear...",
137 service_name_.c_str());
139 if (clock_->now() - now > wait_for_service_timeout) {
140 throw std::runtime_error(
141 service_name_ +
" service client: timed out waiting for service");
146 logger_,
"%s service client: send async request",
147 service_name_.c_str());
148 auto future_result = client_->async_send_request(request);
151 client_->remove_pending_request(future_result);
155 response = future_result.get();
156 return response.get();
164 std::shared_future<typename ResponseType::SharedPtr>
async_call(
165 typename RequestType::SharedPtr & request)
167 auto future_result = client_->async_send_request(request);
168 return future_result.share();
177 template<
typename CallbackT>
178 void async_call(
typename RequestType::SharedPtr request, CallbackT && callback)
180 client_->async_send_request(request, callback);
188 bool wait_for_service(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds::max())
190 return client_->wait_for_service(timeout);
200 template<
typename FutureT>
202 const FutureT & future,
203 const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1))
205 if (use_internal_executor_) {
206 return callback_group_executor_->spin_until_future_complete(future, timeout);
208 return rclcpp::spin_until_future_complete(node_base_interface_, future, timeout);
218 return service_name_;
222 std::string service_name_;
223 rclcpp::Clock::SharedPtr clock_;
224 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_ros_common")};
225 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
226 rclcpp::CallbackGroup::SharedPtr callback_group_{
nullptr};
227 rclcpp::executors::SingleThreadedExecutor::SharedPtr callback_group_executor_;
228 typename rclcpp::Client<ServiceT>::SharedPtr client_;
229 bool use_internal_executor_;
A simple wrapper on ROS2 services client.
std::shared_future< typename ResponseType::SharedPtr > async_call(typename RequestType::SharedPtr &request)
Asynchronously call the service.
rclcpp::FutureReturnCode spin_until_complete(const FutureT &future, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Spins the executor until the provided future is complete or the timeout is reached.
ResponseType::SharedPtr invoke(typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1), const std::chrono::nanoseconds wait_for_service_timeout=std::chrono::seconds(10))
Invoke the service and block until completed or timed out.
void async_call(typename RequestType::SharedPtr request, CallbackT &&callback)
Asynchronously call the service with a callback.
bool invoke(typename RequestType::SharedPtr &request, typename ResponseType::SharedPtr &response, const std::chrono::nanoseconds wait_for_service_timeout=std::chrono::seconds(10))
Invoke the service and block until completed.
ServiceClient(const std::string &service_name, const NodeT &provided_node, bool use_internal_executor=false)
A constructor.
bool wait_for_service(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::max())
Block until a service is available or timeout.
std::string getServiceName()
Gets the service name.