Skip to content

Commit 32c257b

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
feat(CallbackGroup): Added API to get registered objects as weak ptr
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent 265f5ec commit 32c257b

File tree

2 files changed

+25
-0
lines changed

2 files changed

+25
-0
lines changed

rclcpp/include/rclcpp/callback_group.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -202,6 +202,14 @@ class CallbackGroup
202202
std::function<void(const rclcpp::TimerBase::SharedPtr &)> timer_func,
203203
std::function<void(const rclcpp::Waitable::SharedPtr &)> waitable_func) const;
204204

205+
RCLCPP_PUBLIC
206+
void collect_all_ptrs(
207+
std::vector<rclcpp::SubscriptionBase::WeakPtr> & subscription_ptrs_,
208+
std::vector<rclcpp::TimerBase::WeakPtr> & timer_ptrs_,
209+
std::vector<rclcpp::ServiceBase::WeakPtr> & service_ptrs_,
210+
std::vector<rclcpp::ClientBase::WeakPtr> & client_ptrs_,
211+
std::vector<rclcpp::Waitable::WeakPtr> & waitable_ptrs_) const;
212+
205213
/// Return a reference to the 'associated with executor' atomic boolean.
206214
/**
207215
* When a callback group is added to an executor this boolean is checked

rclcpp/src/rclcpp/callback_group.cpp

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,23 @@ CallbackGroup::size() const
6666
timer_ptrs_.size() +
6767
waitable_ptrs_.size();
6868
}
69+
70+
void CallbackGroup::collect_all_ptrs(
71+
std::vector<rclcpp::SubscriptionBase::WeakPtr> & subscription_ptrs,
72+
std::vector<rclcpp::TimerBase::WeakPtr> & timer_ptrs,
73+
std::vector<rclcpp::ServiceBase::WeakPtr> & service_ptrs,
74+
std::vector<rclcpp::ClientBase::WeakPtr> & client_ptrs,
75+
std::vector<rclcpp::Waitable::WeakPtr> & waitable_ptrs) const
76+
{
77+
std::lock_guard<std::mutex> lock(mutex_);
78+
79+
subscription_ptrs = this->subscription_ptrs_;
80+
timer_ptrs = this->timer_ptrs_;
81+
service_ptrs = this->service_ptrs_;
82+
client_ptrs = this->client_ptrs_;
83+
waitable_ptrs = this->waitable_ptrs_;
84+
}
85+
6986
void CallbackGroup::collect_all_ptrs(
7087
std::function<void(const rclcpp::SubscriptionBase::SharedPtr &)> sub_func,
7188
std::function<void(const rclcpp::ServiceBase::SharedPtr &)> service_func,

0 commit comments

Comments
 (0)