00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #ifndef CLASP_CLAUSE_H_INCLUDED
00021 #define CLASP_CLAUSE_H_INCLUDED
00022
00023 #ifdef _MSC_VER
00024 #pragma warning (disable : 4200) // nonstandard extension used : zero-sized array
00025 #pragma once
00026 #endif
00027
00028 #include <clasp/solver_types.h>
00029 #include <clasp/util/atomic.h>
00030 namespace Clasp {
00031
00033 class SharedLiterals {
00034 public:
00036
00039 static SharedLiterals* newShareable(const LitVec& lits, ConstraintType t, uint32 numRefs = 1) {
00040 return newShareable(!lits.empty() ? &lits[0]:0, static_cast<uint32>(lits.size()), t, numRefs);
00041 }
00042 static SharedLiterals* newShareable(const Literal* lits, uint32 size, ConstraintType t, uint32 numRefs = 1);
00043
00045 const Literal* begin() const { return lits_; }
00047 const Literal* end() const { return lits_+size(); }
00049 uint32 size() const { return size_type_ >> 2; }
00051 ConstraintType type() const { return ConstraintType( size_type_ & uint32(3) ); }
00053
00059 uint32 simplify(Solver& s);
00060
00061 void release();
00062 SharedLiterals* share();
00063 bool unique() const { return refCount_ <= 1; }
00064 uint32 refCount() const { return refCount_; }
00065 private:
00066 void destroy();
00067 SharedLiterals(const Literal* lits, uint32 size, ConstraintType t, uint32 numRefs);
00068 SharedLiterals(const SharedLiterals&);
00069 SharedLiterals& operator=(const SharedLiterals&);
00070 Clasp::atomic<int32> refCount_;
00071 uint32 size_type_;
00072 Literal lits_[0];
00073 };
00074
00076
00082 class ClauseCreator {
00083 public:
00085
00088 explicit ClauseCreator(Solver* s = 0);
00090 void setSolver(Solver& s) { solver_ = &s; }
00092 void addDefaultFlags(uint32 f) { flags_ |= f; }
00094 void reserve(LitVec::size_type s) { literals_.reserve(s); }
00096 void clear() { literals_.clear(); }
00097
00099
00102 enum Status {
00103
00104 status_open = 0,
00105 status_sat = 1,
00106 status_unsat = 2,
00107 status_unit = 4,
00108
00109 status_sat_asserting= 5,
00110 status_asserting = 6,
00111 status_subsumed = 9,
00112 status_empty = 10,
00113 };
00115 struct Result {
00116 explicit Result(ClauseHead* loc = 0, Status st = status_open)
00117 : local(loc)
00118 , status(st) {}
00119 ClauseHead* local;
00120 Status status;
00122 bool ok() const { return (status & status_unsat) == 0; }
00124 bool unit() const { return (status & status_unit) != 0; }
00125 operator bool() const { return ok(); }
00126 };
00128
00131 ClauseCreator& start(ConstraintType t = Constraint_t::static_constraint);
00133 ClauseCreator& setActivity(uint32 a) { extra_.setActivity(a); return *this; }
00135 ClauseCreator& setLbd(uint32 lbd) { extra_.setLbd(lbd); return *this; }
00137 ClauseCreator& add(const Literal& p) { literals_.push_back(p); return *this; }
00139 ClauseRep prepare(bool fullSimplify);
00141 uint32 size() const { return (uint32)literals_.size(); }
00143 Literal& operator[](uint32 i) { return literals_[i]; }
00144 Literal operator[](uint32 i) const { return literals_[i]; }
00146 const LitVec& lits() const { return literals_; }
00147 LitVec& lits() { return literals_; }
00149 ConstraintType type() const { return extra_.type(); }
00151 ClauseInfo info() const { return extra_; }
00153
00160 Result end(uint32 flags = clause_not_sat | clause_not_conflict);
00161
00167
00168 enum CreateFlag {
00169
00170 clause_no_add = 1,
00171 clause_explicit = 2,
00172
00173 clause_not_sat = 4,
00174 clause_not_root_sat = 8,
00175 clause_not_conflict = 16,
00176
00177 clause_no_release = 32,
00178 clause_int_lbd = 64,
00179
00180 clause_no_prepare = 128,
00181 clause_force_simplify= 256,
00182 clause_no_heuristic = 512
00183 };
00185 static Status status(const Solver& s, const Literal* clause_begin, const Literal* clause_end);
00186 static Status status(const Solver& s, const ClauseRep& c);
00187
00189
00195 static uint32 watchOrder(const Solver& s, Literal p);
00196
00198
00212 static ClauseRep prepare(Solver& s, LitVec& lits, uint32 flags, const ClauseInfo& info = ClauseInfo());
00213
00215
00238 static Result create(Solver& s, LitVec& lits, uint32 flags, const ClauseInfo& info = ClauseInfo());
00239 static Result create(Solver& s, const ClauseRep& rep, uint32 flags);
00241
00271 static Result integrate(Solver& s, SharedLiterals* clause, uint32 flags, ConstraintType t);
00275 static Result integrate(Solver& s, SharedLiterals* clause, uint32 flags);
00277 private:
00278 static ClauseRep prepare(Solver& s, const Literal* in, uint32 inSize, const ClauseInfo& e, uint32 flags, Literal* out, uint32 outMax = UINT32_MAX);
00279 static Result create_prepared(Solver& s, const ClauseRep& pc, uint32 flags);
00280 static ClauseHead* newProblemClause(Solver& s, const ClauseRep& clause, uint32 flags);
00281 static ClauseHead* newLearntClause(Solver& s, const ClauseRep& clause, uint32 flags);
00282 static ClauseHead* newUnshared(Solver& s, SharedLiterals* clause, const Literal* w, const ClauseInfo& e);
00283 static bool ignoreClause(const Solver& s, const ClauseRep& cl, Status st, uint32 modeFlags);
00284 Solver* solver_;
00285 LitVec literals_;
00286 ClauseInfo extra_;
00287 uint32 flags_;
00288 };
00289
00291 class Clause : public ClauseHead {
00292 public:
00293 typedef Constraint::PropResult PropResult;
00294 enum { MAX_SHORT_LEN = 5 };
00295
00297 static void* alloc(Solver& s, uint32 mLits, bool learnt);
00298
00300
00308 static ClauseHead* newClause(Solver& s, const ClauseRep& rep) {
00309 return newClause(alloc(s, rep.size, rep.info.learnt()), s, rep);
00310 }
00312
00315 static ClauseHead* newClause(void* mem, Solver& s, const ClauseRep& rep);
00316
00318
00328 static ClauseHead* newContractedClause(Solver& s, const ClauseRep& rep, uint32 tailPos, bool extend);
00329
00331
00338 static ClauseHead* newShared(Solver& s, SharedLiterals* lits, const ClauseInfo& e, const Literal head[3], bool addRef = true);
00339
00340
00341
00342 Constraint* cloneAttach(Solver& other);
00343
00350 void reason(Solver& s, Literal p, LitVec& lits);
00351
00352 bool minimize(Solver& m, Literal p, CCMinRecursive* r);
00353
00354 bool isReverseReason(const Solver& s, Literal p, uint32 maxL, uint32 maxN);
00355
00357
00360 bool simplify(Solver& s, bool = false);
00361
00363 void destroy(Solver* s = 0, bool detach = false);
00364
00365
00366
00368 uint32 isOpen(const Solver& s, const TypeSet& t, LitVec& freeLits);
00369
00370
00371 BoolPair strengthen(Solver& s, Literal p, bool allowToShort);
00372 void detach(Solver&);
00373 uint32 size() const;
00374 void toLits(LitVec& out) const;
00375 bool contracted() const { return data_.local.contracted(); }
00376 bool isSmall() const { return data_.local.isSmall(); }
00377 bool strengthened() const { return data_.local.strengthened(); }
00378 uint32 computeAllocSize() const;
00379 private:
00380 Clause(Solver& s, const ClauseRep& rep, uint32 tail = UINT32_MAX, bool extend = false);
00381 Clause(Solver& s, const Clause& other);
00382 typedef std::pair<Literal*, Literal*> LitRange;
00383 void undoLevel(Solver& s);
00384 bool updateWatch(Solver& s, uint32 pos);
00385 Literal* removeFromTail(Solver& s, Literal* it, Literal* end);
00386 Literal* longEnd() { return head_+data_.local.size(); }
00387 LitRange tail() {
00388 if (!isSmall()) { return LitRange(head_+ClauseHead::HEAD_LITS, longEnd()); }
00389 uint32 ts = (data_.lits[0] != 2) + (data_.lits[1] != 2);
00390 return LitRange((Literal*)data_.lits, (Literal*)(data_.lits + ts));
00391 }
00392 };
00393
00395
00423 class LoopFormula : public LearntConstraint {
00424 public:
00435 static LoopFormula* newLoopFormula(Solver& s, Literal* bodyLits, uint32 numBodies, uint32 bodyToWatch, uint32 numAtoms, const Activity& act);
00436
00438
00441 void addAtom(Literal atom, Solver& s);
00442
00444 void updateHeuristic(Solver& s);
00445
00447 uint32 size() const;
00448
00449
00450 Constraint* cloneAttach(Solver&) { return 0; }
00451 PropResult propagate(Solver& s, Literal p, uint32& data);
00452 void reason(Solver&, Literal p, LitVec& lits);
00453 bool minimize(Solver& s, Literal p, CCMinRecursive* ccMin);
00454 bool simplify(Solver& s, bool = false);
00455 void destroy(Solver* = 0, bool = false);
00456
00457
00458 bool locked(const Solver& s) const;
00459
00460 uint32 isOpen(const Solver& s, const TypeSet& t, LitVec& freeLits);
00461
00463
00466 Activity activity() const { return act_; }
00467
00469 void decreaseActivity() { act_ = Activity(act_.activity()>>1, act_.lbd()); }
00470 void resetActivity(Activity hint){ act_ = hint; }
00471
00473 ConstraintType type() const { return Constraint_t::learnt_loop; }
00474 private:
00475 LoopFormula(Solver& s, uint32 size, Literal* bodyLits, uint32 numBodies, uint32 bodyToWatch, const Activity& a);
00476 bool watchable(const Solver& s, uint32 idx);
00477 bool isTrue(const Solver& s, uint32 idx);
00478 Activity act_;
00479 uint32 end_;
00480 uint32 size_;
00481 uint32 other_;
00482 Literal lits_[0];
00483 };
00484
00485 namespace mt {
00486
00488
00496 class SharedLitsClause : public ClauseHead {
00497 public:
00499
00506 static ClauseHead* newClause(Solver& s, SharedLiterals* shared_lits, const ClauseInfo& e, const Literal* lits, bool addRef = true);
00507
00508 Constraint* cloneAttach(Solver& other);
00509 void reason(Solver& s, Literal p, LitVec& out);
00510 bool minimize(Solver& s, Literal p, CCMinRecursive* rec);
00511 bool isReverseReason(const Solver& s, Literal p, uint32 maxL, uint32 maxN);
00512 bool simplify(Solver& s, bool);
00513 void destroy(Solver* s, bool detach);
00514 uint32 isOpen(const Solver& s, const TypeSet& t, LitVec& freeLits);
00515 uint32 size() const;
00516 void toLits(LitVec& out) const;
00517 private:
00518 SharedLitsClause(Solver& s, SharedLiterals* x, const Literal* lits, const ClauseInfo&, bool addRef);
00519 bool updateWatch(Solver& s, uint32 pos);
00520 BoolPair strengthen(Solver& s, Literal p, bool allowToShort);
00521 };
00522 }
00523
00524 }
00525 #endif