-
Notifications
You must be signed in to change notification settings - Fork 522
Expand file tree
/
Copy pathcallback_group.hpp
More file actions
292 lines (256 loc) · 9.46 KB
/
callback_group.hpp
File metadata and controls
292 lines (256 loc) · 9.46 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
// Copyright 2014 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP__CALLBACK_GROUP_HPP_
#define RCLCPP__CALLBACK_GROUP_HPP_
#include <atomic>
#include <functional>
#include <memory>
#include <mutex>
#include <vector>
#include "rclcpp/client.hpp"
#include "rclcpp/context.hpp"
#include "rclcpp/guard_condition.hpp"
#include "rclcpp/publisher_base.hpp"
#include "rclcpp/service.hpp"
#include "rclcpp/subscription_base.hpp"
#include "rclcpp/timer.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rclcpp/waitable.hpp"
namespace rclcpp
{
// Forward declarations for friend statement in class CallbackGroup
namespace node_interfaces
{
class NodeServices;
class NodeTimers;
class NodeTopics;
class NodeWaitables;
} // namespace node_interfaces
enum class CallbackGroupType
{
MutuallyExclusive,
Reentrant
};
class CallbackGroup
{
friend class rclcpp::node_interfaces::NodeServices;
friend class rclcpp::node_interfaces::NodeTimers;
friend class rclcpp::node_interfaces::NodeTopics;
friend class rclcpp::node_interfaces::NodeWaitables;
public:
RCLCPP_SMART_PTR_DEFINITIONS(CallbackGroup)
/// Constructor for CallbackGroup.
/**
* Callback Groups have a type, either 'Mutually Exclusive' or 'Reentrant'
* and when creating one the type must be specified.
*
* Callbacks in Reentrant Callback Groups must be able to:
* - run at the same time as themselves (reentrant)
* - run at the same time as other callbacks in their group
* - run at the same time as other callbacks in other groups
*
* Callbacks in Mutually Exclusive Callback Groups:
* - will not be run multiple times simultaneously (non-reentrant)
* - will not be run at the same time as other callbacks in their group
* - but must run at the same time as callbacks in other groups
*
* Additionally, callback groups have a property which determines whether or
* not they are added to an executor with their associated node automatically.
* When creating a callback group the automatically_add_to_executor_with_node
* argument determines this behavior, and if true it will cause the newly
* created callback group to be added to an executor with the node when the
* Executor::add_node method is used.
* If false, this callback group will not be added automatically and would
* have to be added to an executor manually using the
* Executor::add_callback_group method.
*
* Whether the node was added to the executor before creating the callback
* group, or after, is irrelevant; the callback group will be automatically
* added to the executor in either case.
*
* \param[in] group_type The type of the callback group.
* \param[in] context A weak pointer to the context associated with this callback group.
* \param[in] automatically_add_to_executor_with_node A boolean that
* determines whether a callback group is automatically added to an executor
* with the node with which it is associated.
*/
RCLCPP_PUBLIC
explicit CallbackGroup(
CallbackGroupType group_type,
rclcpp::Context::WeakPtr context,
bool automatically_add_to_executor_with_node = true);
/// Default destructor.
RCLCPP_PUBLIC
~CallbackGroup();
template<typename Function>
rclcpp::SubscriptionBase::SharedPtr
find_subscription_ptrs_if(Function func) const
{
return _find_ptrs_if_impl<rclcpp::SubscriptionBase, Function>(func, subscription_ptrs_);
}
template<typename Function>
rclcpp::TimerBase::SharedPtr
find_timer_ptrs_if(Function func) const
{
return _find_ptrs_if_impl<rclcpp::TimerBase, Function>(func, timer_ptrs_);
}
template<typename Function>
rclcpp::ServiceBase::SharedPtr
find_service_ptrs_if(Function func) const
{
return _find_ptrs_if_impl<rclcpp::ServiceBase, Function>(func, service_ptrs_);
}
template<typename Function>
rclcpp::ClientBase::SharedPtr
find_client_ptrs_if(Function func) const
{
return _find_ptrs_if_impl<rclcpp::ClientBase, Function>(func, client_ptrs_);
}
template<typename Function>
rclcpp::Waitable::SharedPtr
find_waitable_ptrs_if(Function func) const
{
return _find_ptrs_if_impl<rclcpp::Waitable, Function>(func, waitable_ptrs_);
}
/// Get the total number of entities in this callback group.
/**
* \return the number of entities in the callback group.
*/
RCLCPP_PUBLIC
size_t
size() const;
/// Return a reference to the 'can be taken' atomic boolean.
/**
* The resulting bool will be true in the case that no executor is currently
* using an executable entity from this group.
* The resulting bool will be false in the case that an executor is currently
* using an executable entity from this group, and the group policy doesn't
* allow a second take (eg mutual exclusion)
* \return a reference to the flag
*/
RCLCPP_PUBLIC
std::atomic_bool &
can_be_taken_from();
/// Get the group type.
/**
* \return the group type
*/
RCLCPP_PUBLIC
const CallbackGroupType &
type() const;
/// Collect all of the entity pointers contained in this callback group.
/**
* \param[in] sub_func Function to execute for each subscription
* \param[in] service_func Function to execute for each service
* \param[in] client_func Function to execute for each client
* \param[in] timer_func Function to execute for each timer
* \param[in] waitable_fuinc Function to execute for each waitable
*/
RCLCPP_PUBLIC
void
collect_all_ptrs(
std::function<void(const rclcpp::SubscriptionBase::SharedPtr &)> sub_func,
std::function<void(const rclcpp::ServiceBase::SharedPtr &)> service_func,
std::function<void(const rclcpp::ClientBase::SharedPtr &)> client_func,
std::function<void(const rclcpp::TimerBase::SharedPtr &)> timer_func,
std::function<void(const rclcpp::Waitable::SharedPtr &)> waitable_func) const;
/// Return a reference to the 'associated with executor' atomic boolean.
/**
* When a callback group is added to an executor this boolean is checked
* to ensure it has not already been added to another executor.
* If it has not been, then this boolean is set to true to indicate it is
* now associated with an executor.
*
* When the callback group is removed from the executor, this atomic boolean
* is set back to false.
*
* \return the 'associated with executor' atomic boolean
*/
RCLCPP_PUBLIC
std::atomic_bool &
get_associated_with_executor_atomic();
/// Return true if this callback group should be automatically added to an executor by the node.
/**
* \return boolean true if this callback group should be automatically added
* to an executor when the associated node is added, otherwise false.
*/
RCLCPP_PUBLIC
bool
automatically_add_to_executor_with_node() const;
/// Retrieve the guard condition used to signal changes to this callback group.
/**
* \return guard condition if it is valid, otherwise nullptr.
*/
RCLCPP_PUBLIC
rclcpp::GuardCondition::SharedPtr
get_notify_guard_condition();
/// Trigger the notify guard condition.
RCLCPP_PUBLIC
void
trigger_notify_guard_condition();
protected:
RCLCPP_DISABLE_COPY(CallbackGroup)
RCLCPP_PUBLIC
void
add_publisher(const rclcpp::PublisherBase::SharedPtr publisher_ptr);
RCLCPP_PUBLIC
void
add_subscription(const rclcpp::SubscriptionBase::SharedPtr subscription_ptr);
RCLCPP_PUBLIC
void
add_timer(const rclcpp::TimerBase::SharedPtr timer_ptr);
RCLCPP_PUBLIC
void
add_service(const rclcpp::ServiceBase::SharedPtr service_ptr);
RCLCPP_PUBLIC
void
add_client(const rclcpp::ClientBase::SharedPtr client_ptr);
RCLCPP_PUBLIC
void
add_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr);
RCLCPP_PUBLIC
void
remove_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr) noexcept;
CallbackGroupType type_;
// Mutex to protect the subsequent vectors of pointers.
mutable std::mutex mutex_;
std::atomic_bool associated_with_executor_;
std::vector<rclcpp::SubscriptionBase::WeakPtr> subscription_ptrs_;
std::vector<rclcpp::TimerBase::WeakPtr> timer_ptrs_;
std::vector<rclcpp::ServiceBase::WeakPtr> service_ptrs_;
std::vector<rclcpp::ClientBase::WeakPtr> client_ptrs_;
std::vector<rclcpp::Waitable::WeakPtr> waitable_ptrs_;
std::atomic_bool can_be_taken_from_;
const bool automatically_add_to_executor_with_node_;
// defer the creation of the guard condition
std::shared_ptr<rclcpp::GuardCondition> notify_guard_condition_ = nullptr;
std::recursive_mutex notify_guard_condition_mutex_;
rclcpp::Context::WeakPtr context_;
private:
template<typename TypeT, typename Function>
typename TypeT::SharedPtr _find_ptrs_if_impl(
Function func, const std::vector<typename TypeT::WeakPtr> & vect_ptrs) const
{
std::lock_guard<std::mutex> lock(mutex_);
for (auto & weak_ptr : vect_ptrs) {
auto ref_ptr = weak_ptr.lock();
if (ref_ptr && func(ref_ptr)) {
return ref_ptr;
}
}
return typename TypeT::SharedPtr();
}
};
} // namespace rclcpp
#endif // RCLCPP__CALLBACK_GROUP_HPP_