#include <solver.h>
Classes | |
struct | CmpScore |
struct | DBInfo |
struct | DecisionLevels |
struct | DLevel |
struct | PPList |
Public Types | |
typedef PodVector< Constraint * > ::type | ConstraintDB |
typedef const ConstraintDB & | DBRef |
typedef SingleOwnerPtr < DecisionHeuristic > | Heuristic |
Public Member Functions | |
void | add (Constraint *c) |
Adds the problem constraint c to the solver. | |
bool | add (const ClauseRep &c, bool isNew=true) |
Adds a suitable representation of the given clause to the solver. | |
bool | addPost (PostPropagator *p) |
Adds p as post propagator to this solver. | |
bool | allowImplicit (const ClauseRep &c) const |
Returns whether c can be stored in the shared short implication graph. | |
const SolverParams & | configuration () const |
Returns the configuration for this object. | |
PostPropagator * | getPost (uint32 prio) const |
Returns the post propagator with the given priority or 0 if no such post propagator exists. | |
const Heuristic & | heuristic () const |
Heuristic & | heuristic () |
uint32 | id () const |
void | removePost (PostPropagator *p) |
Removes p from the solver's list of post propagators. | |
SatPreprocessor * | satPrepro () const |
Returns a pointer to the sat-preprocessor used by this solver. | |
const SolveParams & | searchConfig () const |
Returns the solve parameters for this object. | |
const SharedContext * | sharedContext () const |
Returns a pointer to the shared context object of this solver. | |
const SymbolTable & | symbolTable () const |
Literal | tagLiteral () const |
VarInfo | varInfo (Var v) const |
CDNL-functions. | |
ValueRep | search (SearchLimits &limit, double randf=0.0) |
Searches for a model as long as the given limit is not reached. | |
ValueRep | search (uint64 maxC, uint32 maxL, bool local=false, double rp=0.0) |
bool | pushRoot (const LitVec &path) |
Adds path to the current root-path and adjusts the root-level accordingly. | |
bool | pushRoot (Literal p) |
void | setEnumerationConstraint (Constraint *c) |
void | pushRootLevel (uint32 i=1) |
Moves the root-level i levels down (i.e. away from the top-level). | |
bool | popRootLevel (uint32 i=1, LitVec *popped=0, bool aux=true) |
Moves the root-level i levels up (i.e. towards the top-level). | |
void | clearStopConflict () |
Removes a previously set stop conflict and restores the root level. | |
uint32 | rootLevel () const |
Returns the current root level. | |
bool | clearAssumptions () |
Removes any implications made between the top-level and the root-level. | |
void | addLearnt (LearntConstraint *c, uint32 size, ConstraintType type) |
Adds the learnt constraint c to the solver. | |
void | addLearnt (LearntConstraint *c, uint32 size) |
uint32 | receive (SharedLiterals **out, uint32 maxOut) const |
Tries to receive at most maxOut clauses. | |
SharedLiterals * | distribute (const Literal *lits, uint32 size, const ClauseInfo &extra) |
Distributes the clause in lits via the distributor. | |
void | restart () |
Returns to the maximum of rootLevel() and backtrackLevel() and increases the number of restarts. | |
void | setBacktrackLevel (uint32 dl) |
Sets the backtracking level to dl. | |
uint32 | backtrackLevel () const |
Returns the current backtracking level. | |
bool | splittable () const |
Returns whether the solver can split-off work. | |
bool | split (LitVec &out) |
Tries to split-off disjoint work from the solver's currrent guiding path and returns it in out. | |
void | copyGuidingPath (LitVec &out) |
Copies the solver's currrent guiding path to gp. | |
bool | simplify () |
If called on top-level, removes SAT-clauses + Constraints for which Constraint::simplify returned true. | |
void | shuffleOnNextSimplify () |
Shuffle constraints upon next simplification. | |
Var | pushTagVar (bool pushToRoot) |
Requests a special aux variable for tagging conditional knowledge. | |
void | removeConditional () |
Removes all conditional knowledge, i.e. all previously tagged learnt clauses. | |
void | strengthenConditional () |
Resolves all tagged clauses with the tag literal and thereby strengthens the learnt db. | |
bool | force (const Literal &p, const Antecedent &a) |
Sets the literal p to true and schedules p for propagation. | |
bool | force (const Literal &p, const Antecedent &a, uint32 data) |
bool | force (Literal p, uint32 dl, const Antecedent &r, uint32 d=UINT32_MAX) |
Assigns p at dl because of r. | |
bool | force (Literal p) |
Assigns p as a fact at decision level 0. | |
bool | assume (const Literal &p) |
Assumes the literal p if possible. | |
bool | decideNextBranch (double f=0.0) |
Selects and assumes the next branching literal by calling the installed decision heuristic. | |
void | setStopConflict () |
Sets a conflict that forces the solver to terminate its search. | |
bool | propagate () |
bool | propagateUntil (PostPropagator *p) |
bool | test (Literal p, PostPropagator *c) |
Executes a one-step lookahead on p. | |
uint32 | estimateBCP (const Literal &p, int maxRecursionDepth=5) const |
Estimates the number of assignments following from setting p to true. | |
uint32 | inDegree (WeightLitVec &out) |
Computes the number of in-edges for each assigned literal. | |
DBInfo | reduceLearnts (float remMax, const ReduceStrategy &rs=ReduceStrategy()) |
Removes upto remMax percent of the learnt nogoods. | |
bool | resolveConflict () |
Resolves the active conflict using the selected strategy. | |
bool | backtrack () |
Backtracks the last decision and sets the backtrack-level to the resulting decision level. | |
void | undoUntil (uint32 dl) |
Undoes all assignments up to (but not including) decision level dl. | |
uint32 | undoUntil (uint32 dl, bool popBtLevel) |
Var | pushAuxVar () |
Adds a new auxiliary variable to this solver. | |
void | popAuxVar (uint32 num=UINT32_MAX) |
Pops the num most recently added auxiliary variables from this solver. | |
Watch management | |
Functions for setting/removing watches.
| |
uint32 | numWatches (Literal p) const |
Returns the number of constraints watching the literal p. | |
bool | hasWatch (Literal p, Constraint *c) const |
Returns true if the constraint c watches the literal p. | |
bool | hasWatch (Literal p, ClauseHead *c) const |
GenericWatch * | getWatch (Literal p, Constraint *c) const |
Returns c's watch-structure associated with p. | |
void | addWatch (Literal p, Constraint *c, uint32 data=0) |
Adds c to the watch-list of p. | |
void | addWatch (Literal p, const ClauseWatch &w) |
Adds w to the clause watch-list of p. | |
void | removeWatch (const Literal &p, Constraint *c) |
Removes c from p's watch-list. | |
void | removeWatch (const Literal &p, ClauseHead *c) |
void | addUndoWatch (uint32 dl, Constraint *c) |
Adds c to the watch-list of decision-level dl. | |
bool | removeUndoWatch (uint32 dl, Constraint *c) |
Removes c from the watch-list of the decision level dl. | |
Misc functions | |
Low-level implementation functions. Use with care and only if you know what you are doing! | |
bool | addPost (PostPropagator *p, bool init) |
bool | setReason (Literal p, const Antecedent &x, uint32 data=UINT32_MAX) |
Updates the reason for p being tue. | |
void | requestData (Var v) |
Request additional reason data slot for variable v. | |
void | setPref (Var v, ValueSet::Value which, ValueRep to) |
void | reason (Literal p, LitVec &out) |
Returns the reason for p being true as a set of literals. | |
uint32 | updateLearnt (Literal p, const Literal *first, const Literal *last, uint32 cLbd, bool forceUp=false) |
Computes a new lbd for the antecedent of p given as the range [first, last). | |
bool | ccMinimize (Literal p, CCMinRecursive *rec) const |
Visitor function for antecedents used during conflict clause minimization. | |
bool | learntLimit (const SearchLimits &x) const |
Returns true if number of learnts exceeds x.learnts or the soft memory limit is exceeded. | |
void * | allocSmall () |
Allocates a small block (32-bytes) from the solver's small block pool. | |
void | freeSmall (void *m) |
Frees a small block previously allocated from the solver's small block pool. | |
void | addLearntBytes (uint32 bytes) |
void | freeLearntBytes (uint64 bytes) |
uint32 | simplifyConflictClause (LitVec &cc, ClauseInfo &info, ClauseHead *rhs) |
simplifies cc and returns finalizeConflictClause(cc, info); | |
uint32 | finalizeConflictClause (LitVec &cc, ClauseInfo &info, uint32 ccRepMode=0) |
uint32 | countLevels (const Literal *first, const Literal *last, uint32 maxLevels) |
bool | hasLevel (uint32 dl) const |
bool | frozenLevel (uint32 dl) const |
void | markLevel (uint32 dl) |
void | freezeLevel (uint32 dl) |
void | unmarkLevel (uint32 dl) |
void | unfreezeLevel (uint32 dl) |
void | markSeen (Var v) |
void | markSeen (Literal p) |
void | clearSeen (Var v) |
Private Types | |
typedef PodVector< Antecedent > ::type | ReasonVec |
typedef PodVector< WatchList > ::type | Watches |
Private Member Functions | |
ConstraintDB * | allocUndo (Constraint *c) |
uint32 | analyzeConflict () |
void | cancelPropagation () |
Antecedent | ccHasReverseArc (Literal p, uint32 maxLevel, uint32 maxNew) |
uint32 | ccMinimize (LitVec &cc, LitVec &removed, uint32 antes, CCMinRecursive *ccMin) |
bool | ccRemovable (Literal p, uint32 antes, CCMinRecursive *ccMin) |
void | ccResolve (LitVec &cc, uint32 pos, const LitVec &reason) |
void | freeMem () |
void | otfs (Antecedent &lhs, const Antecedent &rhs, Literal p, bool final) |
ClauseHead * | otfsRemove (ClauseHead *c, const LitVec *newC) |
DBInfo | reduceLinear (uint32 maxR, const CmpScore &cmp) |
DBInfo | reduceSort (uint32 maxR, const CmpScore &cmp) |
DBInfo | reduceSortInPlace (uint32 maxR, const CmpScore &cmp, bool onlyPartialSort) |
void | setConflict (Literal p, const Antecedent &a, uint32 data) |
bool | simplifySAT () |
void | undoFree (ConstraintDB *x) |
void | undoLevel (bool sp) |
bool | unitPropagate () |
uint64 | updateBranch (uint32 cfl) |
bool | validWatch (Literal p) const |
Private Attributes | |
Assignment | assign_ |
WeightLitVec | bumpAct_ |
LitVec | cc_ |
ClauseInfo | ccInfo_ |
CCMinRecursive * | ccMin_ |
VarVec | cflStamp_ |
LitVec | conflict_ |
ConstraintDB | constraints_ |
uint32 | dbIdx_ |
Constraint * | enum_ |
Heuristic | heuristic_ |
ImpliedList | impliedLits_ |
uint32 | initPost_: 1 |
uint32 | lastSimp_:30 |
VarVec | lbdStamp_ |
uint32 | lbdTime_ |
ConstraintDB | learnts_ |
DecisionLevels | levels_ |
uint64 | memUse_ |
PPList | post_ |
SharedContext * | shared_ |
uint32 | shufSimp_: 1 |
SmallClauseAlloc * | smallAlloc_ |
Literal | tag_ |
LitVec | temp_ |
ConstraintDB * | undoHead_ |
Watches | watches_ |
Construction/Destruction/Setup | |
class | SharedContext |
Solver (SharedContext *ctx, uint32 id) | |
Creates an empty solver object with all strategies set to their default value. | |
~Solver () | |
Destroys the solver object and all contained constraints. | |
void | reset () |
Resets a solver object to the state it had after construction. | |
void | resetId (uint32 id) |
void | startInit (uint32 constraintGuess) |
bool | cloneDB (const ConstraintDB &db) |
bool | preparePost () |
bool | endInit () |
state inspection | |
Functions for inspecting the state of the solver & search.
| |
SolverStrategies | strategy |
RNG | rng |
ValueVec | model |
SolverStats | stats |
uint32 | numProblemVars () const |
Returns the number of problem variables. | |
uint32 | numAuxVars () const |
Returns the number of active solver-local aux variables. | |
uint32 | numVars () const |
Returns the number of solver variables, i.e. numProblemVars() + numAuxVars() | |
bool | validVar (Var var) const |
Returns true if var represents a valid variable in this solver. | |
bool | auxVar (Var var) const |
Returns true if var is a solver-local aux var. | |
uint32 | numAssignedVars () const |
Returns the number of assigned variables. | |
uint32 | numFreeVars () const |
Returns the number of free variables. | |
ValueRep | value (Var v) const |
Returns the value of v w.r.t the current assignment. | |
ValueRep | topValue (Var v) const |
Returns the value of v w.r.t the top level. | |
ValueSet | pref (Var v) const |
Returns the set of preferred values of v. | |
bool | isTrue (Literal p) const |
Returns true if p is true w.r.t the current assignment. | |
bool | isFalse (Literal p) const |
Returns true if p is false w.r.t the current assignment. | |
Literal | trueLit (Var v) const |
Returns the literal of v being true in the current assignment. | |
uint32 | level (Var v) const |
Returns the decision level on which v was assigned. | |
bool | seen (Var v) const |
Returns true if v is currently marked as seen. | |
bool | seen (Literal p) const |
Returns true if the literal p is currently marked as seen. | |
uint32 | decisionLevel () const |
Returns the current decision level. | |
bool | validLevel (uint32 dl) const |
uint32 | levelStart (uint32 dl) const |
Returns the starting position of decision level dl in the trail. | |
Literal | decision (uint32 dl) const |
Returns the decision literal of the decision level dl. | |
bool | hasConflict () const |
Returns true, if the current assignment is conflicting. | |
bool | hasStopConflict () const |
uint32 | queueSize () const |
Returns the number of (unprocessed) literals in the propagation queue. | |
uint32 | numConstraints () const |
Number of problem constraints in this solver. | |
uint32 | numLearntConstraints () const |
Returns the number of constraints that are currently in the solver's learnt database. | |
const Antecedent & | reason (Literal p) const |
Returns the reason for p being true. | |
uint32 | reasonData (Literal p) const |
Returns the additional reason data associated with p. | |
const LitVec & | trail () const |
Returns the current (partial) assignment as a set of true literals. | |
const Assignment & | assignment () const |
const LitVec & | conflict () const |
Returns the current conflict as a set of literals. | |
const LitVec & | conflictClause () const |
Returns the most recently derived conflict clause. | |
const LitVec & | symmetric () const |
Returns the set of eliminated literals that are unconstraint w.r.t the last model. | |
Constraint * | enumerationConstraint () const |
Returns the enumeration constraint set by the enumerator used. | |
DBRef | constraints () const |
LearntConstraint & | getLearnt (uint32 idx) const |
Returns the idx'th learnt constraint. |
clasp's Solver class.
A Solver-object maintains the state and provides the functions necessary to implement our CDNL-algorithm.
The interface supports incremental solving (search under assumptions) as well as solution enumeration. To make this possible the solver maintains two special decision levels: the root-level and the backtrack-level.
The root-level is the lowest decision level to which a search can return. Conflicts on the root-level are non-resolvable and end a search - the root-level therefore acts as an artificial top-level during search. Incremental solving is then implemented by first adding a list of unit assumptions and second initializing the root-level to the current decision level. Once search terminates assumptions can be undone by calling clearAssumptions and a new a search can be started using different assumptions.
For model enumeration the solver maintains a backtrack-level which restricts backjumping in order to prevent repeating already enumerated solutions. The solver will never backjump above that level and conflicts on the backtrack-level are resolved by backtracking, i.e. flipping the corresponding decision literal.
typedef PodVector<Constraint*>::type Clasp::Solver::ConstraintDB |
typedef const ConstraintDB& Clasp::Solver::DBRef |
typedef PodVector<Antecedent>::type Clasp::Solver::ReasonVec [private] |
typedef PodVector<WatchList>::type Clasp::Solver::Watches [private] |
Clasp::Solver::Solver | ( | SharedContext * | ctx, |
uint32 | id | ||
) | [private] |
Creates an empty solver object with all strategies set to their default value.
Definition at line 112 of file solver.cpp.
Clasp::Solver::~Solver | ( | ) | [private] |
Destroys the solver object and all contained constraints.
Definition at line 131 of file solver.cpp.
void Clasp::Solver::add | ( | Constraint * | c | ) |
Adds the problem constraint c to the solver.
Problem constraints shall only be added to the master solver of a SharedContext object and only during the setup phase.
Definition at line 267 of file solver.cpp.
bool Clasp::Solver::add | ( | const ClauseRep & | c, |
bool | isNew = true |
||
) |
Adds a suitable representation of the given clause to the solver.
Depending on the type and size of the given clause, the function either adds a (learnt) constraint to this solver or an implication to the shared implication graph.
Definition at line 270 of file solver.cpp.
void Clasp::Solver::addLearnt | ( | LearntConstraint * | c, |
uint32 | size, | ||
ConstraintType | type | ||
) | [inline] |
void Clasp::Solver::addLearnt | ( | LearntConstraint * | c, |
uint32 | size | ||
) | [inline] |
void Clasp::Solver::addLearntBytes | ( | uint32 | bytes | ) | [inline] |
bool Clasp::Solver::addPost | ( | PostPropagator * | p | ) | [inline] |
Adds p as post propagator to this solver.
bool Clasp::Solver::addPost | ( | PostPropagator * | p, |
bool | init | ||
) | [inline] |
void Clasp::Solver::addUndoWatch | ( | uint32 | dl, |
Constraint * | c | ||
) | [inline] |
void Clasp::Solver::addWatch | ( | Literal | p, |
Constraint * | c, | ||
uint32 | data = 0 |
||
) | [inline] |
void Clasp::Solver::addWatch | ( | Literal | p, |
const ClauseWatch & | w | ||
) | [inline] |
void* Clasp::Solver::allocSmall | ( | ) | [inline] |
Solver::ConstraintDB * Clasp::Solver::allocUndo | ( | Constraint * | c | ) | [private] |
Definition at line 886 of file solver.cpp.
bool Clasp::Solver::allowImplicit | ( | const ClauseRep & | c | ) | const [inline] |
uint32 Clasp::Solver::analyzeConflict | ( | ) | [private] |
Definition at line 924 of file solver.cpp.
const Assignment& Clasp::Solver::assignment | ( | ) | const [inline] |
bool Clasp::Solver::assume | ( | const Literal & | p | ) |
Assumes the literal p if possible.
If p is currently unassigned, sets p to true and starts a new decision level.
p | The literal to assume. |
Definition at line 653 of file solver.cpp.
bool Clasp::Solver::auxVar | ( | Var | var | ) | const [inline] |
bool Clasp::Solver::backtrack | ( | ) |
Backtracks the last decision and sets the backtrack-level to the resulting decision level.
Definition at line 778 of file solver.cpp.
uint32 Clasp::Solver::backtrackLevel | ( | ) | const [inline] |
void Clasp::Solver::cancelPropagation | ( | ) | [inline, private] |
Antecedent Clasp::Solver::ccHasReverseArc | ( | Literal | p, |
uint32 | maxLevel, | ||
uint32 | maxNew | ||
) | [private] |
Definition at line 1209 of file solver.cpp.
bool Clasp::Solver::ccMinimize | ( | Literal | p, |
CCMinRecursive * | rec | ||
) | const [inline] |
uint32 Clasp::Solver::ccMinimize | ( | LitVec & | cc, |
LitVec & | removed, | ||
uint32 | antes, | ||
CCMinRecursive * | ccMin | ||
) | [private] |
Definition at line 1133 of file solver.cpp.
bool Clasp::Solver::ccRemovable | ( | Literal | p, |
uint32 | antes, | ||
CCMinRecursive * | ccMin | ||
) | [private] |
Definition at line 1164 of file solver.cpp.
void Clasp::Solver::ccResolve | ( | LitVec & | cc, |
uint32 | pos, | ||
const LitVec & | reason | ||
) | [private] |
Definition at line 1225 of file solver.cpp.
bool Clasp::Solver::clearAssumptions | ( | ) |
Removes any implications made between the top-level and the root-level.
The function also resets the current backtrack-level and re-assigns learnt facts.
Definition at line 425 of file solver.cpp.
void Clasp::Solver::clearSeen | ( | Var | v | ) | [inline] |
void Clasp::Solver::clearStopConflict | ( | ) |
Removes a previously set stop conflict and restores the root level.
Definition at line 430 of file solver.cpp.
bool Clasp::Solver::cloneDB | ( | const ConstraintDB & | db | ) | [private] |
Definition at line 227 of file solver.cpp.
const SolverParams & Clasp::Solver::configuration | ( | ) | const |
Returns the configuration for this object.
Definition at line 162 of file solver.cpp.
const LitVec& Clasp::Solver::conflict | ( | ) | const [inline] |
const LitVec& Clasp::Solver::conflictClause | ( | ) | const [inline] |
DBRef Clasp::Solver::constraints | ( | ) | const [inline] |
void Clasp::Solver::copyGuidingPath | ( | LitVec & | out | ) |
Copies the solver's currrent guiding path to gp.
[out] | gp | where to store the guiding path |
Definition at line 454 of file solver.cpp.
uint32 Clasp::Solver::countLevels | ( | const Literal * | first, |
const Literal * | last, | ||
uint32 | maxLevels | ||
) |
Definition at line 1501 of file solver.cpp.
bool Clasp::Solver::decideNextBranch | ( | double | f = 0.0 | ) |
Selects and assumes the next branching literal by calling the installed decision heuristic.
Definition at line 1330 of file solver.cpp.
Literal Clasp::Solver::decision | ( | uint32 | dl | ) | const [inline] |
uint32 Clasp::Solver::decisionLevel | ( | ) | const [inline] |
SharedLiterals * Clasp::Solver::distribute | ( | const Literal * | lits, |
uint32 | size, | ||
const ClauseInfo & | extra | ||
) |
Distributes the clause in lits via the distributor.
The function first calls the distribution strategy to decides whether the clause is a valid candidate for distribution. If so and a distributor was set, it distributes the clause and returns a handle to the now shared literals of the clause. Otherwise, it returns 0.
owner | The solver that created the clause. |
lits | The literals of the clause. |
size | The number of literals in the clause. |
extra | Additional information about the clause. |
Definition at line 298 of file solver.cpp.
bool Clasp::Solver::endInit | ( | ) | [private] |
Definition at line 254 of file solver.cpp.
Constraint* Clasp::Solver::enumerationConstraint | ( | ) | const [inline] |
uint32 Clasp::Solver::estimateBCP | ( | const Literal & | p, |
int | maxRecursionDepth = 5 |
||
) | const |
Estimates the number of assignments following from setting p to true.
Definition at line 835 of file solver.cpp.
uint32 Clasp::Solver::finalizeConflictClause | ( | LitVec & | cc, |
ClauseInfo & | info, | ||
uint32 | ccRepMode = 0 |
||
) |
Definition at line 1247 of file solver.cpp.
bool Clasp::Solver::force | ( | const Literal & | p, |
const Antecedent & | a | ||
) | [inline] |
Sets the literal p to true and schedules p for propagation.
Setting a literal p to true means assigning the appropriate value to p's variable. That is: value_false if p is a negative literal and value_true if p is a positive literal.
p | The literal that should become true. |
a | The reason for the literal to become true or 0 if no reason exists. |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
bool Clasp::Solver::force | ( | const Literal & | p, |
const Antecedent & | a, | ||
uint32 | data | ||
) | [inline] |
bool Clasp::Solver::force | ( | Literal | p, |
uint32 | dl, | ||
const Antecedent & | r, | ||
uint32 | d = UINT32_MAX |
||
) | [inline] |
Assigns p at dl because of r.
bool Clasp::Solver::force | ( | Literal | p | ) | [inline] |
void Clasp::Solver::freeLearntBytes | ( | uint64 | bytes | ) | [inline] |
void Clasp::Solver::freeMem | ( | ) | [private] |
Definition at line 135 of file solver.cpp.
void Clasp::Solver::freeSmall | ( | void * | m | ) | [inline] |
void Clasp::Solver::freezeLevel | ( | uint32 | dl | ) | [inline] |
bool Clasp::Solver::frozenLevel | ( | uint32 | dl | ) | const [inline] |
LearntConstraint& Clasp::Solver::getLearnt | ( | uint32 | idx | ) | const [inline] |
Returns the idx'th learnt constraint.
PostPropagator * Clasp::Solver::getPost | ( | uint32 | prio | ) | const |
Returns the post propagator with the given priority or 0 if no such post propagator exists.
Definition at line 247 of file solver.cpp.
GenericWatch * Clasp::Solver::getWatch | ( | Literal | p, |
Constraint * | c | ||
) | const |
Returns c's watch-structure associated with p.
Definition at line 511 of file solver.cpp.
bool Clasp::Solver::hasConflict | ( | ) | const [inline] |
bool Clasp::Solver::hasLevel | ( | uint32 | dl | ) | const [inline] |
bool Clasp::Solver::hasStopConflict | ( | ) | const [inline] |
bool Clasp::Solver::hasWatch | ( | Literal | p, |
Constraint * | c | ||
) | const |
Returns true if the constraint c watches the literal p.
Definition at line 499 of file solver.cpp.
bool Clasp::Solver::hasWatch | ( | Literal | p, |
ClauseHead * | c | ||
) | const |
Definition at line 505 of file solver.cpp.
const Heuristic& Clasp::Solver::heuristic | ( | ) | const [inline] |
Heuristic& Clasp::Solver::heuristic | ( | ) | [inline] |
uint32 Clasp::Solver::id | ( | ) | const [inline] |
uint32 Clasp::Solver::inDegree | ( | WeightLitVec & | out | ) |
Computes the number of in-edges for each assigned literal.
Definition at line 857 of file solver.cpp.
bool Clasp::Solver::isFalse | ( | Literal | p | ) | const [inline] |
bool Clasp::Solver::isTrue | ( | Literal | p | ) | const [inline] |
bool Clasp::Solver::learntLimit | ( | const SearchLimits & | x | ) | const [inline] |
uint32 Clasp::Solver::level | ( | Var | v | ) | const [inline] |
uint32 Clasp::Solver::levelStart | ( | uint32 | dl | ) | const [inline] |
void Clasp::Solver::markLevel | ( | uint32 | dl | ) | [inline] |
void Clasp::Solver::markSeen | ( | Var | v | ) | [inline] |
void Clasp::Solver::markSeen | ( | Literal | p | ) | [inline] |
uint32 Clasp::Solver::numAssignedVars | ( | ) | const [inline] |
uint32 Clasp::Solver::numAuxVars | ( | ) | const [inline] |
uint32 Clasp::Solver::numConstraints | ( | ) | const |
Number of problem constraints in this solver.
Definition at line 313 of file solver.cpp.
uint32 Clasp::Solver::numFreeVars | ( | ) | const [inline] |
uint32 Clasp::Solver::numLearntConstraints | ( | ) | const [inline] |
uint32 Clasp::Solver::numProblemVars | ( | ) | const [inline] |
uint32 Clasp::Solver::numVars | ( | ) | const [inline] |
Returns the number of solver variables, i.e. numProblemVars() + numAuxVars()
uint32 Clasp::Solver::numWatches | ( | Literal | p | ) | const |
Returns the number of constraints watching the literal p.
Definition at line 492 of file solver.cpp.
void Clasp::Solver::otfs | ( | Antecedent & | lhs, |
const Antecedent & | rhs, | ||
Literal | p, | ||
bool | final | ||
) | [private] |
Definition at line 993 of file solver.cpp.
ClauseHead * Clasp::Solver::otfsRemove | ( | ClauseHead * | c, |
const LitVec * | newC | ||
) | [private] |
Definition at line 1020 of file solver.cpp.
void Clasp::Solver::popAuxVar | ( | uint32 | num = UINT32_MAX | ) |
Pops the num most recently added auxiliary variables from this solver.
Definition at line 325 of file solver.cpp.
bool Clasp::Solver::popRootLevel | ( | uint32 | i = 1 , |
LitVec * | popped = 0 , |
||
bool | aux = true |
||
) |
Moves the root-level i levels up (i.e. towards the top-level).
The function removes all levels between the new root level and the current decision level, resets the current backtrack-level, and re-assigns any implied literals.
i | Number of root decisions to pop. | |
[out] | popped | Optional storage for popped root decisions. |
filter | Whether or not aux variables should be added to popped. |
Definition at line 404 of file solver.cpp.
ValueSet Clasp::Solver::pref | ( | Var | v | ) | const [inline] |
bool Clasp::Solver::preparePost | ( | ) | [private] |
Definition at line 236 of file solver.cpp.
bool Clasp::Solver::propagate | ( | ) |
Propagates all enqueued literals. If a conflict arises during propagation propagate returns false and the current conflict (as a set of literals) is stored in the solver's conflict variable.
Definition at line 663 of file solver.cpp.
bool Clasp::Solver::propagateUntil | ( | PostPropagator * | p | ) | [inline] |
Does unit propagation and calls x->propagateFixpoint(*this) for all post propagators x up to but not including p.
Adds a new auxiliary variable to this solver.
Auxiliary variables are local to one solver and are not considered as part of the problem. They shall be added/used only during solving, i.e. after problem setup is completed.
Definition at line 318 of file solver.cpp.
bool Clasp::Solver::pushRoot | ( | const LitVec & | path | ) |
Adds path to the current root-path and adjusts the root-level accordingly.
Definition at line 382 of file solver.cpp.
bool Clasp::Solver::pushRoot | ( | Literal | p | ) |
Definition at line 394 of file solver.cpp.
void Clasp::Solver::pushRootLevel | ( | uint32 | i = 1 | ) | [inline] |
Var Clasp::Solver::pushTagVar | ( | bool | pushToRoot | ) |
Requests a special aux variable for tagging conditional knowledge.
Once a tag variable t is set, learnt clauses containing ~t are tagged as "conditional". Conditional clauses are removed once t becomes unassigned or Solver::removeConditional() is called. Furthermore, calling Solver::strengthenConditional() removes ~t from conditional clauses and transforms them to unconditional knowledge.
Definition at line 564 of file solver.cpp.
uint32 Clasp::Solver::queueSize | ( | ) | const [inline] |
const Antecedent& Clasp::Solver::reason | ( | Literal | p | ) | const [inline] |
void Clasp::Solver::reason | ( | Literal | p, |
LitVec & | out | ||
) | [inline] |
uint32 Clasp::Solver::reasonData | ( | Literal | p | ) | const [inline] |
uint32 Clasp::Solver::receive | ( | SharedLiterals ** | out, |
uint32 | maxOut | ||
) | const |
Tries to receive at most maxOut clauses.
The function queries the distributor object for new clauses to be delivered to this solver. Clauses are stored in out.
Definition at line 292 of file solver.cpp.
Solver::DBInfo Clasp::Solver::reduceLearnts | ( | float | remMax, |
const ReduceStrategy & | rs = ReduceStrategy() |
||
) |
Removes upto remMax percent of the learnt nogoods.
remMax | Fraction of nogoods to remove ([0.0,1.0]). |
rs | Strategy to apply during nogood deletion. |
Definition at line 1348 of file solver.cpp.
Solver::DBInfo Clasp::Solver::reduceLinear | ( | uint32 | maxR, |
const CmpScore & | cmp | ||
) | [private] |
Definition at line 1367 of file solver.cpp.
Solver::DBInfo Clasp::Solver::reduceSort | ( | uint32 | maxR, |
const CmpScore & | cmp | ||
) | [private] |
Definition at line 1405 of file solver.cpp.
Solver::DBInfo Clasp::Solver::reduceSortInPlace | ( | uint32 | maxR, |
const CmpScore & | cmp, | ||
bool | onlyPartialSort | ||
) | [private] |
Definition at line 1449 of file solver.cpp.
void Clasp::Solver::removeConditional | ( | ) |
Removes all conditional knowledge, i.e. all previously tagged learnt clauses.
Definition at line 569 of file solver.cpp.
void Clasp::Solver::removePost | ( | PostPropagator * | p | ) | [inline] |
bool Clasp::Solver::removeUndoWatch | ( | uint32 | dl, |
Constraint * | c | ||
) |
Removes c from the watch-list of the decision level dl.
Definition at line 532 of file solver.cpp.
void Clasp::Solver::removeWatch | ( | const Literal & | p, |
Constraint * | c | ||
) |
Removes c from p's watch-list.
Definition at line 520 of file solver.cpp.
void Clasp::Solver::removeWatch | ( | const Literal & | p, |
ClauseHead * | c | ||
) |
Definition at line 526 of file solver.cpp.
void Clasp::Solver::requestData | ( | Var | v | ) | [inline] |
void Clasp::Solver::reset | ( | ) | [private] |
Resets a solver object to the state it had after construction.
Definition at line 165 of file solver.cpp.
void Clasp::Solver::resetId | ( | uint32 | id | ) | [inline, private] |
bool Clasp::Solver::resolveConflict | ( | ) |
Resolves the active conflict using the selected strategy.
If the SearchStrategy is set to learning, resolveConflict implements First-UIP learning and backjumping. Otherwise, it simply applies chronological backtracking.
Definition at line 762 of file solver.cpp.
void Clasp::Solver::restart | ( | ) | [inline] |
Returns to the maximum of rootLevel() and backtrackLevel() and increases the number of restarts.
uint32 Clasp::Solver::rootLevel | ( | ) | const [inline] |
SatPreprocessor * Clasp::Solver::satPrepro | ( | ) | const |
Returns a pointer to the sat-preprocessor used by this solver.
Definition at line 161 of file solver.cpp.
ValueRep Clasp::Solver::search | ( | SearchLimits & | limit, |
double | randf = 0.0 |
||
) |
Searches for a model as long as the given limit is not reached.
The search function implements the CDNL-algorithm. It searches for a model as long as none of the limits given by limit is reached. The limits are updated during search.
limit | Imposed limit on conflicts and number of learnt constraints. |
randf | Pick next decision variable randomly with a probability of randf. |
Definition at line 1526 of file solver.cpp.
ValueRep Clasp::Solver::search | ( | uint64 | maxC, |
uint32 | maxL, | ||
bool | local = false , |
||
double | rp = 0.0 |
||
) | [inline] |
const SolveParams & Clasp::Solver::searchConfig | ( | ) | const |
Returns the solve parameters for this object.
Definition at line 163 of file solver.cpp.
bool Clasp::Solver::seen | ( | Var | v | ) | const [inline] |
bool Clasp::Solver::seen | ( | Literal | p | ) | const [inline] |
void Clasp::Solver::setBacktrackLevel | ( | uint32 | dl | ) | [inline] |
void Clasp::Solver::setConflict | ( | Literal | p, |
const Antecedent & | a, | ||
uint32 | data | ||
) | [private] |
Definition at line 634 of file solver.cpp.
void Clasp::Solver::setEnumerationConstraint | ( | Constraint * | c | ) |
Definition at line 308 of file solver.cpp.
void Clasp::Solver::setPref | ( | Var | v, |
ValueSet::Value | which, | ||
ValueRep | to | ||
) | [inline] |
bool Clasp::Solver::setReason | ( | Literal | p, |
const Antecedent & | x, | ||
uint32 | data = UINT32_MAX |
||
) | [inline] |
void Clasp::Solver::setStopConflict | ( | ) |
Sets a conflict that forces the solver to terminate its search.
Definition at line 438 of file solver.cpp.
const SharedContext* Clasp::Solver::sharedContext | ( | ) | const [inline] |
void Clasp::Solver::shuffleOnNextSimplify | ( | ) | [inline] |
bool Clasp::Solver::simplify | ( | ) |
If called on top-level, removes SAT-clauses + Constraints for which Constraint::simplify returned true.
Definition at line 552 of file solver.cpp.
uint32 Clasp::Solver::simplifyConflictClause | ( | LitVec & | cc, |
ClauseInfo & | info, | ||
ClauseHead * | rhs | ||
) |
simplifies cc and returns finalizeConflictClause(cc, info);
Definition at line 1046 of file solver.cpp.
bool Clasp::Solver::simplifySAT | ( | ) | [private] |
Definition at line 604 of file solver.cpp.
bool Clasp::Solver::split | ( | LitVec & | out | ) |
Tries to split-off disjoint work from the solver's currrent guiding path and returns it in out.
Definition at line 481 of file solver.cpp.
bool Clasp::Solver::splittable | ( | ) | const |
Returns whether the solver can split-off work.
Definition at line 468 of file solver.cpp.
void Clasp::Solver::startInit | ( | uint32 | constraintGuess | ) | [private] |
Definition at line 172 of file solver.cpp.
void Clasp::Solver::strengthenConditional | ( | ) |
Resolves all tagged clauses with the tag literal and thereby strengthens the learnt db.
Definition at line 586 of file solver.cpp.
const SymbolTable& Clasp::Solver::symbolTable | ( | ) | const [inline] |
const LitVec& Clasp::Solver::symmetric | ( | ) | const [inline] |
Literal Clasp::Solver::tagLiteral | ( | ) | const [inline] |
bool Clasp::Solver::test | ( | Literal | p, |
PostPropagator * | c | ||
) |
Executes a one-step lookahead on p.
Assumes p and propagates this assumption. If propagations leads to a conflict, false is returned. Otherwise the assumption is undone and the function returns true.
p | The literal to test. |
c | The constraint that wants to test p (can be 0). |
Definition at line 745 of file solver.cpp.
ValueRep Clasp::Solver::topValue | ( | Var | v | ) | const [inline] |
const LitVec& Clasp::Solver::trail | ( | ) | const [inline] |
Literal Clasp::Solver::trueLit | ( | Var | v | ) | const [inline] |
void Clasp::Solver::undoFree | ( | ConstraintDB * | x | ) | [private] |
Definition at line 897 of file solver.cpp.
void Clasp::Solver::undoLevel | ( | bool | sp | ) | [private] |
Definition at line 904 of file solver.cpp.
void Clasp::Solver::undoUntil | ( | uint32 | dl | ) |
Undoes all assignments up to (but not including) decision level dl.
Definition at line 811 of file solver.cpp.
uint32 Clasp::Solver::undoUntil | ( | uint32 | dl, |
bool | popBtLevel | ||
) |
Similar to undoUntil but optionally also pops the backtrack-level to dl if possible.
Definition at line 824 of file solver.cpp.
void Clasp::Solver::unfreezeLevel | ( | uint32 | dl | ) | [inline] |
bool Clasp::Solver::unitPropagate | ( | ) | [private] |
Definition at line 693 of file solver.cpp.
void Clasp::Solver::unmarkLevel | ( | uint32 | dl | ) | [inline] |
uint64 Clasp::Solver::updateBranch | ( | uint32 | cfl | ) | [private] |
Definition at line 1517 of file solver.cpp.
uint32 Clasp::Solver::updateLearnt | ( | Literal | p, |
const Literal * | first, | ||
const Literal * | last, | ||
uint32 | cLbd, | ||
bool | forceUp = false |
||
) | [inline] |
Computes a new lbd for the antecedent of p given as the range [first, last).
p | A literal implied by [first, last) |
[first,last) | The literals of a learnt nogood implying p. |
cLbd | The current lbd of the learnt nogood. |
bool Clasp::Solver::validLevel | ( | uint32 | dl | ) | const [inline] |
bool Clasp::Solver::validVar | ( | Var | var | ) | const [inline] |
bool Clasp::Solver::validWatch | ( | Literal | p | ) | const [inline, private] |
ValueRep Clasp::Solver::value | ( | Var | v | ) | const [inline] |
VarInfo Clasp::Solver::varInfo | ( | Var | v | ) | const [inline] |
friend class SharedContext [friend] |
Assignment Clasp::Solver::assign_ [private] |
WeightLitVec Clasp::Solver::bumpAct_ [private] |
LitVec Clasp::Solver::cc_ [private] |
ClauseInfo Clasp::Solver::ccInfo_ [private] |
CCMinRecursive* Clasp::Solver::ccMin_ [private] |
VarVec Clasp::Solver::cflStamp_ [private] |
LitVec Clasp::Solver::conflict_ [private] |
ConstraintDB Clasp::Solver::constraints_ [private] |
uint32 Clasp::Solver::dbIdx_ [private] |
Constraint* Clasp::Solver::enum_ [private] |
Heuristic Clasp::Solver::heuristic_ [private] |
ImpliedList Clasp::Solver::impliedLits_ [private] |
uint32 Clasp::Solver::initPost_ [private] |
uint32 Clasp::Solver::lastSimp_ [private] |
VarVec Clasp::Solver::lbdStamp_ [private] |
uint32 Clasp::Solver::lbdTime_ [private] |
ConstraintDB Clasp::Solver::learnts_ [private] |
DecisionLevels Clasp::Solver::levels_ [private] |
uint64 Clasp::Solver::memUse_ [private] |
PPList Clasp::Solver::post_ [private] |
SharedContext* Clasp::Solver::shared_ [private] |
uint32 Clasp::Solver::shufSimp_ [private] |
SmallClauseAlloc* Clasp::Solver::smallAlloc_ [private] |
Literal Clasp::Solver::tag_ [private] |
LitVec Clasp::Solver::temp_ [private] |
ConstraintDB* Clasp::Solver::undoHead_ [private] |
Watches Clasp::Solver::watches_ [private] |