00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #ifndef CLASP_SOLVER_H_INCLUDED
00021 #define CLASP_SOLVER_H_INCLUDED
00022 #ifdef _MSC_VER
00023 #pragma once
00024 #pragma warning (disable : 4996) // 'std::copy': Function call with parameters that may be unsafe
00025 #endif
00026
00027 #include <clasp/solver_types.h>
00028 #include <clasp/solver_strategies.h>
00029 #include <clasp/shared_context.h>
00030
00031 namespace Clasp {
00032
00034 struct SearchLimits {
00035 explicit SearchLimits(uint64 conf = UINT64_MAX)
00036 : conflicts(conf)
00037 , local(UINT64_MAX)
00038 , memLimit(UINT64_MAX)
00039 , dynamic(0)
00040 , learnts(UINT32_MAX) {
00041 }
00042 bool reached() const { return conflicts == 0 || local == 0 || hasDynamicRestart(); }
00043 bool hasDynamicRestart() const { return dynamic && dynamic->isRestart(); }
00044 void setMemLimit(uint32 limitInMB) { memLimit = limitInMB ? static_cast<uint64>(limitInMB)<<20 : UINT64_MAX; }
00045 uint64 conflicts;
00046 uint64 local;
00047 uint64 memLimit;
00048 SumQueue* dynamic;
00049 uint32 learnts;
00050 };
00051
00056
00058
00082 class Solver {
00083 public:
00084 typedef PodVector<Constraint*>::type ConstraintDB;
00085 typedef const ConstraintDB& DBRef;
00086 typedef SingleOwnerPtr<DecisionHeuristic> Heuristic;
00087 private:
00092 friend class SharedContext;
00094 Solver(SharedContext* ctx, uint32 id);
00096 ~Solver();
00098 void reset();
00099 void resetId(uint32 id) { strategy.id = id; }
00100 void startInit(uint32 constraintGuess);
00101 bool cloneDB(const ConstraintDB& db);
00102 bool preparePost();
00103 bool endInit();
00105 public:
00107 const SharedContext* sharedContext() const { return shared_; }
00109 SatPreprocessor* satPrepro() const;
00111 const SolverParams& configuration() const;
00113 const SolveParams& searchConfig() const;
00114 const Heuristic& heuristic() const { return heuristic_;}
00115 uint32 id() const { return strategy.id; }
00116 Heuristic& heuristic() { return heuristic_;}
00117 VarInfo varInfo(Var v) const { return shared_->validVar(v) ? shared_->varInfo(v) : VarInfo(); }
00118 const SymbolTable& symbolTable() const { return shared_->symbolTable(); }
00119 Literal tagLiteral() const { return tag_; }
00121
00126 void add(Constraint* c);
00128
00134 bool add(const ClauseRep& c, bool isNew = true);
00136 bool allowImplicit(const ClauseRep& c) const {
00137 return c.isImp()
00138 ? shared_->allowImplicit(c.info.type()) && !c.info.aux() && (c.prep == 1 || (!auxVar(c.lits[0].var()) && !auxVar(c.lits[1].var()) && (c.size == 2 || !auxVar(c.lits[2].var()))))
00139 : c.size <= 1;
00140 }
00142 PostPropagator* getPost(uint32 prio) const;
00144
00149 bool addPost(PostPropagator* p) { return addPost(p, initPost_ != 0); }
00151
00155 void removePost(PostPropagator* p){ post_.remove(p); }
00160
00161
00176 ValueRep search(SearchLimits& limit, double randf = 0.0);
00177 ValueRep search(uint64 maxC, uint32 maxL, bool local = false, double rp = 0.0) {
00178 SearchLimits limit;
00179 if (!local) { limit.conflicts = maxC; }
00180 else { limit.conflicts = UINT64_MAX; limit.local = maxC; }
00181 limit.learnts = maxL;
00182 return search(limit, rp);
00183 }
00184
00186 bool pushRoot(const LitVec& path);
00187 bool pushRoot(Literal p);
00188
00189 void setEnumerationConstraint(Constraint* c);
00190
00192
00197 void pushRootLevel(uint32 i = 1) {
00198 levels_.root = std::min(decisionLevel(), levels_.root+i);
00199 levels_.backtrack = std::max(levels_.backtrack, levels_.root);
00200 }
00201
00203
00214 bool popRootLevel(uint32 i = 1, LitVec* popped = 0, bool aux = true);
00215
00217 void clearStopConflict();
00218
00220 uint32 rootLevel() const { return levels_.root; }
00221
00223
00228 bool clearAssumptions();
00229
00231 void addLearnt(LearntConstraint* c, uint32 size, ConstraintType type) {
00232 learnts_.push_back(c);
00233 stats.addLearnt(size, type);
00234 }
00235 void addLearnt(LearntConstraint* c, uint32 size) { addLearnt(c, size, c->type()); }
00237
00242 uint32 receive(SharedLiterals** out, uint32 maxOut) const;
00244
00259 SharedLiterals* distribute(const Literal* lits, uint32 size, const ClauseInfo& extra);
00260
00261
00263 void restart() {
00264 undoUntil(0);
00265 ++stats.restarts;
00266 ccInfo_.setActivity(ccInfo_.activity() + 1);
00267 }
00268
00270 void setBacktrackLevel(uint32 dl) {
00271 levels_.backtrack = std::max(std::min(dl, decisionLevel()), rootLevel());
00272 }
00274 uint32 backtrackLevel() const { return levels_.backtrack; }
00275
00277 bool splittable() const;
00278
00280
00283 bool split(LitVec& out);
00284
00286
00294 void copyGuidingPath(LitVec& out);
00295
00297
00302 bool simplify();
00304 void shuffleOnNextSimplify(){ shufSimp_ = 1; }
00305
00307
00317 Var pushTagVar(bool pushToRoot);
00319
00322 void removeConditional();
00323
00325
00328 void strengthenConditional();
00329
00331
00350 bool force(const Literal& p, const Antecedent& a) {
00351 assert(!hasConflict() || isTrue(p));
00352 if (assign_.assign(p, decisionLevel(), a)) return true;
00353 setConflict(p, a, UINT32_MAX);
00354 return false;
00355 }
00360 bool force(const Literal& p, const Antecedent& a, uint32 data) {
00361 return data != UINT32_MAX
00362 ? assign_.assign(p, decisionLevel(), a.constraint(), data) || (setConflict(p, a, data), false)
00363 : force(p, a);
00364 }
00365
00367
00374 bool force(Literal p, uint32 dl, const Antecedent& r, uint32 d = UINT32_MAX) {
00375
00376 if (dl == decisionLevel()) { return force(p, r, d); }
00377 ImpliedLiteral* x = 0;
00378
00379 if (isTrue(p) && (level(p.var()) <= dl || (x = impliedLits_.find(p)) != 0)) {
00380 if (level(p.var()) <= dl) { return true; }
00381 if (x->level <= dl) { return true; }
00382 *x = ImpliedLiteral(p, dl, r, d);
00383 return setReason(p, r, d);
00384 }
00385
00386 if (undoUntil(dl, false) == dl) { return force(p, r, d); }
00387
00388
00389 assert(!x);
00390 impliedLits_.add(decisionLevel(), ImpliedLiteral(p, dl, r, d));
00391 return (isTrue(p) && setReason(p, r, d)) || force(p, r, d);
00392 }
00394 bool force(Literal p) { return force(p, 0, Antecedent(posLit(0))); }
00395
00397
00403 bool assume(const Literal& p);
00404
00406
00415 bool decideNextBranch(double f = 0.0);
00416
00418
00428 void setStopConflict();
00429
00439 bool propagate();
00440
00448 bool propagateUntil(PostPropagator* p) { assert((!p || post_.active()) && "OP not allowed during init!"); return unitPropagate() && (p == post_.active() || post_.propagate(*this, p)); }
00449
00451
00464 bool test(Literal p, PostPropagator* c);
00465
00467
00470 uint32 estimateBCP(const Literal& p, int maxRecursionDepth = 5) const;
00471
00473
00479 uint32 inDegree(WeightLitVec& out);
00480
00481 struct DBInfo { uint32 size; uint32 locked; uint32 pinned; };
00483
00491 DBInfo reduceLearnts(float remMax, const ReduceStrategy& rs = ReduceStrategy());
00492
00494
00505 bool resolveConflict();
00506
00508
00513 bool backtrack();
00514
00516
00520 void undoUntil(uint32 dl);
00521
00527 uint32 undoUntil(uint32 dl, bool popBtLevel);
00528
00530
00535 Var pushAuxVar();
00537 void popAuxVar(uint32 num = UINT32_MAX);
00539
00547
00548 uint32 numProblemVars() const { return shared_->numVars(); }
00550 uint32 numAuxVars() const { return numVars() - numProblemVars(); }
00552 uint32 numVars() const { return assign_.numVars() - 1; }
00554 bool validVar(Var var) const { return var <= numVars(); }
00556 bool auxVar(Var var) const { return shared_->numVars() < var; }
00558 uint32 numAssignedVars() const { return assign_.assigned(); }
00560
00564 uint32 numFreeVars() const { return assign_.free()-1; }
00566 ValueRep value(Var v) const { assert(validVar(v)); return assign_.value(v); }
00568 ValueRep topValue(Var v) const { return level(v) == 0 ? value(v) : value_free; }
00570 ValueSet pref(Var v) const { assert(validVar(v)); return assign_.pref(v);}
00572 bool isTrue(Literal p) const { assert(validVar(p.var())); return assign_.value(p.var()) == trueValue(p); }
00574 bool isFalse(Literal p) const { assert(validVar(p.var())); return assign_.value(p.var()) == falseValue(p); }
00576
00579 Literal trueLit(Var v) const { assert(value(v) != value_free); return Literal(v, valSign(value(v))); }
00581
00584 uint32 level(Var v) const { assert(validVar(v)); return assign_.level(v); }
00586
00589 bool seen(Var v) const { assert(validVar(v)); return assign_.seen(v, 3u); }
00591 bool seen(Literal p) const { assert(validVar(p.var())); return assign_.seen(p.var(), uint8(1+p.sign())); }
00593 uint32 decisionLevel() const { return (uint32)levels_.size(); }
00594 bool validLevel(uint32 dl) const { return dl != 0 && dl <= decisionLevel(); }
00596
00599 uint32 levelStart(uint32 dl) const { assert(validLevel(dl)); return levels_[dl-1].trailPos; }
00601
00604 Literal decision(uint32 dl) const { assert(validLevel(dl)); return assign_.trail[ levels_[dl-1].trailPos ]; }
00606 bool hasConflict() const { return !conflict_.empty(); }
00607 bool hasStopConflict() const { return hasConflict() && conflict_[0] == negLit(0); }
00609 uint32 queueSize() const { return (uint32) assign_.qSize(); }
00611 uint32 numConstraints() const;
00613 uint32 numLearntConstraints() const { return (uint32)learnts_.size(); }
00615
00618 const Antecedent& reason(Literal p) const { assert(isTrue(p)); return assign_.reason(p.var()); }
00620 uint32 reasonData(Literal p) const { return assign_.data(p.var()); }
00622
00626 const LitVec& trail() const { return assign_.trail; }
00627 const Assignment& assignment() const { return assign_; }
00629 const LitVec& conflict() const { return conflict_; }
00631 const LitVec& conflictClause() const { return cc_; }
00633 const LitVec& symmetric() const { return temp_; }
00635 Constraint* enumerationConstraint() const { return enum_; }
00636 DBRef constraints() const { return constraints_; }
00638
00641 LearntConstraint& getLearnt(uint32 idx) const {
00642 assert(idx < numLearntConstraints());
00643 return *static_cast<LearntConstraint*>(learnts_[ idx ]);
00644 }
00645
00646 SolverStrategies strategy;
00647 RNG rng;
00648 ValueVec model;
00649 SolverStats stats;
00651
00658
00659 uint32 numWatches(Literal p) const;
00661 bool hasWatch(Literal p, Constraint* c) const;
00662 bool hasWatch(Literal p, ClauseHead* c) const;
00664
00667 GenericWatch* getWatch(Literal p, Constraint* c) const;
00669
00673 void addWatch(Literal p, Constraint* c, uint32 data = 0) {
00674 assert(validWatch(p));
00675 watches_[p.index()].push_right(GenericWatch(c, data));
00676 }
00678 void addWatch(Literal p, const ClauseWatch& w) {
00679 assert(validWatch(p));
00680 watches_[p.index()].push_left(w);
00681 }
00683
00686 void removeWatch(const Literal& p, Constraint* c);
00687 void removeWatch(const Literal& p, ClauseHead* c);
00689
00694 void addUndoWatch(uint32 dl, Constraint* c) {
00695 assert(validLevel(dl));
00696 if (levels_[dl-1].undo != 0) {
00697 levels_[dl-1].undo->push_back(c);
00698 }
00699 else {
00700 levels_[dl-1].undo = allocUndo(c);
00701 }
00702 }
00704 bool removeUndoWatch(uint32 dl, Constraint* c);
00706
00713 bool addPost(PostPropagator* p, bool init) { post_.add(p, p->priority()); return !init || p->init(*this); }
00715
00718 bool setReason(Literal p, const Antecedent& x, uint32 data = UINT32_MAX) {
00719 assert(isTrue(p) || shared_->eliminated(p.var()));
00720 assign_.setReason(p.var(), x);
00721 if (data != UINT32_MAX) { assign_.setData(p.var(), data); }
00722 return true;
00723 }
00725 void requestData(Var v) { assign_.requestData(v + 1); }
00726 void setPref(Var v, ValueSet::Value which, ValueRep to) {
00727 assert(validVar(v) && to <= value_false);
00728 assign_.requestPrefs();
00729 assign_.setPref(v, which, to);
00730 }
00732 void reason(Literal p, LitVec& out) { assert(isTrue(p)); out.clear(); return assign_.reason(p.var()).reason(*this, p, out); }
00734
00744 uint32 updateLearnt(Literal p, const Literal* first, const Literal* last, uint32 cLbd, bool forceUp = false) {
00745 uint32 up = strategy.updateLbd;
00746 if ((up || forceUp) && cLbd > 1) {
00747 uint32 strict = (up == 2u);
00748 uint32 p1 = (up == 3u);
00749 uint32 nLbd = (strict|p1) + countLevels(first, last, cLbd - strict);
00750 if (nLbd < cLbd) { cLbd = nLbd - p1; }
00751 }
00752 if (strategy.bumpVarAct && isTrue(p)) { bumpAct_.push_back(WeightLiteral(p, cLbd)); }
00753 return cLbd;
00754 }
00756 bool ccMinimize(Literal p, CCMinRecursive* rec) const {
00757 return seen(p.var()) ||
00758 (rec && hasLevel(level(p.var())) && rec->checkRecursive(p));
00759 }
00760
00762 bool learntLimit(const SearchLimits& x) const { return numLearntConstraints() > x.learnts || memUse_ > x.memLimit; }
00763
00765 void* allocSmall() { return smallAlloc_->allocate(); }
00767 void freeSmall(void* m) { smallAlloc_->free(m); }
00768
00769 void addLearntBytes(uint32 bytes) { memUse_ += bytes; }
00770 void freeLearntBytes(uint64 bytes) { memUse_ -= (bytes < memUse_) ? bytes : memUse_; }
00771
00773 uint32 simplifyConflictClause(LitVec& cc, ClauseInfo& info, ClauseHead* rhs);
00774 uint32 finalizeConflictClause(LitVec& cc, ClauseInfo& info, uint32 ccRepMode = 0);
00775 uint32 countLevels(const Literal* first, const Literal* last, uint32 maxLevels);
00776 bool hasLevel(uint32 dl) const { assert(validLevel(dl)); return levels_[dl-1].marked != 0; }
00777 bool frozenLevel(uint32 dl) const { assert(validLevel(dl)); return levels_[dl-1].freeze != 0; }
00778 void markLevel(uint32 dl) { assert(validLevel(dl)); levels_[dl-1].marked = 1; }
00779 void freezeLevel(uint32 dl) { assert(validLevel(dl)); levels_[dl-1].freeze = 1; }
00780 void unmarkLevel(uint32 dl) { assert(validLevel(dl)); levels_[dl-1].marked = 0; }
00781 void unfreezeLevel(uint32 dl){ assert(validLevel(dl)); levels_[dl-1].freeze = 0; }
00782 void markSeen(Var v) { assert(validVar(v)); assign_.setSeen(v, 3u); }
00783 void markSeen(Literal p) { assert(validVar(p.var())); assign_.setSeen(p.var(), uint8(1+p.sign())); }
00784 void clearSeen(Var v) { assert(validVar(v)); assign_.clearSeen(v); }
00786 private:
00787 struct DLevel {
00788 explicit DLevel(uint32 pos = 0, ConstraintDB* u = 0)
00789 : trailPos(pos)
00790 , marked(0)
00791 , freeze(0)
00792 , undo(u) {}
00793 uint32 trailPos : 30;
00794 uint32 marked : 1;
00795 uint32 freeze : 1;
00796 ConstraintDB* undo;
00797 };
00798 struct DecisionLevels : public PodVector<DLevel>::type {
00799 DecisionLevels() : root(0), backtrack(0) {}
00800 uint32 root;
00801 uint32 backtrack;
00802 };
00803 typedef PodVector<Antecedent>::type ReasonVec;
00804 typedef PodVector<WatchList>::type Watches;
00805 struct PPList {
00806 PPList();
00807 ~PPList();
00808 void add(PostPropagator* p, uint32 prio);
00809 void remove(PostPropagator* p);
00810 bool propagate(Solver& s, PostPropagator* p) const;
00811 void simplify(Solver& s, bool shuf);
00812 void cancel() const;
00813 bool isModel(Solver& s) const;
00814 void disable();
00815 void enable();
00816 PostPropagator* head() const { return list; }
00817 PostPropagator* active()const { return *act; }
00818 PostPropagator* list;
00819 PostPropagator**act;
00820 };
00821 struct CmpScore {
00822 typedef std::pair<uint32, Activity> ViewPair;
00823 CmpScore(const ConstraintDB& learnts, ReduceStrategy::Score sc, uint32 g) : db(learnts), rs(sc), glue(g) {}
00824 uint32 score(const Activity& act) const { return ReduceStrategy::asScore(rs, act); }
00825 bool operator()(uint32 lhsId, uint32 rhsId) const { return (*this)(db[lhsId], db[rhsId]); }
00826 bool operator()(const ViewPair& lhs, const ViewPair& rhs) const { return this->operator()(lhs.second, rhs.second); }
00827 bool operator()(Activity lhs, Activity rhs) const { return ReduceStrategy::compare(rs, lhs, rhs) < 0;}
00828 bool operator()(const Constraint* lhs, const Constraint* rhs) const {
00829 return this->operator()(
00830 static_cast<const LearntConstraint*>(lhs)->activity(),
00831 static_cast<const LearntConstraint*>(rhs)->activity());
00832 }
00833 const ConstraintDB& db;
00834 ReduceStrategy::Score rs;
00835 uint32 glue;
00836 private: CmpScore& operator=(const CmpScore&);
00837 };
00838 bool validWatch(Literal p) const { return p.index() < (uint32)watches_.size(); }
00839 void freeMem();
00840 bool simplifySAT();
00841 bool unitPropagate();
00842 void cancelPropagation() { assign_.qReset(); post_.cancel(); }
00843 void undoLevel(bool sp);
00844 uint32 analyzeConflict();
00845 void otfs(Antecedent& lhs, const Antecedent& rhs, Literal p, bool final);
00846 ClauseHead* otfsRemove(ClauseHead* c, const LitVec* newC);
00847 uint32 ccMinimize(LitVec& cc, LitVec& removed, uint32 antes, CCMinRecursive* ccMin);
00848 bool ccRemovable(Literal p, uint32 antes, CCMinRecursive* ccMin);
00849 Antecedent ccHasReverseArc(Literal p, uint32 maxLevel, uint32 maxNew);
00850 void ccResolve(LitVec& cc, uint32 pos, const LitVec& reason);
00851 void undoFree(ConstraintDB* x);
00852 void setConflict(Literal p, const Antecedent& a, uint32 data);
00853 uint64 updateBranch(uint32 cfl);
00854 DBInfo reduceLinear(uint32 maxR, const CmpScore& cmp);
00855 DBInfo reduceSort(uint32 maxR, const CmpScore& cmp);
00856 DBInfo reduceSortInPlace(uint32 maxR, const CmpScore& cmp, bool onlyPartialSort);
00857 ConstraintDB* allocUndo(Constraint* c);
00858 SharedContext* shared_;
00859 Heuristic heuristic_;
00860 CCMinRecursive* ccMin_;
00861 SmallClauseAlloc* smallAlloc_;
00862 ConstraintDB* undoHead_;
00863 Constraint* enum_;
00864 uint64 memUse_;
00865 Assignment assign_;
00866 DecisionLevels levels_;
00867 ConstraintDB constraints_;
00868 ConstraintDB learnts_;
00869 PPList post_;
00870 Watches watches_;
00871 LitVec conflict_;
00872 LitVec cc_;
00873 LitVec temp_;
00874 WeightLitVec bumpAct_;
00875 VarVec lbdStamp_;
00876 VarVec cflStamp_;
00877 ImpliedList impliedLits_;
00878 ClauseInfo ccInfo_;
00879 Literal tag_;
00880 uint32 lbdTime_;
00881 uint32 dbIdx_;
00882 uint32 lastSimp_ :30;
00883 uint32 shufSimp_ : 1;
00884 uint32 initPost_ : 1;
00885 };
00886
00887 inline bool isRevLit(const Solver& s, Literal p, uint32 maxL) {
00888 return s.isFalse(p) && (s.seen(p) || s.level(p.var()) < maxL);
00889 }
00890
00891 template <class C>
00892 void simplifyDB(Solver& s, C& db, bool shuffle) {
00893 typename C::size_type j = 0;
00894 for (typename C::size_type i = j, end = db.size(); i != end; ++i) {
00895 Constraint* c = db[i];
00896 if (c->simplify(s, shuffle)){ c->destroy(&s, false); }
00897 else { db[j++] = c; }
00898 }
00899 shrinkVecTo(db, j);
00900 }
00901
00903
00908
00910
00915 class DecisionHeuristic {
00916 public:
00917 DecisionHeuristic() {}
00918 virtual ~DecisionHeuristic();
00924 virtual void startInit(const Solver& ) {}
00925
00932 virtual void endInit(Solver& ) { }
00933
00946 virtual void updateVar(const Solver& , Var , uint32 ) = 0;
00947
00957 virtual void simplify(const Solver& , LitVec::size_type ) { }
00958
00966 virtual void undoUntil(const Solver& , LitVec::size_type ) {}
00967
00977 virtual void newConstraint(const Solver&, const Literal* , LitVec::size_type , ConstraintType ) {}
00978
00989 virtual void updateReason(const Solver& , const LitVec& , Literal ) {}
00990
00992
00996 virtual bool bump(const Solver& , const WeightLitVec& , double ) { return false; }
00997
01008 bool select(Solver& s) { return s.numFreeVars() != 0 && s.assume(doSelect(s)); }
01009
01011
01017 virtual Literal doSelect(Solver& ) = 0;
01018
01027 virtual Literal selectRange(Solver& , const Literal* first, const Literal* ) {
01028 return *first;
01029 }
01030 static Literal selectLiteral(Solver& s, Var v, int signScore) {
01031 ValueSet prefs = s.pref(v);
01032 if (signScore != 0 && !prefs.has(ValueSet::user_value | ValueSet::saved_value | ValueSet::pref_value)) {
01033 return Literal(v, signScore < 0);
01034 }
01035 else if (!prefs.empty()) {
01036 return Literal(v, prefs.sign());
01037 }
01038 return defaultLiteral(s, v);
01039 }
01040 static Literal defaultLiteral(Solver& s, Var v) {
01041 switch(s.strategy.signDef) {
01042 default:
01043 case SolverStrategies::sign_atom: return Literal(v, !s.varInfo(v).has(VarInfo::BODY));
01044 case SolverStrategies::sign_no : return posLit(v);
01045 case SolverStrategies::sign_yes : return negLit(v);
01046 case SolverStrategies::sign_rnd : return Literal(v, s.rng.drand() < 0.5);
01047 case SolverStrategies::sign_disj: return Literal(v, !s.varInfo(v).has(VarInfo::BODY|VarInfo::DISJ));
01048 }
01049 }
01050 private:
01051 DecisionHeuristic(const DecisionHeuristic&);
01052 DecisionHeuristic& operator=(const DecisionHeuristic&);
01053 };
01054
01056 class SelectFirst : public DecisionHeuristic {
01057 public:
01058 void updateVar(const Solver& , Var , uint32 ) {}
01059 private:
01060 Literal doSelect(Solver& s);
01061 };
01062
01064 }
01065 #endif