Skip to content

Commit

Permalink
reset the preempt flag when leaving Task::plan()
Browse files Browse the repository at this point in the history
  • Loading branch information
captain-yoshi committed Jul 16, 2024
1 parent ff9b77b commit 6bbd283
Showing 1 changed file with 33 additions and 25 deletions.
58 changes: 33 additions & 25 deletions core/src/task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,31 +234,39 @@ void Task::compute() {
}

moveit::core::MoveItErrorCode Task::plan(size_t max_solutions) {
auto impl = pimpl();
init();

// Print state and return success if there are solutions otherwise the input error_code
const auto success_or = [this](const int32_t error_code) -> int32_t {
if (numSolutions() > 0)
return moveit::core::MoveItErrorCode::SUCCESS;
printState();
explainFailure();
return error_code;
};
const double available_time = timeout();
const auto start_time = std::chrono::steady_clock::now();
while (canCompute() && (max_solutions == 0 || numSolutions() < max_solutions)) {
if (impl->preempt_requested_)
return success_or(moveit::core::MoveItErrorCode::PREEMPTED);
if (std::chrono::duration<double>(std::chrono::steady_clock::now() - start_time).count() >= available_time)
return success_or(moveit::core::MoveItErrorCode::TIMED_OUT);
compute();
for (const auto& cb : impl->task_cbs_)
cb(*this);
if (impl->introspection_)
impl->introspection_->publishTaskState();
};
return success_or(moveit::core::MoveItErrorCode::PLANNING_FAILED);
try {
auto impl = pimpl();
init();

// Print state and return success if there are solutions otherwise the input error_code
const auto success_or = [this](const int32_t error_code) -> int32_t {
// reset preempt flag
pimpl()->preempt_requested_ = false;

if (numSolutions() > 0)
return moveit::core::MoveItErrorCode::SUCCESS;
printState();
explainFailure();
return error_code;
};
const double available_time = timeout();
const auto start_time = std::chrono::steady_clock::now();
while (canCompute() && (max_solutions == 0 || numSolutions() < max_solutions)) {
if (impl->preempt_requested_)
return success_or(moveit::core::MoveItErrorCode::PREEMPTED);
if (std::chrono::duration<double>(std::chrono::steady_clock::now() - start_time).count() >= available_time)
return success_or(moveit::core::MoveItErrorCode::TIMED_OUT);
compute();
for (const auto& cb : impl->task_cbs_)
cb(*this);
if (impl->introspection_)
impl->introspection_->publishTaskState();
};
return success_or(moveit::core::MoveItErrorCode::PLANNING_FAILED);
} catch (const std::exception& e) {
pimpl()->preempt_requested_ = false;
throw; // rethrow the original exception
}
}

void Task::preempt() {
Expand Down

0 comments on commit 6bbd283

Please sign in to comment.