Skip to content

Commit a7e3961

Browse files
authored
Fix #737 (pruning in fallback stages with a connect stage) (#742)
* Add unit test for #737 * Consider pruning property in Connect stage Even if pruning was disabled, pruning could sneak in via the Connect stage. * Shift definition of pruning property's default Previously, it was explicitly disabled in Task's constructor. Child containers inherited the setting from their parent, i.e. ultimately the task. However, this meant that the property remained undefined for standalone containers. Now, the default value is declared in each container. Additionally, the property is still inherited from the parent. * Reenable state before passing it to Fallbacks child - fixing the pruning problem
1 parent a3d4e74 commit a7e3961

4 files changed

Lines changed: 23 additions & 3 deletions

File tree

core/src/container.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -327,7 +327,7 @@ void ContainerBasePrivate::liftSolution(const SolutionBasePtr& solution, const I
327327

328328
ContainerBase::ContainerBase(ContainerBasePrivate* impl) : Stage(impl) {
329329
auto& p = properties();
330-
p.declare<bool>("pruning", std::string("enable pruning?")).configureInitFrom(Stage::PARENT, "pruning");
330+
p.declare<bool>("pruning", false, std::string("enable pruning?")).configureInitFrom(Stage::PARENT, "pruning");
331331
}
332332

333333
size_t ContainerBase::numChildren() const {
@@ -1029,6 +1029,11 @@ bool FallbacksPrivatePropagator::nextJob() {
10291029
}
10301030

10311031
// When arriving here, we have a valid job_ and a current_ child to feed it. Let's do that.
1032+
if (dir_ == Interface::FORWARD)
1033+
setStatus<Interface::BACKWARD>(nullptr, nullptr, &*job_, InterfaceState::Status::ENABLED);
1034+
else
1035+
setStatus<Interface::FORWARD>(nullptr, nullptr, &*job_, InterfaceState::Status::ENABLED);
1036+
10321037
copyState(dir_, job_, (*current_)->pimpl()->pullInterface(dir_), Interface::UpdateFlags());
10331038
return true;
10341039
}

core/src/stage.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -820,7 +820,7 @@ void ConnectingPrivate::newState(Interface::iterator it, Interface::UpdateFlags
820820
for (Interface::iterator oit : oit_to_enable)
821821
parent_pimpl->setStatus<opposite<dir>()>(me(), &*it, &*oit, InterfaceState::Status::ENABLED);
822822

823-
if (!have_enabled_opposites) // prune new state and associated branch if necessary
823+
if (!have_enabled_opposites && parent()->pruning()) // prune new state and associated branch if necessary
824824
// pass creator=nullptr to skip hasPendingOpposites() check as we did this here already
825825
parent_pimpl->setStatus<dir>(nullptr, nullptr, &*it, InterfaceState::Status::ARMED);
826826
}

core/src/task.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,6 @@ const ContainerBase* TaskPrivate::stages() const {
9494

9595
Task::Task(const std::string& ns, bool introspection, ContainerBase::pointer&& container)
9696
: WrapperBase(new TaskPrivate(this, ns), std::move(container)) {
97-
setPruning(false);
9897
setTimeout(std::numeric_limits<double>::max());
9998

10099
// monitor state on commandline

core/test/test_fallback.cpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -195,3 +195,19 @@ TEST_F(FallbacksFixtureConnect, connectStageInsideFallbacks) {
195195
EXPECT_TRUE(t.plan());
196196
EXPECT_COSTS(t.solutions(), testing::ElementsAre(11, 12, 22, 121));
197197
}
198+
199+
TEST_F(FallbacksFixtureConnect, connectInsideSerialInsideFallbacks) {
200+
t.add(std::make_unique<GeneratorMockup>(PredefinedCosts({ 0.0 })));
201+
auto fallbacks = std::make_unique<Fallbacks>("Fallbacks");
202+
auto serial = std::make_unique<SerialContainer>("Serial1");
203+
serial->add(std::make_unique<ForwardMockup>(PredefinedCosts::constant(0.0)));
204+
serial->add(std::make_unique<ConnectMockup>(PredefinedCosts::constant(1.0)));
205+
serial->add(std::make_unique<BackwardMockup>(PredefinedCosts::constant(INF)));
206+
serial->add(std::make_unique<GeneratorMockup>(PredefinedCosts::single(2.0)));
207+
fallbacks->add(std::move(serial));
208+
fallbacks->add(std::make_unique<ForwardMockup>(PredefinedCosts::constant(4.0)));
209+
210+
t.add(std::move(fallbacks));
211+
EXPECT_TRUE(t.plan());
212+
EXPECT_COSTS(t.solutions(), testing::ElementsAre(4.0));
213+
}

0 commit comments

Comments
 (0)