Reasoner.cpp
Go to the documentation of this file.
00001 
00002 #include <actasp/reasoners/Reasoner.h>
00003 
00004 #include <actasp/QueryGenerator.h>
00005 #include <actasp/action_utils.h>
00006 
00007 #include "LexComparator.h"
00008 #include "IsNotLocallyOptimal.h"
00009 
00010 #include <vector>
00011 #include <functional>
00012 #include <sstream>
00013 #include <cmath>
00014 #include <iostream>
00015 #include <iterator>
00016 
00017 
00018 using namespace std;
00019 
00020 namespace actasp {
00021   
00022 Reasoner::Reasoner(QueryGenerator *actualReasoner,unsigned int max_n,const ActionSet& allActions) :
00023             clingo(actualReasoner), max_n(max_n), allActions(allActions) {}
00024   
00025 ActionSet Reasoner::availableActions() const throw() {
00026   list<AnswerSet> actions = clingo->lengthRangePlanQuery(vector<AspRule>(),true,1,1,0);
00027 
00028   ActionSet computed;
00029 
00030   list<AnswerSet>::iterator act = actions.begin();
00031   for (; act != actions.end(); ++act) {
00032     computed.insert(act->getFluents().begin(), act->getFluents().end());
00033   }
00034 
00035   return computed;
00036 }
00037 
00038 AnswerSet Reasoner::currentStateQuery(const std::vector<actasp::AspRule>& query) const throw() {
00039   return clingo->currentStateQuery(query);
00040 }
00041 
00042 struct fluent2Rule {
00043   
00044   fluent2Rule() : timeStep(0), useTimeStep(false) {}
00045   fluent2Rule(unsigned int timeStep) : timeStep(timeStep), useTimeStep(true) {}
00046     
00047   AspRule operator() (const AspFluent& fluent){
00048       AspRule rule;
00049       rule.head.push_back(fluent);
00050       if(useTimeStep)
00051         rule.head[0].setTimeStep(timeStep);
00052       return rule;
00053   }
00054   
00055   unsigned int timeStep;
00056   bool useTimeStep;
00057 };
00058 
00059 bool Reasoner::updateFluents(const std::vector<actasp::AspFluent> &observations) throw() {
00060 
00061   //copy the observations in the heads of rules
00062   vector<AspRule> obsRules;
00063   obsRules.reserve(observations.size()+1); //we'll add noop later
00064   transform(observations.begin(),observations.end(),back_inserter(obsRules),fluent2Rule(1));
00065   //add the rule for the noop action
00066   
00067   AspRule noopRule;
00068   noopRule.head.push_back(AspFluent("noop",vector<string>(),1));
00069   
00070   obsRules.push_back(noopRule);
00071 
00072   list<AnswerSet> currentState = clingo->genericQuery(obsRules,1,"observationQuery",1);
00073 
00074   if (currentState.empty())
00075     return false; //the observations are incompatible with the current state and are discarded
00076    
00077   //the last answer set is the one with the timestep at 1. The ones before may have 0.
00078   set<AspFluent> newStateFluents = currentState.rbegin()->getFluentsAtTime(1);
00079   
00080   newStateFluents.erase(AspFluent("noop",vector<string>(),1));
00081   
00082   clingo->setCurrentState(newStateFluents);
00083 
00084   return true;
00085 }
00086 
00087  bool Reasoner::isPlanValid(const AnswerSet& plan, const std::vector<actasp::AspRule>& goal)  const throw() {
00088 
00089   return !(clingo->monitorQuery(goal,plan).empty()); 
00090 }
00091 
00092 void Reasoner::resetCurrentState() throw() {
00093 clingo->setCurrentState(set<AspFluent>());
00094 }
00095 
00096 void Reasoner::setCurrentState(const std::set<actasp::AspFluent>& newState) throw() {
00097   clingo->setCurrentState(newState);
00098 }
00099 
00100 AnswerSet Reasoner::computePlan(const std::vector<actasp::AspRule>& goal) const throw (std::logic_error){
00101   list<AnswerSet> plans = clingo->minimalPlanQuery(goal,true,max_n,1);
00102   
00103   if(plans.empty())
00104     return AnswerSet();
00105   
00106   else return *(plans.begin()); //it's really at most one
00107 }
00108 
00109 struct AnswerSetToList {
00110   list <AspFluentRef> operator()(const AnswerSet& aset) const {
00111 
00112     return list <AspFluentRef>(aset.getFluents().begin(), aset.getFluents().end());
00113 
00114   }
00115 };
00116 
00117 struct PlanLongerThan {
00118 
00119   PlanLongerThan(unsigned int length) : length(length) {}
00120 
00121   bool operator()(const AnswerSet& plan) const {
00122     return plan.maxTimeStep() > length;
00123   }
00124 
00125   unsigned int length;
00126 };
00127 
00128 struct AnswerSetRef {
00129   AnswerSetRef(const AnswerSet& aset) : aset(&aset) {}
00130 
00131   operator const AnswerSet&() const {
00132     return *aset;
00133   }
00134 
00135   const AnswerSet *aset;
00136 };
00137 
00138 std::vector< AnswerSet > Reasoner::computeAllPlans(const std::vector<actasp::AspRule>& goal, double suboptimality) const throw (std::logic_error) {
00139 
00140   if (suboptimality < 1) {
00141     stringstream num;
00142     num << suboptimality;
00143     throw logic_error("Clingo: suboptimality value cannot be less then one, found: " + num.str());
00144   }
00145 
00146  
00147   list<AnswerSet> firstAnswerSets = clingo->minimalPlanQuery(goal,true,max_n,0);
00148 
00149   if (firstAnswerSets.empty())
00150     return vector<AnswerSet>();
00151 
00152   unsigned int shortestLength = firstAnswerSets.begin()->maxTimeStep();
00153 
00154   int maxLength = ceil(suboptimality * shortestLength);
00155 
00156   if (maxLength == shortestLength)
00157     return vector<AnswerSet>(firstAnswerSets.begin(), firstAnswerSets.end());
00158 
00159   set< list <AspFluentRef>, LexComparator > goodPlans;
00160   transform(firstAnswerSets.begin(), firstAnswerSets.end(),inserter(goodPlans,goodPlans.begin()),AnswerSetToList());
00161 
00162   list<AnswerSet> moreAnswerSets = clingo->lengthRangePlanQuery(goal,true,shortestLength+1,maxLength,0);
00163 
00164   list<AnswerSet>::iterator currentFirst = moreAnswerSets.begin();
00165 
00166   set< list<AspFluentRef>, LexComparator > badPlans;
00167   //this object remembers the set of bad plans, cannot be created inside the loop
00168 
00169   IsNotLocallyOptimal isNotLocallyOptimal(&goodPlans, &badPlans,allActions,shortestLength,true);
00170 
00171   list<AnswerSetRef> goodPointers(firstAnswerSets.begin(),firstAnswerSets.end());
00172   while (currentFirst != moreAnswerSets.end()) {
00173 
00174     //process the plans in groups of increasing length
00175 
00176     list<AnswerSet>::iterator currentLast = find_if(currentFirst,moreAnswerSets.end(),PlanLongerThan(currentFirst->maxTimeStep()));
00177 
00178     size_t size_pre_copy = goodPointers.size();
00179 
00180     remove_copy_if(currentFirst,currentLast,back_inserter(goodPointers),isNotLocallyOptimal);
00181 
00182     list<AnswerSetRef>::iterator from = goodPointers.begin();
00183     advance(from,size_pre_copy);
00184     transform(from, goodPointers.end(),inserter(goodPlans,goodPlans.begin()),AnswerSetToList());
00185 
00186     currentFirst = currentLast;
00187   }
00188 
00189   vector<AnswerSet> finalVector(goodPointers.begin(),goodPointers.end());
00190   
00191 //   cout << "  ---  good plans ---" << endl;
00192 //   vector< AnswerSet>::const_iterator printIt = finalVector.begin();
00193 //   for (; printIt != finalVector.end(); ++printIt) {
00194 //     copy(printIt->getFluents().begin(),printIt->getFluents().end(),ostream_iterator<string>(cout, " "));
00195 //     cout << endl;
00196 //   }
00197 //   cout << " ---- " << endl;
00198 
00199   return finalVector;
00200 
00201 }
00202 
00203 AnswerSet Reasoner::computeOptimalPlan(const std::vector<actasp::AspRule>& goal, bool filterActions, double suboptimality, bool minimum) const throw (std::logic_error) {
00204   if (suboptimality < 1) {
00205     stringstream num;
00206     num << suboptimality;
00207     throw logic_error("Clingo: suboptimality value cannot be less then one, found: " + num.str());
00208   }
00209 
00210  
00211   list<AnswerSet> firstAnswerSets = clingo->minimalPlanQuery(goal,true,max_n,0);
00212 
00213   if (firstAnswerSets.empty())
00214     return AnswerSet();
00215 
00216   unsigned int shortestLength = firstAnswerSets.begin()->maxTimeStep();
00217 
00218   int maxLength = ceil(suboptimality * shortestLength);
00219 
00220   AnswerSet optimalAnswerSet = clingo->optimalPlanQuery(goal,filterActions,maxLength,0,minimum);
00221 
00222   return optimalAnswerSet;
00223 }
00224 
00225 
00226 struct PolicyMerger {
00227 
00228   PolicyMerger(PartialPolicy * policy) :
00229     policy(policy) {}
00230 
00231   void operator()(const AnswerSet& set) {
00232     policy->merge(set);
00233   }
00234 
00235   PartialPolicy *policy;
00236 };
00237 
00238 
00239 
00240 struct CleanPlan {
00241 
00242   CleanPlan(const ActionSet &allActions) : allActions(allActions) {}
00243 
00244   list<AspFluentRef> operator()(const AnswerSet &planWithStates) const {
00245     list<AspFluentRef> actionsOnly;
00246 
00247     remove_copy_if(planWithStates.getFluents().begin(), planWithStates.getFluents().end(),
00248                    back_inserter(actionsOnly),not1(IsAnAction(allActions)));
00249 
00250     return actionsOnly;
00251 
00252   }
00253 
00254   const ActionSet &allActions;
00255 
00256 };
00257 
00258 PartialPolicy *Reasoner::computePolicy(const std::vector<actasp::AspRule>& goal, double suboptimality) const throw (std::logic_error) {
00259 
00260   MultiPolicy *p = new MultiPolicy(allActions);
00261   computePolicyHelper(goal,suboptimality,p);
00262   return p;
00263 
00264 }
00265 
00266 void Reasoner::computePolicyHelper(const std::vector<actasp::AspRule>& goal, double suboptimality, PartialPolicy* policy) const throw (std::logic_error) {
00267     if (suboptimality < 1) {
00268     stringstream num;
00269     num << suboptimality;
00270     throw logic_error("Clingo: suboptimality value cannot be less than one, found: " + num.str());
00271   }
00272 
00273 //   clock_t kr1_begin = clock();
00274   list<AnswerSet> firstAnswerSets = clingo->minimalPlanQuery(goal,false,max_n,0);
00275 //   clock_t kr1_end = clock();
00276 //   cout << "The first kr call took " << (double(kr1_end - kr1_begin) / CLOCKS_PER_SEC) << " seconds" << endl;
00277 
00278   if (firstAnswerSets.empty())
00279     return;
00280 
00281   unsigned int shortestLength = firstAnswerSets.begin()->maxTimeStep();
00282 
00283   for_each(firstAnswerSets.begin(),firstAnswerSets.end(),PolicyMerger(policy));
00284 
00285   int maxLength = ceil(suboptimality * shortestLength);
00286 
00287   //cout << "min lenght is " << shortestLength << " ; max lenght is " << maxLength << endl;
00288 
00289   if (maxLength == shortestLength)
00290     return;
00291 
00292   //all accepted plans sorted lexicographically
00293   set< list <AspFluentRef>, LexComparator > goodPlans;
00294 
00295   //remove the states from the plans
00296   transform(firstAnswerSets.begin(),firstAnswerSets.end(),inserter(goodPlans,goodPlans.begin()), CleanPlan(allActions));
00297 
00298 
00299 
00300 //   clock_t kr2_begin = clock();
00301   list<AnswerSet> answerSets = clingo->lengthRangePlanQuery(goal,false,shortestLength+1,maxLength,0);
00302 //   clock_t kr2_end = clock();
00303 //   cout << "The second kr call took " << (double(kr2_end - kr2_begin) / CLOCKS_PER_SEC) << " seconds" << endl;
00304 
00305   set< list <AspFluentRef>, LexComparator > badPlans;
00306   //this object remembers the set of bad plans, cannot be created inside the loop
00307   IsNotLocallyOptimal isNotLocallyOptimal(&goodPlans,&badPlans, allActions, shortestLength,false);
00308 
00309   list<AnswerSet>::iterator currentFirst = answerSets.begin();
00310 //   clock_t filter_begin = clock();
00311   while (currentFirst != answerSets.end()) {
00312 
00313     //process the plans in groups of increasing length
00314 
00315     list<AnswerSet>::iterator currentLast = find_if(currentFirst,answerSets.end(),PlanLongerThan(currentFirst->maxTimeStep()));
00316 
00317     list<AnswerSetRef> goodPointers;
00318     remove_copy_if(currentFirst,currentLast,back_inserter(goodPointers),isNotLocallyOptimal);
00319 
00320     for_each(goodPointers.begin(),goodPointers.end(),PolicyMerger(policy));
00321 
00322     transform(goodPointers.begin(),goodPointers.end(),inserter(goodPlans, goodPlans.begin()), CleanPlan(allActions));
00323 
00324     currentFirst = currentLast;
00325 
00326   }
00327 //   clock_t filter_end = clock();
00328 
00329 
00330    set< list <AspFluentRef>, LexComparator >::const_iterator printIt = goodPlans.begin();
00331    for (; printIt != goodPlans.end(); ++printIt) {
00332      copy(printIt->begin(),printIt->end(),ostream_iterator<string>(cout, " "));
00333      cout << endl;
00334    }
00335 //   
00336 //   cout << "filtering took " << (double(filter_end - filter_begin) / CLOCKS_PER_SEC) << " seconds" << endl;
00337 
00338 
00339   return;
00340   
00341 }
00342 
00343 std::list< std::list<AspAtom> > Reasoner::query(const std::string &queryString, unsigned int timestep) const throw() {
00344   
00345   return clingo->genericQuery(queryString,timestep,"query_output",0);
00346 }
00347 
00348 }


bwi_kr_execution
Author(s): Matteo Leonetti, Piyush Khandelwal
autogenerated on Thu Jun 6 2019 17:57:37