Skip to content

Commit

Permalink
Better not touch NodeOptions in ComponentManager since it's public
Browse files Browse the repository at this point in the history
Signed-off-by: Martijn Buijs <martijn.buijs@gmail.com>
  • Loading branch information
mbuijs committed Sep 27, 2020
1 parent b069705 commit 1704b29
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 5 deletions.
9 changes: 8 additions & 1 deletion rclcpp_components/src/component_container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,15 @@ int main(int argc, char * argv[])
{
/// Component container with a single-threaded executor.
rclcpp::init(argc, argv);

rclcpp::NodeOptions options;
options.start_parameter_services(false);
options.start_parameter_event_publisher(false);

auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
auto node = std::make_shared<rclcpp_components::ComponentManager>(exec);
auto node = std::make_shared<rclcpp_components::ComponentManager>(
exec, "ComponentManager",
options);
exec->add_node(node);
exec->spin();
}
9 changes: 8 additions & 1 deletion rclcpp_components/src/component_container_mt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,15 @@ int main(int argc, char * argv[])
{
/// Component container with a multi-threaded executor.
rclcpp::init(argc, argv);

rclcpp::NodeOptions options;
options.start_parameter_services(false);
options.start_parameter_event_publisher(false);

auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();
auto node = std::make_shared<rclcpp_components::ComponentManager>(exec);
auto node = std::make_shared<rclcpp_components::ComponentManager>(
exec, "ComponentManager",
options);
exec->add_node(node);
exec->spin();
}
4 changes: 1 addition & 3 deletions rclcpp_components/src/component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,7 @@ ComponentManager::ComponentManager(
std::weak_ptr<rclcpp::Executor> executor,
std::string node_name,
const rclcpp::NodeOptions & node_options)
: Node(std::move(node_name), rclcpp::NodeOptions(node_options)
.start_parameter_services(false)
.start_parameter_event_publisher(false)),
: Node(std::move(node_name), node_options),
executor_(executor)
{
loadNode_srv_ = create_service<LoadNode>(
Expand Down

0 comments on commit 1704b29

Please sign in to comment.