logic_program_types.cpp
Go to the documentation of this file.
00001 // 
00002 // Copyright (c) 2006-2007, Benjamin Kaufmann
00003 // 
00004 // This file is part of Clasp. See http://www.cs.uni-potsdam.de/clasp/ 
00005 // 
00006 // Clasp is free software; you can redistribute it and/or modify
00007 // it under the terms of the GNU General Public License as published by
00008 // the Free Software Foundation; either version 2 of the License, or
00009 // (at your option) any later version.
00010 // 
00011 // Clasp is distributed in the hope that it will be useful,
00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014 // GNU General Public License for more details.
00015 // 
00016 // You should have received a copy of the GNU General Public License
00017 // along with Clasp; if not, write to the Free Software
00018 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
00019 //
00020 #ifdef _MSC_VER
00021 #pragma warning (disable : 4146) // unary minus operator applied to unsigned type, result still unsigned
00022 #pragma warning (disable : 4996) // 'std::_Fill_n' was declared deprecated
00023 #endif
00024 
00025 #include <clasp/logic_program_types.h>
00026 #include <clasp/logic_program.h>
00027 #include <clasp/solver.h>
00028 #include <clasp/clause.h>
00029 #include <clasp/weight_constraint.h>
00030 #include <clasp/util/misc_types.h>
00031 
00032 #include <deque>
00033 
00034 namespace Clasp { namespace Asp {
00035 
00037 // class Rule
00038 //
00039 // Code for handling a rule of a logic program
00041 void Rule::clear() {
00042         heads.clear();
00043         body.clear();
00044         bound_  = 0;
00045         type_   = ENDRULE;
00046 }
00047 
00048 // Adds atomId as head to this rule.
00049 Rule& Rule::addHead(Var atomId) {
00050         assert(type_ != ENDRULE && "Invalid operation - Start rule not called");
00051         heads.push_back(atomId);
00052         return *this;
00053 }
00054 
00055 // Adds atomId to the body of this rule. If pos is true, atomId is added to B+
00056 // otherwise to B-. The weight is ignored (set to 1) unless the rule is a weight/optimize rule
00057 Rule& Rule::addToBody(Var atomId, bool pos, weight_t weight) {
00058         assert(type_ != ENDRULE && "Invalid operation - Start rule not called");
00059         assert( weight >= 0 && "Invalid weight - negative weights are not supported");
00060         if (weight == 0) return *this;  // ignore weightless atoms
00061         if (weight != 1 && !bodyHasWeights()) {
00062                 weight = 1;
00063         }
00064         body.push_back(WeightLiteral(Literal(atomId, pos == false), weight));
00065         return *this;
00066 }
00067 
00068 uint32 BodyInfo::findLit(Literal x) const {
00069         for (WeightLitVec::const_iterator it = lits.begin(), end = lits.end(); it != end; ++it) {
00070                 if (it->first == x) { return static_cast<uint32>(it - lits.begin()); }
00071         }
00072         return UINT32_MAX;
00073 }
00074 
00075 weight_t BodyInfo::sum() const  {
00076         wsum_t s = 0;
00077         for (WeightLitVec::const_iterator it = lits.begin(), end = lits.end(); it != end; ++it) {
00078                 s += it->second;
00079         }
00080         assert(s <= std::numeric_limits<weight_t>::max());
00081         return static_cast<weight_t>(s);
00082 }
00084 // class RuleTransform
00085 //
00086 // class for transforming extended rules to normal rules
00088 Var RuleTransform::AdaptBuilder::newAtom() {
00089         return prg_->newAtom();
00090 }
00091 void RuleTransform::AdaptBuilder::addRule(Rule& rule) {
00092         prg_->addRule(rule);
00093 }
00094 
00095 class RuleTransform::Impl {
00096 public:
00097         Impl(ProgramAdapter& prg, Rule& r);
00098         ~Impl();
00099         uint32 transform();
00100 private:
00101         Impl(const Impl&);
00102         Impl& operator=(const Impl&);
00103         struct TodoItem {
00104                 TodoItem(uint32 i, weight_t w, Var v) : idx(i), bound(w), var(v) {}
00105                 uint32   idx;
00106                 weight_t bound;
00107                 Var      var;
00108         };
00109         typedef std::deque<TodoItem> TodoList;
00110         bool   isBogusRule() const { return rule_.bound() > sumW_[0]; }
00111         bool   isFact()      const { return rule_.bound() <= 0; }
00112         void   createRule(Var head, Literal* bodyFirst, Literal* bodyEnd);
00113         uint32 addRule(Var head, bool addLit, const TodoItem& aux);
00114         Var    getAuxVar(const TodoItem& i) {
00115                 assert(i.bound > 0);
00116                 uint32 k = i.bound-1;
00117                 if (aux_[k] == 0) {
00118                         todo_.push_back(i);
00119                         aux_[k]          = prg_.newAtom();
00120                         todo_.back().var = aux_[k];
00121                 }
00122                 return aux_[k];
00123         }
00124         TodoList        todo_; // heads todo
00125         ProgramAdapter& prg_;  // program to which rules are added
00126         Rule&           rule_; // rule to translate
00127         Rule            out_;  // transformed rule
00128         Var*            aux_;  // newly created atoms for one level of the tree
00129         weight_t*       sumW_; // achievable weight for individual literals
00130 };
00131 
00132 RuleTransform::RuleTransform() {}
00133 
00134 uint32 RuleTransform::transform(ProgramAdapter& prg, Rule& rule) {
00135         if (rule.type() == CHOICERULE) {
00136                 return transformChoiceRule(prg, rule);
00137         }
00138         else if (rule.type() == DISJUNCTIVERULE) {
00139                 return transformDisjunctiveRule(prg, rule);
00140         }
00141         return Impl(prg, rule).transform();
00142 }
00143 
00144 RuleTransform::Impl::Impl(ProgramAdapter& prg, Rule& r)
00145         : prg_(prg)
00146         , rule_(r) {
00147         aux_     = new Var[r.bound()];
00148         sumW_    = new weight_t[r.body.size()+1];
00149         std::memset(aux_ , 0, r.bound()*sizeof(Var));
00150         RuleTransform::prepareRule(r, sumW_);
00151 }
00152 RuleTransform::Impl::~Impl() {
00153         delete [] aux_;
00154         delete [] sumW_;
00155 }
00156 
00157 // Quadratic transformation of cardinality and weight constraint.
00158 // Introduces aux atoms. 
00159 // E.g. a rule h = 2 {a,b,c,d} is translated into the following eight rules:
00160 // h       :- a, aux_1_1.
00161 // h       :- aux_1_2.
00162 // aux_1_1 :- b.
00163 // aux_1_1 :- aux_2_1.
00164 // aux_1_2 :- b, aux_2_1.
00165 // aux_1_2 :- c, d.
00166 // aux_2_1 :- c.
00167 // aux_2_1 :- d.
00168 uint32 RuleTransform::Impl::transform() {
00169         if (isBogusRule()) { 
00170                 return 0;
00171         }
00172         if (isFact()) {
00173                 createRule(rule_.heads[0], 0, 0);
00174                 return 1;
00175         }
00176         todo_.push_back(TodoItem(0, rule_.bound(), rule_.heads[0]));
00177         uint32 normalRules = 0;
00178         uint32 level = 0;
00179         while (!todo_.empty()) {
00180                 TodoItem i = todo_.front();
00181                 todo_.pop_front();
00182                 if (i.idx > level) {
00183                         // We are about to start a new level of the tree.
00184                         // Reset the aux_ array
00185                         level = i.idx;
00186                         std::memset(aux_ , 0, rule_.bound()*sizeof(Var));
00187                 }
00188                 // For a todo item i with var v create at most two rules:
00189                 // r1: v :- lit(i.idx), AuxLit(i.idx+1, i.bound-weight(lit(i.idx)))
00190                 // r2: v :- AuxLit(i.idx+1, i.bound).
00191                 // The first rule r1 represents the case where lit(i.idx) is true, while
00192                 // the second rule encodes the case where the literal is false.
00193                 normalRules += addRule(i.var, true,  TodoItem(i.idx+1, i.bound - rule_.body[i.idx].second, 0));
00194                 normalRules += addRule(i.var, false, TodoItem(i.idx+1, i.bound, 0));
00195         }
00196         return normalRules;
00197 }
00198 
00199 uint32 RuleTransform::Impl::addRule(Var head, bool addLit, const TodoItem& aux) {
00200         // create rule head :- posLit(aux.var) resp. head :- posLit(aux.var), ruleLit(aux.idx-1)
00201         //
00202         // Let B be the bound of aux, 
00203         //  - skip rule, iff sumW(aux.idx) < B, i.e. rule is not applicable.
00204         //  - replace rule with list of body literals if sumW(aux.idx)-minW < B or B <= 0
00205         weight_t minW = rule_.body.back().second;
00206         if (aux.bound <= 0 || sumW_[aux.idx] >= aux.bound) {
00207                 if (aux.bound <= 0) {
00208                         assert(addLit);
00209                         Literal body = rule_.body[aux.idx-1].first;
00210                         createRule(head, &body, &body+1);
00211                 }
00212                 else if ((sumW_[aux.idx] - minW) < aux.bound) {
00213                         LitVec nb;
00214                         if (addLit) {
00215                                 nb.push_back(rule_.body[aux.idx-1].first);
00216                         }
00217                         for (uint32 r = aux.idx; r != rule_.body.size(); ++r) {
00218                                 nb.push_back(rule_.body[r].first);
00219                         }
00220                         createRule(head, &nb[0], &nb[0]+nb.size());
00221                 }
00222                 else {
00223                         Var auxVar      = getAuxVar(aux);
00224                         Literal body[2] = { rule_.body[aux.idx-1].first, posLit(auxVar) };
00225                         createRule(head, body+!addLit, body+2);
00226                 }
00227                 return 1;
00228         }
00229         return 0;
00230 }
00231 
00232 void RuleTransform::Impl::createRule(Var head, Literal* bodyFirst, Literal* bodyEnd) {
00233         out_.clear();
00234         out_.setType(BASICRULE);                
00235         out_.addHead(head);
00236         while (bodyFirst != bodyEnd) {
00237                 out_.addToBody(bodyFirst->var(), !bodyFirst->sign());
00238                 ++bodyFirst;
00239         }
00240         prg_.addRule(out_);
00241 }
00242 
00243 weight_t RuleTransform::prepareRule(Rule& r, weight_t* sumVec) {
00244         if (r.type() != CONSTRAINTRULE && r.type() != WEIGHTRULE) { return 0; }
00245         weight_t sum = 0;
00246         if (r.type() == WEIGHTRULE) {
00247                 std::stable_sort(r.body.begin(), r.body.end(), compose22(
00248                                 std::greater<weight_t>(),
00249                                 select2nd<WeightLiteral>(),
00250                                 select2nd<WeightLiteral>()));
00251                 for (uint32 i = r.body.size(); i--; ) {
00252                         sum      += r.body[i].second;
00253                         sumVec[i] = sum;
00254                 }
00255         }
00256         else { // no weights allowed!
00257                 for (uint32 i = r.body.size(); i--; ) {
00258                         sum      += (r.body[i].second = 1);
00259                         sumVec[i] = sum;
00260                 }
00261         }
00262         return sum;
00263 }
00264 
00265 // Exponential transformation of cardinality and weight constraint.
00266 // Creates minimal subsets, no aux atoms.
00267 // E.g. a rule h = 2 {a,b,c,d} is translated into the following six rules:
00268 // h :- a, b.
00269 // h :- a, c.
00270 // h :- a, d.
00271 // h :- b, c.
00272 // h :- b, d.
00273 // h :- c, d.
00274 uint32 RuleTransform::transformNoAux(ProgramAdapter& prg, Rule& rule) {
00275         assert(rule.type() == WEIGHTRULE || rule.type() == CONSTRAINTRULE);
00276         WeightVec sumWeights(rule.body.size() + 1, 0);
00277         prepareRule(rule, &sumWeights[0]);
00278         uint32 newRules = 0;
00279         VarVec    nextStack;
00280         WeightVec weights;
00281         Rule r(BASICRULE);
00282         r.addHead(rule.heads[0]);
00283         uint32    end   = (uint32)rule.body.size();
00284         weight_t  cw    = 0;
00285         uint32    next  = 0;
00286         if (next == end) { prg.addRule(r); return 1; }
00287         while (next != end) {
00288                 r.addToBody(rule.body[next].first.var(), rule.body[next].first.sign() == false);
00289                 weights.push_back( rule.body[next].second );
00290                 cw += weights.back();
00291                 ++next;
00292                 nextStack.push_back(next);
00293                 if (cw >= rule.bound()) {
00294                         prg.addRule(r);
00295                         r.setType(BASICRULE);
00296                         ++newRules;
00297                         r.body.pop_back();
00298                         cw -= weights.back();
00299                         nextStack.pop_back();
00300                         weights.pop_back();
00301                 }
00302                 while (next == end && !nextStack.empty()) {
00303                         r.body.pop_back();
00304                         cw -= weights.back();
00305                         weights.pop_back();
00306                         next = nextStack.back();
00307                         nextStack.pop_back();
00308                         if (next != end && (cw + sumWeights[next]) < rule.bound()) {
00309                                 next = end;
00310                         }
00311                 }
00312         }
00313         return newRules;
00314 }
00315 
00316 // A choice rule {h1,...hn} :- BODY
00317 // is replaced with:
00318 // h1   :- BODY, not aux1.
00319 // aux1 :- not h1.
00320 // ...
00321 // hn   :- BODY, not auxN.
00322 // auxN :- not hn.
00323 // If n is large or BODY contains many literals BODY is replaced with auxB and
00324 // auxB :- BODY.
00325 uint32 RuleTransform::transformChoiceRule(ProgramAdapter& prg, Rule& rule) const {
00326         uint32 newRules = 0;
00327         Var extraHead = ((rule.heads.size() * (rule.body.size()+1)) + rule.heads.size()) > (rule.heads.size()*3)+rule.body.size()
00328                         ? prg.newAtom()
00329                         : varMax;
00330         Rule r1, r2;
00331         r1.setType(BASICRULE); r2.setType(BASICRULE);
00332         if (extraHead != varMax) { r1.addToBody( extraHead, true, 1 ); }
00333         else { r1.body.swap(rule.body); }
00334         for (VarVec::iterator it = rule.heads.begin(), end = rule.heads.end(); it != end; ++it) {
00335                 r1.heads.clear(); r2.heads.clear();
00336                 Var aux = prg.newAtom();
00337                 r1.heads.push_back(*it);  r1.addToBody(aux, false, 1);
00338                 r2.heads.push_back(aux);  r2.addToBody(*it, false, 1);
00339                 prg.addRule(r1);  // h    :- body, not aux
00340                 prg.addRule(r2);  // aux  :- not h
00341                 r1.body.pop_back();
00342                 r2.body.pop_back();
00343                 newRules += 2;
00344         }
00345         if (extraHead != varMax) {
00346                 r1.heads.clear();
00347                 r1.body.clear();
00348                 r1.body.swap(rule.body);
00349                 r1.heads.push_back(extraHead);
00350                 prg.addRule(r1);
00351                 ++newRules;
00352         }
00353         rule.body.swap(r1.body);
00354         return newRules;
00355 }
00356 
00357 // A disjunctiive rule h1|...|hn :- BODY
00358 // is replaced with:
00359 // hi   :- BODY, {not hj | 1 <= j != i <= n}.
00360 // If BODY contains more than one literal, BODY is replaced with auxB and
00361 // auxB :- BODY.
00362 uint32 RuleTransform::transformDisjunctiveRule(ProgramAdapter& prg, Rule& rule) const {
00363         uint32 newRules = 0;
00364         Rule temp; temp.setType(BASICRULE);
00365         if (rule.body.size() > 1) {
00366                 Rule bodyR;
00367                 bodyR.setType(BASICRULE);
00368                 bodyR.body.swap(rule.body);
00369                 Var auxB = prg.newAtom();
00370                 bodyR.addHead(auxB);
00371                 prg.addRule(bodyR);
00372                 ++newRules;
00373                 rule.body.swap(bodyR.body);
00374                 temp.addToBody(auxB, true);
00375         }
00376         else {
00377                 temp.body = rule.body;
00378         }
00379         for (VarVec::const_iterator it = rule.heads.begin(), end = rule.heads.end(); it != end; ++it) {
00380                 temp.heads.assign(1, *it);
00381                 temp.body.erase(temp.body.begin()+1, temp.body.end());
00382                 for (VarVec::const_iterator j = rule.heads.begin(); j != end; ++j) {
00383                         if (j != it) { temp.addToBody(*j, false); }
00384                 }
00385                 prg.addRule(temp);
00386                 ++newRules;
00387         }
00388         return newRules;
00389 }
00390 
00392 // class SccChecker
00393 // 
00394 // SCC/cycle checking
00396 SccChecker::SccChecker(LogicProgram& prg, AtomList& sccAtoms, uint32 startScc)
00397         : prg_(&prg), sccAtoms_(&sccAtoms), count_(0), sccs_(startScc) {
00398         for (uint32 i = 0; i != prg.numAtoms(); ++i) {
00399                 visit(prg.getAtom(i));
00400         }
00401         for (uint32 i = 0; i != prg.numBodies(); ++i) {
00402                 visit(prg.getBody(i));
00403         }
00404 }
00405 
00406 void SccChecker::visitDfs(PrgNode* node, NodeType t) {
00407         if (!prg_ || !doVisit(node)) {
00408                 return;
00409         }
00410         callStack_.clear();
00411         nodeStack_.clear();
00412         count_ = 0;
00413         addCall(node, t, 0);
00414         while (!callStack_.empty()) {
00415                 Call c = callStack_.back();
00416                 callStack_.pop_back();
00417                 if (!recurse(c)) {
00418                         node = unpackNode(c.node);
00419                         if (c.min < node->id()) {
00420                                 node->resetId( c.min, true );
00421                         }
00422                         else if (c.node == nodeStack_.back()) {
00423                                 // node is trivially-connected; all such nodes are in the same Pseudo-SCC
00424                                 if (isNode(nodeStack_.back(), PrgEdge::ATOM_NODE)) {
00425                                         static_cast<PrgAtom*>(node)->setScc(PrgNode::noScc);
00426                                 }
00427                                 node->resetId(PrgNode::maxVertex, true);
00428                                 nodeStack_.pop_back();
00429                         }
00430                         else { // non-trivial SCC
00431                                 PrgNode* succVertex;
00432                                 do {
00433                                         succVertex = unpackNode(nodeStack_.back());
00434                                         if (isNode(nodeStack_.back(), PrgEdge::ATOM_NODE)) {
00435                                                 static_cast<PrgAtom*>(succVertex)->setScc(sccs_);
00436                                                 sccAtoms_->push_back(static_cast<PrgAtom*>(succVertex));
00437                                         }
00438                                         nodeStack_.pop_back();
00439                                         succVertex->resetId(PrgNode::maxVertex, true);
00440                                 } while (succVertex != node);
00441                                 ++sccs_;
00442                         }
00443                 }
00444         }
00445 }
00446 
00447 bool SccChecker::recurse(Call& c) {
00448         PrgNode* n = unpackNode(c.node);
00449         if (!n->seen()) {
00450                 nodeStack_.push_back(c.node);
00451                 c.min = count_++;
00452                 n->resetId(c.min, true);
00453         }
00454         if (isNode(c.node, PrgEdge::BODY_NODE)) {
00455                 PrgBody* b = static_cast<PrgBody*>(n);
00456                 PrgHead* h = 0; NodeType t;
00457                 for (PrgBody::head_iterator it = b->heads_begin() + c.next, end = b->heads_end(); it != end; ++it) {
00458                         if   (it->isAtom()){ h = prg_->getAtom(it->node()); t = PrgEdge::ATOM_NODE; }
00459                         else               { h = prg_->getDisj(it->node()); t = PrgEdge::DISJ_NODE; }
00460                         if (doVisit(h, false) && onNode(h, t, c, static_cast<uint32>(it-b->heads_begin()))) {
00461                                 return true;
00462                         }
00463                 }
00464         }
00465         else if (isNode(c.node, PrgEdge::ATOM_NODE)) {
00466                 PrgAtom* a = static_cast<PrgAtom*>(n);
00467                 for (PrgAtom::dep_iterator it = a->deps_begin() + c.next, end = a->deps_end(); it != end; ++it) {
00468                         if (it->sign()) continue;
00469                         PrgBody* bn = prg_->getBody(it->var());
00470                         if (doVisit(bn, false) && onNode(bn, PrgEdge::BODY_NODE, c, static_cast<uint32>(it-a->deps_begin()))) {
00471                                 return true;
00472                         }
00473                 }
00474         }
00475         else if (isNode(c.node, PrgEdge::DISJ_NODE)) {
00476                 PrgDisj* d = static_cast<PrgDisj*>(n);
00477                 for (PrgDisj::atom_iterator it = d->begin() + c.next, end = d->end(); it != end; ++it) {
00478                         PrgAtom* a = prg_->getAtom(it->node());
00479                         if (doVisit(a, false) && onNode(a, PrgEdge::ATOM_NODE, c, static_cast<uint32>(it-d->begin()))) {
00480                                 return true;
00481                         }
00482                 }
00483         }
00484         return false;
00485 }
00486 
00487 bool SccChecker::onNode(PrgNode* n, NodeType t, Call& c, uint32 data) {
00488         if (!n->seen()) {
00489                 Call rec = {c.node, c.min, data};
00490                 callStack_.push_back(rec);
00491                 addCall(n, t, 0);
00492                 return true;
00493         }
00494         if (n->id() < c.min) {
00495                 c.min = n->id();
00496         }
00497         return false;
00498 }
00500 PrgNode::PrgNode(uint32 id, bool checkScc) 
00501         : litIdx_(noIdx), noScc_(1-checkScc), id_(id), val_(value_free), eq_(0), seen_(0) {
00502         static_assert(sizeof(PrgNode) == sizeof(uint64), "Unsupported Alignment");
00503 }
00505 // class PrgHead
00507 PrgHead::PrgHead(uint32 id, NodeType t, uint32 data, bool checkScc)
00508         : PrgNode(id, checkScc)
00509         , data_(data), upper_(0), dirty_(0), state_(0), isAtom_(t == PrgEdge::ATOM_NODE)  {
00510         struct X { uint64 x; EdgeVec y; uint32 z; };
00511         static_assert(sizeof(PrgHead) == sizeof(X), "Unsupported Alignment");
00512 }
00513 // Adds the node with given id as a support to this head
00514 // and marks the head as dirty so that any duplicates/false/eq
00515 // supports are removed once simplify() is called.
00516 void PrgHead::addSupport(PrgEdge r, Simplify s) {
00517         supports_.push_back(r);
00518         if (s == force_simplify) { dirty_ = (supports_.size() > 1); }
00519 }
00520 // Removes the given node from the set of supports of this head.
00521 void PrgHead::removeSupport(PrgEdge r) {
00522         if (relevant()) {
00523                 supports_.erase(std::remove(supports_.begin(), supports_.end(), r), supports_.end());
00524         }
00525         dirty_ = 1;
00526 }
00527         
00528 void PrgHead::clearSupports() {
00529         supports_.clear(); 
00530         upper_  = 0;
00531         dirty_  = 0;
00532 }
00533 // Simplifies the set of predecessors supporting this head.
00534 // Removes false/eq supports and returns the number of 
00535 // different supporting literals in numDiffSupps.
00536 bool PrgHead::simplifySupports(LogicProgram& prg, bool strong, uint32* numDiffSupps) {
00537         uint32 numLits = supports();
00538         uint32 choices = 0;
00539         if (dirty_ == 1) {
00540                 dirty_                  = 0;
00541                 numLits                 = 0;
00542                 SharedContext& ctx      = *prg.ctx();
00543                 EdgeVec::iterator it,n,j= supports_.begin();
00544                 for (it = supports_.begin(); it != supports_.end(); ++it) {
00545                         PrgNode* x = prg.getSupp(*it);
00546                         if (x->relevant() && x->value() != value_false && (!strong || x->hasVar())) {
00547                                 if      (!x->seen()) { *j++ = *it; x->markSeen(true); }
00548                                 else if (!choices)   { continue; }
00549                                 else                 {
00550                                         for (n = supports_.begin(); n != it && n->node() != it->node(); ++n) {;}
00551                                         if (*it < *n)      { *n = *it; }
00552                                         else               { continue; }
00553                                 }
00554                                 choices += (it->isBody() && it->isChoice());
00555                                 if (strong && !ctx.marked(x->literal())) {
00556                                         ++numLits;
00557                                         ctx.mark(x->literal());
00558                                 }
00559                         }
00560                 }
00561                 supports_.erase(j, supports_.end());
00562                 uint32 dis = 0;
00563                 choices    = 0;
00564                 for (it = supports_.begin(); it != supports_.end(); ++it) {
00565                         PrgNode* x = prg.getSupp(*it);
00566                         x->markSeen(false);
00567                         if (strong && ctx.marked(x->literal())) { ctx.unmark(x->var()); }
00568                         if (it->isChoice()) {
00569                                 ++choices;
00570                                 dis += it->isDisj();
00571                         }
00572                 }
00573                 numLits += choices;
00574         }
00575         if (numDiffSupps) { *numDiffSupps = numLits; }
00576         return supports() > 0 || prg.assignValue(this, value_false);
00577 }
00578 
00579 // Assigns a variable to this head.
00580 // No support: no var and value false
00581 // More than one support or type not normal: new var
00582 // Exactly one support that is normal: use that 
00583 void PrgHead::assignVar(LogicProgram& prg, PrgEdge support) {
00584         if (hasVar() || !relevant()) { return; }
00585         uint32 numB = supports();
00586         if (numB == 0 && support == PrgEdge::noEdge()) {
00587                 prg.assignValue(this, value_false);
00588         }
00589         else {
00590                 PrgNode* sup = prg.getSupp(support);
00591                 if (support.isNormal() && (numB == 1 || sup->value() == value_true)) {
00592                         // head is equivalent to sup
00593                         setLiteral(sup->literal());
00594                         prg.ctx()->setVarEq(var(), true);
00595                         prg.incEqs(Var_t::atom_body_var);
00596                 }
00597                 else {
00598                         setLiteral(posLit(prg.ctx()->addVar(Var_t::atom_var)));
00599                 }
00600         }
00601 }
00602 
00603 // Backpropagates the value of this head to its supports.
00604 bool PrgHead::backpropagate(LogicProgram& prg, ValueRep val, bool bpFull) {
00605         bool ok = true;
00606         if (val == value_false) {
00607                 // a false head can't have supports
00608                 EdgeVec temp; temp.swap(supports_);
00609                 markDirty();
00610                 for (EdgeIterator it = temp.begin(), end = temp.end(); it != end && ok; ++it) {
00611                         if (it->isBody()) {
00612                                 ok = prg.getBody(it->node())->propagateAssigned(prg, this, it->type());
00613                         }
00614                         else { assert(it->isDisj());
00615                                 ok = prg.getDisj(it->node())->propagateAssigned(prg, this, it->type());
00616                         }
00617                 }
00618         }
00619         else if (val != value_free && supports() == 1 && bpFull) {
00620                 // head must be true and only has one support, thus the only support must
00621                 // be true, too.
00622                 PrgBody* b   = 0;
00623                 if (supports_[0].isBody()) {
00624                         b   = prg.getBody(supports_[0].node());
00625                 }
00626                 else if (supports_[0].isDisj()) {
00627                         PrgDisj* d = prg.getDisj(supports_[0].node());
00628                         if (d->supports() == 1) { b = prg.getBody(d->supps_begin()->node()); }
00629                 }
00630                 ok = !b || b->value() == val || (b->assignValue(val) && b->propagateValue(prg, bpFull));
00631         }
00632         return ok;
00633 }
00634 
00636 // class PrgAtom
00638 PrgAtom::PrgAtom(uint32 id, bool checkScc) 
00639         : PrgHead(id, PrgEdge::ATOM_NODE, PrgNode::noScc, checkScc) {
00640         static_assert(sizeof(PrgAtom) == sizeof(PrgHead) + sizeof(LitVec), "Unsupported Alignment");
00641 }               
00642 
00643 void PrgAtom::setEqGoal(Literal x) {
00644         if (eq()) {
00645                 data_ = x.sign() ? x.var() : noScc;
00646         }
00647 }
00648 Literal PrgAtom::eqGoal(bool sign) const {
00649         if (!eq() || sign || data_ == noScc) {
00650                 return Literal(id(), sign);
00651         }
00652         return negLit(data_);
00653 }
00654 
00655 // Adds a dependency between this atom and the body with
00656 // the given id. If pos is true, atom appears positively
00657 // in body, otherwise negatively.
00658 void PrgAtom::addDep(Var bodyId, bool pos) {
00659         deps_.push_back(Literal(bodyId, !pos)); 
00660 }
00661 
00662 // Removes a dependency between this atom and the body with
00663 // the given id. If pos is true, atom appears positively
00664 // in body, otherwise negatively.
00665 void PrgAtom::removeDep(Var bodyId, bool pos) {
00666         LitVec::iterator it = std::find(deps_.begin(), deps_.end(), Literal(bodyId, !pos));
00667         if (it != deps_.end()) { deps_.erase(it); }
00668 }
00669 
00670 // Removes the subset of dependencies given by d
00671 void PrgAtom::clearDeps(Dependency d) {
00672         if (d == dep_all) {
00673                 deps_.clear();
00674         }
00675         else {
00676                 bool sign = d == dep_neg;
00677                 LitVec::iterator j = deps_.begin();
00678                 for (LitVec::iterator it = deps_.begin(), end = deps_.end(); it != end; ++it) {
00679                         if (it->sign() != sign) { *j++ = *it; }
00680                 }
00681                 deps_.erase(j, deps_.end());
00682         }
00683 }
00684 
00685 bool PrgAtom::hasDep(Dependency d) const {
00686         if (d == dep_all) { return !deps_.empty(); }
00687         for (LitVec::const_iterator it = deps_.begin(), end = deps_.end(); it != end; ++it) {
00688                 if (static_cast<Dependency>(it->sign()) == d) { return true; }
00689         }
00690         return false;
00691 }
00692 
00693 bool PrgAtom::inDisj() const {
00694         for (EdgeIterator it= supports_.begin(), end = supports_.end(); it != end; ++it) {
00695                 if (it->isDisj()) { return true; }
00696         }
00697         return false;
00698 }
00699 
00700 // Propagates the value of this atom to its depending bodies
00701 // and, if backpropagation is enabled, to its supporting bodies/disjunctions.
00702 // PRE: value() != value_free
00703 bool PrgAtom::propagateValue(LogicProgram& prg, bool backprop) {
00704         ValueRep val = value();
00705         assert(val != value_free);
00706         // propagate value forward
00707         Literal dep = posLit(id());
00708         for (dep_iterator it = deps_.begin(), end = deps_end(); it != end; ++it) {
00709                 if (!prg.getBody(it->var())->propagateAssigned(prg, dep ^ it->sign(), val)) {
00710                         return false;
00711                 }
00712         }
00713         if (prg.isFact(this) && inDisj()) {
00714                 // - atom is true, thus all disjunctive rules containing it are superfluous
00715                 EdgeVec temp; temp.swap(supports_);
00716                 EdgeVec::iterator j = temp.begin();
00717                 EdgeType t          = PrgEdge::CHOICE_EDGE;
00718                 for (EdgeIterator it= temp.begin(), end = temp.end(); it != end; ++it) {
00719                         if      (!it->isDisj())                                            { *j++ = *it; }
00720                         else if (!prg.getDisj(it->node())->propagateAssigned(prg, this, t)){ return false; }
00721                 }
00722                 temp.erase(j, temp.end());
00723                 supports_.swap(temp);
00724         }
00725         return backpropagate(prg, val, backprop);
00726 }
00727 
00728 // Adds the atom-oriented nogoods for this atom in form of clauses.
00729 // Adds the support clause [~a S1...Sn] (where each Si is a supporting node of a)
00730 // representing the tableau-rules BTA and FFA.
00731 // Furthermore, adds the clause [a ~Bj] representing tableau-rules FTA and BFA
00732 // if Bj supports a via a "normal" edge. 
00733 bool PrgAtom::addConstraints(const LogicProgram& prg, ClauseCreator& gc) {
00734         SharedContext& ctx  = *prg.ctx();
00735         EdgeVec::iterator j = supports_.begin();
00736         bool           nant = false;
00737         gc.start().add(~literal());
00738         for (EdgeVec::iterator it = supports_.begin(); it != supports_.end(); ++it) {
00739                 PrgNode* n = prg.getSupp(*it);
00740                 Literal  B = n->literal();
00741                 // consider only bodies which are part of the simplified program, i.e.
00742                 // are associated with a variable in the solver.
00743                 if (n->relevant() && n->hasVar()) {
00744                         *j++ = *it;
00745                         nant = nant || it->isChoice();
00746                         if (!it->isDisj()) { gc.add(B); }
00747                         if (it->isNormal() && !ctx.addBinary(literal(), ~B)) { // FTA/BFA
00748                                 return false;
00749                         }
00750                 }
00751         }
00752         supports_.erase(j, supports_.end());
00753         if (nant ||     hasDep(PrgAtom::dep_neg)) { ctx.setNant(var(), true); }
00754         return gc.end(ClauseCreator::clause_force_simplify);
00755 }
00756 
00758 // class PrgBody
00760 PrgBody::PrgBody(LogicProgram& prg, uint32 id, const BodyInfo& body, bool addDeps)
00761         : PrgNode(id, true)
00762         , size_(body.size()), extHead_(0), type_(body.type()), sBody_(0), sHead_(0), unsupp_(0) {
00763         Literal* lits  = goals_begin();
00764         Literal* p[2]  = {lits, lits + body.posSize()};
00765         weight_t sw[2] = {0,0}; // sum of positive/negative weights
00766         const bool W   = type() == BodyInfo::SUM_BODY;
00767         if (W) {
00768                 data_.ext[0] = SumExtra::create(body.size());
00769         }
00770         weight_t   w   = 1;
00771         // store B+ followed by B- followed by optional weights
00772         for (WeightLitVec::const_iterator it = body.lits.begin(), end = body.lits.end(); it != end; ++it) {
00773                 Literal x    = it->first;
00774                 *p[x.sign()] = x;
00775                 if (W) {   w = it->second; data_.ext[0]->weights[p[x.sign()] - lits] = w; }
00776                 ++p[x.sign()];
00777                 sw[x.sign()] += w;
00778                 if (addDeps) { prg.getAtom(x.var())->addDep(id, !x.sign()); }
00779         }
00780         if (body.type() == BodyInfo::COUNT_BODY) {
00781                 data_.lits[0] = body.bound();
00782         }
00783         else if (W) {
00784                 data_.ext[0]->bound = body.bound();
00785                 data_.ext[0]->sumW  = sw[0] + sw[1];
00786         }
00787         unsupp_ = static_cast<weight_t>(this->bound() - sw[1]);
00788         if (bound() == 0) {
00789                 assignValue(value_true);
00790                 markDirty();
00791         }
00792 }
00793 
00794 PrgBody* PrgBody::create(LogicProgram& prg, uint32 id, const BodyInfo& body, bool addDeps) {
00795         uint32 bytes = sizeof(PrgBody) + (body.size() * sizeof(Literal));
00796         if (body.type() != BodyInfo::NORMAL_BODY) {
00797                 bytes += (SumExtra::LIT_OFFSET * sizeof(uint32));
00798         }
00799         return new (::operator new(bytes)) PrgBody(prg, id, body, addDeps);
00800 }
00801 
00802 PrgBody::~PrgBody() {
00803         clearHeads();
00804         if (hasWeights()) {
00805                 data_.ext[0]->destroy();
00806         }
00807 }
00808 
00809 void PrgBody::destroy() {
00810         this->~PrgBody();
00811         ::operator delete(this);
00812 }
00813 
00814 PrgBody::SumExtra* PrgBody::SumExtra::create(uint32 size) {
00815         uint32 bytes = sizeof(SumExtra) + (size * sizeof(weight_t));
00816         return new (::operator new(bytes)) SumExtra;
00817 }
00818 void PrgBody::SumExtra::destroy() {
00819         ::operator delete(this);
00820 }
00821 
00822 uint32 PrgBody::findLit(const LogicProgram& prg, Literal p) const {
00823         for (const Literal* it = goals_begin(), *end = it + size(); it != end; ++it) {
00824                 Literal x = prg.getAtom(it->var())->literal();
00825                 if (it->sign()) x = ~x;
00826                 if (x == p) return static_cast<uint32>(it - goals_begin());
00827         }
00828         return varMax;
00829 }
00830 
00831 // Sets the unsupported counter back to
00832 // bound() - negWeight()
00833 bool PrgBody::resetSupported() {
00834         unsupp_ = bound();
00835         for (uint32 x = size(); x && goal(--x).sign(); ) {
00836                 unsupp_ -= weight(x);
00837         }
00838         return isSupported();
00839 }
00840 
00841 // Removes all heads from this body *without* notifying them 
00842 void PrgBody::clearHeads() {
00843         if (extHead()) { delete heads_.ext; }
00844         extHead_ = 0;
00845 }
00846 
00847 // Makes h a head-successor of this body and adds this
00848 // body as a support for h.
00849 void PrgBody::addHead(PrgHead* h, EdgeType t) {
00850         assert(relevant() && h->relevant());
00851         PrgEdge fwdEdge = PrgEdge::newEdge(h->id(), t, h->isAtom() ? PrgEdge::ATOM_NODE : PrgEdge::DISJ_NODE);
00852         PrgEdge bwdEdge = PrgEdge::newEdge(id(), t, PrgEdge::BODY_NODE);
00853         addHead(fwdEdge);
00854         h->addSupport(bwdEdge);
00855         // mark head-set as dirty
00856         if (extHead_ > 1) {  sHead_ = 1; }
00857 }
00858 
00859 void PrgBody::addHead(PrgEdge h) {
00860         if      (extHead_ < 2u) { heads_.simp[extHead_++] = h; }
00861         else if (extHead())     { heads_.ext->push_back(h);    }
00862         else                    { 
00863                 EdgeVec* t  = new EdgeVec(heads_.simp, heads_.simp+2);
00864                 t->push_back(h);
00865                 heads_.ext  = t;
00866                 extHead_    = 3u;
00867         }
00868 }
00869 
00870 void PrgBody::removeHead(PrgHead* h, EdgeType t) {
00871         PrgEdge x = PrgEdge::newEdge(h->id(), t, h->isAtom() ? PrgEdge::ATOM_NODE : PrgEdge::DISJ_NODE);
00872         if (eraseHead(x)) {
00873                 h->removeSupport(PrgEdge::newEdge(id(), t, PrgEdge::BODY_NODE)); // also remove back edge
00874         }
00875 }
00876 
00877 bool PrgBody::eraseHead(PrgEdge h) {
00878         PrgEdge* it = const_cast<PrgEdge*>(std::find(heads_begin(), heads_end(), h));
00879         if (it != heads_end()) {
00880                 if (extHead()) { heads_.ext->erase(it); }
00881                 else           { *it = heads_.simp[1]; --extHead_; }
00882                 return true;
00883         }
00884         return false;
00885 }
00886 
00887 // Simplifies the body by removing assigned atoms & replacing eq atoms.
00888 // Checks whether simplified body must be false (CONTRA) or is
00889 // structurally equivalent to some other body.
00890 // prg    The program containing this body
00891 // strong If true, treats atoms that have no variable associated as false. 
00892 // eqId   The id of a body in prg that is equivalent to this body        
00893 bool PrgBody::simplifyBody(LogicProgram& prg, bool strong, uint32* eqId) {
00894         if (eqId)        { *eqId  = id(); }
00895         if (sBody_ == 0) { return true;   }
00896         // update body - compute old hash value
00897         SharedContext& ctx = *prg.ctx();
00898         uint32 oldHash     = 0;
00899         weight_t bound     = this->bound();
00900         weight_t w         = 1, *jw = hasWeights() ? data_.ext[0]->weights : 0;
00901         Literal* lits      = goals_begin();
00902         Literal* j         = lits;
00903         RuleState& todo    = prg.ruleState();
00904         Var a;
00905         bool mark, isEq;
00906         int todos = 0;
00907         for (Literal* it = j, *end = j + size(); it != end; ++it) {
00908                 a       = it->var();
00909                 isEq    = a != prg.getEqAtom(a);
00910                 oldHash+= hashId(it->sign()?-a:a);
00911                 if (isEq) {
00912                         prg.getAtom(a)->removeDep(id(), !it->sign()); // remove old edge
00913                         *it   = prg.getAtom(a)->eqGoal(it->sign());   // replace with eq goal
00914                         a     = it->var();                            // and check it
00915                 }
00916                 Literal aLit = it->sign() ? ~prg.getAtom(a)->literal() : prg.getAtom(a)->literal();
00917                 ValueRep v   = prg.getAtom(a)->value();
00918                 mark         = strong || prg.getAtom(a)->hasVar();
00919                 if (strong && !prg.getAtom(a)->hasVar()) {
00920                         v          = value_false;
00921                 }
00922                 if (v == value_weak_true && it->sign()) {
00923                         v = value_true;
00924                 }
00925                 if (v == value_true || v == value_false) { // truth value is known - remove subgoal
00926                         if (v == trueValue(*it)) {
00927                                 // subgoal is true: decrease necessary lower bound
00928                                 bound -= weight(uint32(it - lits));
00929                         }
00930                         prg.getAtom(a)->removeDep(id(), !it->sign());
00931                 }
00932                 else if (!mark || !ctx.marked(aLit)) {
00933                         if (mark) { ctx.mark(aLit); }
00934                         if (isEq) { // remember to add edge for new goal later
00935                                 todo.addToBody(Literal(*it));
00936                                 ++todos;
00937                         }
00938                         *j++    = *it;       // copy literal
00939                         if (hasWeights()) {  // and weight
00940                                 *jw++ = weight(uint32(it - lits));
00941                         }
00942                 }
00943                 else { // body contains aLit more than once 
00944                         if (type() != BodyInfo::NORMAL_BODY) { // merge subgoal
00945                                 if (!hasWeights()) {
00946                                         SumExtra* extra = SumExtra::create(size());
00947                                         extra->bound    = this->bound();
00948                                         extra->sumW     = this->sumW();
00949                                         type_           = BodyInfo::SUM_BODY;
00950                                         w               = 1;
00951                                         std::fill_n(extra->weights, size(), w);
00952                                         data_.ext[0]    = extra;
00953                                         jw              = extra->weights + (it - lits);
00954                                 }
00955                                 else { w          = weight(uint32(it - lits)); }
00956                                 uint32 pos        = findLit(prg, aLit);
00957                                 data_.ext[0]->weights[pos] += w;
00958                         }
00959                         else { // ignore if normal
00960                                 --bound;
00961                                 if (!isEq) { // remove edge
00962                                         if (todo.inBody(*it)) { todo.clearBody(*it); --todos; }
00963                                         else                  { prg.getAtom(it->var())->removeDep(id(), !it->sign()); }
00964                                 }
00965                         } 
00966                 }
00967         }
00968         // unmark atoms, compute new hash value,
00969         // and restore pos | neg partition in case
00970         // we changed some positive goals to negative ones 
00971         size_           = j - lits;
00972         if (jw) jw      = data_.ext[0]->weights;
00973         uint32 p = 0, n = size_, newHash = 0;
00974         weight_t sumW   = 0, reachW = 0;
00975         for (uint32 a, h, i; p < n;) {
00976                 if      (!lits[p].sign())      { h = hashId( (a = lits[i = p++].var()));  }
00977                 else if (lits[n-1].sign())     { h = hashId(-(a = lits[i = --n].var()));  }
00978                 else /* restore pos|neg order */ {
00979                         std::swap(lits[p], lits[n-1]);
00980                         if (jw) { std::swap(jw[p], jw[n-1]); }
00981                         continue;
00982                 }
00983                 assert(a == lits[i].var());
00984                 if (todos && todo.inBody(lits[i])) {
00985                         prg.getAtom(a)->addDep(id(), !lits[i].sign());
00986                         todo.clearBody(lits[i]);
00987                         --todos;
00988                 }
00989                 Var v   = prg.getAtom(a)->var();
00990                 w       = !jw ? 1 : jw[i];
00991                 sumW   += w;
00992                 reachW += w;
00993                 if (ctx.marked(posLit(v)) && ctx.marked(negLit(v))) {
00994                         // body contains aLit and ~aLit
00995                         if  (type() != BodyInfo::SUM_BODY) { reachW -= 1; }
00996                         else {
00997                                 Literal other = prg.getAtom(a)->literal() ^ !goal(i).sign();
00998                                 uint32 pos    = findLit(prg, other);
00999                                 assert(pos != varMax && pos != i);
01000                                 reachW       -= std::min(w, jw[pos]);
01001                         }
01002                 }
01003                 ctx.unmark( v );
01004                 newHash += h;
01005         }
01006         bool ok = normalize(prg, bound, sumW, reachW, newHash);
01007         if (ok) {
01008                 Var xId = id();
01009                 if (oldHash != newHash) {
01010                         xId = prg.update(this, oldHash, newHash);
01011                 }
01012                 if (eqId) { *eqId = xId != varMax ? xId : id(); }
01013         }
01014         if (strong) sBody_ = 0;
01015         return ok && (value() == value_free || propagateValue(prg, prg.options().backprop));    
01016 }
01017 
01018 bool PrgBody::normalize(const LogicProgram& prg, weight_t bound, weight_t sumW, weight_t reachW, uint32& hashOut) {
01019         BodyInfo::BodyType nt = (sumW == bound || size() == 1) ? BodyInfo::NORMAL_BODY : type();
01020         bool ok = true;
01021         if (sumW >= bound && type() != BodyInfo::NORMAL_BODY) {
01022                 if (type() == BodyInfo::SUM_BODY) {
01023                         data_.ext[0]->bound   = bound;
01024                         data_.ext[0]->sumW    = sumW;
01025                 }
01026                 else if (type() == BodyInfo::COUNT_BODY) {
01027                         data_.lits[0] = bound;
01028                 }
01029         }
01030         if (bound <= 0) {
01031                 for (uint32 i = 0, myId = id(); i != size_; ++i) {
01032                         prg.getAtom(goal(i).var())->removeDep(myId, !goal(i).sign());
01033                 }
01034                 size_  = 0; hashOut = 0, unsupp_ = 0;
01035                 nt     = BodyInfo::NORMAL_BODY;
01036                 ok     = assignValue(value_true);
01037         }
01038         else if (reachW < bound) {
01039                 ok     = assignValue(value_false);
01040                 sHead_ = 1;
01041                 markRemoved();
01042         }
01043         if (nt != type()) {
01044                 assert(nt == BodyInfo::NORMAL_BODY);
01045                 if (type() == BodyInfo::SUM_BODY) {
01046                         data_.ext[0]->destroy();
01047                 }
01048                 Literal* to   = reinterpret_cast<Literal*>(data_.lits);
01049                 Literal* from = goals_begin();
01050                 std::copy(from, from+size(), to);
01051                 type_         = nt;
01052         }
01053         return ok;
01054 }
01055 
01056 // Marks the set of heads in rs and removes
01057 // any duplicate heads.
01058 void PrgBody::prepareSimplifyHeads(LogicProgram& prg, RuleState& rs) {
01059         head_iterator end = heads_end();
01060         uint32 size       = 0;
01061         for (PrgEdge*  j  = const_cast<PrgEdge*>(heads_begin()); j != end;) {
01062                 if (!rs.inHead(*j)) {
01063                         rs.addToHead(*j);
01064                         ++j; ++size;
01065                 }       
01066                 else { 
01067                         prg.getHead(*j)->markDirty();
01068                         *j = *--end; 
01069                 }
01070         }
01071         if (extHead()) { shrinkVecTo(*heads_.ext, size); }
01072         else           { extHead_ = size; }
01073 }
01074 
01075 // Simplifies the heads of this body wrt target.
01076 // Removes superfluous/eq/unsupported heads and checks for self-blocking
01077 // situations.
01078 // PRE: prepareSimplifyHeads was called
01079 bool PrgBody::simplifyHeadsImpl(LogicProgram& prg, PrgBody& target, RuleState& rs, bool strong) {
01080         PrgHead* cur;
01081         PrgEdge* j     = const_cast<PrgEdge*>(heads_begin());
01082         uint32 newSize = 0;
01083         bool merge     = this != &target;
01084         bool block     = value() == value_false || (merge && target.value() == value_false);
01085         for (head_iterator it = heads_begin(), end = heads_end(); it != end; ++it) {
01086                 cur  = prg.getHead(*it);
01087                 block= block || target.blockedHead(*it, rs);
01088                 if (!cur->relevant() || (strong && !cur->hasVar()) 
01089                         || block || target.superfluousHead(prg, cur, *it, rs) || cur->value() == value_false) {
01090                         // remove superfluous and unsupported heads
01091                         cur->removeSupport(PrgEdge::newEdge(id(), it->type(), PrgEdge::BODY_NODE));
01092                         rs.clearHead(*it);
01093                         block = block || (cur->value() == value_false && it->type() == PrgEdge::NORMAL_EDGE);
01094                 }
01095                 else { 
01096                         *j++ = *it; 
01097                         ++newSize; 
01098                         if (merge) { target.addHead(cur, it->type()); }
01099                 }
01100         }
01101         if (extHead()) { shrinkVecTo(*heads_.ext, newSize); }
01102         else           { extHead_ = (j - heads_.simp); }
01103         return !block;
01104 }
01105 
01106 bool PrgBody::simplifyHeads(LogicProgram& prg, bool strong) {
01107         if (sHead_ == 0) { return true; }
01108         return PrgBody::mergeHeads(prg, *this, strong);
01109 }
01110 
01111 bool PrgBody::mergeHeads(LogicProgram& prg, PrgBody& heads, bool strong, bool simplify) {
01112         RuleState& rs = prg.ruleState();
01113         bool       ok = true;
01114         assert((this == &heads || heads.sHead_ == 0) && "Heads to merge not simplified!");
01115         if (simplify || &heads == this) {
01116                 // mark the body literals so that we can easily detect superfluous atoms
01117                 // and selfblocking situations. 
01118                 for (const Literal* it = goals_begin(), *end = it + size(); it != end; ++it) {
01119                         rs.addToBody(*it);
01120                 }
01121                 // remove duplicate/superfluous heads & check for blocked atoms
01122                 prepareSimplifyHeads(prg, rs);
01123                 if (this == &heads) {
01124                         ok = simplifyHeadsImpl(prg, *this, rs, strong);
01125                 }
01126                 else {
01127                         assert(heads.sHead_ == 0 && "Heads to merge not simplified!");
01128                         heads.prepareSimplifyHeads(prg, rs);
01129                         ok = simplifyHeadsImpl(prg, *this, rs, strong) && heads.simplifyHeadsImpl(prg, *this, rs, strong);
01130                         assert(ok || heads.heads_begin() == heads.heads_end());
01131                 }
01132                 // clear temporary flags & reestablish ordering
01133                 std::sort(const_cast<PrgEdge*>(heads_begin()), const_cast<PrgEdge*>(heads_end()));
01134                 for (head_iterator it = heads_begin(), end = heads_end(); it != end; ++it) {    
01135                         rs.clear(it->node());
01136                 }
01137                 for (const Literal* it = goals_begin(), *end = it + size(); it != end; ++it) {
01138                         rs.clear(it->var());
01139                 }       
01140                 sHead_ = 0;
01141         }
01142         else if (relevant()) {
01143                 for (head_iterator it = heads.heads_begin(), end = heads.heads_end(); it != end; ++it) {
01144                         PrgHead* h = prg.getHead(*it);
01145                         if (h->relevant()) { addHead(h, it->type()); }
01146                 }
01147         }
01148         return ok || (assignValue(value_false) && propagateValue(prg, prg.options().backprop));
01149 }
01150 
01151 // Checks whether the head is superfluous w.r.t this body, i.e.
01152 //  - is needed to satisfy the body
01153 //  - it appears in the body and is a choice
01154 //  - it is a disjunction and one of the atoms is needed to satisfy the body
01155 bool PrgBody::superfluousHead(const LogicProgram& prg, const PrgHead* head, PrgEdge it, const RuleState& rs) const {
01156         if (it.isAtom()) {
01157                 // the head is an atom
01158                 uint32 atomId = it.node();      
01159                 weight_t    w = 1;
01160                 if (rs.inBody(posLit(atomId))) {
01161                         if (type() == BodyInfo::SUM_BODY) {
01162                                 const Literal* lits = goals_begin();
01163                                 const Literal* x    = std::find(lits, lits + size(), posLit(atomId));   
01164                                 assert(x != lits + size());
01165                                 w                   = data_.ext[0]->weights[ x - lits ];
01166                         }
01167                         if (it.isChoice() || (sumW() - w) < bound()) {
01168                                 return true;
01169                         }
01170                 }
01171                 return it.isChoice() 
01172                         && (rs.inBody(negLit(atomId)) || rs.inHead(PrgEdge::newEdge(atomId, PrgEdge::NORMAL_EDGE, PrgEdge::ATOM_NODE)));
01173         }
01174         else { assert(it.isDisj()); 
01175                 // check each contained atom
01176                 const PrgDisj* dis = static_cast<const PrgDisj*>(head);
01177                 for (PrgDisj::atom_iterator it = dis->begin(), end = dis->end(); it != end; ++it) {
01178                         if (rs.inBody(posLit(it->node())) || rs.inHead(PrgEdge::newEdge(it->node(), PrgEdge::NORMAL_EDGE, PrgEdge::ATOM_NODE))) {
01179                                 return true;
01180                         }
01181                         if (prg.isFact(prg.getAtom(it->node()))) {
01182                                 return true;
01183                         }
01184                 }
01185                 // check for subsumption
01186                 if (prg.options().iters == LogicProgram::AspOptions::MAX_EQ_ITERS) {
01187                         for (head_iterator it = heads_begin(), end = heads_end(); it != end; ++it) {
01188                                 if (it->isDisj() && prg.getDisj(it->node())->size() < dis->size()) {
01189                                         const PrgDisj* other = prg.getDisj(it->node());
01190                                         for (PrgDisj::atom_iterator a = other->begin(), aEnd = other->end(); a != aEnd && other; ++a) {
01191                                                 if (std::find(dis->begin(), dis->end(), *a) == dis->end()) {
01192                                                         other = 0;
01193                                                 }
01194                                         }
01195                                         if (other && other->size() > 0) { 
01196                                                 return true; 
01197                                         }
01198                                 }
01199                         }
01200                 }
01201         }
01202         return false;
01203 }
01204 
01205 // Checks whether the rule it.node() :- *this is selfblocking, i.e. 
01206 // from TB follows conflict
01207 bool PrgBody::blockedHead(PrgEdge it, const RuleState& rs) const {
01208         if (it.isAtom() && it.isNormal() && rs.inBody(negLit(it.node()))) {
01209                 weight_t w = 1;
01210                 if (type() == BodyInfo::SUM_BODY) {
01211                         const Literal* lits = goals_begin();
01212                         const Literal* x    = std::find(lits, lits + size(), negLit(it.node()));        
01213                         assert(x != lits + size());
01214                         w                   = data_.ext[0]->weights[ x - lits ];
01215                 }
01216                 return (sumW() - w) < bound();
01217         }
01218         return false;
01219 }
01220 
01221 void PrgBody::assignVar(LogicProgram& prg) {
01222         if (hasVar() || !relevant()) { return; }
01223         uint32 size = this->size();
01224         if (size == 0 || value() == value_true) {
01225                 setLiteral(posLit(0));
01226         }
01227         else if (size == 1 && prg.getAtom(goal(0).var())->hasVar()) {
01228                 Literal x = prg.getAtom(goal(0).var())->literal();
01229                 setLiteral(goal(0).sign() ? ~x : x);
01230                 prg.ctx()->setVarEq(var(), true);
01231                 prg.incEqs(Var_t::atom_body_var);
01232         }
01233         else if (value() != value_false) {
01234                 setLiteral(posLit(prg.ctx()->addVar(Var_t::body_var))); 
01235         }
01236         else {
01237                 setLiteral(negLit(0));
01238         }
01239 }
01240 
01241 bool PrgBody::eqLits(WeightLitVec& vec, bool& sorted) const {
01242         if (!sorted && vec.size() <= 10) {
01243                 for (WeightLitVec::const_iterator it = vec.begin(), end = vec.end(); it != end; ++it) {
01244                         const Literal* x = std::find(goals_begin(), goals_end(), it->first);
01245                         if (x == goals_end() || weight((uint32)std::distance(goals_begin(), x)) != it->second) {
01246                                 return false;
01247                         }
01248                 }
01249         }
01250         else {
01251                 if (!sorted) { std::stable_sort(vec.begin(), vec.end()); sorted = true; }
01252                 for (uint32 x = 0, end = size(); x != end; ++x) {
01253                         WeightLiteral w(goal(x), weight(x));
01254                         if (!std::binary_search(vec.begin(), vec.end(), w)) {
01255                                 return false;
01256                         }
01257                 }
01258         }
01259         return true;
01260 }
01261 bool PrgBody::propagateSupported(Var v) {
01262         weight_t w = 1;
01263         if (hasWeights()) {
01264                 uint32 pos = (uint32)std::distance(goals_begin(), std::find(goals_begin(), goals_end(), posLit(v)));
01265                 w          = weight(pos);
01266         }
01267         return (unsupp_ -= w) <= 0;
01268 }
01269 
01270 bool PrgBody::propagateAssigned(LogicProgram& prg, Literal p, ValueRep v) {
01271         if (!relevant()) return true;
01272         assert(std::find(goals_begin(), goals_end(), p) != goals_end());
01273         markDirty();
01274         ValueRep x = v == value_weak_true ? value_true : v;
01275         weight_t w = 1; // TODO: find weight of p for weight rule
01276         if (x == falseValue(p) && (sumW() - w) < bound() && value() != value_false) {
01277                 return assignValue(value_false) && propagateValue(prg, prg.options().backprop);
01278         }
01279         else if (x == trueValue(p) && (bound() - w) <= 0 && value() != value_weak_true) {
01280                 return assignValue(value_weak_true) && propagateValue(prg, prg.options().backprop);
01281         }
01282         return true;
01283 }
01284 
01285 bool PrgBody::propagateAssigned(LogicProgram& prg, PrgHead* h, EdgeType t) {
01286         if (!relevant()) return true;
01287         markHeadsDirty();
01288         if (h->value() == value_false && eraseHead(PrgEdge::newEdge(h->id(), t, h->isAtom() ? PrgEdge::ATOM_NODE : PrgEdge::DISJ_NODE)) && t == PrgEdge::NORMAL_EDGE) {
01289                 return value() == value_false || (assignValue(value_false) && propagateValue(prg, prg.options().backprop));
01290         }
01291         return true;
01292 }
01293 
01294 bool PrgBody::propagateValue(LogicProgram& prg, bool backprop) {
01295         ValueRep val = value();
01296         assert(value() != value_free);
01297         // propagate value forward
01298         for (head_iterator h = heads_begin(), end = heads_end(); h != end; ++h) {
01299                 PrgHead* head = prg.getHead(*h);
01300                 if (val == value_false) {
01301                         head->removeSupport(PrgEdge::newEdge(id(), h->type(), PrgEdge::BODY_NODE));
01302                 }
01303                 else if (!h->isChoice() && head->value() != val && !prg.assignValue(head, val)) {
01304                         return false;
01305                 }
01306         }
01307         if (val == value_false) { clearHeads(); }
01308         // propagate value backward
01309         if (backprop && relevant()) {
01310                 const uint32 W = type() == BodyInfo::SUM_BODY;
01311                 weight_t MAX_W = 1;
01312                 weight_t* wPos = W == 0 ? &MAX_W : data_.ext[0]->weights;
01313                 MAX_W          = *std::max_element(wPos, wPos + (size() * W));
01314                 weight_t bound = value()==value_false ? this->bound() : (sumW() - this->bound())+1;
01315                 if (MAX_W >= bound) {
01316                         ValueRep goalVal;
01317                         for (const Literal* it = goals_begin(), *end = goals_end(); it != end; ++it) {
01318                                 if ((bound - *wPos) <= 0) {
01319                                         if (!it->sign()) { goalVal = val; }
01320                                         else             { goalVal = val == value_false ? value_weak_true : value_false; }
01321                                         if (!prg.assignValue(prg.getAtom(it->var()), goalVal)) {
01322                                                 return false;
01323                                         }
01324                                 }
01325                                 wPos += W;
01326                         }
01327                 }
01328         }
01329         return true;
01330 }
01331 
01332 // Adds nogoods for the tableau-rules FFB and BTB as well as FTB, BFB.
01333 // For normal bodies, clauses are used, i.e:
01334 //   FFB and BTB:
01335 //     - a binary clause [~b s] for every positive subgoal of b
01336 //     - a binary clause [~b ~n] for every negative subgoal of b
01337 //   FTB and BFB:
01338 //     - a clause [b ~s1...~sn n1..nn] where si is a positive and ni a negative subgoal
01339 // For count/sum bodies, a weight constraint is created
01340 bool PrgBody::addConstraints(const LogicProgram& prg, ClauseCreator& gc) {
01341         if (type() == BodyInfo::NORMAL_BODY) {
01342                 bool    taut= false;
01343                 Literal negB= ~literal();
01344                 gc.start().add(literal()); 
01345                 for (const Literal* it = goals_begin(), *end = goals_end(); it != end; ++it) {
01346                         assert(it->var() != 0);
01347                         Literal li = prg.getAtom(it->var())->literal() ^ it->sign();
01348                         if (li == literal()) { taut = true; continue; }
01349                         if (!prg.ctx()->addBinary(negB, li)) { // [~B li]
01350                                 return false;
01351                         }
01352                         if (li.var() != negB.var()) { gc.add(~li); }  // [B v ~l1 v ... v ~ln]
01353                 }
01354                 return taut || gc.end();
01355         }
01356         WeightLitVec lits;
01357         for (uint32 i = 0, end = size_; i != end; ++i) {
01358                 Literal eq = prg.getAtom(goal(i).var())->literal() ^ goal(i).sign();
01359                 lits.push_back(WeightLiteral(eq, weight(i)));
01360         }
01361         return WeightConstraint::create(*prg.ctx()->master(), literal(), lits, bound()).ok();
01362 }
01363 
01364 // Returns the SCC of body B, i.e.
01365 // - scc if exist atom a in B.heads(), a' in B+, s.th. a.scc == a'.scc
01366 // - noScc otherwise
01367 uint32 PrgBody::scc(const LogicProgram& prg) const {
01368         uint64 sccMask = 0;
01369         uint32 end     = size();
01370         uint32 scc     = PrgNode::noScc;
01371         bool   large   = false;
01372         for (uint32 i  = 0; i != end; ++i) {
01373                 if      (goal(i).sign()) { 
01374                         end = i; 
01375                         break; 
01376                 }
01377                 else if ((scc = prg.getAtom(goal(i).var())->scc()) != PrgNode::noScc) {
01378                         sccMask |= uint64(1) << (scc & 63);
01379                         large   |= scc > 63;
01380                 }
01381         }
01382         if (sccMask != 0) {
01383                 PrgDisj::atom_iterator aIt = 0, aEnd = 0;
01384                 Var atom;
01385                 for (head_iterator h = heads_begin(), hEnd = heads_end(); h != hEnd; ++h) {
01386                         if (h->isAtom()) { aIt = h; aEnd = h+1; }
01387                         else             { PrgDisj* d = prg.getDisj(h->node()); aIt = d->begin(), aEnd = d->end(); }
01388                         for (; aIt != aEnd; ++aIt) {
01389                                 atom = aIt->node();
01390                                 scc  = prg.getAtom(atom)->scc();
01391                                 if (scc != PrgNode::noScc && (sccMask & (uint64(1) << (scc&63))) != 0) {
01392                                         if (!large) { return scc; }
01393                                         for (uint32 j = 0; j != end; ++j) {
01394                                                 if (scc == prg.getAtom(goal(j).var())->scc()) { return scc; }
01395                                         }
01396                                 }
01397                         }
01398                 }
01399         }
01400         return PrgNode::noScc;
01401 }
01402 
01404 // class PrgDisj
01405 //
01406 // Head of a disjunctive rule
01408 PrgDisj* PrgDisj::create(uint32 id, const VarVec& heads) {
01409         void* m = ::operator new(sizeof(PrgDisj) + (heads.size()*sizeof(Var)));
01410         return new (m) PrgDisj(id, heads);
01411 }
01412 
01413 PrgDisj::PrgDisj(uint32 id, const VarVec& atoms) : PrgHead(id, PrgEdge::DISJ_NODE, (uint32)atoms.size()) {
01414         PrgEdge* a  = atoms_;
01415         for (VarVec::const_iterator it = atoms.begin(), end = atoms.end(); it != end; ++it) {
01416                 *a++ = PrgEdge::newEdge(*it, PrgEdge::CHOICE_EDGE, PrgEdge::ATOM_NODE);
01417         }
01418         std::sort(atoms_, atoms_+size());
01419 }
01420 PrgDisj::~PrgDisj() {}
01421 void PrgDisj::destroy() {
01422         this->~PrgDisj();
01423         ::operator delete(this);
01424 }
01425 
01426 void PrgDisj::detach(LogicProgram& prg) {
01427         PrgEdge edge = PrgEdge::newEdge(id(), PrgEdge::CHOICE_EDGE, PrgEdge::DISJ_NODE);
01428         for (atom_iterator it = begin(), end = this->end(); it != end; ++it) {
01429                 prg.getAtom(it->node())->removeSupport(edge);
01430         }
01431         EdgeVec temp; temp.swap(supports_);
01432         for (PrgDisj::sup_iterator it = temp.begin(), end = temp.end(); it != end; ++it) {
01433                 prg.getBody(it->node())->removeHead(this, PrgEdge::NORMAL_EDGE);
01434         }
01435         setInUpper(false);
01436         markRemoved();
01437 }
01438 
01439 bool PrgDisj::propagateAssigned(LogicProgram& prg, PrgHead* head, EdgeType t) {
01440         assert(head->isAtom() && t == PrgEdge::CHOICE_EDGE);
01441         if (prg.isFact(static_cast<PrgAtom*>(head)) || head->value() == value_false) {
01442                 atom_iterator it = std::find(begin(), end(), PrgEdge::newEdge(head->id(), t, PrgEdge::ATOM_NODE));
01443                 if (it != end()) {
01444                         if      (head->value() == value_true) { detach(prg); }
01445                         else if (head->value() == value_false){
01446                                 head->removeSupport(PrgEdge::newEdge(id(), t, PrgEdge::DISJ_NODE));
01447                                 std::copy(it+1, end(), (PrgEdge*)it);
01448                                 if (--data_ == 1) { 
01449                                         PrgAtom* last = prg.getAtom(begin()->node());
01450                                         EdgeVec temp;
01451                                         clearSupports(temp);
01452                                         for (EdgeVec::const_iterator it = temp.begin(), end = temp.end(); it != end; ++it) {
01453                                                 prg.getBody(it->node())->removeHead(this, PrgEdge::NORMAL_EDGE);
01454                                                 prg.getBody(it->node())->addHead(last, PrgEdge::NORMAL_EDGE);
01455                                         }
01456                                         detach(prg);
01457                                 }
01458                         }
01459                 }
01460         }
01461         return true;
01462 }
01463 
01464 } }


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