Skip to content

Commit fdc06c3

Browse files
Reduce stop time due to preempt (#598)
The preempt_request_ flag was only checked at the top-level task container before each compute iteration. As a single sweep might take a while, we should check the flag before computing each stage.
1 parent 4f69a22 commit fdc06c3

File tree

5 files changed

+56
-11
lines changed

5 files changed

+56
-11
lines changed

core/include/moveit/task_constructor/stage_p.h

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,13 @@
5757
namespace moveit {
5858
namespace task_constructor {
5959

60+
/// exception thrown by StagePrivate::runCompute()
61+
class PreemptStageException : public std::exception
62+
{
63+
public:
64+
explicit PreemptStageException() {}
65+
};
66+
6067
class ContainerBase;
6168
class StagePrivate
6269
{
@@ -146,6 +153,10 @@ class StagePrivate
146153
bool storeFailures() const { return introspection_ != nullptr; }
147154
void runCompute() {
148155
ROS_DEBUG_STREAM_NAMED("Stage", fmt::format("Computing stage '{}'", name()));
156+
157+
if (preempted())
158+
throw PreemptStageException();
159+
149160
auto compute_start_time = std::chrono::steady_clock::now();
150161
try {
151162
compute();
@@ -159,6 +170,11 @@ class StagePrivate
159170
/** compute cost for solution through configured CostTerm */
160171
void computeCost(const InterfaceState& from, const InterfaceState& to, SolutionBase& solution);
161172

173+
void setPreemptRequestedMember(const std::atomic<bool>* preempt_requested) {
174+
preempt_requested_ = preempt_requested;
175+
}
176+
bool preempted() const { return preempt_requested_ != nullptr && *preempt_requested_; }
177+
162178
protected:
163179
StagePrivate& operator=(StagePrivate&& other);
164180

@@ -197,6 +213,8 @@ class StagePrivate
197213
InterfaceWeakPtr next_starts_; // interface to be used for sendForward()
198214

199215
Introspection* introspection_; // task's introspection instance
216+
217+
const std::atomic<bool>* preempt_requested_;
200218
};
201219
PIMPL_FUNCTIONS(Stage)
202220
std::ostream& operator<<(std::ostream& os, const StagePrivate& stage);

core/src/stage.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,8 @@ StagePrivate::StagePrivate(Stage* me, const std::string& name)
102102
, cost_term_{ std::make_unique<CostTerm>() }
103103
, total_compute_time_{}
104104
, parent_{ nullptr }
105-
, introspection_{ nullptr } {}
105+
, introspection_{ nullptr }
106+
, preempt_requested_{ nullptr } {}
106107

107108
StagePrivate& StagePrivate::operator=(StagePrivate&& other) {
108109
assert(typeid(*this) == typeid(other));

core/src/task.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -213,11 +213,12 @@ void Task::init() {
213213
// task expects its wrapped child to push to both ends, this triggers interface resolution
214214
stages()->pimpl()->resolveInterface(InterfaceFlags({ GENERATE }));
215215

216-
// provide introspection instance to all stages
216+
// provide introspection instance and preempt_requested to all stages
217217
auto* introspection = impl->introspection_.get();
218218
impl->traverseStages(
219-
[introspection](Stage& stage, int /*depth*/) {
219+
[introspection, impl](Stage& stage, int /*depth*/) {
220220
stage.pimpl()->setIntrospection(introspection);
221+
stage.pimpl()->setPreemptRequestedMember(&impl->preempt_requested_);
221222
return true;
222223
},
223224
1, UINT_MAX);
@@ -232,7 +233,11 @@ bool Task::canCompute() const {
232233
}
233234

234235
void Task::compute() {
235-
stages()->pimpl()->runCompute();
236+
try {
237+
stages()->pimpl()->runCompute();
238+
} catch (const PreemptStageException& e) {
239+
// do nothing, needed for early stop
240+
}
236241
}
237242

238243
moveit::core::MoveItErrorCode Task::plan(size_t max_solutions) {

core/test/stage_mockups.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ struct GeneratorMockup : public Generator
6565
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
6666
bool canCompute() const override;
6767
void compute() override;
68+
virtual void reset() override { runs_ = 0; };
6869
};
6970

7071
struct MonitoringGeneratorMockup : public MonitoringGenerator
@@ -81,6 +82,7 @@ struct MonitoringGeneratorMockup : public MonitoringGenerator
8182
bool canCompute() const override { return false; }
8283
void compute() override {}
8384
void onNewSolution(const SolutionBase& s) override;
85+
virtual void reset() override { runs_ = 0; };
8486
};
8587

8688
struct ConnectMockup : public Connecting
@@ -97,6 +99,7 @@ struct ConnectMockup : public Connecting
9799
using Connecting::compatible; // make this accessible for testing
98100

99101
void compute(const InterfaceState& from, const InterfaceState& to) override;
102+
virtual void reset() override { runs_ = 0; };
100103
};
101104

102105
struct PropagatorMockup : public PropagatingEitherWay
@@ -113,6 +116,7 @@ struct PropagatorMockup : public PropagatingEitherWay
113116

114117
void computeForward(const InterfaceState& from) override;
115118
void computeBackward(const InterfaceState& to) override;
119+
virtual void reset() override { runs_ = 0; };
116120
};
117121

118122
struct ForwardMockup : public PropagatorMockup

core/test/test_container.cpp

Lines changed: 24 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -674,21 +674,20 @@ TEST(Task, timeout) {
674674
}
675675

676676
// https://github.com/moveit/moveit_task_constructor/pull/597
677+
// https://github.com/moveit/moveit_task_constructor/pull/598
677678
// start planning in another thread, then preempt it in this thread
678-
TEST(Task, preempt) {
679+
TEST_F(TaskTestBase, preempt) {
679680
moveit::core::MoveItErrorCode ec;
680681
resetMockupIds();
681682

682-
Task t;
683-
t.setRobotModel(getModel());
684-
685683
auto timeout = std::chrono::milliseconds(10);
686-
t.add(std::make_unique<GeneratorMockup>(PredefinedCosts::constant(0.0)));
687-
t.add(std::make_unique<TimedForwardMockup>(timeout));
684+
auto gen1 = add(t, new GeneratorMockup(PredefinedCosts::constant(0.0)));
685+
auto fwd1 = add(t, new TimedForwardMockup(timeout));
686+
auto fwd2 = add(t, new TimedForwardMockup(timeout));
688687

689688
// preempt before preempt_request_ is reset in plan()
690689
{
691-
std::thread thread{ [&ec, &t, timeout] {
690+
std::thread thread{ [&ec, this, timeout] {
692691
std::this_thread::sleep_for(timeout);
693692
ec = t.plan(1);
694693
} };
@@ -698,5 +697,23 @@ TEST(Task, preempt) {
698697

699698
EXPECT_EQ(ec, moveit::core::MoveItErrorCode::PREEMPTED);
700699
EXPECT_EQ(t.solutions().size(), 0u);
700+
EXPECT_EQ(gen1->runs_, 0u);
701+
EXPECT_EQ(fwd1->runs_, 0u);
702+
EXPECT_EQ(fwd2->runs_, 0u);
703+
EXPECT_TRUE(t.plan(1)); // make sure the preempt request has been resetted on the previous call to plan()
704+
705+
t.reset();
706+
{
707+
std::thread thread{ [&ec, this] { ec = t.plan(1); } };
708+
std::this_thread::sleep_for(timeout / 2.0);
709+
t.preempt();
710+
thread.join();
711+
}
712+
713+
EXPECT_EQ(ec, moveit::core::MoveItErrorCode::PREEMPTED);
714+
EXPECT_EQ(t.solutions().size(), 0u);
715+
EXPECT_EQ(gen1->runs_, 1u);
716+
EXPECT_EQ(fwd1->runs_, 1u);
717+
EXPECT_EQ(fwd2->runs_, 0u);
701718
EXPECT_TRUE(t.plan(1)); // make sure the preempt request has been resetted on the previous call to plan()
702719
}

0 commit comments

Comments
 (0)