Skip to content

Commit

Permalink
incorporate suggestions
Browse files Browse the repository at this point in the history
  • Loading branch information
captain-yoshi committed Jul 18, 2024
1 parent b8a0d2d commit 972c276
Show file tree
Hide file tree
Showing 5 changed files with 6 additions and 29 deletions.
10 changes: 3 additions & 7 deletions core/include/moveit/task_constructor/stage_p.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,7 @@ class PreemptStageException : public std::exception
{
public:
explicit PreemptStageException() {}
const char* what() const noexcept override {
static const char* msg = "";
return msg;
}
const char* what() const noexcept override { return ""; }
};

class ContainerBase;
Expand Down Expand Up @@ -174,9 +171,8 @@ class StagePrivate
/** compute cost for solution through configured CostTerm */
void computeCost(const InterfaceState& from, const InterfaceState& to, SolutionBase& solution);

void setPreemptedCheck(const std::atomic<bool>* preempt_requested);
/// is the stage preempted ? defaults to false
bool preempted() const;
void setPreemptRequestedMember(const std::atomic<bool>* preempt_requested);
bool preempted() const { return preempt_requested_ != nullptr && *preempt_requested_; }

protected:
StagePrivate& operator=(StagePrivate&& other);
Expand Down
1 change: 0 additions & 1 deletion core/include/moveit/task_constructor/task.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,6 @@ class Task : protected WrapperBase
/// interrupt current planning
void preempt();
void resetPreemptRequest();
bool isPreempted();
/// execute solution, return the result
moveit::core::MoveItErrorCode execute(const SolutionBase& s);

Expand Down
9 changes: 1 addition & 8 deletions core/src/stage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,17 +306,10 @@ void StagePrivate::computeCost(const InterfaceState& from, const InterfaceState&
}
}

void StagePrivate::setPreemptedCheck(const std::atomic<bool>* preempt_requested) {
void StagePrivate::setPreemptRequestedMember(const std::atomic<bool>* preempt_requested) {
preempt_requested_ = preempt_requested;
}

bool StagePrivate::preempted() const {
if (preempt_requested_)
return *preempt_requested_;

return false;
}

Stage::Stage(StagePrivate* impl) : pimpl_(impl) {
assert(impl);
auto& p = properties();
Expand Down
6 changes: 1 addition & 5 deletions core/src/task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,7 @@ void Task::init() {
impl->traverseStages(
[introspection, impl](Stage& stage, int /*depth*/) {
stage.pimpl()->setIntrospection(introspection);
stage.pimpl()->setPreemptedCheck(&impl->preempt_requested_);
stage.pimpl()->setPreemptRequestedMember(&impl->preempt_requested_);
return true;
},
1, UINT_MAX);
Expand Down Expand Up @@ -279,10 +279,6 @@ void Task::resetPreemptRequest() {
pimpl()->preempt_requested_ = false;
}

bool Task::isPreempted() {
return pimpl()->preempt_requested_;
}

moveit::core::MoveItErrorCode Task::execute(const SolutionBase& s) {
actionlib::SimpleActionClient<moveit_task_constructor_msgs::ExecuteTaskSolutionAction> ac("execute_task_solution");
if (!ac.waitForServer(ros::Duration(0.5))) {
Expand Down
9 changes: 1 addition & 8 deletions core/test/test_container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -702,17 +702,10 @@ TEST_F(TaskTestBase, preempt) {
EXPECT_EQ(fwd2->runs_, 0u);
EXPECT_TRUE(t.plan(1)); // make sure the preempt request has been resetted on the previous call to plan()

// prempt in between stage computation
// Failing stage(s):
// 0 - ← 0 → - 0 / task pipeline
// 1 - ← 1 → - 0 / GEN1
// - 0 → 1 → - 1 / FWD1
// - 1 → 0 → - 0 / FWD2
t.reset();
resetMockupIds();
{
std::thread thread{ [&ec, this] { ec = t.plan(1); } };
std::this_thread::sleep_for(timeout);
std::this_thread::sleep_for(timeout / 2.0);
t.preempt();
thread.join();
}
Expand Down

0 comments on commit 972c276

Please sign in to comment.