@@ -63,6 +63,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
6363
6464 declare_parameter (" failure_tolerance" , rclcpp::ParameterValue (0.0 ));
6565 declare_parameter (" use_realtime_priority" , rclcpp::ParameterValue (false ));
66+ declare_parameter (" publish_zero_velocity" , rclcpp::ParameterValue (true ));
6667
6768 // The costmap node is used in the implementation of the controller
6869 costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
@@ -128,6 +129,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
128129 get_parameter (" speed_limit_topic" , speed_limit_topic);
129130 get_parameter (" failure_tolerance" , failure_tolerance_);
130131 get_parameter (" use_realtime_priority" , use_realtime_priority_);
132+ get_parameter (" publish_zero_velocity" , publish_zero_velocity_);
131133
132134 costmap_ros_->configure ();
133135 // Launch a thread to run the costmap node
@@ -292,7 +294,7 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
292294 */
293295 costmap_ros_->deactivate ();
294296
295- publishZeroVelocity ();
297+ onGoalExit ();
296298 vel_publisher_->on_deactivate ();
297299
298300 remove_on_set_parameters_callback (dyn_params_handler_.get ());
@@ -470,7 +472,7 @@ void ControllerServer::computeControl()
470472 if (controllers_[current_controller_]->cancel ()) {
471473 RCLCPP_INFO (get_logger (), " Cancellation was successful. Stopping the robot." );
472474 action_server_->terminate_all ();
473- publishZeroVelocity ();
475+ onGoalExit ();
474476 return ;
475477 } else {
476478 RCLCPP_INFO_THROTTLE (
@@ -503,56 +505,56 @@ void ControllerServer::computeControl()
503505 }
504506 } catch (nav2_core::InvalidController & e) {
505507 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
506- publishZeroVelocity ();
508+ onGoalExit ();
507509 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
508510 result->error_code = Action::Result::INVALID_CONTROLLER;
509511 action_server_->terminate_current (result);
510512 return ;
511513 } catch (nav2_core::ControllerTFError & e) {
512514 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
513- publishZeroVelocity ();
515+ onGoalExit ();
514516 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
515517 result->error_code = Action::Result::TF_ERROR;
516518 action_server_->terminate_current (result);
517519 return ;
518520 } catch (nav2_core::NoValidControl & e) {
519521 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
520- publishZeroVelocity ();
522+ onGoalExit ();
521523 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
522524 result->error_code = Action::Result::NO_VALID_CONTROL;
523525 action_server_->terminate_current (result);
524526 return ;
525527 } catch (nav2_core::FailedToMakeProgress & e) {
526528 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
527- publishZeroVelocity ();
529+ onGoalExit ();
528530 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
529531 result->error_code = Action::Result::FAILED_TO_MAKE_PROGRESS;
530532 action_server_->terminate_current (result);
531533 return ;
532534 } catch (nav2_core::PatienceExceeded & e) {
533535 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
534- publishZeroVelocity ();
536+ onGoalExit ();
535537 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
536538 result->error_code = Action::Result::PATIENCE_EXCEEDED;
537539 action_server_->terminate_current (result);
538540 return ;
539541 } catch (nav2_core::InvalidPath & e) {
540542 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
541- publishZeroVelocity ();
543+ onGoalExit ();
542544 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
543545 result->error_code = Action::Result::INVALID_PATH;
544546 action_server_->terminate_current (result);
545547 return ;
546548 } catch (nav2_core::ControllerException & e) {
547549 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
548- publishZeroVelocity ();
550+ onGoalExit ();
549551 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
550552 result->error_code = Action::Result::UNKNOWN;
551553 action_server_->terminate_current (result);
552554 return ;
553555 } catch (std::exception & e) {
554556 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
555- publishZeroVelocity ();
557+ onGoalExit ();
556558 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
557559 result->error_code = Action::Result::UNKNOWN;
558560 action_server_->terminate_current (result);
@@ -561,7 +563,7 @@ void ControllerServer::computeControl()
561563
562564 RCLCPP_DEBUG (get_logger (), " Controller succeeded, setting result" );
563565
564- publishZeroVelocity ();
566+ onGoalExit ();
565567
566568 // TODO(orduno) #861 Handle a pending preemption and set controller name
567569 action_server_->succeeded_current ();
@@ -729,6 +731,13 @@ void ControllerServer::publishZeroVelocity()
729731 velocity.header .frame_id = costmap_ros_->getBaseFrameID ();
730732 velocity.header .stamp = now ();
731733 publishVelocity (velocity);
734+ }
735+
736+ void ControllerServer::onGoalExit ()
737+ {
738+ if (publish_zero_velocity_) {
739+ publishZeroVelocity ();
740+ }
732741
733742 // Reset the state of the controllers after the task has ended
734743 ControllerMap::iterator it;
0 commit comments