Skip to content

Commit 0f71505

Browse files
haider8645mergify[bot]
authored andcommitted
Publish zero velocitiy in case of goal failure (#5279)
Signed-off-by: haider8645 <haider_lodhi@hotmail.com> (cherry picked from commit 22d8d91)
1 parent 7ca94d4 commit 0f71505

File tree

2 files changed

+17
-18
lines changed

2 files changed

+17
-18
lines changed

nav2_controller/include/nav2_controller/controller_server.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -179,7 +179,7 @@ class ControllerServer : public nav2_util::LifecycleNode
179179
/**
180180
* @brief Called on goal exit
181181
*/
182-
void onGoalExit();
182+
void onGoalExit(bool force_stop);
183183
/**
184184
* @brief Checks if goal is reached
185185
* @return true or false

nav2_controller/src/controller_server.cpp

Lines changed: 16 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -482,7 +482,7 @@ void ControllerServer::computeControl()
482482
if (controllers_[current_controller_]->cancel()) {
483483
RCLCPP_INFO(get_logger(), "Cancellation was successful. Stopping the robot.");
484484
action_server_->terminate_all();
485-
onGoalExit();
485+
onGoalExit(true);
486486
return;
487487
} else {
488488
RCLCPP_INFO_THROTTLE(
@@ -519,71 +519,71 @@ void ControllerServer::computeControl()
519519
}
520520
} catch (nav2_core::InvalidController & e) {
521521
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
522-
onGoalExit();
522+
onGoalExit(true);
523523
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
524524
result->error_code = Action::Result::INVALID_CONTROLLER;
525525
result->error_msg = e.what();
526526
action_server_->terminate_current(result);
527527
return;
528528
} catch (nav2_core::ControllerTFError & e) {
529529
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
530-
onGoalExit();
530+
onGoalExit(true);
531531
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
532532
result->error_code = Action::Result::TF_ERROR;
533533
result->error_msg = e.what();
534534
action_server_->terminate_current(result);
535535
return;
536536
} catch (nav2_core::NoValidControl & e) {
537537
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
538-
onGoalExit();
538+
onGoalExit(true);
539539
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
540540
result->error_code = Action::Result::NO_VALID_CONTROL;
541541
result->error_msg = e.what();
542542
action_server_->terminate_current(result);
543543
return;
544544
} catch (nav2_core::FailedToMakeProgress & e) {
545545
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
546-
onGoalExit();
546+
onGoalExit(true);
547547
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
548548
result->error_code = Action::Result::FAILED_TO_MAKE_PROGRESS;
549549
result->error_msg = e.what();
550550
action_server_->terminate_current(result);
551551
return;
552552
} catch (nav2_core::PatienceExceeded & e) {
553553
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
554-
onGoalExit();
554+
onGoalExit(true);
555555
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
556556
result->error_code = Action::Result::PATIENCE_EXCEEDED;
557557
result->error_msg = e.what();
558558
action_server_->terminate_current(result);
559559
return;
560560
} catch (nav2_core::InvalidPath & e) {
561561
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
562-
onGoalExit();
562+
onGoalExit(true);
563563
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
564564
result->error_code = Action::Result::INVALID_PATH;
565565
result->error_msg = e.what();
566566
action_server_->terminate_current(result);
567567
return;
568568
} catch (nav2_core::ControllerTimedOut & e) {
569569
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
570-
onGoalExit();
570+
onGoalExit(true);
571571
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
572572
result->error_code = Action::Result::CONTROLLER_TIMED_OUT;
573573
result->error_msg = e.what();
574574
action_server_->terminate_current(result);
575575
return;
576576
} catch (nav2_core::ControllerException & e) {
577577
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
578-
onGoalExit();
578+
onGoalExit(true);
579579
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
580580
result->error_code = Action::Result::UNKNOWN;
581581
result->error_msg = e.what();
582582
action_server_->terminate_current(result);
583583
return;
584584
} catch (std::exception & e) {
585585
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
586-
onGoalExit();
586+
onGoalExit(true);
587587
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
588588
result->error_code = Action::Result::UNKNOWN;
589589
result->error_msg = e.what();
@@ -593,7 +593,7 @@ void ControllerServer::computeControl()
593593

594594
RCLCPP_DEBUG(get_logger(), "Controller succeeded, setting result");
595595

596-
onGoalExit();
596+
onGoalExit(false);
597597

598598
// TODO(orduno) #861 Handle a pending preemption and set controller name
599599
action_server_->succeeded_current();
@@ -783,16 +783,15 @@ void ControllerServer::publishZeroVelocity()
783783
publishVelocity(velocity);
784784
}
785785

786-
void ControllerServer::onGoalExit()
786+
void ControllerServer::onGoalExit(bool force_stop)
787787
{
788-
if (publish_zero_velocity_) {
788+
if (publish_zero_velocity_ || force_stop) {
789789
publishZeroVelocity();
790790
}
791791

792-
// Reset the state of the controllers after the task has ended
793-
ControllerMap::iterator it;
794-
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
795-
it->second->reset();
792+
// Reset controller state
793+
for (auto & controller : controllers_) {
794+
controller.second->reset();
796795
}
797796
}
798797

0 commit comments

Comments
 (0)