@@ -476,7 +476,7 @@ void ControllerServer::computeControl()
476476 if (controllers_[current_controller_]->cancel ()) {
477477 RCLCPP_INFO (get_logger (), " Cancellation was successful. Stopping the robot." );
478478 action_server_->terminate_all ();
479- onGoalExit ();
479+ onGoalExit (true );
480480 return ;
481481 } else {
482482 RCLCPP_INFO_THROTTLE (
@@ -513,71 +513,71 @@ void ControllerServer::computeControl()
513513 }
514514 } catch (nav2_core::InvalidController & e) {
515515 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
516- onGoalExit ();
516+ onGoalExit (true );
517517 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
518518 result->error_code = Action::Result::INVALID_CONTROLLER;
519519 result->error_msg = e.what ();
520520 action_server_->terminate_current (result);
521521 return ;
522522 } catch (nav2_core::ControllerTFError & e) {
523523 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
524- onGoalExit ();
524+ onGoalExit (true );
525525 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
526526 result->error_code = Action::Result::TF_ERROR;
527527 result->error_msg = e.what ();
528528 action_server_->terminate_current (result);
529529 return ;
530530 } catch (nav2_core::NoValidControl & e) {
531531 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
532- onGoalExit ();
532+ onGoalExit (true );
533533 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
534534 result->error_code = Action::Result::NO_VALID_CONTROL;
535535 result->error_msg = e.what ();
536536 action_server_->terminate_current (result);
537537 return ;
538538 } catch (nav2_core::FailedToMakeProgress & e) {
539539 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
540- onGoalExit ();
540+ onGoalExit (true );
541541 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
542542 result->error_code = Action::Result::FAILED_TO_MAKE_PROGRESS;
543543 result->error_msg = e.what ();
544544 action_server_->terminate_current (result);
545545 return ;
546546 } catch (nav2_core::PatienceExceeded & e) {
547547 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
548- onGoalExit ();
548+ onGoalExit (true );
549549 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
550550 result->error_code = Action::Result::PATIENCE_EXCEEDED;
551551 result->error_msg = e.what ();
552552 action_server_->terminate_current (result);
553553 return ;
554554 } catch (nav2_core::InvalidPath & e) {
555555 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
556- onGoalExit ();
556+ onGoalExit (true );
557557 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
558558 result->error_code = Action::Result::INVALID_PATH;
559559 result->error_msg = e.what ();
560560 action_server_->terminate_current (result);
561561 return ;
562562 } catch (nav2_core::ControllerTimedOut & e) {
563563 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
564- onGoalExit ();
564+ onGoalExit (true );
565565 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
566566 result->error_code = Action::Result::CONTROLLER_TIMED_OUT;
567567 result->error_msg = e.what ();
568568 action_server_->terminate_current (result);
569569 return ;
570570 } catch (nav2_core::ControllerException & e) {
571571 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
572- onGoalExit ();
572+ onGoalExit (true );
573573 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
574574 result->error_code = Action::Result::UNKNOWN;
575575 result->error_msg = e.what ();
576576 action_server_->terminate_current (result);
577577 return ;
578578 } catch (std::exception & e) {
579579 RCLCPP_ERROR (this ->get_logger (), " %s" , e.what ());
580- onGoalExit ();
580+ onGoalExit (true );
581581 std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
582582 result->error_code = Action::Result::UNKNOWN;
583583 result->error_msg = e.what ();
@@ -587,7 +587,7 @@ void ControllerServer::computeControl()
587587
588588 RCLCPP_DEBUG (get_logger (), " Controller succeeded, setting result" );
589589
590- onGoalExit ();
590+ onGoalExit (false );
591591
592592 // TODO(orduno) #861 Handle a pending preemption and set controller name
593593 action_server_->succeeded_current ();
@@ -775,16 +775,15 @@ void ControllerServer::publishZeroVelocity()
775775 publishVelocity (velocity);
776776}
777777
778- void ControllerServer::onGoalExit ()
778+ void ControllerServer::onGoalExit (bool force_stop )
779779{
780- if (publish_zero_velocity_) {
780+ if (publish_zero_velocity_ || force_stop ) {
781781 publishZeroVelocity ();
782782 }
783783
784- // Reset the state of the controllers after the task has ended
785- ControllerMap::iterator it;
786- for (it = controllers_.begin (); it != controllers_.end (); ++it) {
787- it->second ->reset ();
784+ // Reset controller state
785+ for (auto & controller : controllers_) {
786+ controller.second ->reset ();
788787 }
789788}
790789
0 commit comments