Classes | Public Types | Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes
Clasp::WeightConstraint Class Reference

Class implementing smodels-like cardinality- and weight constraints. More...

#include <weight_constraint.h>

Inheritance diagram for Clasp::WeightConstraint:
Inheritance graph
[legend]

List of all members.

Classes

class  CPair
struct  UndoInfo
struct  WL

Public Types

enum  ActiveConstraint { FFB_BTB = 0, FTB_BFB = 1 }
enum  CreationFlags {
  create_explicit = 1u, create_no_add = 3u, create_sat = 4u, create_no_freeze = 8u,
  create_no_share = 16u, create_eq_bound = 32u
}

Public Member Functions

ConstraintcloneAttach (Solver &)
 Returns a clone of this and adds necessary watches to the given solver.
void destroy (Solver *, bool)
 Default is to call delete this.
uint32 estimateComplexity (const Solver &s) const
 Returns an estimate of the constraint's complexity relative to a clause (complexity = 1).
uint32 getBpIndex () const
bool isWeight () const
 Returns false if constraint is a cardinality constraint.
Literal lit (uint32 i, ActiveConstraint c) const
bool minimize (Solver &s, Literal p, CCMinRecursive *r)
PropResult propagate (Solver &s, Literal p, uint32 &data)
void reason (Solver &, Literal p, LitVec &lits)
bool simplify (Solver &s, bool=false)
uint32 size () const
 Returns the number of literals in this constraint (including W).
void undoLevel (Solver &s)
 Called when the solver undid a decision level watched by this constraint.
weight_t weight (uint32 i) const
 Returns the weight of the i'th literal or 1 if constraint is a cardinality constraint.

Static Public Member Functions

static CPair create (Solver &s, Literal W, WeightLitVec &lits, weight_t bound, uint32 creationFlags=0)
 Creates a new weight constraint from the given weight literals.
static CPair create (Solver &s, Literal W, WeightLitsRep rep, uint32 creationFlags)

Private Member Functions

void addWatch (Solver &s, uint32 idx, ActiveConstraint c)
uint32 highestUndoLevel (Solver &) const
bool integrateRoot (Solver &s)
bool litSeen (uint32 idx) const
void setBpIndex (uint32 n)
void toggleLitSeen (uint32 idx)
uint32 undoStart () const
UndoInfo undoTop () const
void updateConstraint (Solver &s, uint32 idx, ActiveConstraint c)
 WeightConstraint (Solver &s, SharedContext *ctx, Literal W, const WeightLitsRep &, WL *out)
 WeightConstraint (Solver &s, const WeightConstraint &other)
 ~WeightConstraint ()

Static Private Member Functions

static WeightConstraintcreateImpl (Solver &s, Literal W, WeightLitsRep &rep, uint32 flags)

Private Attributes

uint32 active_: 2
weight_t bound_ [2]
WLlits_
uint32 ownsLit_: 1
UndoInfo undo_ [0]
uint32 up_: 29

Static Private Attributes

static const uint32 NOT_ACTIVE = 3u

Detailed Description

Class implementing smodels-like cardinality- and weight constraints.

This class represents a constraint of type W == w1*x1 ... wn*xn >= B, where W and each xi are literals and B and each wi are strictly positive integers. The class is used to represent smodels-like weight constraint, i.e. the body of a basic weight rule. In this case W is the literal associated with the body. A cardinality constraint is handled like a weight constraint where all weights are equal to 1.

The class implements the following four inference rules: Let L be the set of literals of the constraint, let sumTrue be the sum of the weights of all literals l in L that are currently true, let sumReach be the sum of the weights of all literals l in L that are currently not false, let U = {l in L | value(l.var()) == value_free}

Definition at line 78 of file weight_constraint.h.


Member Enumeration Documentation

Logically, we distinguish two constraints: FFB_BTB for handling forward false body and backward true body and FTB_BFB for handling forward true body and backward false body. Physically, we store the literals in one array: ~W=1, l0=w0,...,ln-1=wn-1.

Enumerator:
FFB_BTB 

(SumW-bound)+1 [~W=1, l0=w0,..., ln-1=wn-1];

FTB_BFB 

bound [ W=1,~l0=w0,...,~ln-1=wn-1]

Definition at line 129 of file weight_constraint.h.

Enumerator:
create_explicit 

Force creation of explicit constraint even if size/bound is small.

create_no_add 

Do not add constraint to solver db.

create_sat 

Force creation even if constraint is always satisfied.

create_no_freeze 

Do not freeze variables in constraint.

create_no_share 

Do not allow sharing of literals.

create_eq_bound 

Create equality instead of less-than constraint.

Definition at line 80 of file weight_constraint.h.


Constructor & Destructor Documentation

Clasp::WeightConstraint::WeightConstraint ( Solver s,
SharedContext ctx,
Literal  W,
const WeightLitsRep rep,
WL out 
) [private]

Definition at line 229 of file weight_constraint.cpp.

Clasp::WeightConstraint::WeightConstraint ( Solver s,
const WeightConstraint other 
) [private]

Definition at line 274 of file weight_constraint.cpp.

Definition at line 301 of file weight_constraint.cpp.


Member Function Documentation

void Clasp::WeightConstraint::addWatch ( Solver s,
uint32  idx,
ActiveConstraint  c 
) [private]

Definition at line 338 of file weight_constraint.cpp.

Returns a clone of this and adds necessary watches to the given solver.

The function shall create and return a copy of this constraint to be used in the given solver. Furthermore, it shall add necessary watches to the given solver.

Note:
Return 0 to indicate that cloning is not supported.

Implements Clasp::Constraint.

Definition at line 302 of file weight_constraint.cpp.

WeightConstraint::CPair Clasp::WeightConstraint::create ( Solver s,
Literal  W,
WeightLitVec lits,
weight_t  bound,
uint32  creationFlags = 0 
) [static]

Creates a new weight constraint from the given weight literals.

If the right hand side of the weight constraint is initially true/false (FTB/FFB), W is assigned appropriately but no constraint is created. Otherwise, the new weight constraint is added to s unless creationFlags contains create_no_add.

Parameters:
sSolver in which the new constraint is to be used.
WThe literal that is associated with the constraint.
litsThe literals of the weight constraint.
boundThe lower bound of the weight constraint.
Note:
Cardinality constraint are represented as weight constraints with all weights equal to 1.
If creationFlags contains create_eq_bound, a constraint W == (lits == bound) is created that is represented by up to two weight constraints.

Definition at line 162 of file weight_constraint.cpp.

WeightConstraint::CPair Clasp::WeightConstraint::create ( Solver s,
Literal  W,
WeightLitsRep  rep,
uint32  creationFlags 
) [static]

Definition at line 165 of file weight_constraint.cpp.

WeightConstraint * Clasp::WeightConstraint::createImpl ( Solver s,
Literal  W,
WeightLitsRep rep,
uint32  flags 
) [static, private]

Definition at line 178 of file weight_constraint.cpp.

void Clasp::WeightConstraint::destroy ( Solver s,
bool  detach 
) [virtual]

Default is to call delete this.

Reimplemented from Clasp::Constraint.

Definition at line 346 of file weight_constraint.cpp.

uint32 Clasp::WeightConstraint::estimateComplexity ( const Solver s) const [virtual]

Returns an estimate of the constraint's complexity relative to a clause (complexity = 1).

Reimplemented from Clasp::Constraint.

Definition at line 550 of file weight_constraint.cpp.

uint32 Clasp::WeightConstraint::getBpIndex ( ) const [inline]

Definition at line 146 of file weight_constraint.h.

uint32 Clasp::WeightConstraint::highestUndoLevel ( Solver s) const [private]

Definition at line 367 of file weight_constraint.cpp.

Definition at line 307 of file weight_constraint.cpp.

bool Clasp::WeightConstraint::isWeight ( ) const [inline]

Returns false if constraint is a cardinality constraint.

Definition at line 144 of file weight_constraint.h.

Literal Clasp::WeightConstraint::lit ( uint32  i,
ActiveConstraint  c 
) const [inline]

Returns the i'th literal of constraint c, i.e. li, iff c == FFB_BTB ~li, iff c == FTB_BFB.

Definition at line 138 of file weight_constraint.h.

bool Clasp::WeightConstraint::litSeen ( uint32  idx) const [inline, private]

Definition at line 186 of file weight_constraint.h.

bool Clasp::WeightConstraint::minimize ( Solver s,
Literal  p,
CCMinRecursive rec 
) [virtual]

Called during minimization of learnt clauses.

Precondition:
This constraint is the reason for p being true in s.
Returns:
true if p can be removed from the current learnt clause, false otherwise.
Note:
The default implementation uses the following inefficient algorithm
   LitVec temp;
   reason(s, p, temp);
   for each x in temp 
     if (!s.ccMinimize(p, rec)) return false;
   return true;

Reimplemented from Clasp::Constraint.

Definition at line 463 of file weight_constraint.cpp.

Constraint::PropResult Clasp::WeightConstraint::propagate ( Solver s,
Literal  p,
uint32 &  data 
) [virtual]

Propagate is called for each constraint that watches p. It shall enqueue all consequences of p becoming true.

Precondition:
p is true in s
Parameters:
sThe solver in which p became true.
pA literal watched by this constraint that recently became true.
dataThe data-blob that this constraint passed when the watch for p was registered.

Implements Clasp::Constraint.

Definition at line 407 of file weight_constraint.cpp.

void Clasp::WeightConstraint::reason ( Solver s,
Literal  p,
LitVec lits 
) [virtual]
Precondition:
This constraint is the reason for p being true in s.
Postcondition:
The literals implying p were added to lits.

Implements Clasp::Constraint.

Definition at line 448 of file weight_constraint.cpp.

void Clasp::WeightConstraint::setBpIndex ( uint32  n) [private]

Definition at line 362 of file weight_constraint.cpp.

bool Clasp::WeightConstraint::simplify ( Solver s,
bool  reinit = false 
) [virtual]

Simplify this constraint.

Precondition:
s.decisionLevel() == 0 and the current assignment is fully propagated.
Returns:
true if this constraint can be ignored (e.g. is satisfied), false otherwise.
Postcondition:
If simplify returned true, this constraint has previously removed all its watches from the solver.
Note:
The default implementation is a noop and returns false.

Reimplemented from Clasp::Constraint.

Definition at line 493 of file weight_constraint.cpp.

uint32 Clasp::WeightConstraint::size ( ) const [inline]

Returns the number of literals in this constraint (including W).

Definition at line 142 of file weight_constraint.h.

void Clasp::WeightConstraint::toggleLitSeen ( uint32  idx) [inline, private]

Definition at line 188 of file weight_constraint.h.

void Clasp::WeightConstraint::undoLevel ( Solver s) [virtual]

Called when the solver undid a decision level watched by this constraint.

Parameters:
sthe solver in which the decision level is undone.

Reimplemented from Clasp::Constraint.

Definition at line 482 of file weight_constraint.cpp.

uint32 Clasp::WeightConstraint::undoStart ( ) const [inline, private]

Definition at line 195 of file weight_constraint.h.

UndoInfo Clasp::WeightConstraint::undoTop ( ) const [inline, private]

Definition at line 196 of file weight_constraint.h.

void Clasp::WeightConstraint::updateConstraint ( Solver s,
uint32  idx,
ActiveConstraint  c 
) [private]

Definition at line 376 of file weight_constraint.cpp.

weight_t Clasp::WeightConstraint::weight ( uint32  i) const [inline]

Returns the weight of the i'th literal or 1 if constraint is a cardinality constraint.

Definition at line 140 of file weight_constraint.h.


Member Data Documentation

Definition at line 204 of file weight_constraint.h.

Definition at line 205 of file weight_constraint.h.

Definition at line 201 of file weight_constraint.h.

const uint32 Clasp::WeightConstraint::NOT_ACTIVE = 3u [static, private]

Definition at line 172 of file weight_constraint.h.

Definition at line 203 of file weight_constraint.h.

Definition at line 206 of file weight_constraint.h.

uint32 Clasp::WeightConstraint::up_ [private]

Definition at line 202 of file weight_constraint.h.


The documentation for this class was generated from the following files:


clasp
Author(s): Benjamin Kaufmann
autogenerated on Thu Aug 27 2015 12:41:41