Skip to content

Commit 2bf88de

Browse files
committed
Deprecate callback_group call taking context
Signed-off-by: Michael Carroll <[email protected]>
1 parent 20e9cd1 commit 2bf88de

File tree

4 files changed

+73
-4
lines changed

4 files changed

+73
-4
lines changed

rclcpp/include/rclcpp/callback_group.hpp

Lines changed: 31 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -89,13 +89,16 @@ class CallbackGroup
8989
* added to the executor in either case.
9090
*
9191
* \param[in] group_type The type of the callback group.
92+
* \param[in] get_node_context Lambda to retrieve the node context when
93+
* checking that the creating node is valid and using the guard condition.
9294
* \param[in] automatically_add_to_executor_with_node A boolean that
9395
* determines whether a callback group is automatically added to an executor
9496
* with the node with which it is associated.
9597
*/
9698
RCLCPP_PUBLIC
9799
explicit CallbackGroup(
98100
CallbackGroupType group_type,
101+
std::function<rclcpp::Context::SharedPtr(void)> get_node_context,
99102
bool automatically_add_to_executor_with_node = true);
100103

101104
/// Default destructor.
@@ -137,6 +140,18 @@ class CallbackGroup
137140
return _find_ptrs_if_impl<rclcpp::Waitable, Function>(func, waitable_ptrs_);
138141
}
139142

143+
/// Return if the node that created this callback group still exists
144+
/**
145+
* As nodes can share ownership of callback groups with an executor, this
146+
* may be used to ensures that the executor doesn't operate on a callback
147+
* group that has outlived it's creating node.
148+
*
149+
* \return true if the creating node still exists, otherwise false
150+
*/
151+
RCLCPP_PUBLIC
152+
bool
153+
has_valid_node();
154+
140155
RCLCPP_PUBLIC
141156
std::atomic_bool &
142157
can_be_taken_from();
@@ -178,11 +193,24 @@ class CallbackGroup
178193
bool
179194
automatically_add_to_executor_with_node() const;
180195

181-
/// Defer creating the notify guard condition and return it.
196+
/// Retrieve the guard condition used to signal changes to this callback group.
197+
/**
198+
* \param[in] context_ptr context to use when creating the guard condition
199+
* \return guard condition if it is valid, otherwise nullptr.
200+
*/
201+
[[deprecated("Use get_notify_guard_condition() without arguments")]]
182202
RCLCPP_PUBLIC
183203
rclcpp::GuardCondition::SharedPtr
184204
get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr);
185205

206+
/// Retrieve the guard condition used to signal changes to this callback group.
207+
/**
208+
* \return guard condition if it is valid, otherwise nullptr.
209+
*/
210+
RCLCPP_PUBLIC
211+
rclcpp::GuardCondition::SharedPtr
212+
get_notify_guard_condition();
213+
186214
/// Trigger the notify guard condition.
187215
RCLCPP_PUBLIC
188216
void
@@ -234,6 +262,8 @@ class CallbackGroup
234262
std::shared_ptr<rclcpp::GuardCondition> notify_guard_condition_ = nullptr;
235263
std::recursive_mutex notify_guard_condition_mutex_;
236264

265+
std::function<rclcpp::Context::SharedPtr(void)> get_context_;
266+
237267
private:
238268
template<typename TypeT, typename Function>
239269
typename TypeT::SharedPtr _find_ptrs_if_impl(

rclcpp/src/rclcpp/callback_group.cpp

Lines changed: 32 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,17 +31,25 @@ using rclcpp::CallbackGroupType;
3131

3232
CallbackGroup::CallbackGroup(
3333
CallbackGroupType group_type,
34+
std::function<rclcpp::Context::SharedPtr(void)> get_context,
3435
bool automatically_add_to_executor_with_node)
3536
: type_(group_type), associated_with_executor_(false),
3637
can_be_taken_from_(true),
37-
automatically_add_to_executor_with_node_(automatically_add_to_executor_with_node)
38+
automatically_add_to_executor_with_node_(automatically_add_to_executor_with_node),
39+
get_context_(get_context)
3840
{}
3941

4042
CallbackGroup::~CallbackGroup()
4143
{
4244
trigger_notify_guard_condition();
4345
}
4446

47+
bool
48+
CallbackGroup::has_valid_node()
49+
{
50+
return nullptr != this->get_context_();
51+
}
52+
4553
std::atomic_bool &
4654
CallbackGroup::can_be_taken_from()
4755
{
@@ -111,6 +119,7 @@ CallbackGroup::automatically_add_to_executor_with_node() const
111119
return automatically_add_to_executor_with_node_;
112120
}
113121

122+
// \TODO(mjcarroll) Deprecated, remove on tock
114123
rclcpp::GuardCondition::SharedPtr
115124
CallbackGroup::get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr)
116125
{
@@ -129,6 +138,28 @@ CallbackGroup::get_notify_guard_condition(const rclcpp::Context::SharedPtr conte
129138
return notify_guard_condition_;
130139
}
131140

141+
rclcpp::GuardCondition::SharedPtr
142+
CallbackGroup::get_notify_guard_condition()
143+
{
144+
auto context_ptr = this->get_context_();
145+
if (context_ptr && context_ptr->is_valid()) {
146+
std::lock_guard<std::recursive_mutex> lock(notify_guard_condition_mutex_);
147+
if (notify_guard_condition_ && context_ptr != notify_guard_condition_->get_context()) {
148+
if (associated_with_executor_) {
149+
trigger_notify_guard_condition();
150+
}
151+
notify_guard_condition_ = nullptr;
152+
}
153+
154+
if (!notify_guard_condition_) {
155+
notify_guard_condition_ = std::make_shared<rclcpp::GuardCondition>(context_ptr);
156+
}
157+
158+
return notify_guard_condition_;
159+
}
160+
return nullptr;
161+
}
162+
132163
void
133164
CallbackGroup::trigger_notify_guard_condition()
134165
{

rclcpp/src/rclcpp/executor.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -222,8 +222,7 @@ Executor::add_callback_group_to_map(
222222
weak_groups_to_nodes_.insert(std::make_pair(weak_group_ptr, node_ptr));
223223

224224
if (node_ptr->get_context()->is_valid()) {
225-
auto callback_group_guard_condition =
226-
group_ptr->get_notify_guard_condition(node_ptr->get_context());
225+
auto callback_group_guard_condition = group_ptr->get_notify_guard_condition();
227226
weak_groups_to_guard_conditions_[weak_group_ptr] = callback_group_guard_condition.get();
228227
// Add the callback_group's notify condition to the guard condition handles
229228
memory_strategy_->add_guard_condition(*callback_group_guard_condition);

rclcpp/src/rclcpp/node_interfaces/node_base.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -202,8 +202,17 @@ NodeBase::create_callback_group(
202202
rclcpp::CallbackGroupType group_type,
203203
bool automatically_add_to_executor_with_node)
204204
{
205+
auto weak_ptr = this->weak_from_this();
205206
auto group = std::make_shared<rclcpp::CallbackGroup>(
206207
group_type,
208+
[this]() -> rclcpp::Context::SharedPtr {
209+
auto weak_ptr = this->weak_from_this();
210+
auto node_ptr = weak_ptr.lock();
211+
if (node_ptr) {
212+
return node_ptr->get_context();
213+
}
214+
return nullptr;
215+
},
207216
automatically_add_to_executor_with_node);
208217
std::lock_guard<std::mutex> lock(callback_groups_mutex_);
209218
callback_groups_.push_back(group);

0 commit comments

Comments
 (0)