Skip to content

Commit

Permalink
Deprecate callback_group call taking context
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <mjcarroll@intrinsic.ai>
  • Loading branch information
mjcarroll committed Mar 29, 2023
1 parent 20e9cd1 commit 5718fe1
Show file tree
Hide file tree
Showing 4 changed files with 77 additions and 4 deletions.
32 changes: 31 additions & 1 deletion rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,13 +89,16 @@ class CallbackGroup
* added to the executor in either case.
*
* \param[in] group_type The type of the callback group.
* \param[in] get_node_context Lambda to retrieve the node context when
* checking that the creating node is valid and using the guard condition.
* \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,
std::function<rclcpp::Context::SharedPtr(void)> get_node_context,
bool automatically_add_to_executor_with_node = true);

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

/// Return if the node that created this callback group still exists
/**
* As nodes can share ownership of callback groups with an executor, this
* may be used to ensures that the executor doesn't operate on a callback
* group that has outlived it's creating node.
*
* \return true if the creating node still exists, otherwise false
*/
RCLCPP_PUBLIC
bool
has_valid_node();

RCLCPP_PUBLIC
std::atomic_bool &
can_be_taken_from();
Expand Down Expand Up @@ -178,11 +193,24 @@ class CallbackGroup
bool
automatically_add_to_executor_with_node() const;

/// Defer creating the notify guard condition and return it.
/// Retrieve the guard condition used to signal changes to this callback group.
/**
* \param[in] context_ptr context to use when creating the guard condition
* \return guard condition if it is valid, otherwise nullptr.
*/
[[deprecated("Use get_notify_guard_condition() without arguments")]]
RCLCPP_PUBLIC
rclcpp::GuardCondition::SharedPtr
get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr);

/// 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
Expand Down Expand Up @@ -234,6 +262,8 @@ class CallbackGroup
std::shared_ptr<rclcpp::GuardCondition> notify_guard_condition_ = nullptr;
std::recursive_mutex notify_guard_condition_mutex_;

std::function<rclcpp::Context::SharedPtr(void)> get_context_;

private:
template<typename TypeT, typename Function>
typename TypeT::SharedPtr _find_ptrs_if_impl(
Expand Down
34 changes: 33 additions & 1 deletion rclcpp/src/rclcpp/callback_group.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,17 +31,25 @@ using rclcpp::CallbackGroupType;

CallbackGroup::CallbackGroup(
CallbackGroupType group_type,
std::function<rclcpp::Context::SharedPtr(void)> get_context,
bool automatically_add_to_executor_with_node)
: type_(group_type), associated_with_executor_(false),
can_be_taken_from_(true),
automatically_add_to_executor_with_node_(automatically_add_to_executor_with_node)
automatically_add_to_executor_with_node_(automatically_add_to_executor_with_node),
get_context_(get_context)
{}

CallbackGroup::~CallbackGroup()
{
trigger_notify_guard_condition();
}

bool
CallbackGroup::has_valid_node()
{
return nullptr != this->get_context_();
}

std::atomic_bool &
CallbackGroup::can_be_taken_from()
{
Expand Down Expand Up @@ -111,6 +119,7 @@ CallbackGroup::automatically_add_to_executor_with_node() const
return automatically_add_to_executor_with_node_;
}

// \TODO(mjcarroll) Deprecated, remove on tock
rclcpp::GuardCondition::SharedPtr
CallbackGroup::get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr)
{
Expand All @@ -129,6 +138,29 @@ CallbackGroup::get_notify_guard_condition(const rclcpp::Context::SharedPtr conte
return notify_guard_condition_;
}

rclcpp::GuardCondition::SharedPtr
CallbackGroup::get_notify_guard_condition()
{
auto context_ptr = this->get_context_();
if (context_ptr && context_ptr->is_valid())
{
std::lock_guard<std::recursive_mutex> lock(notify_guard_condition_mutex_);
if (notify_guard_condition_ && context_ptr != notify_guard_condition_->get_context()) {
if (associated_with_executor_) {
trigger_notify_guard_condition();
}
notify_guard_condition_ = nullptr;
}

if (!notify_guard_condition_) {
notify_guard_condition_ = std::make_shared<rclcpp::GuardCondition>(context_ptr);
}

return notify_guard_condition_;
}
return nullptr;
}

void
CallbackGroup::trigger_notify_guard_condition()
{
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,8 +222,7 @@ Executor::add_callback_group_to_map(
weak_groups_to_nodes_.insert(std::make_pair(weak_group_ptr, node_ptr));

if (node_ptr->get_context()->is_valid()) {
auto callback_group_guard_condition =
group_ptr->get_notify_guard_condition(node_ptr->get_context());
auto callback_group_guard_condition = group_ptr->get_notify_guard_condition();
weak_groups_to_guard_conditions_[weak_group_ptr] = callback_group_guard_condition.get();
// Add the callback_group's notify condition to the guard condition handles
memory_strategy_->add_guard_condition(*callback_group_guard_condition);
Expand Down
12 changes: 12 additions & 0 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,8 +202,20 @@ NodeBase::create_callback_group(
rclcpp::CallbackGroupType group_type,
bool automatically_add_to_executor_with_node)
{
auto weak_node = this->weak_from_this();
auto group = std::make_shared<rclcpp::CallbackGroup>(
group_type,
[weak_node]() -> rclcpp::Context::SharedPtr {
if (weak_node.expired()) {
return nullptr;
}

auto node = weak_node.lock();
if (node && node->get_context()->is_valid()) {
return node->get_context();
}
return nullptr;
},
automatically_add_to_executor_with_node);
std::lock_guard<std::mutex> lock(callback_groups_mutex_);
callback_groups_.push_back(group);
Expand Down

0 comments on commit 5718fe1

Please sign in to comment.