00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #ifndef CLASP_SOLVER_STRATEGIES_H_INCLUDED
00021 #define CLASP_SOLVER_STRATEGIES_H_INCLUDED
00022 #ifdef _MSC_VER
00023 #pragma once
00024 #endif
00025
00026 #include <clasp/constraint.h>
00027 #include <clasp/util/misc_types.h>
00028
00033 namespace Clasp {
00034
00036
00054 struct ScheduleStrategy {
00055 public:
00056 enum Type { geometric_schedule = 0, arithmetic_schedule = 1, luby_schedule = 2, user_schedule = 3 };
00057
00058 ScheduleStrategy(Type t = geometric_schedule, uint32 b = 100, double g = 1.5, uint32 o = 0);
00060 static ScheduleStrategy luby(uint32 unit, uint32 limit = 0) { return ScheduleStrategy(luby_schedule, unit, 0, limit); }
00062 static ScheduleStrategy geom(uint32 base, double grow, uint32 limit = 0) { return ScheduleStrategy(geometric_schedule, base, grow, limit); }
00064 static ScheduleStrategy arith(uint32 base, double add, uint32 limit = 0) { return ScheduleStrategy(arithmetic_schedule, base, add, limit); }
00066 static ScheduleStrategy fixed(uint32 base) { return ScheduleStrategy(arithmetic_schedule, base, 0, 0); }
00067 static ScheduleStrategy none() { return ScheduleStrategy(geometric_schedule, 0); }
00068 static ScheduleStrategy def() { return ScheduleStrategy(user_schedule, 0, 0.0); }
00069 uint64 current() const;
00070 bool disabled() const { return base == 0; }
00071 bool defaulted()const { return base == 0 && type == user_schedule; }
00072 void reset() { idx = 0; }
00073 uint64 next();
00074 void advanceTo(uint32 idx);
00075 uint32 base : 30;
00076 uint32 type : 2;
00077 uint32 idx;
00078 uint32 len;
00079 float grow;
00080 };
00081
00082 uint32 lubyR(uint32 idx);
00083 double growR(uint32 idx, double g);
00084 double addR(uint32 idx, double a);
00085 inline uint32 log2(uint32 x) {
00086 uint32 ln = 0;
00087 if (x & 0xFFFF0000u) { x >>= 16; ln |= 16; }
00088 if (x & 0xFF00u ) { x >>= 8; ln |= 8; }
00089 if (x & 0xF0u ) { x >>= 4; ln |= 4; }
00090 if (x & 0xCu ) { x >>= 2; ln |= 2; }
00091 if (x & 0x2u ) {; ln |= 1; }
00092 return ln;
00093 }
00094
00095 class DecisionHeuristic;
00096
00097 struct SolverStrategies {
00099 enum SearchStrategy {
00100 use_learning = 0,
00101 no_learning = 1
00102 };
00104 enum SignHeu {
00105 sign_atom = 0,
00106 sign_no = 1,
00107 sign_yes = 2,
00108 sign_rnd = 3,
00109 sign_disj = 4,
00110 };
00112 enum CCMinAntes {
00113 no_antes = 0,
00114 all_antes = 1,
00115 short_antes = 2,
00116 binary_antes = 3,
00117 };
00119 enum CCRepMode {
00120 cc_no_replace = 0,
00121 cc_rep_decision= 1,
00122 cc_rep_uip = 2,
00123 cc_rep_dynamic = 3,
00124 };
00125 enum OptHeu {
00126 opt_sign = 1,
00127 opt_model = 2,
00128 };
00130 enum OptStrategy {
00131 opt_def = 0,
00132 opt_hier = 1,
00133 opt_inc = 2,
00134 opt_dec = 3,
00135 opt_unsat = 4,
00136 opt_unsat_pre= 5,
00137 };
00138 enum WatchInit { watch_first = 0, watch_rand = 1, watch_least = 2 };
00139 enum UpdateMode { update_on_propagate = 0, update_on_conflict = 1 };
00140
00141 SolverStrategies();
00142 void prepare();
00143
00144 uint32 compress : 16;
00145 uint32 saveProgress : 16;
00146
00147 uint32 reverseArcs : 2;
00148 uint32 otfs : 2;
00149 uint32 updateLbd : 2;
00150 uint32 ccMinAntes : 2;
00151 uint32 ccRepMode : 2;
00152 uint32 initWatches : 2;
00153 uint32 optHeu : 2;
00154 uint32 upMode : 1;
00155 uint32 bumpVarAct : 1;
00156 uint32 search : 1;
00157 uint32 restartOnModel: 1;
00158 uint32 signDef : 3;
00159 uint32 signFix : 1;
00160 uint32 loadCfg : 1;
00161 uint32 id : 6;
00162 uint32 heuReserved : 3;
00163 };
00164
00166 struct SolverParams : SolverStrategies {
00167 SolverParams();
00168 uint32 prepare();
00169 uint32 seed;
00170
00171 uint32 heuParam : 16;
00172 uint32 lookOps : 16;
00173
00174 uint32 optStrat : 3;
00175 uint32 heuId : 3;
00176 uint32 heuOther : 2;
00177 uint32 heuReinit : 1;
00178 uint32 heuMoms : 1;
00179 uint32 berkHuang : 1;
00180 uint32 berkOnce : 1;
00181 uint32 unitNant : 1;
00182 uint32 lookType : 2;
00183 uint32 loopRep : 2;
00184 uint32 ccMinRec : 1;
00185 uint32 dropLearnt: 2;
00186 uint32 domPref : 6;
00187 uint32 domMod : 3;
00188 uint32 reserved : 3;
00189 };
00190
00191 typedef Range<uint32> Range32;
00192
00194
00197 struct RestartParams {
00198 RestartParams() : sched(), counterRestart(0), counterBump(9973), shuffle(0), shuffleNext(0), upRestart(0), cntLocal(0), dynRestart(0) {}
00199 enum SeqUpdate { seq_continue = 0, seq_repeat = 1, seq_disable = 2 };
00200 uint32 prepare(bool withLookback);
00201 void disable();
00202 bool dynamic() const { return dynRestart != 0; }
00203 bool local() const { return cntLocal != 0; }
00204 SeqUpdate update() const { return static_cast<SeqUpdate>(upRestart); }
00205 ScheduleStrategy sched;
00206 uint32 counterRestart:16;
00207 uint32 counterBump:16;
00208 uint32 shuffle :14;
00209 uint32 shuffleNext:14;
00210 uint32 upRestart : 2;
00211 uint32 cntLocal : 1;
00212 uint32 dynRestart : 1;
00213 };
00214
00216
00220 struct ReduceStrategy {
00222 enum Algorithm {
00223 reduce_linear = 0,
00224 reduce_stable = 1,
00225 reduce_sort = 2,
00226 reduce_heap = 3
00227 };
00229 enum Score {
00230 score_act = 0,
00231 score_lbd = 1,
00232 score_both = 2
00233 };
00234 enum EstimateSize {
00235 est_dynamic = 0,
00236 est_con_complexity = 1,
00237 est_num_constraints = 2,
00238 est_num_vars = 3
00239 };
00240 static uint32 scoreAct(const Activity& act) { return act.activity(); }
00241 static uint32 scoreLbd(const Activity& act) { return uint32(128)-act.lbd(); }
00242 static uint32 scoreBoth(const Activity& act) { return (act.activity()+1) * scoreLbd(act); }
00243 ReduceStrategy() : glue(0), fReduce(75), fRestart(0), score(0), algo(0), estimate(0), noGlue(0) {}
00244 static int compare(Score sc, const Clasp::Activity& lhs, const Clasp::Activity& rhs) {
00245 int fs = 0;
00246 if (sc == score_act) { fs = ((int)scoreAct(lhs)) - ((int)scoreAct(rhs)); }
00247 else if (sc == score_lbd) { fs = ((int)scoreLbd(lhs)) - ((int)scoreLbd(rhs)); }
00248 return fs != 0 ? fs : ((int)scoreBoth(lhs)) - ((int)scoreBoth(rhs));
00249 }
00250 static uint32 asScore(Score sc, const Clasp::Activity& act) {
00251 if (sc == score_act) { return scoreAct(act); }
00252 if (sc == score_lbd) { return scoreLbd(act); }
00253 { return scoreBoth(act);}
00254 }
00255 uint32 glue : 8;
00256 uint32 fReduce : 7;
00257 uint32 fRestart: 7;
00258 uint32 score : 2;
00259 uint32 algo : 2;
00260 uint32 estimate: 2;
00261 uint32 noGlue : 1;
00262 };
00263
00265
00273 struct ReduceParams {
00274 ReduceParams() : cflSched(ScheduleStrategy::none()), growSched(ScheduleStrategy::def())
00275 , fInit(1.0f/3.0f)
00276 , fMax(3.0f)
00277 , fGrow(1.1f)
00278 , initRange(10, UINT32_MAX)
00279 , maxRange(UINT32_MAX)
00280 , memMax(0) {}
00281 void disable();
00282 uint32 prepare(bool withLookback);
00283 Range32 sizeInit(const SharedContext& ctx) const;
00284 uint32 cflInit(const SharedContext& ctx) const;
00285 uint32 getBase(const SharedContext& ctx) const;
00286 float fReduce() const { return strategy.fReduce / 100.0f; }
00287 float fRestart() const { return strategy.fRestart/ 100.0f; }
00288 static uint32 getLimit(uint32 base, double f, const Range<uint32>& r);
00289 ScheduleStrategy cflSched;
00290 ScheduleStrategy growSched;
00291 ReduceStrategy strategy;
00292 float fInit;
00293 float fMax;
00294 float fGrow;
00295 Range32 initRange;
00296 uint32 maxRange;
00297 uint32 memMax;
00298 };
00299
00301
00304 struct SolveParams {
00306
00313 SolveParams();
00314 uint32 prepare(bool withLookback);
00315 bool randomize(Solver& s) const;
00316 RestartParams restart;
00317 ReduceParams reduce;
00318 uint32 randRuns:16;
00319 uint32 randConf:16;
00320 float randProb;
00321 struct FwdCheck {
00322 uint32 initHigh : 24;
00323 uint32 highPct : 7;
00324 uint32 incHigh : 1;
00325 FwdCheck() { *reinterpret_cast<uint32*>(this) = 0; }
00326 } fwdCheck;
00327 };
00328
00329 class SharedContext;
00330 class SatPreprocessor;
00331
00333 struct SatPreParams {
00334 enum Mode {
00335 prepro_preserve_sat = 0,
00336 prepro_preserve_models = 1,
00337 };
00338 enum Type {
00339 sat_pre_no = 0,
00340 sat_pre_ve = 1,
00341 sat_pre_ve_bce = 2,
00342 sat_pre_full = 3,
00343 };
00344 SatPreParams() : type(0u), mode(0u), limIters(0u), limTime(0u), limFrozen(0u), limClause(4000u), limOcc(0u) {}
00345 uint32 type : 2;
00346 uint32 mode : 1;
00347 uint32 limIters : 10;
00348 uint32 limTime : 12;
00349 uint32 limFrozen: 7;
00350 uint32 limClause: 16;
00351 uint32 limOcc : 16;
00352 bool clauseLimit(uint32 nc) const { return limClause && nc > (limClause*1000u); }
00353 bool occLimit(uint32 pos, uint32 neg) const { return limOcc && pos > (limOcc-1u) && neg > (limOcc-1u); }
00354 uint32 bce() const { return type != sat_pre_no ? type - 1 : 0; }
00355 void disableBce() { type = std::min(type, uint32(sat_pre_ve));}
00356 static SatPreprocessor* create(const SatPreParams&);
00357 };
00358
00360 struct ContextParams {
00362 enum ShortMode {
00363 short_implicit = 0,
00364 short_explicit = 1,
00365 };
00367 enum ShareMode {
00368 share_no = 0,
00369 share_problem = 1,
00370 share_learnt = 2,
00371 share_all = 3,
00372 share_auto = 4,
00373 };
00374 ContextParams() : shareMode(share_auto), stats(0), shortMode(short_implicit), seed(0), reserved(0), cliConfig(0), cliId(0), cliMode(0) {}
00375 SatPreParams satPre;
00376 uint8 shareMode : 3;
00377 uint8 stats : 2;
00378 uint8 shortMode : 1;
00379 uint8 seed : 1;
00380 uint8 reserved : 1;
00381 uint8 cliConfig;
00382 uint8 cliId;
00383 uint8 cliMode;
00384 };
00385
00387 class Configuration {
00388 public:
00389 typedef SolverParams SolverOpts;
00390 typedef SolveParams SearchOpts;
00391 typedef ContextParams CtxOpts;
00392 virtual ~Configuration();
00394 virtual void prepare(SharedContext&) = 0;
00396 virtual const CtxOpts& context() const = 0;
00398 virtual uint32 numSolver() const = 0;
00400 virtual uint32 numSearch() const = 0;
00402 virtual const SolverOpts& solver(uint32 i) const = 0;
00404 virtual const SearchOpts& search(uint32 i) const = 0;
00406
00410 virtual DecisionHeuristic* heuristic(uint32 i) const = 0;
00412
00417 virtual bool addPost(Solver& s) const;
00418 };
00419
00421 class UserConfiguration : public Configuration {
00422 public:
00424
00429 virtual bool addPost(Solver& s) const;
00431 virtual SolverOpts& addSolver(uint32 i) = 0;
00433 virtual SearchOpts& addSearch(uint32 i) = 0;
00434 };
00435
00436 class BasicSatConfig : public UserConfiguration, public ContextParams {
00437 public:
00438 BasicSatConfig();
00439 void prepare(SharedContext&);
00440 const CtxOpts& context() const { return *this; }
00441 uint32 numSolver() const { return solver_.size(); }
00442 uint32 numSearch() const { return search_.size(); }
00443 const SolverOpts& solver(uint32 i) const { return solver_[i % solver_.size() ]; }
00444 const SearchOpts& search(uint32 i) const { return search_[i % search_.size() ]; }
00445 DecisionHeuristic* heuristic(uint32 i) const;
00446 SolverOpts& addSolver(uint32 i);
00447 SearchOpts& addSearch(uint32 i);
00448
00449 virtual void reset();
00450 virtual void resize(uint32 numSolver, uint32 numSearch);
00451 private:
00452 typedef PodVector<SolverOpts>::type SolverVec;
00453 typedef PodVector<SearchOpts>::type SearchVec;
00454 SolverVec solver_;
00455 SearchVec search_;
00456 };
00457
00459 struct Heuristic_t {
00460 enum Type { heu_default = 0, heu_berkmin = 1, heu_vsids = 2, heu_vmtf = 3, heu_domain = 4, heu_unit = 5, heu_none = 6 };
00461 static inline bool isLookback(uint32 type) { return type >= (uint32)heu_berkmin && type <= (uint32)heu_vmtf; }
00462 static DecisionHeuristic* create(const SolverParams&);
00463 };
00464
00465 }
00466 #endif