diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index ff86f642557..3dc7ef494e2 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -63,9 +63,6 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) // The costmap node is used in the implementation of the controller costmap_ros_ = std::make_shared( "local_costmap", std::string{get_namespace()}, "local_costmap"); - - // Launch a thread to run the costmap node - costmap_thread_ = std::make_unique(costmap_ros_); } ControllerServer::~ControllerServer() diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 453cf8292bc..67d3506d0ea 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -62,9 +62,6 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) // Setup the global costmap costmap_ros_ = std::make_shared( "global_costmap", std::string{get_namespace()}, "global_costmap"); - - // Launch a thread to run the costmap node - costmap_thread_ = std::make_unique(costmap_ros_); } PlannerServer::~PlannerServer()