@@ -32,7 +32,7 @@ namespace nav2_controller
3232{
3333
3434ControllerServer::ControllerServer ()
35- : LifecycleNode(" controller_server" , " " , true ),
35+ : nav2_util:: LifecycleNode(" controller_server" , " " ),
3636 progress_checker_loader_ (" nav2_core" , " nav2_core::ProgressChecker" ),
3737 default_progress_checker_id_{" progress_checker" },
3838 default_progress_checker_type_{" nav2_controller::SimpleProgressChecker" },
@@ -195,8 +195,12 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
195195
196196 // Create the action server that we implement with our followPath method
197197 action_server_ = std::make_unique<ActionServer>(
198- rclcpp_node_, " follow_path" ,
199- std::bind (&ControllerServer::computeControl, this ));
198+ shared_from_this (),
199+ " follow_path" ,
200+ std::bind (&ControllerServer::computeControl, this ),
201+ nullptr ,
202+ std::chrono::milliseconds (500 ),
203+ true );
200204
201205 // Set subscribtion to the speed limiting topic
202206 speed_limit_sub_ = create_subscription<nav2_msgs::msg::SpeedLimit>(
@@ -266,7 +270,6 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & state)
266270 odom_sub_.reset ();
267271 vel_publisher_.reset ();
268272 speed_limit_sub_.reset ();
269- action_server_.reset ();
270273
271274 return nav2_util::CallbackReturn::SUCCESS;
272275}
0 commit comments