Skip to content

Commit fd648c2

Browse files
author
wep21
committed
Add set executor
Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>
1 parent 186aa75 commit fd648c2

File tree

3 files changed

+20
-9
lines changed

3 files changed

+20
-9
lines changed

rclcpp_components/include/rclcpp_components/component_manager.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,14 @@ class ComponentManager : public rclcpp::Node
130130
virtual std::shared_ptr<rclcpp_components::NodeFactory>
131131
create_component_factory(const ComponentResource & resource);
132132

133+
/// Member function to set a executor in the component
134+
/**
135+
* \param executor executor to be set
136+
*/
137+
RCLCPP_COMPONENTS_PUBLIC
138+
virtual void
139+
set_executor(const std::weak_ptr<rclcpp::Executor> executor);
140+
133141
protected:
134142
/// Create node options for loaded component
135143
/**

rclcpp_components/src/component_container_mt.cpp

+6-9
Original file line numberDiff line numberDiff line change
@@ -26,17 +26,14 @@ int main(int argc, char * argv[])
2626
auto options = rclcpp::NodeOptions{}.start_parameter_event_publisher(false);
2727
auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();
2828
auto node = std::make_shared<rclcpp_components::ComponentManager>(
29-
exec, "ComponentManager", options);
29+
std::weak_ptr<rclcpp::executors::MultiThreadedExecutor>(), "ComponentManager", options);
3030
if (node->has_parameter("thread_num")) {
3131
const auto thread_num = node->get_parameter("thread_num").as_int();
32-
if (thread_num < std::thread::hardware_concurrency()) {
33-
exec.reset();
34-
node.reset();
35-
exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>(
36-
rclcpp::ExecutorOptions{}, thread_num);
37-
node = std::make_shared<rclcpp_components::ComponentManager>(
38-
exec, "ComponentManager", options);
39-
}
32+
exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>(
33+
rclcpp::ExecutorOptions{}, thread_num);
34+
node->set_executor(exec);
35+
} else {
36+
node->set_executor(exec);
4037
}
4138
exec->add_node(node);
4239
exec->spin();

rclcpp_components/src/component_manager.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -180,6 +180,12 @@ ComponentManager::create_node_options(const std::shared_ptr<LoadNode::Request> r
180180
return options;
181181
}
182182

183+
void
184+
ComponentManager::set_executor(const std::weak_ptr<rclcpp::Executor> executor)
185+
{
186+
executor_ = executor;
187+
}
188+
183189
void
184190
ComponentManager::on_load_node(
185191
const std::shared_ptr<rmw_request_id_t> request_header,

0 commit comments

Comments
 (0)