Skip to content

Commit

Permalink
Fixed timed_behavior.hpp (#4602)
Browse files Browse the repository at this point in the history
Signed-off-by: Vladyslav Hrynchak <[email protected]>
  • Loading branch information
VladyslavHrynchak200204 authored Aug 8, 2024
1 parent 3a4219d commit 746bb88
Showing 1 changed file with 9 additions and 9 deletions.
18 changes: 9 additions & 9 deletions nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,15 +237,6 @@ class TimedBehavior : public nav2_core::Behavior

while (rclcpp::ok()) {
elasped_time_ = clock_->now() - start_time;
if (action_server_->is_cancel_requested()) {
RCLCPP_INFO(logger_, "Canceling %s", behavior_name_.c_str());
stopRobot();
result->total_elapsed_time = elasped_time_;
onActionCompletion(result);
action_server_->terminate_all(result);
return;
}

// TODO(orduno) #868 Enable preempting a Behavior on-the-fly without stopping
if (action_server_->is_preempt_requested()) {
RCLCPP_ERROR(
Expand All @@ -259,6 +250,15 @@ class TimedBehavior : public nav2_core::Behavior
return;
}

if (action_server_->is_cancel_requested()) {
RCLCPP_INFO(logger_, "Canceling %s", behavior_name_.c_str());
stopRobot();
result->total_elapsed_time = elasped_time_;
onActionCompletion(result);
action_server_->terminate_all(result);
return;
}

ResultStatus on_cycle_update_result = onCycleUpdate();
switch (on_cycle_update_result.status) {
case Status::SUCCEEDED:
Expand Down

0 comments on commit 746bb88

Please sign in to comment.