Skip to content

Commit 4f13c4d

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
feat: Added new CBGExecutor
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent d4a694f commit 4f13c4d

File tree

8 files changed

+2193
-0
lines changed

8 files changed

+2193
-0
lines changed

rclcpp/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,7 @@ set(${PROJECT_NAME}_SRCS
6363
src/rclcpp/executable_list.cpp
6464
src/rclcpp/executor.cpp
6565
src/rclcpp/executors.cpp
66+
src/rclcpp/executors/cbg_executor.cpp
6667
src/rclcpp/executors/executor_entities_collection.cpp
6768
src/rclcpp/executors/executor_entities_collector.cpp
6869
src/rclcpp/executors/executor_notify_waitable.cpp
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
#pragma once
2+
#include <rclcpp/callback_group.hpp>
3+
#include <rclcpp/guard_condition.hpp>
4+
#include <vector>
5+
6+
namespace rclcpp::executors
7+
{
8+
9+
/**
10+
* Snapshot of the state of a callback group.
11+
*
12+
* Contains all registered entities from the point in timer
13+
* when the snapshot was taken, as weak ptrs.
14+
*/
15+
struct CallbackGroupState
16+
{
17+
CallbackGroupState(rclcpp::CallbackGroup & cbg)
18+
{
19+
update(cbg);
20+
}
21+
22+
/// Update the state from the callback group
23+
void update(rclcpp::CallbackGroup & cbg)
24+
{
25+
cbg.collect_all_ptrs(subscription_ptrs, timer_ptrs, service_ptrs, client_ptrs, waitable_ptrs);
26+
trigger_ptr = cbg.get_notify_guard_condition();
27+
}
28+
29+
std::vector<rclcpp::SubscriptionBase::WeakPtr> subscription_ptrs;
30+
std::vector<rclcpp::TimerBase::WeakPtr> timer_ptrs;
31+
std::vector<rclcpp::ServiceBase::WeakPtr> service_ptrs;
32+
std::vector<rclcpp::ClientBase::WeakPtr> client_ptrs;
33+
std::vector<rclcpp::Waitable::WeakPtr> waitable_ptrs;
34+
35+
rclcpp::GuardCondition::WeakPtr trigger_ptr;
36+
};
37+
}

0 commit comments

Comments
 (0)