00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #include <clasp/lookahead.h>
00021 #include <algorithm>
00022 namespace Clasp {
00024
00026 uint32 ScoreLook::countNant(const Solver& s, const Literal* b, const Literal *e) const {
00027 uint32 sc = 1;
00028 for (; b != e; ++b) { sc += s.varInfo(b->var()).nant(); }
00029 return sc;
00030 }
00031 void ScoreLook::scoreLits(const Solver& s, const Literal* b, const Literal *e) {
00032 assert(b < e);
00033 uint32 sc = !nant ? uint32(e-b) : countNant(s, b, e);
00034 Var v = b->var();
00035 assert(validVar(v));
00036 score[v].setScore(*b, sc);
00037 if (addDeps) {
00038 if ((score[v].testedBoth() || mode == score_max) && greater(v, best)) {
00039 best = v;
00040 }
00041 for (; b != e; ++b) {
00042 v = b->var();
00043 if (validVar(v) && (s.varInfo(v).type() & types) != 0) {
00044 if (!score[v].seen()) { deps.push_back(v); }
00045 score[v].setDepScore(*b, sc);
00046 score[v].setSeen(*b);
00047 }
00048 }
00049 }
00050 }
00051 void ScoreLook::clearDeps() {
00052 for (VarVec::size_type i = 0, end = deps.size(); i != end; ++i) {
00053 score[deps[i]].clear();
00054 }
00055 deps.clear();
00056 best = 0;
00057 }
00058 bool ScoreLook::greater(Var lhs, Var rhs) const {
00059 uint32 rhsMax, rhsMin;
00060 score[rhs].score(rhsMax, rhsMin);
00061 return mode == score_max
00062 ? greaterMax(lhs, rhsMax)
00063 : greaterMaxMin(lhs, rhsMax, rhsMin);
00064 }
00066
00068 Lookahead::Lookahead(const Params& p)
00069 : nodes_(2, LitNode(posLit(0)))
00070 , last_(head_id)
00071 , pos_(head_id)
00072 , top_(uint32(-2))
00073 , limit_(0) {
00074 head()->next = head_id;
00075 undo()->next = UINT32_MAX;
00076 if (p.type != hybrid_lookahead) {
00077 score.mode = ScoreLook::score_max_min;
00078 score.types= (p.type == body_lookahead)
00079 ? Var_t::body_var
00080 : Var_t::atom_var;
00081 }
00082 else {
00083 score.mode = ScoreLook::score_max;
00084 score.types= Var_t::atom_body_var;
00085 }
00086 if (p.topLevelImps) { head()->lit.watch(); }
00087 score.nant = p.restrictNant;
00088 }
00089
00090 Lookahead::~Lookahead() { }
00091
00092 void Lookahead::destroy(Solver* s, bool detach) {
00093 if (s && detach) {
00094 s->removePost(this);
00095 while (saved_.size()>1) {
00096 s->removeUndoWatch(uint32(saved_.size()-1), this);
00097 saved_.pop_back();
00098 }
00099 }
00100 PostPropagator::destroy(s, detach);
00101 }
00102
00103 uint32 Lookahead::priority() const { return priority_reserved_look; }
00104
00105 void Lookahead::clear() {
00106 score.clearDeps();
00107 while (!saved_.empty()) {
00108 if (saved_.back() != UINT32_MAX) {
00109 splice(saved_.back());
00110 }
00111 saved_.pop_back();
00112 }
00113 LookList(2, *head()).swap(nodes_);
00114 head()->next = head_id;
00115 undo()->next = UINT32_MAX;
00116 last_ = head_id;
00117 top_ = UINT32_MAX;
00118 }
00119
00120 bool Lookahead::init(Solver& s) {
00121 ScoreLook& sc = score;
00122 sc.clearDeps();
00123 Var start = (uint32)sc.score.size();
00124 sc.score.resize(s.numVars()+1);
00125 const VarType types= sc.types;
00126 const bool uniform = types != Var_t::atom_body_var;
00127 uint32 add = 0;
00128 uint32 nants = 0;
00129 for (Var v = start; v <= s.numVars(); ++v) {
00130 if (s.value(v) == value_free && (s.varInfo(v).type() & types) != 0 ) {
00131 ++add;
00132 nants += s.varInfo(v).nant();
00133 }
00134 }
00135 nodes_.reserve(nodes_.size() + add);
00136 for (Var v = start; v <= s.numVars(); ++v) {
00137 if (s.value(v) == value_free && (s.varInfo(v).type() & types) != 0 ) {
00138 append(Literal(v, s.varInfo(v).preferredSign()), uniform || s.varInfo(v).type() == Var_t::atom_body_var);
00139 }
00140 }
00141 if (add && score.nant) {
00142 score.nant = add != nants && nants != 0;
00143 }
00144 return true;
00145 }
00146
00147 void Lookahead::append(Literal p, bool testBoth) {
00148 node(last_)->next = static_cast<NodeId>(nodes_.size());
00149 nodes_.push_back(LitNode(p));
00150 last_ = node(last_)->next;
00151 node(last_)->next = head_id;
00152
00153 if (testBoth) { node(last_)->lit.watch(); }
00154 }
00155
00156
00157 bool Lookahead::test(Solver& s, Literal p) {
00158 return (score.score[p.var()].seen(p) || s.test(p, this))
00159 && (!p.watched() || score.score[p.var()].seen(~p) || s.test(~p, this))
00160 && (imps_.empty() || checkImps(s, p));
00161 }
00162
00163 bool Lookahead::checkImps(Solver& s, Literal p) {
00164 assert(!imps_.empty());
00165 bool ok = true;
00166 if (score.score[p.var()].testedBoth()) {
00167 for (LitVec::const_iterator it = imps_.begin(), end = imps_.end(); it != end && ok; ++it) {
00168 ok = s.force(*it, posLit(0));
00169 }
00170 }
00171 imps_.clear();
00172 return ok && (s.queueSize() == 0 || s.propagateUntil(this));
00173 }
00174
00175
00176 bool Lookahead::propagateLevel(Solver& s) {
00177 assert(!s.hasConflict());
00178 saved_.resize(s.decisionLevel()+1, UINT32_MAX);
00179 uint32 undoId = saved_[s.decisionLevel()];
00180 if (undoId == UINT32_MAX) {
00181 undoId = undo_id;
00182 if (s.decisionLevel() != 0) {
00183 s.addUndoWatch(s.decisionLevel(), this);
00184 }
00185 }
00186 score.clearDeps();
00187 score.addDeps = true;
00188 Literal p = node(pos_)->lit;
00189 bool ok = s.value(p.var()) != value_free || test(s, p);
00190 for (LitNode* r = node(pos_); r->next != pos_ && ok; ) {
00191 p = node(r->next)->lit;
00192 if (s.value(p.var()) == value_free) {
00193 if (test(s, p)) { r = node(r->next); }
00194 else { pos_= r->next; ok = false; }
00195 }
00196 else if (r->next != last_ && r->next != head_id) {
00197
00198 NodeId t = r->next;
00199 r->next = node(t)->next;
00200
00201 LitNode* u = node(undoId);
00202 node(t)->next = u->next;
00203 u->next = t;
00204 undoId = t;
00205 }
00206 else { r = node(r->next); }
00207 }
00208 saved_.back() = undoId;
00209 return ok;
00210 }
00211
00212 bool Lookahead::propagateFixpoint(Solver& s, PostPropagator*) {
00213 if ((empty() || top_ == s.numAssignedVars()) && !score.deps.empty()) {
00214
00215 return true;
00216 }
00217 bool ok = true;
00218 uint32 dl;
00219 for (dl = s.decisionLevel(); !propagateLevel(s); dl = s.decisionLevel()) {
00220
00221
00222 assert(s.decisionLevel() >= dl);
00223 if (!s.resolveConflict() || !s.propagateUntil(this)) {
00224 ok = false;
00225 score.clearDeps();
00226 break;
00227 }
00228 }
00229 if (dl == 0 && ok) {
00230
00231
00232 assert(s.queueSize() == 0);
00233 top_ = s.numAssignedVars();
00234 LitVec().swap(imps_);
00235 }
00236 if (limit_ && !limit_->notify(s)) { Lookahead::destroy(&s, true); }
00237 return ok;
00238 }
00239
00240
00241 void Lookahead::splice(NodeId ul) {
00242 assert(ul != UINT32_MAX);
00243 if (ul != undo_id) {
00244 assert(undo()->next != UINT32_MAX);
00245
00246 LitNode* ulNode= node(ul);
00247 NodeId first = undo()->next;
00248 undo()->next = ulNode->next;
00249
00250 ulNode->next = head()->next;
00251 head()->next = first;
00252 }
00253 }
00254
00255 void Lookahead::undoLevel(Solver& s) {
00256 if (s.decisionLevel() == saved_.size()) {
00257 const LitVec& a = s.trail();
00258 score.scoreLits(s, &a[0]+s.levelStart(s.decisionLevel()), &a[0]+a.size());
00259 if (s.decisionLevel() == static_cast<uint32>(head()->lit.watched())) {
00260 const Literal* b = &a[0]+s.levelStart(s.decisionLevel());
00261 if (b->watched()) {
00262
00263 uint32 dist = static_cast<uint32>(((&a[0]+a.size()) - b));
00264 imps_.assign(b+1, b + std::min(dist, uint32(2048)));
00265 }
00266 else if (score.score[b->var()].testedBoth()) {
00267
00268
00269 LitVec::iterator j = imps_.begin();
00270 for (LitVec::iterator it = imps_.begin(), end = imps_.end(); it != end; ++it) {
00271 if (s.isTrue(*it)) { *j++ = *it; }
00272 }
00273 imps_.erase(j, imps_.end());
00274 }
00275 }
00276 }
00277 else {
00278 assert(saved_.size() >= s.decisionLevel()+1);
00279 saved_.resize(s.decisionLevel()+1);
00280 NodeId n = saved_.back();
00281 saved_.pop_back();
00282 splice(n);
00283 assert(node(last_)->next == head_id);
00284 score.clearDeps();
00285 }
00286 }
00287
00288 Literal Lookahead::heuristic(Solver& s) {
00289 if (s.value(score.best) != value_free) {
00290
00291 return posLit(0);
00292 }
00293 ScoreLook& sc = score;
00294 Literal choice= Literal(sc.best, sc.score[sc.best].prefSign());
00295 if (!sc.deps.empty() && sc.mode == ScoreLook::score_max_min) {
00296
00297 uint32 min, max;
00298 sc.score[sc.best].score(max, min);
00299 sc.addDeps = false;
00300 bool ok = true;
00301 LitVec::size_type i = 0;
00302 do {
00303 Var v = sc.deps[i];
00304 VarScore& vs = sc.score[v];
00305 if (s.value(v) == value_free) {
00306 uint32 vMin, vMax;
00307 vs.score(vMax, vMin);
00308 if (vMin == 0 || vMin > min || (vMin == min && vMax > max)) {
00309 uint32 neg = vs.score(negLit(v)) > 0 ? vs.score(negLit(v)) : max+1;
00310 uint32 pos = vs.score(posLit(v)) > 0 ? vs.score(posLit(v)) : max+1;
00311 if (!vs.tested(negLit(v))) {
00312 ok = ok && s.test(negLit(v), this);
00313 neg = vs.score(negLit(v));
00314 }
00315 if ((neg > min || (neg == min && pos > max)) && !vs.tested(posLit(v))) {
00316 ok = ok && s.test(posLit(v), this);
00317 }
00318 }
00319 if (vs.testedBoth() && sc.greaterMaxMin(v, max, min)) {
00320 vs.score(max, min);
00321 choice = Literal(v, vs.prefSign());
00322 }
00323 }
00324 } while (++i != sc.deps.size() && ok);
00325 if (!ok) {
00326
00327
00328
00329
00330
00331
00332 assert(s.hasConflict());
00333 return negLit(0);
00334 }
00335 }
00336 return choice;
00337 }
00338 void Lookahead::setLimit(UnitHeuristic* h) { limit_ = h; }
00340
00342 UnitHeuristic::UnitHeuristic(const Lookahead::Params& p)
00343 : look_(new Lookahead(p)) {
00344 }
00345
00346 void UnitHeuristic::endInit(Solver& s) {
00347 assert(s.decisionLevel() == 0);
00348 if (look_.is_owner()) {
00349 s.addPost(look_.release());
00350 }
00351 }
00352
00353 Literal UnitHeuristic::doSelect(Solver& s) {
00354 Literal x = look_->heuristic(s);
00355 if (x != posLit(0) || s.numFreeVars() == 0) { return x; }
00356
00357
00358
00359
00360 VarType types = look_->score.types;
00361 uint32 added = 0;
00362 for (Var v = 1, end = s.numProblemVars()+1; v != end; ++v) {
00363 if ((s.value(v) == value_free || s.level(v) > 0) && (s.varInfo(v).type() & types) == 0) {
00364 look_->append(Literal(v, s.varInfo(v).preferredSign()), true);
00365 ++added;
00366 }
00367 }
00368 assert(added);
00369 look_->score.clearDeps();
00370 look_->score.types = Var_t::atom_body_var;
00371 return s.propagate()
00372 ? look_->heuristic(s)
00373 : negLit(0);
00374 }
00375
00376 void UnitHeuristic::updateVar(const Solver& s, Var v, uint32 n) {
00377 if (s.validVar(v) && !s.auxVar(v)) {
00378 growVecTo(look_->score.score, v + n);
00379 for (uint32 end = v + n; v != end; ++v) {
00380 VarInfo vd = s.varInfo(v);
00381 if ((vd.type() & look_->score.types) != 0) {
00382 look_->append(Literal(v, vd.preferredSign()), vd.type() == Var_t::atom_body_var || look_->score.types != Var_t::atom_body_var);
00383 }
00384 }
00385 }
00386 }
00388
00390 class Restricted : public UnitHeuristic {
00391 public:
00392 typedef LitVec::size_type size_t;
00393 typedef ConstraintType con_t;
00394 Restricted(const Lookahead::Params& p, uint32 numOps, DecisionHeuristic* other)
00395 : UnitHeuristic(p)
00396 , other_(other)
00397 , numOps_(numOps) {
00398 }
00399 void restoreOther(Solver& s) {
00400 s.heuristic().reset(other_.release());
00401 }
00402
00403 bool notify(Solver& s) {
00404 if (--numOps_) { return UnitHeuristic::notify(s); }
00405 restoreOther(s);
00406 return false;
00407 }
00408 void updateVar(const Solver& s, Var v, uint32 n) { other_->updateVar(s, v, n); UnitHeuristic::updateVar(s, v, n); }
00409 void endInit(Solver& s) {
00410 UnitHeuristic::endInit(s);
00411 other_->endInit(s);
00412 if (numOps_ > 0){ look_->setLimit(this); }
00413 else { restoreOther(s); }
00414 }
00415 Literal doSelect(Solver& s) {
00416 return s.value(look_->score.best) == value_free
00417 ? UnitHeuristic::doSelect(s)
00418 : other_->doSelect(s);
00419 }
00420
00421 void startInit(const Solver& s) { other_->startInit(s); }
00422 void simplify(const Solver& s, size_t st) { other_->simplify(s, st); }
00423 void undoUntil(const Solver& s, size_t st){ other_->undoUntil(s, st); }
00424 void updateReason(const Solver& s, const LitVec& x, Literal r) { other_->updateReason(s, x, r); }
00425 bool bump(const Solver& s, const WeightLitVec& w, double d) { return other_->bump(s, w, d); }
00426 void newConstraint(const Solver& s, const Literal* p, size_t sz, con_t t) { other_->newConstraint(s, p, sz, t); }
00427 Literal selectRange(Solver& s, const Literal* f, const Literal* l) { return other_->selectRange(s, f, l); }
00428 private:
00429 typedef SingleOwnerPtr<DecisionHeuristic> HeuPtr;
00430 HeuPtr other_;
00431 uint32 numOps_;
00432 };
00433
00434 UnitHeuristic* UnitHeuristic::restricted(const Lookahead::Params& p, uint32 numOps, DecisionHeuristic* other) {
00435 return new Restricted(p, numOps, other);
00436 }
00437 }