Skip to content

Commit c7b2067

Browse files
committed
Merge PR #309: Fix Pruning
2 parents 184fab8 + 5956e70 commit c7b2067

File tree

19 files changed

+950
-339
lines changed

19 files changed

+950
-339
lines changed

.github/workflows/ci.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ jobs:
3232
DOCKER_RUN_OPTS: >-
3333
-e PRELOAD=libasan.so.5
3434
-e LSAN_OPTIONS="suppressions=$PWD/.github/workflows/lsan.suppressions"
35-
TARGET_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-fsanitize=address -fno-omit-frame-pointer -O1"
35+
TARGET_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-fsanitize=address -fno-omit-frame-pointer -O1 -g"
3636

3737
env:
3838
CATKIN_LINT: true

.pre-commit-config.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
repos:
1616
# Standard hooks
1717
- repo: https://github.com/pre-commit/pre-commit-hooks
18-
rev: v3.4.0
18+
rev: v4.0.1
1919
hooks:
2020
- id: check-added-large-files
2121
- id: check-case-conflict
@@ -29,7 +29,7 @@ repos:
2929
- id: trailing-whitespace
3030

3131
- repo: https://github.com/psf/black
32-
rev: 20.8b1
32+
rev: 21.11b1
3333
hooks:
3434
- id: black
3535

core/include/moveit/task_constructor/container.h

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -150,6 +150,7 @@ class Alternatives : public ParallelContainerBase
150150
void onNewSolution(const SolutionBase& s) override;
151151
};
152152

153+
class FallbacksPrivate;
153154
/** Plan for different alternatives in sequence.
154155
*
155156
* Try to find feasible solutions using first child. Only if this fails,
@@ -158,17 +159,23 @@ class Alternatives : public ParallelContainerBase
158159
*/
159160
class Fallbacks : public ParallelContainerBase
160161
{
161-
mutable Stage* active_child_ = nullptr;
162+
inline void replaceImpl();
162163

163164
public:
164-
Fallbacks(const std::string& name = "fallbacks") : ParallelContainerBase(name) {}
165+
PRIVATE_CLASS(Fallbacks);
166+
Fallbacks(const std::string& name = "fallbacks");
165167

166168
void reset() override;
167169
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
168-
bool canCompute() const override;
169-
void compute() override;
170170

171+
protected:
172+
Fallbacks(FallbacksPrivate* impl);
171173
void onNewSolution(const SolutionBase& s) override;
174+
175+
private:
176+
// not needed, we directly use corresponding virtual methods of FallbacksPrivate
177+
bool canCompute() const final { return false; }
178+
void compute() final {}
172179
};
173180

174181
class MergerPrivate;

core/include/moveit/task_constructor/container_p.h

Lines changed: 94 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ namespace task_constructor {
7676
class ContainerBasePrivate : public StagePrivate
7777
{
7878
friend class ContainerBase;
79-
friend void swap(StagePrivate*& lhs, StagePrivate*& rhs);
79+
friend class ConnectingPrivate; // needed propagate setStatus() in newState()
8080

8181
public:
8282
using container_type = StagePrivate::container_type;
@@ -131,10 +131,11 @@ class ContainerBasePrivate : public StagePrivate
131131
inline const auto& externalToInternalMap() const { return internal_external_.by<EXTERNAL>(); }
132132

133133
/// called by a (direct) child when a solution failed
134-
void onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to);
134+
virtual void onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to);
135135

136136
protected:
137137
ContainerBasePrivate(ContainerBase* me, const std::string& name);
138+
ContainerBasePrivate& operator=(ContainerBasePrivate&& other);
138139

139140
// Set child's push interfaces: allow pushing if child requires it.
140141
inline void setChildsPushBackwardInterface(StagePrivate* child) {
@@ -148,14 +149,19 @@ class ContainerBasePrivate : public StagePrivate
148149
child->setNextStarts(allowed ? pending_forward_ : InterfacePtr());
149150
}
150151

151-
/// Set ENABLED / PRUNED status of the solution tree starting from s into given direction
152+
/// Set ENABLED/PRUNED status of a solution branch starting from target into the given direction
152153
template <Interface::Direction dir>
153-
void setStatus(const InterfaceState* s, InterfaceState::Status status);
154+
void setStatus(const Stage* creator, const InterfaceState* source, const InterfaceState* target,
155+
InterfaceState::Status status);
154156

155-
/// copy external_state to a child's interface and remember the link in internal_external map
157+
/// Copy external_state to a child's interface and remember the link in internal_external map
156158
template <Interface::Direction>
157-
void copyState(Interface::iterator external, const InterfacePtr& target, bool updated);
158-
/// lift solution from internal to external level
159+
void copyState(Interface::iterator external, const InterfacePtr& target, Interface::UpdateFlags updated);
160+
// non-template version
161+
void copyState(Interface::Direction dir, Interface::iterator external, const InterfacePtr& target,
162+
Interface::UpdateFlags updated);
163+
164+
/// Lift solution from internal to external level
159165
void liftSolution(const SolutionBasePtr& solution, const InterfaceState* internal_from,
160166
const InterfaceState* internal_to);
161167

@@ -228,12 +234,91 @@ class ParallelContainerBasePrivate : public ContainerBasePrivate
228234
void validateInterfaces(const StagePrivate& child, InterfaceFlags& external, bool first = false) const;
229235

230236
private:
231-
/// callback for new externally received states
237+
/// notify callback for new externally received interface states
232238
template <typename Interface::Direction>
233-
void onNewExternalState(Interface::iterator external, bool updated);
239+
void propagateStateToAllChildren(Interface::iterator external, Interface::UpdateFlags updated);
240+
241+
// override to customize behavior on received interface states (default: propagateStateToAllChildren())
242+
virtual void initializeExternalInterfaces();
234243
};
235244
PIMPL_FUNCTIONS(ParallelContainerBase)
236245

246+
/* The Fallbacks container needs to implement different behaviour based on its interface.
247+
* Thus, we implement 3 different classes: for Generator, Propagator, and Connect-like interfaces.
248+
* FallbacksPrivate is the common base class for all of them, defining the common API
249+
* to be used by the Fallbacks container.
250+
* The actual interface-specific class is instantiated in initializeExternalInterfaces()
251+
* resp. Fallbacks::replaceImpl() when the actual interface is known.
252+
* The key difference between the 3 variants is how they advance to the next job. */
253+
class FallbacksPrivate : public ParallelContainerBasePrivate
254+
{
255+
public:
256+
FallbacksPrivate(Fallbacks* me, const std::string& name);
257+
FallbacksPrivate(FallbacksPrivate&& other);
258+
259+
void initializeExternalInterfaces() final;
260+
void onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to) override;
261+
262+
// virtual methods specific to each variant
263+
virtual void onNewSolution(const SolutionBase& s);
264+
virtual void reset() {}
265+
};
266+
PIMPL_FUNCTIONS(Fallbacks)
267+
268+
/* Class shared between FallbacksPrivateGenerator and FallbacksPrivatePropagator,
269+
which both have the notion of a currently active child stage */
270+
class FallbacksPrivateCommon : public FallbacksPrivate
271+
{
272+
public:
273+
FallbacksPrivateCommon(FallbacksPrivate&& other) : FallbacksPrivate(std::move(other)) {}
274+
275+
/// Advance to next child
276+
inline void nextChild();
277+
/// Advance to the next job, assuming that the current child is exhausted on the current job.
278+
virtual bool nextJob() = 0;
279+
280+
void reset() override;
281+
bool canCompute() const override;
282+
void compute() override;
283+
284+
container_type::const_iterator current_; // currently active child
285+
};
286+
287+
/// Fallbacks implementation for GENERATOR interface
288+
struct FallbacksPrivateGenerator : FallbacksPrivateCommon
289+
{
290+
FallbacksPrivateGenerator(FallbacksPrivate&& old);
291+
bool nextJob() override;
292+
};
293+
294+
/// Fallbacks implementation for FORWARD or BACKWARD interface
295+
struct FallbacksPrivatePropagator : FallbacksPrivateCommon
296+
{
297+
FallbacksPrivatePropagator(FallbacksPrivate&& old);
298+
void reset() override;
299+
void onNewSolution(const SolutionBase& s) override;
300+
bool nextJob() override;
301+
302+
Interface::Direction dir_; // propagation direction
303+
Interface::iterator job_; // pointer to currently processed external state
304+
bool job_has_solutions_; // flag indicating whether the current job generated solutions
305+
};
306+
307+
/// Fallbacks implementation for CONNECT interface
308+
struct FallbacksPrivateConnect : FallbacksPrivate
309+
{
310+
FallbacksPrivateConnect(FallbacksPrivate&& old);
311+
void reset() override;
312+
bool canCompute() const override;
313+
void compute() override;
314+
void onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to) override;
315+
316+
template <Interface::Direction dir>
317+
void propagateStateUpdate(Interface::iterator external, Interface::UpdateFlags updated);
318+
319+
mutable container_type::const_iterator active_; // child picked for compute()
320+
};
321+
237322
class WrapperBasePrivate : public ParallelContainerBasePrivate
238323
{
239324
friend class WrapperBase;

core/include/moveit/task_constructor/stage_p.h

Lines changed: 27 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,6 @@ class StagePrivate
6161
{
6262
friend class Stage;
6363
friend std::ostream& operator<<(std::ostream& os, const StagePrivate& stage);
64-
friend void swap(StagePrivate*& lhs, StagePrivate*& rhs);
6564

6665
public:
6766
/// container type used to store children
@@ -100,17 +99,11 @@ class StagePrivate
10099
inline InterfaceConstPtr prevEnds() const { return prev_ends_.lock(); }
101100
inline InterfaceConstPtr nextStarts() const { return next_starts_.lock(); }
102101

103-
/// direction-based access to pull/push interfaces
104-
inline InterfacePtr& pullInterface(Interface::Direction dir) { return dir == Interface::FORWARD ? starts_ : ends_; }
105-
inline InterfacePtr pushInterface(Interface::Direction dir) {
106-
return dir == Interface::FORWARD ? next_starts_.lock() : prev_ends_.lock();
107-
}
108-
inline InterfaceConstPtr pullInterface(Interface::Direction dir) const {
109-
return dir == Interface::FORWARD ? starts_ : ends_;
110-
}
111-
inline InterfaceConstPtr pushInterface(Interface::Direction dir) const {
112-
return dir == Interface::FORWARD ? next_starts_.lock() : prev_ends_.lock();
113-
}
102+
/// direction-based access to pull interface
103+
template <Interface::Direction dir>
104+
inline InterfacePtr pullInterface();
105+
// non-template version
106+
inline InterfacePtr pullInterface(Interface::Direction dir) { return dir == Interface::FORWARD ? starts_ : ends_; }
114107

115108
/// set parent of stage
116109
/// enforce only one parent exists
@@ -165,6 +158,8 @@ class StagePrivate
165158
void computeCost(const InterfaceState& from, const InterfaceState& to, SolutionBase& solution);
166159

167160
protected:
161+
StagePrivate& operator=(StagePrivate&& other);
162+
168163
// associated/owning Stage instance
169164
Stage* me_;
170165

@@ -204,6 +199,15 @@ class StagePrivate
204199
PIMPL_FUNCTIONS(Stage)
205200
std::ostream& operator<<(std::ostream& os, const StagePrivate& stage);
206201

202+
template <>
203+
inline InterfacePtr StagePrivate::pullInterface<Interface::FORWARD>() {
204+
return starts_;
205+
}
206+
template <>
207+
inline InterfacePtr StagePrivate::pullInterface<Interface::BACKWARD>() {
208+
return ends_;
209+
}
210+
207211
template <>
208212
inline void StagePrivate::send<Interface::FORWARD>(const InterfaceState& start, InterfaceState&& end,
209213
const SolutionBasePtr& solution) {
@@ -300,6 +304,7 @@ PIMPL_FUNCTIONS(MonitoringGenerator)
300304
class ConnectingPrivate : public ComputeBasePrivate
301305
{
302306
friend class Connecting;
307+
friend struct FallbacksPrivateConnect;
303308

304309
public:
305310
struct StatePair : std::pair<Interface::const_iterator, Interface::const_iterator>
@@ -310,18 +315,15 @@ class ConnectingPrivate : public ComputeBasePrivate
310315
}
311316
static inline bool less(const InterfaceState::Priority& lhsA, const InterfaceState::Priority& lhsB,
312317
const InterfaceState::Priority& rhsA, const InterfaceState::Priority& rhsB) {
313-
unsigned char lhs = (lhsA.enabled() << 1) | lhsB.enabled(); // combine bits into two-digit binary number
314-
unsigned char rhs = (rhsA.enabled() << 1) | rhsB.enabled();
318+
bool lhs = lhsA.enabled() && lhsB.enabled();
319+
bool rhs = rhsA.enabled() && rhsB.enabled();
320+
315321
if (lhs == rhs) // if enabled status is identical
316322
return lhsA + lhsB < rhsA + rhsB; // compare the sums of both contributions
317-
// one of the states in each pair should be enabled
318-
assert(lhs != 0b00 && rhs != 0b00);
319-
// both states valid (b11)
320-
if (lhs == 0b11)
321-
return true;
322-
if (rhs == 0b11)
323-
return false;
324-
return lhs < rhs; // disabled states in 1st component go before disabled states in 2nd component
323+
324+
// sort both-enabled pairs first
325+
static_assert(true > false, "Comparing enabled states requires true > false");
326+
return lhs > rhs;
325327
}
326328
};
327329

@@ -333,7 +335,7 @@ class ConnectingPrivate : public ComputeBasePrivate
333335

334336
// Check whether there are pending feasible states that could connect to source
335337
template <Interface::Direction dir>
336-
bool hasPendingOpposites(const InterfaceState* source) const;
338+
bool hasPendingOpposites(const InterfaceState* source, const InterfaceState* target) const;
337339

338340
std::ostream& printPendingPairs(std::ostream& os = std::cerr) const;
339341

@@ -342,9 +344,9 @@ class ConnectingPrivate : public ComputeBasePrivate
342344
template <Interface::Direction other>
343345
inline StatePair make_pair(Interface::const_iterator first, Interface::const_iterator second);
344346

345-
// get informed when new start or end state becomes available
347+
// notify callback to get informed about newly inserted (or updated) start or end states
346348
template <Interface::Direction other>
347-
void newState(Interface::iterator it, bool updated);
349+
void newState(Interface::iterator it, Interface::UpdateFlags updated);
348350

349351
// ordered list of pending state pairs
350352
ordered<StatePair> pending;

0 commit comments

Comments
 (0)