Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 6 additions & 1 deletion core/src/container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,7 +327,7 @@ void ContainerBasePrivate::liftSolution(const SolutionBasePtr& solution, const I

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

size_t ContainerBase::numChildren() const {
Expand Down Expand Up @@ -1029,6 +1029,11 @@ bool FallbacksPrivatePropagator::nextJob() {
}

// When arriving here, we have a valid job_ and a current_ child to feed it. Let's do that.
if (dir_ == Interface::FORWARD)
setStatus<Interface::BACKWARD>(nullptr, nullptr, &*job_, InterfaceState::Status::ENABLED);
else
setStatus<Interface::FORWARD>(nullptr, nullptr, &*job_, InterfaceState::Status::ENABLED);

copyState(dir_, job_, (*current_)->pimpl()->pullInterface(dir_), Interface::UpdateFlags());
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion core/src/stage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -820,7 +820,7 @@ void ConnectingPrivate::newState(Interface::iterator it, Interface::UpdateFlags
for (Interface::iterator oit : oit_to_enable)
parent_pimpl->setStatus<opposite<dir>()>(me(), &*it, &*oit, InterfaceState::Status::ENABLED);

if (!have_enabled_opposites) // prune new state and associated branch if necessary
if (!have_enabled_opposites && parent()->pruning()) // prune new state and associated branch if necessary
// pass creator=nullptr to skip hasPendingOpposites() check as we did this here already
parent_pimpl->setStatus<dir>(nullptr, nullptr, &*it, InterfaceState::Status::ARMED);
}
Expand Down
1 change: 0 additions & 1 deletion core/src/task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,6 @@ const ContainerBase* TaskPrivate::stages() const {

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

// monitor state on commandline
Expand Down
16 changes: 16 additions & 0 deletions core/test/test_fallback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,3 +195,19 @@ TEST_F(FallbacksFixtureConnect, connectStageInsideFallbacks) {
EXPECT_TRUE(t.plan());
EXPECT_COSTS(t.solutions(), testing::ElementsAre(11, 12, 22, 121));
}

TEST_F(FallbacksFixtureConnect, connectInsideSerialInsideFallbacks) {
t.add(std::make_unique<GeneratorMockup>(PredefinedCosts({ 0.0 })));
auto fallbacks = std::make_unique<Fallbacks>("Fallbacks");
auto serial = std::make_unique<SerialContainer>("Serial1");
serial->add(std::make_unique<ForwardMockup>(PredefinedCosts::constant(0.0)));
serial->add(std::make_unique<ConnectMockup>(PredefinedCosts::constant(1.0)));
serial->add(std::make_unique<BackwardMockup>(PredefinedCosts::constant(INF)));
serial->add(std::make_unique<GeneratorMockup>(PredefinedCosts::single(2.0)));
fallbacks->add(std::move(serial));
fallbacks->add(std::make_unique<ForwardMockup>(PredefinedCosts::constant(4.0)));

t.add(std::move(fallbacks));
EXPECT_TRUE(t.plan());
EXPECT_COSTS(t.solutions(), testing::ElementsAre(4.0));
}
Loading