Skip to content

Commit f8aea8c

Browse files
Implement callback support of async_send_request for service generic client (#2614)
Signed-off-by: Barry Xu <[email protected]>
1 parent 16290fb commit f8aea8c

File tree

3 files changed

+189
-5
lines changed

3 files changed

+189
-5
lines changed

rclcpp/include/rclcpp/generic_client.hpp

+101-5
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <memory>
2020
#include <future>
2121
#include <string>
22+
#include <tuple>
2223
#include <vector>
2324
#include <utility>
2425

@@ -46,6 +47,8 @@ class GenericClient : public ClientBase
4647
using Future = std::future<SharedResponse>;
4748
using SharedFuture = std::shared_future<SharedResponse>;
4849

50+
using CallbackType = std::function<void (SharedFuture)>;
51+
4952
RCLCPP_SMART_PTR_DEFINITIONS(GenericClient)
5053

5154
/// A convenient GenericClient::Future and request id pair.
@@ -76,6 +79,20 @@ class GenericClient : public ClientBase
7679
~FutureAndRequestId() = default;
7780
};
7881

82+
/// A convenient GenericClient::SharedFuture and request id pair.
83+
/**
84+
* Public members:
85+
* - future: a std::shared_future<SharedResponse>.
86+
* - request_id: the request id associated with the future.
87+
*
88+
* All the other methods are equivalent to the ones std::shared_future provides.
89+
*/
90+
struct SharedFutureAndRequestId
91+
: detail::FutureAndRequestId<std::shared_future<SharedResponse>>
92+
{
93+
using detail::FutureAndRequestId<std::shared_future<SharedResponse>>::FutureAndRequestId;
94+
};
95+
7996
GenericClient(
8097
rclcpp::node_interfaces::NodeBaseInterface * node_base,
8198
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
@@ -106,16 +123,16 @@ class GenericClient : public ClientBase
106123
* If the future never completes,
107124
* e.g. the call to Executor::spin_until_future_complete() times out,
108125
* GenericClient::remove_pending_request() must be called to clean the client internal state.
109-
* Not doing so will make the `Client` instance to use more memory each time a response is not
110-
* received from the service server.
126+
* Not doing so will make the `GenericClient` instance to use more memory each time a response is
127+
* not received from the service server.
111128
*
112129
* ```cpp
113-
* auto future = client->async_send_request(my_request);
130+
* auto future = generic_client->async_send_request(my_request);
114131
* if (
115132
* rclcpp::FutureReturnCode::TIMEOUT ==
116133
* executor->spin_until_future_complete(future, timeout))
117134
* {
118-
* client->remove_pending_request(future);
135+
* generic_client->remove_pending_request(future);
119136
* // handle timeout
120137
* } else {
121138
* handle_response(future.get());
@@ -129,6 +146,45 @@ class GenericClient : public ClientBase
129146
FutureAndRequestId
130147
async_send_request(const Request request);
131148

149+
/// Send a request to the service server and schedule a callback in the executor.
150+
/**
151+
* Similar to the previous overload, but a callback will automatically be called when a response
152+
* is received.
153+
*
154+
* If the callback is never called, because we never got a reply for the service server,
155+
* remove_pending_request() has to be called with the returned request id or
156+
* prune_pending_requests().
157+
* Not doing so will make the `GenericClient` instance use more memory each time a response is not
158+
* received from the service server.
159+
* In this case, it's convenient to setup a timer to cleanup the pending requests.
160+
*
161+
* \param[in] request request to be send.
162+
* \param[in] cb callback that will be called when we get a response for this request.
163+
* \return the request id representing the request just sent.
164+
*/
165+
template<
166+
typename CallbackT,
167+
typename std::enable_if<
168+
rclcpp::function_traits::same_arguments<
169+
CallbackT,
170+
CallbackType
171+
>::value
172+
>::type * = nullptr
173+
>
174+
SharedFutureAndRequestId
175+
async_send_request(const Request request, CallbackT && cb)
176+
{
177+
Promise promise;
178+
auto shared_future = promise.get_future().share();
179+
auto req_id = async_send_request_impl(
180+
request,
181+
std::make_tuple(
182+
CallbackType{std::forward<CallbackT>(cb)},
183+
shared_future,
184+
std::move(promise)));
185+
return SharedFutureAndRequestId{std::move(shared_future), req_id};
186+
}
187+
132188
/// Clean all pending requests older than a time_point.
133189
/**
134190
* \param[in] time_point Requests that were sent before this point are going to be removed.
@@ -149,15 +205,52 @@ class GenericClient : public ClientBase
149205
pruned_requests);
150206
}
151207

208+
/// Clean all pending requests.
209+
/**
210+
* \return number of pending requests that were removed.
211+
*/
152212
RCLCPP_PUBLIC
153213
size_t
154214
prune_pending_requests();
155215

216+
/// Cleanup a pending request.
217+
/**
218+
* This notifies the client that we have waited long enough for a response from the server
219+
* to come, we have given up and we are not waiting for a response anymore.
220+
*
221+
* Not calling this will make the client start using more memory for each request
222+
* that never got a reply from the server.
223+
*
224+
* \param[in] request_id request id returned by async_send_request().
225+
* \return true when a pending request was removed, false if not (e.g. a response was received).
226+
*/
156227
RCLCPP_PUBLIC
157228
bool
158229
remove_pending_request(
159230
int64_t request_id);
160231

232+
/// Cleanup a pending request.
233+
/**
234+
* Convenient overload, same as:
235+
*
236+
* `GenericClient::remove_pending_request(this, future.request_id)`.
237+
*/
238+
RCLCPP_PUBLIC
239+
bool
240+
remove_pending_request(
241+
const FutureAndRequestId & future);
242+
243+
/// Cleanup a pending request.
244+
/**
245+
* Convenient overload, same as:
246+
*
247+
* `GenericClient::remove_pending_request(this, future.request_id)`.
248+
*/
249+
RCLCPP_PUBLIC
250+
bool
251+
remove_pending_request(
252+
const SharedFutureAndRequestId & future);
253+
161254
/// Take the next response for this client.
162255
/**
163256
* \sa ClientBase::take_type_erased_response().
@@ -179,9 +272,12 @@ class GenericClient : public ClientBase
179272
}
180273

181274
protected:
275+
using CallbackTypeValueVariant = std::tuple<CallbackType, SharedFuture, Promise>;
182276
using CallbackInfoVariant = std::variant<
183-
std::promise<SharedResponse>>; // Use variant for extension
277+
std::promise<SharedResponse>,
278+
CallbackTypeValueVariant>; // Use variant for extension
184279

280+
RCLCPP_PUBLIC
185281
int64_t
186282
async_send_request_impl(
187283
const Request request,

rclcpp/src/rclcpp/generic_client.cpp

+19
Original file line numberDiff line numberDiff line change
@@ -109,6 +109,13 @@ GenericClient::handle_response(
109109
if (std::holds_alternative<Promise>(value)) {
110110
auto & promise = std::get<Promise>(value);
111111
promise.set_value(std::move(response));
112+
} else if (std::holds_alternative<CallbackTypeValueVariant>(value)) {
113+
auto & inner = std::get<CallbackTypeValueVariant>(value);
114+
const auto & callback = std::get<CallbackType>(inner);
115+
auto & promise = std::get<Promise>(inner);
116+
auto & future = std::get<SharedFuture>(inner);
117+
promise.set_value(std::move(response));
118+
callback(std::move(future));
112119
}
113120
}
114121

@@ -128,6 +135,18 @@ GenericClient::remove_pending_request(int64_t request_id)
128135
return pending_requests_.erase(request_id) != 0u;
129136
}
130137

138+
bool
139+
GenericClient::remove_pending_request(const FutureAndRequestId & future)
140+
{
141+
return this->remove_pending_request(future.request_id);
142+
}
143+
144+
bool
145+
GenericClient::remove_pending_request(const SharedFutureAndRequestId & future)
146+
{
147+
return this->remove_pending_request(future.request_id);
148+
}
149+
131150
std::optional<GenericClient::CallbackInfoVariant>
132151
GenericClient::get_and_erase_pending_request(int64_t request_number)
133152
{

rclcpp/test/rclcpp/test_generic_client.cpp

+69
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414

1515
#include <gtest/gtest.h>
1616

17+
#include <chrono>
18+
#include <cstdint>
1719
#include <string>
1820
#include <memory>
1921
#include <utility>
@@ -28,6 +30,7 @@
2830
#include "../mocking_utils/patch.hpp"
2931

3032
#include "test_msgs/srv/empty.hpp"
33+
#include "test_msgs/srv/basic_types.hpp"
3134

3235
using namespace std::chrono_literals;
3336

@@ -228,3 +231,69 @@ TEST_F(TestGenericClientSub, construction_and_destruction) {
228231
}, rclcpp::exceptions::InvalidServiceNameError);
229232
}
230233
}
234+
235+
TEST_F(TestGenericClientSub, async_send_request_with_request) {
236+
const std::string service_name = "test_service";
237+
int64_t expected_change = 1111;
238+
239+
auto client = node->create_generic_client(service_name, "test_msgs/srv/BasicTypes");
240+
241+
auto callback = [&expected_change](
242+
const test_msgs::srv::BasicTypes::Request::SharedPtr request,
243+
test_msgs::srv::BasicTypes::Response::SharedPtr response) {
244+
response->int64_value = request->int64_value + expected_change;
245+
};
246+
247+
auto service =
248+
node->create_service<test_msgs::srv::BasicTypes>(service_name, std::move(callback));
249+
250+
ASSERT_TRUE(client->wait_for_service(std::chrono::seconds(5)));
251+
ASSERT_TRUE(client->service_is_ready());
252+
253+
test_msgs::srv::BasicTypes::Request request;
254+
request.int64_value = 12345678;
255+
256+
auto future = client->async_send_request(static_cast<void *>(&request));
257+
rclcpp::spin_until_future_complete(
258+
node->get_node_base_interface(), future, std::chrono::seconds(5));
259+
ASSERT_TRUE(future.valid());
260+
auto get_untyped_response = future.get();
261+
auto typed_response =
262+
static_cast<test_msgs::srv::BasicTypes::Response *>(get_untyped_response.get());
263+
EXPECT_EQ(typed_response->int64_value, (request.int64_value + expected_change));
264+
}
265+
266+
TEST_F(TestGenericClientSub, async_send_request_with_request_and_callback) {
267+
const std::string service_name = "test_service";
268+
int64_t expected_change = 2222;
269+
270+
auto client = node->create_generic_client(service_name, "test_msgs/srv/BasicTypes");
271+
272+
auto server_callback = [&expected_change](
273+
const test_msgs::srv::BasicTypes::Request::SharedPtr request,
274+
test_msgs::srv::BasicTypes::Response::SharedPtr response) {
275+
response->int64_value = request->int64_value + expected_change;
276+
};
277+
278+
auto service =
279+
node->create_service<test_msgs::srv::BasicTypes>(service_name, std::move(server_callback));
280+
281+
ASSERT_TRUE(client->wait_for_service(std::chrono::seconds(5)));
282+
ASSERT_TRUE(client->service_is_ready());
283+
284+
test_msgs::srv::BasicTypes::Request request;
285+
request.int64_value = 12345678;
286+
287+
auto client_callback = [&request, &expected_change](
288+
rclcpp::GenericClient::SharedFuture future) {
289+
auto untyped_response = future.get();
290+
auto typed_response =
291+
static_cast<test_msgs::srv::BasicTypes::Response *>(untyped_response.get());
292+
EXPECT_EQ(typed_response->int64_value, (request.int64_value + expected_change));
293+
};
294+
295+
auto future =
296+
client->async_send_request(static_cast<void *>(&request), client_callback);
297+
rclcpp::spin_until_future_complete(
298+
node->get_node_base_interface(), future, std::chrono::seconds(5));
299+
}

0 commit comments

Comments
 (0)