Skip to content

Commit 14c882d

Browse files
committed
Merge remote-tracking branch 'origin/rolling' into mjcarroll/rclcpp_waitset_executor
2 parents 15f321f + b50f9ab commit 14c882d

20 files changed

+1760
-466
lines changed

rclcpp/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ set(${PROJECT_NAME}_SRCS
4545
src/rclcpp/clock.cpp
4646
src/rclcpp/context.cpp
4747
src/rclcpp/contexts/default_context.cpp
48+
src/rclcpp/create_generic_client.cpp
4849
src/rclcpp/detail/add_guard_condition_to_rcl_wait_set.cpp
4950
src/rclcpp/detail/resolve_intra_process_buffer_type.cpp
5051
src/rclcpp/detail/resolve_parameter_overrides.cpp
@@ -73,6 +74,7 @@ set(${PROJECT_NAME}_SRCS
7374
src/rclcpp/experimental/executors/events_executor/events_executor.cpp
7475
src/rclcpp/experimental/timers_manager.cpp
7576
src/rclcpp/future_return_code.cpp
77+
src/rclcpp/generic_client.cpp
7678
src/rclcpp/generic_publisher.cpp
7779
src/rclcpp/generic_subscription.cpp
7880
src/rclcpp/graph_listener.cpp

rclcpp/include/rclcpp/client.hpp

Lines changed: 28 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,29 @@ struct FutureAndRequestId
115115
/// Destructor.
116116
~FutureAndRequestId() = default;
117117
};
118+
119+
template<typename PendingRequestsT, typename AllocatorT = std::allocator<int64_t>>
120+
size_t
121+
prune_requests_older_than_impl(
122+
PendingRequestsT & pending_requests,
123+
std::mutex & pending_requests_mutex,
124+
std::chrono::time_point<std::chrono::system_clock> time_point,
125+
std::vector<int64_t, AllocatorT> * pruned_requests = nullptr)
126+
{
127+
std::lock_guard guard(pending_requests_mutex);
128+
auto old_size = pending_requests.size();
129+
for (auto it = pending_requests.begin(), last = pending_requests.end(); it != last; ) {
130+
if (it->second.first < time_point) {
131+
if (pruned_requests) {
132+
pruned_requests->push_back(it->first);
133+
}
134+
it = pending_requests.erase(it);
135+
} else {
136+
++it;
137+
}
138+
}
139+
return old_size - pending_requests.size();
140+
}
118141
} // namespace detail
119142

120143
namespace node_interfaces
@@ -771,19 +794,11 @@ class Client : public ClientBase
771794
std::chrono::time_point<std::chrono::system_clock> time_point,
772795
std::vector<int64_t, AllocatorT> * pruned_requests = nullptr)
773796
{
774-
std::lock_guard guard(pending_requests_mutex_);
775-
auto old_size = pending_requests_.size();
776-
for (auto it = pending_requests_.begin(), last = pending_requests_.end(); it != last; ) {
777-
if (it->second.first < time_point) {
778-
if (pruned_requests) {
779-
pruned_requests->push_back(it->first);
780-
}
781-
it = pending_requests_.erase(it);
782-
} else {
783-
++it;
784-
}
785-
}
786-
return old_size - pending_requests_.size();
797+
return detail::prune_requests_older_than_impl(
798+
pending_requests_,
799+
pending_requests_mutex_,
800+
time_point,
801+
pruned_requests);
787802
}
788803

789804
/// Configure client introspection.
Lines changed: 90 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,90 @@
1+
// Copyright 2023 Sony Group Corporation.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef RCLCPP__CREATE_GENERIC_CLIENT_HPP_
16+
#define RCLCPP__CREATE_GENERIC_CLIENT_HPP_
17+
18+
#include <memory>
19+
#include <string>
20+
21+
#include "rclcpp/generic_client.hpp"
22+
#include "rclcpp/node_interfaces/get_node_base_interface.hpp"
23+
#include "rclcpp/node_interfaces/get_node_graph_interface.hpp"
24+
#include "rclcpp/node_interfaces/get_node_services_interface.hpp"
25+
#include "rclcpp/node_interfaces/node_base_interface.hpp"
26+
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
27+
#include "rclcpp/node_interfaces/node_services_interface.hpp"
28+
#include "rclcpp/qos.hpp"
29+
30+
namespace rclcpp
31+
{
32+
/// Create a generic service client with a name of given type.
33+
/**
34+
* \param[in] node_base NodeBaseInterface implementation of the node on which
35+
* to create the client.
36+
* \param[in] node_graph NodeGraphInterface implementation of the node on which
37+
* to create the client.
38+
* \param[in] node_services NodeServicesInterface implementation of the node on
39+
* which to create the client.
40+
* \param[in] service_name The name on which the service is accessible.
41+
* \param[in] service_type The name of service type, e.g. "test_msgs/srv/BasicTypes"
42+
* \param[in] qos Quality of service profile for client.
43+
* \param[in] group Callback group to handle the reply to service calls.
44+
* \return Shared pointer to the created client.
45+
*/
46+
RCLCPP_PUBLIC
47+
rclcpp::GenericClient::SharedPtr
48+
create_generic_client(
49+
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
50+
std::shared_ptr<node_interfaces::NodeGraphInterface> node_graph,
51+
std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
52+
const std::string & service_name,
53+
const std::string & service_type,
54+
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
55+
rclcpp::CallbackGroup::SharedPtr group = nullptr);
56+
57+
/// Create a generic service client with a name of given type.
58+
/**
59+
* The NodeT type needs to have NodeBaseInterface implementation, NodeGraphInterface implementation
60+
* and NodeServicesInterface implementation of the node which to create the client.
61+
*
62+
* \param[in] node The node on which to create the client.
63+
* \param[in] service_name The name on which the service is accessible.
64+
* \param[in] service_type The name of service type, e.g. "test_msgs/srv/BasicTypes"
65+
* \param[in] qos Quality of service profile for client.
66+
* \param[in] group Callback group to handle the reply to service calls.
67+
* \return Shared pointer to the created client.
68+
*/
69+
template<typename NodeT>
70+
rclcpp::GenericClient::SharedPtr
71+
create_generic_client(
72+
NodeT node,
73+
const std::string & service_name,
74+
const std::string & service_type,
75+
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
76+
rclcpp::CallbackGroup::SharedPtr group = nullptr)
77+
{
78+
return create_generic_client(
79+
rclcpp::node_interfaces::get_node_base_interface(node),
80+
rclcpp::node_interfaces::get_node_graph_interface(node),
81+
rclcpp::node_interfaces::get_node_services_interface(node),
82+
service_name,
83+
service_type,
84+
qos,
85+
group
86+
);
87+
}
88+
} // namespace rclcpp
89+
90+
#endif // RCLCPP__CREATE_GENERIC_CLIENT_HPP_

rclcpp/include/rclcpp/executor.hpp

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -280,16 +280,23 @@ class Executor
280280
void
281281
spin_node_some(std::shared_ptr<rclcpp::Node> node);
282282

283-
/// Collect work once and execute all available work, optionally within a duration.
283+
/// Collect work once and execute all available work, optionally within a max duration.
284284
/**
285-
* This function can be overridden. The default implementation is suitable for a
286-
* single-threaded model of execution.
287-
* Adding subscriptions, timers, services, etc. with blocking callbacks will cause this function
288-
* to block (which may have unintended consequences).
285+
* This function can be overridden.
286+
* The default implementation is suitable for a single-threaded model of execution.
287+
* Adding subscriptions, timers, services, etc. with blocking or long running
288+
* callbacks may cause the function exceed the max_duration significantly.
289+
*
290+
* If there is no work to be done when this called, it will return immediately
291+
* because the collecting of available work is non-blocking.
292+
* Before each piece of ready work is executed this function checks if the
293+
* max_duration has been exceeded, and if it has it returns without starting
294+
* the execution of the next piece of work.
295+
*
296+
* If a max_duration of 0 is given, then all of the collected work will be
297+
* executed before the function returns.
289298
*
290299
* \param[in] max_duration The maximum amount of time to spend executing work, or 0 for no limit.
291-
* Note that spin_some() may take longer than this time as it only returns once max_duration has
292-
* been exceeded.
293300
*/
294301
RCLCPP_PUBLIC
295302
virtual void

0 commit comments

Comments
 (0)