Skip to content

Commit

Permalink
Fixed lifecycle manager startup (ros-navigation#2917)
Browse files Browse the repository at this point in the history
  • Loading branch information
Matej Vargovcik committed May 20, 2022
1 parent 432b76d commit a3e6384
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,10 +99,10 @@ LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
},
callback_group_);
}
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
executor->add_callback_group(callback_group_, get_node_base_interface());
service_thread_ = std::make_unique<nav2_util::NodeThread>(executor);
});
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
executor->add_callback_group(callback_group_, get_node_base_interface());
service_thread_ = std::make_unique<nav2_util::NodeThread>(executor);
}

LifecycleManager::~LifecycleManager()
Expand Down

0 comments on commit a3e6384

Please sign in to comment.