00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #include <clasp/heuristics.h>
00021 #include <clasp/dependency_graph.h>
00022 #include <clasp/enumerator.h>
00023 #include <clasp/clause.h>
00024 #include <algorithm>
00025 #include <limits>
00026 #include <cstdlib>
00027 #include <string>
00028 #include <utility>
00029 namespace Clasp {
00031
00033 uint32 momsScore(const Solver& s, Var v) {
00034 uint32 sc;
00035 if (s.sharedContext()->numBinary()) {
00036 uint32 s1 = s.estimateBCP(posLit(v), 0) - 1;
00037 uint32 s2 = s.estimateBCP(negLit(v), 0) - 1;
00038 sc = ((s1 * s2)<<10) + (s1 + s2);
00039 }
00040 else {
00041
00042 uint32 s1 = s.numWatches(posLit(v));
00043 uint32 s2 = s.numWatches(negLit(v));
00044 sc = ((s1 * s2)<<10) + (s1 + s2);
00045 }
00046 return sc;
00047 }
00048
00050
00052 #define BERK_NUM_CANDIDATES 5
00053 #define BERK_CACHE_GROW 2.0
00054 #define BERK_MAX_MOMS_VARS 9999
00055 #define BERK_MAX_MOMS_DECS 50
00056 #define BERK_MAX_DECAY 65534
00057
00058 ClaspBerkmin::ClaspBerkmin(uint32 maxB, const HeuParams& params, bool berkHuang)
00059 : order_(berkHuang, params.resScore != 0)
00060 , topConflict_(UINT32_MAX)
00061 , topOther_(UINT32_MAX)
00062 , front_(1)
00063 , cacheSize_(5)
00064 , numVsids_(0)
00065 , maxBerkmin_(maxB == 0 ? UINT32_MAX : maxB) {
00066 if (params.otherScore > 0u) { types_.addSet(Constraint_t::learnt_loop); }
00067 if (params.otherScore ==2u) { types_.addSet(Constraint_t::learnt_other);}
00068 if (params.initScore) { types_.addSet(Constraint_t::static_constraint); }
00069 }
00070
00071 Var ClaspBerkmin::getMostActiveFreeVar(const Solver& s) {
00072 ++numVsids_;
00073
00074 for (Pos end = cache_.end(); cacheFront_ != end; ++cacheFront_) {
00075 if (s.value(*cacheFront_) == value_free) {
00076 return *cacheFront_;
00077 }
00078 }
00079
00080 if (!cache_.empty() && cacheSize_ < s.numFreeVars()/10) {
00081 cacheSize_ = static_cast<uint32>( (cacheSize_*BERK_CACHE_GROW) + .5 );
00082 }
00083 cache_.clear();
00084 Order::Compare comp(&order_);
00085
00086 for (; s.value( front_ ) != value_free; ++front_) {;}
00087 Var v = front_;
00088 LitVec::size_type cs = std::min(cacheSize_, s.numFreeVars());
00089 for (;;) {
00090 cache_.push_back(v);
00091 std::push_heap(cache_.begin(), cache_.end(), comp);
00092 if (cache_.size() == cs) break;
00093 while ( s.value(++v) != value_free ) {;}
00094 }
00095 for (v = (cs == cacheSize_ ? v+1 : s.numVars()+1); v <= s.numVars(); ++v) {
00096
00097 if (s.value(v) == value_free && comp(v, cache_[0])) {
00098 std::pop_heap(cache_.begin(), cache_.end(), comp);
00099 cache_.back() = v;
00100 std::push_heap(cache_.begin(), cache_.end(), comp);
00101 }
00102 }
00103 std::sort_heap(cache_.begin(), cache_.end(), comp);
00104 return *(cacheFront_ = cache_.begin());
00105 }
00106
00107 Var ClaspBerkmin::getTopMoms(const Solver& s) {
00108
00109 for (; s.value( front_ ) != value_free; ++front_) {;}
00110 Var var = front_;
00111 uint32 ms = momsScore(s, var);
00112 uint32 ls = 0;
00113 for (Var v = var+1; v <= s.numVars(); ++v) {
00114 if (s.value(v) == value_free && (ls = momsScore(s, v)) > ms) {
00115 var = v;
00116 ms = ls;
00117 }
00118 }
00119 if (++numVsids_ >= BERK_MAX_MOMS_DECS || ms < 2) {
00120
00121
00122 hasActivities(true);
00123 }
00124 return var;
00125 }
00126
00127 void ClaspBerkmin::startInit(const Solver& s) {
00128 if (s.configuration().heuReinit) {
00129 order_.score.clear();
00130 order_.decay = 0;
00131 }
00132 if (order_.score.empty()) {
00133 rng_.srand(s.rng.seed());
00134 }
00135 order_.score.resize(s.numVars()+1);
00136 initHuang(order_.huang);
00137
00138 cache_.clear();
00139 cacheSize_ = 5;
00140 cacheFront_ = cache_.end();
00141
00142 freeLits_.clear();
00143 freeOtherLits_.clear();
00144 topConflict_ = topOther_ = (uint32)-1;
00145
00146 front_ = 1;
00147 numVsids_ = 0;
00148 }
00149
00150 void ClaspBerkmin::endInit(Solver& s) {
00151 if (initHuang()) {
00152 const bool clearScore = types_.inSet(Constraint_t::static_constraint);
00153
00154 cache_.clear();
00155 for (Var v = 1; v <= s.numVars(); ++v) {
00156 order_.decayedScore(v);
00157 if (order_.occ(v) != 0 && s.pref(v).get(ValueSet::saved_value) == value_free) {
00158 s.setPref(v, ValueSet::saved_value, order_.occ(v) > 0 ? value_true : value_false);
00159 }
00160 if (clearScore) order_.score[v] = HScore(order_.decay);
00161 else cache_.push_back(v);
00162 }
00163 initHuang(false);
00164 }
00165 if (!types_.inSet(Constraint_t::static_constraint) || s.numFreeVars() > BERK_MAX_MOMS_VARS) {
00166 hasActivities(true);
00167 }
00168 std::stable_sort(cache_.begin(), cache_.end(), Order::Compare(&order_));
00169 cacheFront_ = cache_.begin();
00170 }
00171
00172 void ClaspBerkmin::updateVar(const Solver& s, Var v, uint32 n) {
00173 if (s.validVar(v)) { growVecTo(order_.score, v+n); }
00174 front_ = 1;
00175 cache_.clear();
00176 cacheFront_ = cache_.end();
00177 }
00178
00179 void ClaspBerkmin::newConstraint(const Solver&, const Literal* first, LitVec::size_type size, ConstraintType t) {
00180 if (t == Constraint_t::learnt_conflict) {
00181 hasActivities(true);
00182 }
00183 if (order_.huang == (t == Constraint_t::static_constraint)) {
00184 for (const Literal* x = first, *end = first+size; x != end; ++x) {
00185 order_.incOcc(*x);
00186 }
00187 }
00188 }
00189
00190 void ClaspBerkmin::updateReason(const Solver& s, const LitVec& lits, Literal r) {
00191 const bool ms = !order_.once;
00192 for (LitVec::size_type i = 0, e = lits.size(); i != e; ++i) {
00193 if (ms || !s.seen(lits[i])) {
00194 order_.inc(~lits[i]);
00195 }
00196 }
00197 if (!isSentinel(r)) { order_.inc(r); }
00198 }
00199
00200 bool ClaspBerkmin::bump(const Solver&, const WeightLitVec& lits, double adj) {
00201 for (WeightLitVec::const_iterator it = lits.begin(), end = lits.end(); it != end; ++it) {
00202 uint32 xf = order_.decayedScore(it->first.var()) + static_cast<weight_t>(it->second*adj);
00203 order_.score[it->first.var()].act = (uint16)std::min(xf, UINT32_MAX>>16);
00204 }
00205 return true;
00206 }
00207
00208 void ClaspBerkmin::undoUntil(const Solver&, LitVec::size_type) {
00209 topConflict_ = topOther_ = static_cast<uint32>(-1);
00210 front_ = 1;
00211 cache_.clear();
00212 cacheFront_ = cache_.end();
00213 if (cacheSize_ > 5 && numVsids_ > 0 && (numVsids_*3) < cacheSize_) {
00214 cacheSize_ = static_cast<uint32>(cacheSize_/BERK_CACHE_GROW);
00215 }
00216 numVsids_ = 0;
00217 }
00218
00219 bool ClaspBerkmin::hasTopUnsat(Solver& s) {
00220 topConflict_ = std::min(s.numLearntConstraints(), topConflict_);
00221 topOther_ = std::min(s.numLearntConstraints(), topOther_);
00222 assert(topConflict_ <= topOther_);
00223 freeOtherLits_.clear();
00224 freeLits_.clear();
00225 TypeSet ts = types_;
00226 if (ts.m > 1) {
00227 while (topOther_ > topConflict_) {
00228 if (s.getLearnt(topOther_-1).isOpen(s, ts, freeLits_) != 0) {
00229 freeLits_.swap(freeOtherLits_);
00230 ts.m = 0;
00231 break;
00232 }
00233 --topOther_;
00234 freeLits_.clear();
00235 }
00236 }
00237 ts.addSet(Constraint_t::learnt_conflict);
00238 uint32 stopAt = topConflict_ < maxBerkmin_ ? 0 : topConflict_ - maxBerkmin_;
00239 while (topConflict_ != stopAt) {
00240 uint32 x = s.getLearnt(topConflict_-1).isOpen(s, ts, freeLits_);
00241 if (x != 0) {
00242 if (x == Constraint_t::learnt_conflict) { break; }
00243 topOther_ = topConflict_;
00244 freeLits_.swap(freeOtherLits_);
00245 ts.m = 0;
00246 ts.addSet(Constraint_t::learnt_conflict);
00247 }
00248 --topConflict_;
00249 freeLits_.clear();
00250 }
00251 if (freeOtherLits_.empty()) topOther_ = topConflict_;
00252 if (freeLits_.empty()) freeOtherLits_.swap(freeLits_);
00253 return !freeLits_.empty();
00254 }
00255
00256 Literal ClaspBerkmin::doSelect(Solver& s) {
00257 const uint32 decayMask = order_.huang ? 127 : 511;
00258 if ( ((s.stats.choices + 1)&decayMask) == 0 ) {
00259 if ((order_.decay += (1+!order_.huang)) == BERK_MAX_DECAY) {
00260 order_.resetDecay();
00261 }
00262 }
00263 if (hasTopUnsat(s)) {
00264 assert(!freeLits_.empty());
00265 Literal x = selectRange(s, &freeLits_[0], &freeLits_[0]+freeLits_.size());
00266 return selectLiteral(s, x.var(), false);
00267 }
00268 else if (hasActivities()) {
00269 return selectLiteral(s, getMostActiveFreeVar(s), true);
00270 }
00271 else {
00272 return selectLiteral(s, getTopMoms(s), true);
00273 }
00274 }
00275
00276 Literal ClaspBerkmin::selectRange(Solver& s, const Literal* first, const Literal* last) {
00277 Literal candidates[BERK_NUM_CANDIDATES];
00278 candidates[0] = *first;
00279 uint32 c = 1;
00280 uint32 ms = static_cast<uint32>(-1);
00281 uint32 ls = 0;
00282 for (++first; first != last; ++first) {
00283 Var v = first->var();
00284 assert(s.value(v) == value_free);
00285 int cmp = order_.compare(v, candidates[0].var());
00286 if (cmp > 0) {
00287 candidates[0] = *first;
00288 c = 1;
00289 ms = static_cast<uint32>(-1);
00290 }
00291 else if (cmp == 0) {
00292 if (ms == static_cast<uint32>(-1)) ms = momsScore(s, candidates[0].var());
00293 if ( (ls = momsScore(s,v)) > ms) {
00294 candidates[0] = *first;
00295 c = 1;
00296 ms = ls;
00297 }
00298 else if (ls == ms && c != BERK_NUM_CANDIDATES) {
00299 candidates[c++] = *first;
00300 }
00301 }
00302 }
00303 return c == 1 ? candidates[0] : candidates[rng_.irand(c)];
00304 }
00305
00306 Literal ClaspBerkmin::selectLiteral(Solver& s, Var v, bool vsids) const {
00307 ValueSet pref = s.pref(v);
00308 int signScore = order_.occ(v);
00309 if (order_.huang && std::abs(signScore) > 32 && !pref.has(ValueSet::user_value)) {
00310 return Literal(v, signScore < 0);
00311 }
00312
00313 if (vsids && !pref.has(ValueSet::user_value | ValueSet::pref_value | ValueSet::saved_value)) {
00314 int32 w0 = (int32)s.estimateBCP(posLit(v), 5);
00315 int32 w1 = (int32)s.estimateBCP(negLit(v), 5);
00316 if (w1 != 1 || w0 != w1) { signScore = w0 - w1; }
00317 }
00318 return DecisionHeuristic::selectLiteral(s, v, signScore);
00319 }
00320
00321 void ClaspBerkmin::Order::resetDecay() {
00322 for (Scores::size_type i = 1, end = score.size(); i < end; ++i) {
00323 decayedScore(i);
00324 score[i].dec = 0;
00325 }
00326 decay = 0;
00327 }
00329
00331 ClaspVmtf::ClaspVmtf(LitVec::size_type mtf, const HeuParams& params) : decay_(0), MOVE_TO_FRONT(mtf >= 2 ? mtf : 2) {
00332 types_.addSet(Constraint_t::learnt_conflict);
00333 uint32 x = params.otherScore + 1;
00334 if (x & Constraint_t::learnt_loop) { types_.addSet(Constraint_t::learnt_loop); }
00335 if (x & Constraint_t::learnt_other){ types_.addSet(Constraint_t::learnt_other);}
00336 if (params.initScore) { types_.addSet(Constraint_t::static_constraint); }
00337 }
00338
00339
00340 void ClaspVmtf::startInit(const Solver& s) {
00341 if (s.configuration().heuReinit) { score_.clear(); vars_.clear(); decay_ = 0; }
00342 score_.resize(s.numVars()+1, VarInfo(vars_.end()));
00343 }
00344
00345 void ClaspVmtf::endInit(Solver& s) {
00346 bool moms = types_.inSet(Constraint_t::static_constraint);
00347 for (Var v = 1; v <= s.numVars(); ++v) {
00348 if (s.value(v) == value_free && score_[v].pos_ == vars_.end()) {
00349 score_[v].activity(decay_);
00350 if (moms) {
00351 score_[v].activity_ = momsScore(s, v);
00352 score_[v].decay_ = decay_+1;
00353 }
00354 score_[v].pos_ = vars_.insert(vars_.end(), v);
00355 }
00356 }
00357 if (moms) {
00358 vars_.sort(LessLevel(s, score_));
00359 for (VarList::iterator it = vars_.begin(), end = vars_.end(); it != end; ++it) {
00360 if (score_[*it].decay_ != decay_) {
00361 score_[*it].activity_ = 0;
00362 score_[*it].decay_ = decay_;
00363 }
00364 }
00365 }
00366 front_ = vars_.begin();
00367 }
00368
00369 void ClaspVmtf::updateVar(const Solver& s, Var v, uint32 n) {
00370 if (s.validVar(v)) {
00371 growVecTo(score_, v+n, VarInfo(vars_.end()));
00372 for (uint32 end = v+n; v != end; ++v) {
00373 if (score_[v].pos_ == vars_.end()) { score_[v].pos_ = vars_.insert(vars_.end(), v); }
00374 else { front_ = vars_.begin(); }
00375 }
00376 }
00377 else if (v < score_.size()) {
00378 if ((v + n) > score_.size()) { n = score_.size() - v; }
00379 for (uint32 x = v + n; x-- != v; ) {
00380 if (score_[x].pos_ != vars_.end()) {
00381 vars_.erase(score_[x].pos_);
00382 score_[x].pos_ = vars_.end();
00383 }
00384 }
00385 }
00386 }
00387
00388 void ClaspVmtf::simplify(const Solver& s, LitVec::size_type i) {
00389 for (; i < s.numAssignedVars(); ++i) {
00390 if (score_[s.trail()[i].var()].pos_ != vars_.end()) {
00391 vars_.erase(score_[s.trail()[i].var()].pos_);
00392 score_[s.trail()[i].var()].pos_ = vars_.end();
00393 }
00394 }
00395 front_ = vars_.begin();
00396 }
00397
00398 void ClaspVmtf::newConstraint(const Solver& s, const Literal* first, LitVec::size_type size, ConstraintType t) {
00399 if (t != Constraint_t::static_constraint) {
00400 LessLevel comp(s, score_);
00401 VarVec::size_type maxMove = t == Constraint_t::learnt_conflict ? MOVE_TO_FRONT : MOVE_TO_FRONT/2;
00402 const bool upAct = types_.inSet(t);
00403 for (LitVec::size_type i = 0; i < size; ++i, ++first) {
00404 Var v = first->var();
00405 score_[v].occ_ += 1 - (((int)first->sign())<<1);
00406 if (upAct) {
00407 ++score_[v].activity(decay_);
00408 if (mtf_.size() < maxMove) {
00409 mtf_.push_back(v);
00410 std::push_heap(mtf_.begin(), mtf_.end(), comp);
00411 }
00412 else if (comp(v, mtf_[0])) {
00413 assert(s.level(v) <= s.level(mtf_[0]));
00414 std::pop_heap(mtf_.begin(), mtf_.end(), comp);
00415 mtf_.back() = v;
00416 std::push_heap(mtf_.begin(), mtf_.end(), comp);
00417 }
00418 }
00419 }
00420 for (VarVec::size_type i = 0; i != mtf_.size(); ++i) {
00421 Var v = mtf_[i];
00422 if (score_[v].pos_ != vars_.end()) {
00423 vars_.splice(vars_.begin(), vars_, score_[v].pos_);
00424 }
00425 }
00426 mtf_.clear();
00427 front_ = vars_.begin();
00428 }
00429 }
00430
00431 void ClaspVmtf::undoUntil(const Solver&, LitVec::size_type) {
00432 front_ = vars_.begin();
00433 }
00434
00435 void ClaspVmtf::updateReason(const Solver&, const LitVec&, Literal r) {
00436 ++score_[r.var()].activity(decay_);
00437 }
00438
00439 bool ClaspVmtf::bump(const Solver&, const WeightLitVec& lits, double adj) {
00440 for (WeightLitVec::const_iterator it = lits.begin(), end = lits.end(); it != end; ++it) {
00441 score_[it->first.var()].activity(decay_) += static_cast<uint32>(it->second*adj);
00442 }
00443 return true;
00444 }
00445
00446 Literal ClaspVmtf::doSelect(Solver& s) {
00447 decay_ += ((s.stats.choices + 1) & 511) == 0;
00448 for (; s.value(*front_) != value_free; ++front_) {;}
00449 Literal c;
00450 if (s.numFreeVars() > 1) {
00451 VarList::iterator v2 = front_;
00452 uint32 distance = 0;
00453 do {
00454 ++v2;
00455 ++distance;
00456 } while (s.value(*v2) != value_free);
00457 c = (score_[*front_].activity(decay_) + (distance<<1)+ 3) > score_[*v2].activity(decay_)
00458 ? selectLiteral(s, *front_, score_[*front_].occ_)
00459 : selectLiteral(s, *v2, score_[*v2].occ_);
00460 }
00461 else {
00462 c = selectLiteral(s, *front_, score_[*front_].occ_);
00463 }
00464 return c;
00465 }
00466
00467 Literal ClaspVmtf::selectRange(Solver&, const Literal* first, const Literal* last) {
00468 Literal best = *first;
00469 for (++first; first != last; ++first) {
00470 if (score_[first->var()].activity(decay_) > score_[best.var()].activity(decay_)) {
00471 best = *first;
00472 }
00473 }
00474 return best;
00475 }
00476
00478
00480 template <class ScoreType>
00481 ClaspVsids_t<ScoreType>::ClaspVsids_t(double decay, const HeuParams& params)
00482 : vars_(CmpScore(score_))
00483 , decay_(1.0 / std::max(0.01, std::min(1.0, decay)))
00484 , inc_(1.0) {
00485 types_.addSet(Constraint_t::learnt_conflict);
00486 uint32 x = params.otherScore + 1;
00487 if (x & Constraint_t::learnt_loop) { types_.addSet(Constraint_t::learnt_loop); }
00488 if (x & Constraint_t::learnt_other){ types_.addSet(Constraint_t::learnt_other);}
00489 if (params.initScore) { types_.addSet(Constraint_t::static_constraint); }
00490 }
00491
00492 template <class ScoreType>
00493 void ClaspVsids_t<ScoreType>::startInit(const Solver& s) {
00494 if (s.configuration().heuReinit) { score_.clear(); occ_.clear(); vars_.clear(); inc_ = 1.0; }
00495 score_.resize(s.numVars()+1);
00496 occ_.resize(s.numVars()+1);
00497 vars_.reserve(s.numVars() + 1);
00498 }
00499
00500 template <class ScoreType>
00501 void ClaspVsids_t<ScoreType>::endInit(Solver& s) {
00502 vars_.clear();
00503 initScores(s, types_.inSet(Constraint_t::static_constraint));
00504 for (Var v = 1; v <= s.numVars(); ++v) {
00505 if (s.value(v) == value_free && !vars_.is_in_queue(v)) {
00506 vars_.push(v);
00507 }
00508 }
00509 }
00510 template <class ScoreType>
00511 void ClaspVsids_t<ScoreType>::updateVar(const Solver& s, Var v, uint32 n) {
00512 if (s.validVar(v)) {
00513 growVecTo(score_, v+n);
00514 growVecTo(occ_, v+n);
00515 for (uint32 end = v+n; v != end; ++v) { vars_.update(v); }
00516 }
00517 else {
00518 for (uint32 end = v+n; v != end; ++v) { vars_.remove(v); }
00519 }
00520 }
00521 template <class ScoreType>
00522 void ClaspVsids_t<ScoreType>::initScores(Solver& s, bool moms) {
00523 if (!moms) { return; }
00524 double maxS = 0.0, ms;
00525 for (Var v = 1; v <= s.numVars(); ++v) {
00526 if (s.value(v) == value_free && score_[v].get() == 0.0 && (ms = (double)momsScore(s, v)) != 0.0) {
00527 maxS = std::max(maxS, ms);
00528 score_[v].set(-ms);
00529 }
00530 }
00531 for (Var v = 1; v <= s.numVars(); ++v) {
00532 double d = score_[v].get();
00533 if (d < 0) {
00534 d *= -1.0;
00535 d /= maxS;
00536 score_[v].set(d);
00537 }
00538 }
00539 }
00540 template <class ScoreType>
00541 void ClaspVsids_t<ScoreType>::simplify(const Solver& s, LitVec::size_type i) {
00542 for (; i < s.numAssignedVars(); ++i) {
00543 vars_.remove(s.trail()[i].var());
00544 }
00545 }
00546
00547 template <class ScoreType>
00548 void ClaspVsids_t<ScoreType>::normalize() {
00549 const double min = std::numeric_limits<double>::min();
00550 const double minD = min * 1e100;
00551 inc_ *= 1e-100;
00552 for (LitVec::size_type i = 0; i != score_.size(); ++i) {
00553 double d = score_[i].get();
00554 if (d > 0) {
00555
00556
00557 d += minD;
00558 d *= 1e-100;
00559 }
00560 score_[i].set(d);
00561 }
00562 }
00563 template <class ScoreType>
00564 void ClaspVsids_t<ScoreType>::newConstraint(const Solver&, const Literal* first, LitVec::size_type size, ConstraintType t) {
00565 if (t != Constraint_t::static_constraint) {
00566 const bool upAct = types_.inSet(t);
00567 for (LitVec::size_type i = 0; i < size; ++i, ++first) {
00568 incOcc(*first);
00569 if (upAct) {
00570 updateVarActivity(first->var());
00571 }
00572 }
00573 if (t == Constraint_t::learnt_conflict) {
00574 inc_ *= decay_;
00575 }
00576 }
00577 }
00578 template <class ScoreType>
00579 void ClaspVsids_t<ScoreType>::updateReason(const Solver&, const LitVec&, Literal r) {
00580 if (r.var() != 0) updateVarActivity(r.var());
00581 }
00582 template <class ScoreType>
00583 bool ClaspVsids_t<ScoreType>::bump(const Solver&, const WeightLitVec& lits, double adj) {
00584 for (WeightLitVec::const_iterator it = lits.begin(), end = lits.end(); it != end; ++it) {
00585 updateVarActivity(it->first.var(), it->second*adj);
00586 }
00587 return true;
00588 }
00589 template <class ScoreType>
00590 void ClaspVsids_t<ScoreType>::undoUntil(const Solver& s , LitVec::size_type st) {
00591 const LitVec& a = s.trail();
00592 for (; st < a.size(); ++st) {
00593 if (!vars_.is_in_queue(a[st].var())) {
00594 vars_.push(a[st].var());
00595 }
00596 }
00597 }
00598 template <class ScoreType>
00599 Literal ClaspVsids_t<ScoreType>::doSelect(Solver& s) {
00600 while ( s.value(vars_.top()) != value_free ) {
00601 vars_.pop();
00602 }
00603 return selectLiteral(s, vars_.top(), occ(vars_.top()));
00604 }
00605 template <class ScoreType>
00606 Literal ClaspVsids_t<ScoreType>::selectRange(Solver&, const Literal* first, const Literal* last) {
00607 Literal best = *first;
00608 for (++first; first != last; ++first) {
00609 if (vars_.key_compare()(first->var(), best.var())) {
00610 best = *first;
00611 }
00612 }
00613 return best;
00614 }
00615 template class ClaspVsids_t<VsidsScore>;
00616
00618
00620 class DomainHeuristic::DomMinimize : public MinimizeConstraint {
00621 public:
00622 explicit DomMinimize(const LitVec& lits) : MinimizeConstraint(createDataFrom(lits)){ }
00623
00624 PropResult propagate(Solver&, Literal, uint32&) { return PropResult(true, true); }
00625 void reason(Solver&, Literal, LitVec&) { }
00626 bool simplify(Solver& s, bool) { simplifyDB(s, nogoods_, false); return false; }
00627 Constraint* cloneAttach(Solver&) { return 0; }
00628 void destroy(Solver*, bool);
00629
00630 bool attach(Solver&) { return true; }
00631 bool relax(Solver&, bool) { return true; }
00632 bool handleUnsat(Solver&, bool, LitVec&) { return false;}
00633 bool integrate(Solver& s);
00634 bool handleModel(Solver& s);
00635 private:
00636 static SharedMinimizeData* createDataFrom(const LitVec& lits) {
00637 SumVec adjust(1, 0);
00638 SharedMinimizeData* min = new (::operator new(sizeof(SharedMinimizeData) + ((1+lits.size())*sizeof(WeightLiteral)))) SharedMinimizeData(adjust, MinimizeMode_t::enumerate);
00639 WeightLiteral* x = min->lits;
00640 for (LitVec::const_iterator it = lits.begin(), end = lits.end(); it != end; ++it) {
00641 *x++ = WeightLiteral(*it, 1);
00642 }
00643 *x++ = WeightLiteral(posLit(0), 1);
00644 return min;
00645 }
00646 typedef PodVector<Constraint*>::type ConstraintDB;
00647 ConstraintDB nogoods_;
00648 LitVec clause_;
00649 };
00650 struct DomainHeuristic::CmpSymbol {
00651 bool operator()(const SymbolType& lhs, const SymbolType& rhs) const { return std::strcmp(lhs.name.c_str(), rhs.name.c_str()) < 0; }
00652 bool operator()(const SymbolType& lhs, const char* rhs) const { return std::strcmp(lhs.name.c_str(), rhs) < 0; }
00653 bool operator()(const char* lhs, const SymbolType& rhs) const { return std::strcmp(lhs, rhs.name.c_str()) < 0; }
00654 };
00655 const char* const DomainHeuristic::domKey_s = "_heuristic(";
00656 const char* const DomainHeuristic::domEnd_s = "_heuristic)";
00657 bool DomainHeuristic::match(const char*& in, const char* what) {
00658 if (!in || !what) { return what == in; }
00659 const char* t = in;
00660 while (*t && *what && *what == *t) { ++what, ++t; }
00661 return *what == 0 && (in = t) == t;
00662 }
00663 bool DomainHeuristic::matchDom(const char*& key, std::string& out) {
00664 if (!match(key, domKey_s)) { return false; }
00665 out.clear();
00666 for (int p = 0; (*key != ',' || p); ++key) {
00667 if (!*key) { throw std::runtime_error("Invalid domain atom!"); }
00668 else if (*key == '('){ ++p; }
00669 else if (*key == ')'){ --p; }
00670 out += *key;
00671 }
00672 return true;
00673 }
00674 bool DomainHeuristic::matchInt(const char*& key, int& out) {
00675 char* n; out = std::strtol(key, &n, 10);
00676 return key != n && (key = n) != 0;
00677 }
00678 bool DomainHeuristic::DomEntry::parse(const char*& key) {
00679 if (match(key, "init")) { mod = mod_init; }
00680 else if (match(key, "factor")){ mod = mod_factor; }
00681 else if (match(key, "level")) { mod = mod_level; }
00682 else if (match(key, "sign")) { mod = mod_sign; }
00683 else if (match(key, "true")) { mod = mod_tf; sign = sym->lit.sign(); }
00684 else if (match(key, "false")) { mod = mod_tf; sign = !sym->lit.sign(); }
00685 else { return false; }
00686 int temp;
00687 if (!match(key, ",") || !matchInt(key, temp)) {
00688 return false;
00689 }
00690 temp = Range<int>(INT16_MIN, INT16_MAX).clamp(temp);
00691 if (mod == mod_sign && temp) {
00692 temp = value_true + (uint8(temp < 0) ^ uint8(sym->lit.sign()));
00693 }
00694 val = (int16)temp;
00695 if (match(key, ",") && (!matchInt(key, temp) || temp < 0)) {
00696 return false;
00697 }
00698 prio = (uint16)Range<int>(0, INT16_MAX).clamp(std::abs(temp));
00699 return true;
00700 }
00701 DomainHeuristic::DomainHeuristic(double d, const HeuParams& params) : ClaspVsids_t<DomScore>(d, params), solver_(0) {
00702 frames_.push_back(Frame(0,UINT32_MAX));
00703 }
00704 DomainHeuristic::~DomainHeuristic() {
00705 if (solver_) { detach(); }
00706 }
00707 void DomainHeuristic::detach() {
00708 if (solver_) {
00709 for (SymbolTable::const_iterator it = solver_->symbolTable().begin(), end = solver_->symbolTable().end(); it != end; ++it) {
00710 if (it->second.lit.var() && !it->second.name.empty() && *it->second.name.c_str() == '_') {
00711 solver_->removeWatch(it->second.lit, this);
00712 }
00713 }
00714 while (frames_.back().dl != 0) {
00715 solver_->removeUndoWatch(frames_.back().dl, this);
00716 frames_.pop_back();
00717 }
00718 }
00719 actions_.clear();
00720 frames_.clear();
00721 dPrios_.clear();
00722 solver_ = 0;
00723 }
00724 void DomainHeuristic::startInit(const Solver& s) {
00725 BaseType::startInit(s);
00726 if (solver_ && (s.configuration().heuReinit || solver_ != &s)) {
00727 detach();
00728 }
00729 }
00730 void DomainHeuristic::initScores(Solver& s, bool moms) {
00731 if (moms) { BaseType::initScores(s, moms); }
00732 if (s.symbolTable().type() != SymbolTable::map_indirect) { return; }
00733 typedef std::pair<SymbolMap::iterator, SymbolMap::iterator> SymbolRange;
00734 SymbolMap symbols;
00735 for (SymbolTable::const_iterator it = s.configuration().heuReinit ? s.symbolTable().begin() : s.symbolTable().curBegin(), end = s.symbolTable().end(); it != end; ++it) {
00736 if (!it->second.name.empty()) { symbols.push_back(it->second); }
00737 }
00738 std::stable_sort(symbols.begin(), symbols.end(), CmpSymbol());
00739 SymbolRange domRange(std::lower_bound(symbols.begin(), symbols.end(), domKey_s, CmpSymbol()), std::lower_bound(symbols.begin(), symbols.end(), domEnd_s, CmpSymbol()));
00740 std::string name; SymbolType noSym(negLit(0), "");
00741 DomEntry last(&noSym, DomEntry::mod_init);
00742 Literal dyn;
00743 DomPrio prio;
00744 LitVec domMin;
00745 EnumerationConstraint* c = static_cast<EnumerationConstraint*>(s.enumerationConstraint());
00746 const MinimizeConstraint* m = c ? c->minimizer() : 0;
00747 const uint32 gPref = s.configuration().domPref;
00748 minLits_ = s.configuration().domMod >= uint32(gmod_max_value) && !m ? &domMin : 0;
00749 for (SymbolMap::iterator it = domRange.first; it != domRange.second; ++it) {
00750 const char* key = it->name.c_str();
00751 if (!matchDom(key, name)) { continue; }
00752 DomEntry e(last.sym);
00753 if (name != e.sym->name.c_str()) {
00754 SymbolMap::const_iterator heuAtom = std::lower_bound(symbols.begin(), symbols.end(), name.c_str(), CmpSymbol());
00755 if (heuAtom == symbols.end() || name != heuAtom->name.c_str()) { continue; }
00756 endInit(last, prio);
00757 e.sym = &(*heuAtom);
00758 last.sym= e.sym;
00759 last.val= last.prio = 0;
00760 prio.clear();
00761 if (!score_[e.sym->lit.var()].isDom()) {
00762 score_[e.sym->lit.var()].setDom((uint32)dPrios_.size());
00763 }
00764 }
00765 if (!match(key, ",") || !e.parse(key) || !match(key, ")") || *key) {
00766 throw std::runtime_error(std::string("Unknown domain entry: '").append(it->name.c_str()).append(1, '\''));
00767 }
00768 if (e.mod == DomEntry::mod_init) {
00769 if (e.prio >= last.prio && s.isTrue(it->lit)) { last = e; }
00770 continue;
00771 }
00772 for (int numAct = 1;;) {
00773 if (e.mod == DomEntry::mod_tf){ e.mod = DomEntry::mod_level; ++numAct; }
00774 if (e.prio >= prio[e.mod]) {
00775 if (s.isTrue(it->lit)) { prio[e.mod] = e.prio; }
00776 else if (it->lit != dyn) { (solver_=&s)->addWatch(it->lit, this, (uint32)actions_.size()); dyn = it->lit; }
00777 else { actions_.back().comp = 1; }
00778 addAction(s, *it, e);
00779 }
00780 if (--numAct == 0) { break; }
00781 e.mod = DomEntry::mod_sign;
00782 e.val = value_true + e.sign;
00783 }
00784 }
00785 endInit(last, prio);
00786
00787 if (gPref) {
00788 uint32 gModf = s.configuration().domMod;
00789 uint32 graph = gpref_scc | gpref_hcc | gpref_disj;
00790 if (gModf >= uint32(gmod_max_value)) {
00791 gModf = gModf == 6 ? gmod_false : gmod_true;
00792 }
00793 if ((gPref & gpref_min) != 0 && m) {
00794 weight_t w = -1;
00795 int16 x = gpref_show;
00796 for (const WeightLiteral* it = m->shared()->lits; !isSentinel(it->first); ++it) {
00797 if (x > 4 && it->second != w) {
00798 --x;
00799 w = it->second;
00800 }
00801 addAction(s, it->first, gModf, x);
00802 }
00803 }
00804 if ((gPref & graph) != 0 && s.sharedContext()->sccGraph.get()) {
00805 for (uint32 i = 0; i != s.sharedContext()->sccGraph->numAtoms(); ++i) {
00806 const SharedDependencyGraph::AtomNode& a = s.sharedContext()->sccGraph->getAtom(i);
00807 int16 lev = 0;
00808 if ((gPref & gpref_disj) != 0 && a.inDisjunctive()){ lev = 4; }
00809 else if ((gPref & gpref_hcc) != 0 && a.inNonHcf()) { lev = 3; }
00810 else if ((gPref & gpref_scc) != 0) { lev = 2; }
00811 addAction(s, a.lit, gModf, lev);
00812 }
00813 }
00814 if ((gPref & gpref_atom) != 0) {
00815 for (Var v = 1; v <= s.numVars(); ++v) {
00816 if ((s.varInfo(v).type() & Var_t::atom_var) != 0) { addAction(s, posLit(v), gModf, 1); }
00817 }
00818 }
00819 if ((gPref & gpref_show) != 0) {
00820 for (SymbolTable::const_iterator it = s.configuration().heuReinit ? s.symbolTable().begin() : s.symbolTable().curBegin(), end = s.symbolTable().end(); it != end; ++it) {
00821 if (!it->second.name.empty() && *it->second.name.c_str() != '_' && s.value(it->second.lit.var()) == value_free) {
00822 addAction(s, it->second.lit, gModf, gpref_show);
00823 }
00824 }
00825 }
00826 }
00827 LitVec::iterator j = domMin.begin();
00828 for (LitVec::const_iterator it = domMin.begin(), end = domMin.end(); it != end; ++it) {
00829 if (s.value(it->var()) == value_free && score_[it->var()].level > 0 && !s.seen(*it)) {
00830 s.markSeen(*it);
00831 *j++ = *it;
00832 }
00833 }
00834 domMin.erase(j, domMin.end());
00835 for (LitVec::const_iterator it = domMin.begin(), end = domMin.end(); it != end; ++it) { s.clearSeen(it->var()); }
00836 if (!domMin.empty()) {
00837 c->setMinimizer(new DomMinimize(domMin));
00838 }
00839 }
00840 void DomainHeuristic::addAction(Solver& s, const SymbolType& pre, const DomEntry& e) {
00841 assert(e.mod < DomEntry::mod_init);
00842 Var domVar = e.sym->lit.var();
00843 if (s.isTrue(pre.lit)) {
00844 if (e.mod == DomEntry::mod_level) { score_[domVar].level = e.val; }
00845 else if (e.mod == DomEntry::mod_factor){ score_[domVar].factor= e.val; }
00846 else if (e.mod == DomEntry::mod_sign) {
00847 s.setPref(domVar, ValueSet::user_value, e.signValue());
00848 if (minLits_) { minLits_->push_back(e.signValue() == falseValue(e.sym->lit) ? e.sym->lit : ~e.sym->lit); }
00849 }
00850 }
00851 else {
00852 if (score_[domVar].domKey == dPrios_.size()) { dPrios_.push_back(DomPrio()); }
00853 DomAction a = { domVar, (uint32)e.mod, uint32(0), UINT32_MAX, e.val, e.prio };
00854 actions_.push_back(a);
00855 }
00856 }
00857 void DomainHeuristic::addAction(Solver& s, Literal x, uint32 m, int16 lev) {
00858 if (x.var() && lev && !score_[x.var()].isDom()) {
00859 if ((m & gmod_level) != 0) {
00860 score_[x.var()].level = lev;
00861 }
00862 score_[x.var()].setDom((uint32)dPrios_.size());
00863 }
00864 if (x.var() && (m & (gmod_spos|gmod_sneg)) != 0) {
00865 if (!s.pref(x.var()).has(ValueSet::user_value)) {
00866 s.setPref(x.var(), ValueSet::user_value, (m & gmod_spos) != 0 ? trueValue(x) : falseValue(x));
00867 }
00868 if (minLits_) { minLits_->push_back((m & gmod_spos) != 0 ? ~x : x); }
00869 }
00870 }
00871
00872 Literal DomainHeuristic::doSelect(Solver& s) {
00873 Literal x = BaseType::doSelect(s);
00874 s.stats.addDomChoice(score_[x.var()].isDom());
00875 return x;
00876 }
00877
00878 Constraint::PropResult DomainHeuristic::propagate(Solver& s, Literal, uint32& aId) {
00879 uint32 n = aId;
00880 do {
00881 DomAction& a = actions_[n];
00882 uint16& prio = dPrios_[score_[a.var].domKey][a.mod];
00883 if (s.value(a.var) == value_free && a.prio >= prio) {
00884 applyAction(s, a, prio);
00885 pushUndo(s, n);
00886 }
00887 } while (actions_[n++].comp);
00888 return PropResult(true, true);
00889 }
00890
00891 void DomainHeuristic::applyAction(Solver& s, DomAction& a, uint16& gPrio) {
00892 std::swap(gPrio, a.prio);
00893 switch (a.mod) {
00894 default: assert(false); break;
00895 case DomEntry::mod_factor: std::swap(score_[a.var].factor, a.val); break;
00896 case DomEntry::mod_level:
00897 std::swap(score_[a.var].level, a.val);
00898 if (vars_.is_in_queue(a.var)) { vars_.update(a.var); }
00899 break;
00900 case DomEntry::mod_sign:
00901 ValueSet old = s.pref(a.var);
00902 s.setPref(a.var, ValueSet::user_value, ValueRep(a.val));
00903 a.val = old.get(ValueSet::user_value);
00904 break;
00905 }
00906 }
00907 void DomainHeuristic::pushUndo(Solver& s, uint32 actionId) {
00908 if (s.decisionLevel() != frames_.back().dl) {
00909 frames_.push_back(Frame(s.decisionLevel(), UINT32_MAX));
00910 s.addUndoWatch(s.decisionLevel(), this);
00911 }
00912 actions_[actionId].undo = frames_.back().head;
00913 frames_.back().head = actionId;
00914 }
00915
00916 void DomainHeuristic::undoLevel(Solver& s) {
00917 while (frames_.back().dl >= s.decisionLevel()) {
00918 for (uint32 n = frames_.back().head; n != UINT32_MAX;) {
00919 DomAction& a = actions_[n];
00920 n = a.undo;
00921 applyAction(s, a, dPrios_[score_[a.var].domKey][a.mod]);
00922 }
00923 frames_.pop_back();
00924 }
00925 }
00926
00927 void DomainHeuristic::DomMinimize::destroy(Solver* s, bool b) {
00928 while (!nogoods_.empty()) {
00929 nogoods_.back()->destroy(s, b);
00930 nogoods_.pop_back();
00931 }
00932 MinimizeConstraint::destroy(s, b);
00933 }
00934 bool DomainHeuristic::DomMinimize::handleModel(Solver& s) {
00935 clause_.push_back(~s.sharedContext()->stepLiteral());
00936 for (const WeightLiteral* lits = shared_->lits; !isSentinel(lits->first); ++lits) {
00937 if (s.isTrue(lits->first)) { clause_.push_back(~lits->first); }
00938 }
00939 return true;
00940 }
00941 bool DomainHeuristic::DomMinimize::integrate(Solver& s) {
00942 if (clause_.empty()) { return true; }
00943
00944 ClauseInfo e(Constraint_t::learnt_other);
00945 ClauseCreator::Result ret = ClauseCreator::create(s, clause_, ClauseCreator::clause_no_add, e);
00946 clause_.clear();
00947 if (ret.local) { nogoods_.push_back(ret.local); }
00948 return ret.ok();
00949 }
00950
00951 template class ClaspVsids_t<DomScore>;
00952 }