Skip to content

Commit

Permalink
feat: Added new CBGExecutor
Browse files Browse the repository at this point in the history
Signed-off-by: Janosch Machowinski <J.Machowinski@cellumation.com>

# Conflicts:
#	rclcpp/include/rclcpp/executor.hpp
#	rclcpp/src/rclcpp/executor.cpp
#	rclcpp/test/rclcpp/executors/test_executors.cpp
  • Loading branch information
Janosch Machowinski committed Feb 3, 2024
1 parent 261a69b commit 27cc9ac
Show file tree
Hide file tree
Showing 9 changed files with 3,164 additions and 50 deletions.
2 changes: 2 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,8 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/executable_list.cpp
src/rclcpp/executor.cpp
src/rclcpp/executors.cpp
src/rclcpp/executors/cbg_executor.cpp
src/rclcpp/executors/detail/weak_executable_with_rcl_handle_cache.cpp
src/rclcpp/executors/executor_entities_collection.cpp
src/rclcpp/executors/executor_entities_collector.cpp
src/rclcpp/executors/executor_notify_waitable.cpp
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -485,7 +485,7 @@ class Executor
RCLCPP_PUBLIC
static void
execute_subscription(
rclcpp::SubscriptionBase::SharedPtr subscription);
const rclcpp::SubscriptionBase::SharedPtr &subscription);

/// Run timer executable.
/**
Expand All @@ -503,7 +503,7 @@ class Executor
*/
RCLCPP_PUBLIC
static void
execute_service(rclcpp::ServiceBase::SharedPtr service);
execute_service(const rclcpp::ServiceBase::SharedPtr &service);

/// Run service client executable.
/**
Expand All @@ -512,7 +512,7 @@ class Executor
*/
RCLCPP_PUBLIC
static void
execute_client(rclcpp::ClientBase::SharedPtr client);
execute_client(const rclcpp::ClientBase::SharedPtr &client);

protected:
/// Block until more work becomes avilable or timeout is reached.
Expand Down
Loading

0 comments on commit 27cc9ac

Please sign in to comment.