00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #include <clasp/shared_context.h>
00021 #include <clasp/solver.h>
00022 #include <clasp/clause.h>
00023 #include <clasp/dependency_graph.h>
00024 #if WITH_THREADS
00025 #include <clasp/util/thread.h>
00026 #endif
00027 namespace Clasp {
00028 double ProblemStats::operator[](const char* key) const {
00029 #define RETURN_IF(x) if (std::strcmp(key, #x) == 0) return double(x)
00030 RETURN_IF(vars);
00031 RETURN_IF(vars_eliminated);
00032 RETURN_IF(vars_frozen);
00033 RETURN_IF(constraints);
00034 RETURN_IF(constraints_binary);
00035 RETURN_IF(constraints_ternary);
00036 RETURN_IF(complexity);
00037 return -1.0;
00038 #undef RETURN_IF
00039 }
00040 const char* ProblemStats::keys(const char* k) {
00041 if (!k || !*k) { return "vars\0vars_eliminated\0vars_frozen\0constraints\0constraints_binary\0constraints_ternary\0complexity\0"; }
00042 return 0;
00043 }
00045
00047 #if WITH_THREADS
00048 ShortImplicationsGraph::Block::Block() {
00049 for (int i = 0; i != block_cap; ++i) { data[i] = posLit(0); }
00050 size_lock = 0;
00051 next = 0;
00052 }
00053 void ShortImplicationsGraph::Block::addUnlock(uint32 lockedSize, const Literal* x, uint32 xs) {
00054 std::copy(x, x+xs, data+lockedSize);
00055 size_lock = ((lockedSize+xs) << 1);
00056 }
00057 bool ShortImplicationsGraph::Block::tryLock(uint32& size) {
00058 uint32 s = size_lock;
00059 if ((s & 1) == 0 && size_lock.compare_and_swap(s | 1, s) == s) {
00060 size = s >> 1;
00061 return true;
00062 }
00063 return false;
00064 }
00065
00066 #define FOR_EACH_LEARNT(x, Y) \
00067 for (Block* b = (x).learnt; b ; b = b->next) \
00068 for (const Literal* Y = b->begin(), *endof = b->end(); Y != endof; Y += 2 - Y->watched())
00069
00070
00071 ShortImplicationsGraph::ImplicationList::~ImplicationList() {
00072 clear(true);
00073 }
00074
00075 void ShortImplicationsGraph::ImplicationList::clear(bool b) {
00076 ImpListBase::clear(b);
00077 for (Block* x = learnt; x; ) {
00078 Block* t = x;
00079 x = x->next;
00080 delete t;
00081 }
00082 learnt = 0;
00083 }
00084 void ShortImplicationsGraph::ImplicationList::simplifyLearnt(const Solver& s) {
00085 Block* x = learnt;
00086 learnt = 0;
00087 while (x) {
00088 for (const Literal* Y = x->begin(), *endof = x->end(); Y != endof; Y += 2 - Y->watched()) {
00089 Literal p = Y[0], q = !Y->watched() ? Y[1] : negLit(0);
00090 if (!s.isTrue(p) && !s.isTrue(q)) {
00091 addLearnt(p, q);
00092 }
00093 }
00094 Block* t = x;
00095 x = x->next;
00096 delete t;
00097 }
00098 }
00099 void ShortImplicationsGraph::ImplicationList::addLearnt(Literal p, Literal q) {
00100 Literal nc[2] = {p, q};
00101 uint32 ns = 1 + !isSentinel(q);
00102 if (ns == 1) { nc[0].watch(); }
00103 for (Block* x;;) {
00104 x = learnt;
00105 if (x) {
00106 uint32 lockedSize;
00107 if (x->tryLock(lockedSize)) {
00108 if ( (lockedSize + ns) <= Block::block_cap ) {
00109 x->addUnlock(lockedSize, nc, ns);
00110 }
00111 else {
00112 Block* t = new Block();
00113 t->addUnlock(0, nc, ns);
00114 t->next = x;
00115 x = learnt= t;
00116 }
00117 return;
00118 }
00119 else {
00120 Clasp::this_thread::yield();
00121 }
00122 }
00123 else {
00124 x = new Block();
00125 if (learnt.compare_and_swap(x, 0) != 0) {
00126 delete x;
00127 }
00128 }
00129 }
00130 }
00131
00132 bool ShortImplicationsGraph::ImplicationList::hasLearnt(Literal q, Literal r) const {
00133 const bool binary = isSentinel(r);
00134 FOR_EACH_LEARNT(*this, imp) {
00135 if (imp[0] == q || imp[0] == r) {
00136
00137 if (imp->watched()) { return true; }
00138
00139 if (!binary && (imp[1] == q || imp[1] == r)) { return true; }
00140 }
00141 }
00142 return false;
00143 }
00144
00145 void ShortImplicationsGraph::ImplicationList::move(ImplicationList& other) {
00146 ImpListBase::move(other);
00147 delete learnt;
00148 learnt = other.learnt;
00149 other.learnt = 0;
00150 }
00151 #endif
00152
00153
00155 ShortImplicationsGraph::ShortImplicationsGraph() {
00156 bin_[0] = bin_[1] = 0;
00157 tern_[0] = tern_[1] = 0;
00158 shared_ = false;
00159 }
00160 ShortImplicationsGraph::~ShortImplicationsGraph() {
00161 PodVector<ImplicationList>::destruct(graph_);
00162 }
00163 void ShortImplicationsGraph::resize(uint32 nodes) {
00164 if (graph_.capacity() >= nodes) {
00165 graph_.resize(nodes);
00166 }
00167 else {
00168 ImpLists temp; temp.resize(nodes);
00169 for (ImpLists::size_type i = 0; i != graph_.size(); ++i) {
00170 temp[i].move(graph_[i]);
00171 }
00172 graph_.swap(temp);
00173 }
00174 }
00175
00176 uint32 ShortImplicationsGraph::numEdges(Literal p) const { return graph_[p.index()].size(); }
00177
00178 bool ShortImplicationsGraph::add(ImpType t, bool learnt, const Literal* lits) {
00179 uint32& stats= (t == ternary_imp ? tern_ : bin_)[learnt];
00180 Literal p = lits[0], q = lits[1], r = (t == ternary_imp ? lits[2] : negLit(0));
00181 p.clearWatch(), q.clearWatch(), r.clearWatch();
00182 if (!shared_) {
00183 if (learnt) { p.watch(), q.watch(), r.watch(); }
00184 if (t == binary_imp) {
00185 getList(~p).push_left(q);
00186 getList(~q).push_left(p);
00187 }
00188 else {
00189 getList(~p).push_right(std::make_pair(q, r));
00190 getList(~q).push_right(std::make_pair(p, r));
00191 getList(~r).push_right(std::make_pair(p, q));
00192 }
00193 ++stats;
00194 return true;
00195 }
00196 #if WITH_THREADS
00197 else if (learnt && !getList(~p).hasLearnt(q, r)) {
00198 getList(~p).addLearnt(q, r);
00199 getList(~q).addLearnt(p, r);
00200 if (t == ternary_imp) {
00201 getList(~r).addLearnt(p, q);
00202 }
00203 ++stats;
00204 return true;
00205 }
00206 #endif
00207 return false;
00208 }
00209
00210 void ShortImplicationsGraph::remove_bin(ImplicationList& w, Literal p) {
00211 w.erase_left_unordered(std::find(w.left_begin(), w.left_end(), p));
00212 w.try_shrink();
00213 }
00214 void ShortImplicationsGraph::remove_tern(ImplicationList& w, Literal p) {
00215 w.erase_right_unordered(std::find_if(w.right_begin(), w.right_end(), PairContains<Literal>(p)));
00216 w.try_shrink();
00217 }
00218
00219
00220
00221
00222
00223
00224
00225
00226
00227
00228 void ShortImplicationsGraph::removeTrue(const Solver& s, Literal p) {
00229 assert(!shared_);
00230 typedef ImplicationList SWL;
00231 SWL& negPList = graph_[(~p).index()];
00232 SWL& pList = graph_[ (p).index()];
00233
00234 for (SWL::left_iterator it = negPList.left_begin(), end = negPList.left_end(); it != end; ++it) {
00235 --bin_[it->watched()];
00236 remove_bin(graph_[(~*it).index()], p);
00237 }
00238
00239 for (SWL::right_iterator it = negPList.right_begin(), end = negPList.right_end(); it != end; ++it) {
00240 --tern_[it->first.watched()];
00241 remove_tern(graph_[ (~it->first).index() ], p);
00242 remove_tern(graph_[ (~it->second).index() ], p);
00243 }
00244 #if WITH_THREADS
00245 FOR_EACH_LEARNT(negPList, imp) {
00246 graph_[(~imp[0]).index()].simplifyLearnt(s);
00247 if (!imp->watched()){
00248 --tern_[1];
00249 graph_[(~imp[1]).index()].simplifyLearnt(s);
00250 }
00251 if (imp->watched()) { --bin_[1]; }
00252 }
00253 #endif
00254
00255 for (SWL::right_iterator it = pList.right_begin(), end = pList.right_end(); it != end; ++it) {
00256 Literal q = it->first;
00257 Literal r = it->second;
00258 --tern_[q.watched()];
00259 remove_tern(graph_[(~q).index()], ~p);
00260 remove_tern(graph_[(~r).index()], ~p);
00261 if (s.value(q.var()) == value_free && s.value(r.var()) == value_free) {
00262
00263 Literal imp[2] = {q,r};
00264 add(binary_imp, false, imp);
00265 }
00266
00267 }
00268 graph_[(~p).index()].clear(true);
00269 graph_[ (p).index()].clear(true);
00270 }
00271 #undef FOR_EACH_LEARNT
00272 struct ShortImplicationsGraph::Propagate {
00273 Propagate(Solver& a_s) : s(&a_s) {}
00274 bool unary(Literal p, Literal x) const { return s->isTrue(x) || s->force(x, Antecedent(p)); }
00275 bool binary(Literal p, Literal x, Literal y) const {
00276 ValueRep vx = s->value(x.var()), vy;
00277 if (vx != trueValue(x) && (vy=s->value(y.var())) != trueValue(y) && vx + vy) {
00278 return vx != 0 ? s->force(y, Antecedent(p, ~x)) : s->force(x, Antecedent(p, ~y));
00279 }
00280 return true;
00281 }
00282 Solver* s;
00283 };
00284 struct ShortImplicationsGraph::ReverseArc {
00285 ReverseArc(const Solver& a_s, uint32 m, Antecedent& o) : s(&a_s), out(&o), maxL(m) {}
00286 bool unary(Literal, Literal x) const {
00287 if (!isRevLit(*s, x, maxL)) { return true; }
00288 *out = Antecedent(~x);
00289 return false;
00290 }
00291 bool binary(Literal, Literal x, Literal y) const {
00292 if (!isRevLit(*s, x, maxL) || !isRevLit(*s, y, maxL)) { return true; }
00293 *out = Antecedent(~x, ~y);
00294 return false;
00295 }
00296 const Solver* s; Antecedent* out; uint32 maxL;
00297 };
00298 bool ShortImplicationsGraph::propagate(Solver& s, Literal p) const { return forEach(p, Propagate(s)); }
00299 bool ShortImplicationsGraph::reverseArc(const Solver& s, Literal p, uint32 maxLev, Antecedent& out) const { return !forEach(p, ReverseArc(s, maxLev, out)); }
00300 bool ShortImplicationsGraph::propagateBin(Assignment& out, Literal p, uint32 level) const {
00301 const ImplicationList& x = graph_[p.index()];
00302 Antecedent ante(p);
00303 for (ImplicationList::const_left_iterator it = x.left_begin(), end = x.left_end(); it != end; ++it) {
00304 if (!out.assign(*it, level, p)) { return false; }
00305 }
00306 return true;
00307 }
00309
00311 SatPreprocessor::~SatPreprocessor() {
00312 discardClauses(true);
00313 }
00314 void SatPreprocessor::discardClauses(bool full) {
00315 for (ClauseList::size_type i = 0; i != clauses_.size(); ++i) {
00316 if (clauses_[i]) { clauses_[i]->destroy(); }
00317 }
00318 ClauseList().swap(clauses_);
00319 if (Clause* r = (full ? elimTop_ : 0)) {
00320 do {
00321 Clause* t = r;
00322 r = r->next();
00323 t->destroy();
00324 } while (r);
00325 elimTop_ = 0;
00326 }
00327 if (full) { seen_ = Range32(1,1); }
00328 }
00329 void SatPreprocessor::cleanUp(bool full) {
00330 if (ctx_) { seen_.hi = ctx_->numVars() + 1; }
00331 doCleanUp();
00332 discardClauses(full);
00333 }
00334
00335 bool SatPreprocessor::addClause(const Literal* lits, uint32 size) {
00336 if (size > 1) {
00337 clauses_.push_back( Clause::newClause(lits, size) );
00338 }
00339 else if (size == 1) {
00340 units_.push_back(lits[0]);
00341 }
00342 else {
00343 return false;
00344 }
00345 return true;
00346 }
00347
00348 void SatPreprocessor::freezeSeen() {
00349 if (!ctx_->validVar(seen_.lo)) { seen_.lo = 1; }
00350 if (!ctx_->validVar(seen_.hi)) { seen_.hi = ctx_->numVars() + 1; }
00351 for (Var v = seen_.lo; v != seen_.hi; ++v) {
00352 if (!ctx_->eliminated(v)) { ctx_->setFrozen(v, true); }
00353 }
00354 seen_.lo = seen_.hi;
00355 }
00356
00357 bool SatPreprocessor::preprocess(SharedContext& ctx, Options& opts) {
00358 ctx_ = &ctx;
00359 Solver* s = ctx_->master();
00360 struct OnExit {
00361 SharedContext* ctx;
00362 SatPreprocessor* self;
00363 SatPreprocessor* rest;
00364 OnExit(SatPreprocessor* s, SharedContext* c) : ctx(c), self(s), rest(0) {
00365 if (ctx && ctx->satPrepro.get() == s) { rest = ctx->satPrepro.release(); }
00366 }
00367 ~OnExit() {
00368 if (self) self->cleanUp();
00369 if (rest) ctx->satPrepro.reset(rest);
00370 }
00371 } onExit(this, &ctx);
00372 for (LitVec::const_iterator it = units_.begin(), end = units_.end(); it != end; ++it) {
00373 if (!ctx.addUnary(*it)) return false;
00374 }
00375 units_.clear();
00376
00377 if (!s->propagate()) return false;
00378 if (ctx.preserveModels() || opts.mode == Options::prepro_preserve_models) {
00379 opts.mode = Options::prepro_preserve_models;
00380 opts.disableBce();
00381 }
00382
00383 bool limFrozen= false;
00384 if (opts.limFrozen != 0 && ctx_->stats().vars_frozen) {
00385 uint32 varFrozen = ctx_->stats().vars_frozen;
00386 for (LitVec::const_iterator it = s->trail().begin(), end = s->trail().end(); it != end; ++it) {
00387 varFrozen -= (ctx_->varInfo(it->var()).frozen());
00388 }
00389 limFrozen = ((varFrozen / double(s->numFreeVars())) * 100.0) > double(opts.limFrozen);
00390 }
00391
00392 if (opts.type != 0 && !opts.clauseLimit(numClauses()) && !limFrozen && initPreprocess(opts)) {
00393 ClauseList::size_type j = 0;
00394 for (ClauseList::size_type i = 0; i != clauses_.size(); ++i) {
00395 Clause* c = clauses_[i]; assert(c);
00396 clauses_[i] = 0;
00397 c->simplify(*s);
00398 Literal x = (*c)[0];
00399 if (s->value(x.var()) == value_free) {
00400 clauses_[j++] = c;
00401 }
00402 else {
00403 c->destroy();
00404 if (!ctx.addUnary(x)) { return false; }
00405 }
00406 }
00407 clauses_.erase(clauses_.begin()+j, clauses_.end());
00408
00409 freezeSeen();
00410 if (!s->propagate() || !doPreprocess()) {
00411 return false;
00412 }
00413 }
00414
00415 if (!s->simplify()) return false;
00416
00417 for (ClauseList::size_type i = 0; i != clauses_.size(); ++i) {
00418 if (Clause* c = clauses_[i]) {
00419 if (!ClauseCreator::create(*s, ClauseRep::create(&(*c)[0], c->size()), 0)) {
00420 return false;
00421 }
00422 clauses_[i] = 0;
00423 c->destroy();
00424 }
00425 }
00426 ClauseList().swap(clauses_);
00427 return true;
00428 }
00429 bool SatPreprocessor::preprocess(SharedContext& ctx) {
00430 SatPreParams opts = ctx.configuration()->context().satPre;
00431 return preprocess(ctx, opts);
00432 }
00433 void SatPreprocessor::extendModel(ValueVec& m, LitVec& open) {
00434 if (!open.empty()) {
00435
00436 open.back() = ~open.back();
00437 }
00438 doExtendModel(m, open);
00439
00440 while (!open.empty() && open.back().sign()) {
00441 open.pop_back();
00442 }
00443 }
00444 SatPreprocessor::Clause* SatPreprocessor::Clause::newClause(const Literal* lits, uint32 size) {
00445 assert(size > 0);
00446 void* mem = ::operator new( sizeof(Clause) + (size-1)*sizeof(Literal) );
00447 return new (mem) Clause(lits, size);
00448 }
00449 SatPreprocessor::Clause::Clause(const Literal* lits, uint32 size) : size_(size), inQ_(0), marked_(0) {
00450 std::memcpy(lits_, lits, size*sizeof(Literal));
00451 }
00452 void SatPreprocessor::Clause::strengthen(Literal p) {
00453 uint64 a = 0;
00454 uint32 i, end;
00455 for (i = 0; lits_[i] != p; ++i) { a |= Clause::abstractLit(lits_[i]); }
00456 for (end = size_-1; i < end; ++i) { lits_[i] = lits_[i+1]; a |= Clause::abstractLit(lits_[i]); }
00457 --size_;
00458 data_.abstr = a;
00459 }
00460 void SatPreprocessor::Clause::simplify(Solver& s) {
00461 uint32 i;
00462 for (i = 0; i != size_ && s.value(lits_[i].var()) == value_free; ++i) {;}
00463 if (i == size_) { return; }
00464 else if (s.isTrue(lits_[i])){ std::swap(lits_[i], lits_[0]); return; }
00465 uint32 j = i++;
00466 for (; i != size_; ++i) {
00467 if (s.isTrue(lits_[i])) { std::swap(lits_[i], lits_[0]); return; }
00468 if (!s.isFalse(lits_[i])) { lits_[j++] = lits_[i]; }
00469 }
00470 size_ = j;
00471 }
00472 void SatPreprocessor::Clause::destroy() {
00473 void* mem = this;
00474 this->~Clause();
00475 ::operator delete(mem);
00476 }
00478
00480 static BasicSatConfig config_def_s;
00481
00482 EventHandler::~EventHandler() {}
00483 uint32 Event::nextId() { static uint32 id = 0; return id++; }
00484 SharedContext::SharedContext()
00485 : symTabPtr_(new SharedSymTab()), progress_(0), lastTopLevel_(0) {
00486 Antecedent::checkPlatformAssumptions();
00487 init();
00488 }
00489
00490 void SharedContext::init() {
00491 Var sentinel = addVar(Var_t::atom_var);
00492 setFrozen(sentinel, true);
00493 problem_.vars = 0;
00494 config_ = &config_def_s;
00495 config_.release();
00496 addSolver();
00497 }
00498
00499 bool SharedContext::ok() const { return master()->decisionLevel() || !master()->hasConflict() || master()->hasStopConflict(); }
00500 void SharedContext::enableStats(uint32 lev) {
00501 if (lev > 0) { master()->stats.enableExtended(); }
00502 if (lev > 1) { master()->stats.enableJump(); }
00503 }
00504 void SharedContext::cloneVars(const SharedContext& other, InitMode m) {
00505 problem_.vars = other.problem_.vars;
00506 problem_.vars_eliminated = other.problem_.vars_eliminated;
00507 problem_.vars_frozen = other.problem_.vars_frozen;
00508 varInfo_ = other.varInfo_;
00509 if (&symbolTable() != &other.symbolTable()) {
00510 if (m == init_copy_symbols) { other.symbolTable().copyTo(symbolTable()); }
00511 else {
00512 ++other.symTabPtr_->refs;
00513 if (--symTabPtr_->refs == 0) { delete symTabPtr_; }
00514 symTabPtr_ = other.symTabPtr_;
00515 }
00516 }
00517 }
00518
00519 SharedContext::~SharedContext() {
00520 while (!solvers_.empty()) { delete solvers_.back(); solvers_.pop_back(); }
00521 while (!accu_.empty()) { delete accu_.back(); accu_.pop_back(); }
00522 if (--symTabPtr_->refs == 0) delete symTabPtr_;
00523 }
00524
00525 void SharedContext::reset() {
00526 this->~SharedContext();
00527 new (this) SharedContext();
00528 }
00529
00530 void SharedContext::setConcurrency(uint32 n) {
00531 if (n <= 1) { share_.count = 1; share_.shareM = ContextParams::share_auto; }
00532 else { share_.count = n; solvers_.reserve(n); }
00533 while (solvers_.size() > share_.count) {
00534 delete solvers_.back();
00535 solvers_.pop_back();
00536 }
00537 if (share_.shareM == ContextParams::share_auto) {
00538 setShareMode(ContextParams::share_auto);
00539 }
00540 }
00541
00542 void SharedContext::setShareMode(ContextParams::ShareMode m) {
00543 if ( (share_.shareM = static_cast<uint32>(m)) == ContextParams::share_auto && share_.count > 1) {
00544 share_.shareM |= static_cast<uint32>(ContextParams::share_all);
00545 }
00546 }
00547 void SharedContext::setShortMode(ContextParams::ShortMode m) {
00548 share_.shortM = static_cast<uint32>(m);
00549 }
00550
00551 Solver& SharedContext::addSolver() {
00552 uint32 id = (uint32)solvers_.size();
00553 share_.count = std::max(share_.count, id + 1);
00554 Solver* s = new Solver(this, id);
00555 solvers_.push_back(s);
00556 return *s;
00557 }
00558
00559 void SharedContext::setConfiguration(Configuration* c, bool own) {
00560 if (c == 0) { c = &config_def_s; own = false; }
00561 if (config_.get() != c) {
00562 config_ = c;
00563 if (!own) config_.release();
00564 config_->prepare(*this);
00565 const ContextParams& opts = config_->context();
00566 share_.shareM = opts.shareMode;
00567 share_.shortM = opts.shortMode;
00568 share_.seed = opts.seed;
00569 share_.satPreM= opts.satPre.mode;
00570 if (satPrepro.get() == 0 && opts.satPre.type != SatPreParams::sat_pre_no) {
00571 satPrepro.reset(SatPreParams::create(opts.satPre));
00572 }
00573 enableStats(opts.stats);
00574
00575 for (uint32 i = 0; i != solvers_.size(); ++i) {
00576 solvers_[i]->strategy.loadCfg = 1;
00577 }
00578 }
00579 else if (own != config_.is_owner()) {
00580 if (own) config_.acquire();
00581 else config_.release();
00582 }
00583 }
00584
00585 bool SharedContext::unfreeze() {
00586 if (frozen()) {
00587 share_.frozen = 0;
00588 share_.winner = 0;
00589 btig_.markShared(false);
00590 return master()->popRootLevel(master()->rootLevel())
00591 && btig_.propagate(*master(), posLit(0))
00592 && unfreezeStep();
00593 }
00594 return true;
00595 }
00596
00597 bool SharedContext::unfreezeStep() {
00598 for (SolverVec::size_type i = solvers_.size(); i-- ; ) {
00599 Solver& s = *solvers_[i];
00600 s.popRootLevel(s.rootLevel());
00601 s.popAuxVar();
00602 uint32 tp = std::min(lastTopLevel_, (uint32)s.lastSimp_);
00603 if (s.value(step_.var()) == value_free){ s.force(~step_, posLit(0));}
00604 s.post_.disable();
00605 if (s.simplify()) {
00606 while (tp < (uint32)s.assign_.trail.size()) {
00607 Var v = s.assign_.trail[tp].var();
00608 if (v != step_.var()) { master()->force(s.assign_.trail[tp++]); }
00609 else { std::swap(s.assign_.trail[tp], s.assign_.trail.back()); s.assign_.undoLast(); }
00610 }
00611 s.assign_.qReset();
00612 s.assign_.setUnits(s.lastSimp_ = (uint32)s.assign_.trail.size());
00613 }
00614 s.post_.enable();
00615 if (s.configuration().heuReinit) {
00616 s.heuristic_.reset(0);
00617 }
00618 }
00619 return !master()->hasConflict();
00620 }
00621
00622 Var SharedContext::addVar(VarType t, bool eq) {
00623 VarInfo nv;
00624 if (t == Var_t::body_var) { nv.set(VarInfo::BODY); }
00625 if (eq) { nv.set(VarInfo::EQ); }
00626 varInfo_.push_back(nv);
00627 ++problem_.vars;
00628 return numVars();
00629 }
00630
00631 void SharedContext::requestStepVar() { if (step_ == posLit(0)) { step_= negLit(0); } }
00632 void SharedContext::requestData(Var v){ master()->requestData(v); }
00633
00634 void SharedContext::setFrozen(Var v, bool b) {
00635 assert(validVar(v));
00636 if (v && b != varInfo_[v].has(VarInfo::FROZEN)) {
00637 varInfo_[v].toggle(VarInfo::FROZEN);
00638 b ? ++problem_.vars_frozen : --problem_.vars_frozen;
00639 }
00640 }
00641 bool SharedContext::eliminated(Var v) const {
00642 assert(validVar(v));
00643 return !master()->assign_.valid(v);
00644 }
00645
00646 void SharedContext::eliminate(Var v) {
00647 assert(validVar(v) && !frozen() && master()->decisionLevel() == 0);
00648 if (!eliminated(v)) {
00649 ++problem_.vars_eliminated;
00650
00651 master()->assign_.eliminate(v);
00652 }
00653 }
00654
00655 Literal SharedContext::addAuxLit() {
00656 VarInfo nv; nv.set(VarInfo::FROZEN);
00657 varInfo_.push_back(nv);
00658 return posLit(numVars());
00659 }
00660 Solver& SharedContext::startAddConstraints(uint32 constraintGuess) {
00661 if (!unfreeze()) { return *master(); }
00662 if (master()->isFalse(step_)) { step_= addAuxLit(); }
00663 btig_.resize((numVars()+1)<<1);
00664 master()->startInit(constraintGuess);
00665 return *master();
00666 }
00667 bool SharedContext::addUnary(Literal x) {
00668 CLASP_ASSERT_CONTRACT(!frozen() || !isShared());
00669 return master()->force(x);
00670 }
00671 bool SharedContext::addBinary(Literal x, Literal y) {
00672 CLASP_ASSERT_CONTRACT(allowImplicit(Constraint_t::static_constraint));
00673 Literal lits[2] = {x, y};
00674 return ClauseCreator::create(*master(), ClauseRep(lits, 2), ClauseCreator::clause_force_simplify);
00675 }
00676 bool SharedContext::addTernary(Literal x, Literal y, Literal z) {
00677 CLASP_ASSERT_CONTRACT(allowImplicit(Constraint_t::static_constraint));
00678 Literal lits[3] = {x, y, z};
00679 return ClauseCreator::create(*master(), ClauseRep(lits, 3), ClauseCreator::clause_force_simplify);
00680 }
00681 void SharedContext::add(Constraint* c) {
00682 CLASP_ASSERT_CONTRACT(!frozen());
00683 master()->add(c);
00684 }
00685 int SharedContext::addImp(ImpGraph::ImpType t, const Literal* lits, ConstraintType ct) {
00686 if (!allowImplicit(ct)) { return -1; }
00687 bool learnt = ct != Constraint_t::static_constraint;
00688 if (!learnt && !frozen() && satPrepro.get()) {
00689 satPrepro->addClause(lits, static_cast<uint32>(t));
00690 return 1;
00691 }
00692 return int(btig_.add(t, learnt, lits));
00693 }
00694
00695 uint32 SharedContext::numConstraints() const { return numBinary() + numTernary() + master()->constraints_.size(); }
00696
00697 bool SharedContext::endInit(bool attachAll) {
00698 assert(!frozen());
00699 report(message(Event::subsystem_prepare, "Preprocessing"));
00700 initStats(*master());
00701 SatPrePtr temp;
00702 satPrepro.swap(temp);
00703 bool ok = !master()->hasConflict() && master()->preparePost() && (!temp.get() || temp->preprocess(*this)) && master()->endInit();
00704 satPrepro.swap(temp);
00705 btig_.markShared(concurrency() > 1);
00706 master()->dbIdx_ = (uint32)master()->constraints_.size();
00707 lastTopLevel_ = (uint32)master()->assign_.front;
00708 problem_.constraints = master()->constraints_.size();
00709 problem_.constraints_binary = btig_.numBinary();
00710 problem_.constraints_ternary= btig_.numTernary();
00711 problem_.complexity = std::max(problem_.complexity, problemComplexity());
00712 share_.frozen = 1;
00713 for (uint32 i = ok && attachAll ? 1 : concurrency(); i != concurrency(); ++i) {
00714 if (!hasSolver(i)) { addSolver(); }
00715 if (!attach(i)) { return false; }
00716 }
00717 return ok || (detach(*master(), false), false);
00718 }
00719
00720 bool SharedContext::attach(Solver& other) {
00721 assert(frozen() && other.shared_ == this);
00722 if (other.validVar(step_.var())) {
00723 if (!other.popRootLevel(other.rootLevel())){ return false; }
00724 if (&other == master()) { return true; }
00725 }
00726 initStats(other);
00727
00728 Var lastVar = other.numVars();
00729 other.startInit(static_cast<uint32>(master()->constraints_.size()));
00730 other.assign_.requestData(master()->assign_.numData());
00731 Antecedent null;
00732 for (LitVec::size_type i = 0, end = master()->trail().size(); i != end; ++i) {
00733 if (!other.force(master()->trail()[i], null)) { return false; }
00734 }
00735 for (Var v = satPrepro.get() ? lastVar+1 : varMax, end = master()->numVars(); v <= end; ++v) {
00736 if (eliminated(v) && other.value(v) == value_free) {
00737 other.assign_.eliminate(v);
00738 }
00739 }
00740 if (other.constraints_.empty()) { other.lastSimp_ = master()->lastSimp_; }
00741
00742 if (!other.cloneDB(master()->constraints_)) {
00743 return false;
00744 }
00745 Constraint* c = master()->enumerationConstraint();
00746 other.setEnumerationConstraint( c ? c->cloneAttach(other) : 0 );
00747
00748 return (other.preparePost() && other.endInit()) || (detach(other, false), false);
00749 }
00750
00751 void SharedContext::detach(Solver& s, bool reset) {
00752 assert(s.shared_ == this);
00753 if (reset) { s.reset(); }
00754 s.setEnumerationConstraint(0);
00755 s.popAuxVar();
00756 }
00757 void SharedContext::initStats(Solver& s) const {
00758 s.stats.enableStats(master()->stats);
00759 s.stats.reset();
00760 }
00761 const SolverStats& SharedContext::stats(const Solver& s, bool accu) const {
00762 return !accu || s.id() >= accu_.size() || !accu_[s.id()] ? s.stats : *accu_[s.id()];
00763 }
00764 void SharedContext::accuStats() {
00765 accu_.resize(std::max(accu_.size(), solvers_.size()), 0);
00766 for (uint32 i = 0; i != solvers_.size(); ++i) {
00767 if (!accu_[i]) { accu_[i] = new SolverStats(); }
00768 accu_[i]->enableStats(solvers_[i]->stats);
00769 accu_[i]->accu(solvers_[i]->stats);
00770 }
00771 if (sccGraph.get()) { sccGraph->accuStats(); }
00772 }
00773
00774 void SharedContext::simplify(bool shuffle) {
00775 Solver::ConstraintDB& db = master()->constraints_;
00776 if (concurrency() == 1 || master()->dbIdx_ == 0) {
00777 Clasp::simplifyDB(*master(), db, shuffle);
00778 }
00779 else {
00780 uint32 rem = 0;
00781 for (Solver::ConstraintDB::size_type i = 0, end = db.size(); i != end; ++i) {
00782 Constraint* c = db[i];
00783 if (c->simplify(*master(), shuffle)) { c->destroy(master(), false); db[i] = 0; ++rem; }
00784 }
00785 if (rem) {
00786 for (SolverVec::size_type s = 1; s != solvers_.size(); ++s) {
00787 Solver& x = *solvers_[s];
00788 CLASP_FAIL_IF(x.dbIdx_ > db.size(), "Invalid DB idx!");
00789 if (x.dbIdx_ == db.size()) { x.dbIdx_ -= rem; }
00790 else if (x.dbIdx_ != 0) { x.dbIdx_ -= (uint32)std::count_if(db.begin(), db.begin()+x.dbIdx_, IsNull()); }
00791 }
00792 db.erase(std::remove_if(db.begin(), db.end(), IsNull()), db.end());
00793 }
00794 }
00795 master()->dbIdx_ = db.size();
00796 }
00797 void SharedContext::removeConstraint(uint32 idx, bool detach) {
00798 Solver::ConstraintDB& db = master()->constraints_;
00799 CLASP_ASSERT_CONTRACT(idx < db.size());
00800 Constraint* c = db[idx];
00801 for (SolverVec::size_type s = 1; s != solvers_.size(); ++s) {
00802 Solver& x = *solvers_[s];
00803 x.dbIdx_ -= (idx < x.dbIdx_);
00804 }
00805 db.erase(db.begin()+idx);
00806 master()->dbIdx_ = db.size();
00807 c->destroy(master(), detach);
00808 }
00809
00810 void SharedContext::simplifyShort(const Solver& s, Literal p) {
00811 if (!isShared() && p.index() < btig_.size()) { btig_.removeTrue(s, p); }
00812 }
00813
00814 uint32 SharedContext::problemComplexity() const {
00815 if (isExtended()) {
00816 uint32 r = numBinary() + numTernary();
00817 for (uint32 i = 0; i != master()->constraints_.size(); ++i) {
00818 r += master()->constraints_[i]->estimateComplexity(*master());
00819 }
00820 return r;
00821 }
00822 return numConstraints();
00823 }
00825
00827 Distributor::Distributor(const Policy& p) : policy_(p) {}
00828 Distributor::~Distributor() {}
00829
00830 }