RemoteReasoner.cpp
Go to the documentation of this file.
00001 #include "RemoteReasoner.h"
00002 
00003 #include "bwi_kr_execution/CurrentStateQuery.h"
00004 #include "bwi_kr_execution/UpdateFluents.h"
00005 #include "bwi_kr_execution/ComputePlan.h"
00006 #include "bwi_kr_execution/ComputeAllPlans.h"
00007 #include "bwi_kr_execution/IsPlanValid.h"
00008 
00009 #include "msgs_utils.h"
00010 
00011 #include "actasp/Action.h"
00012 
00013 #include <ros/ros.h>
00014 #include <std_srvs/Empty.h>
00015 
00016 #include <algorithm>
00017 #include <iterator>
00018 
00019 using namespace std;
00020 using namespace ros;
00021 
00022 namespace bwi_krexec {
00023   
00024   RemoteReasoner::RemoteReasoner(unsigned int max_n,
00025          const std::string& queryDir,
00026          const std::string& domainDir,
00027          const actasp::ActionSet& actions,
00028          unsigned int max_time) : local(max_n,"n",queryDir,domainDir,actions,max_time) {}
00029   
00030 actasp::AnswerSet RemoteReasoner::currentStateQuery(const std::vector<actasp::AspRule>& query) const throw() {
00031   return local.currentStateQuery(query);
00032 }
00033 
00034 actasp::ActionSet RemoteReasoner::availableActions() const throw() {
00035    return local.availableActions();
00036 }
00037 
00038 std::list< std::list<actasp::AspAtom> > RemoteReasoner::query(const std::string &queryString, unsigned int initialTimeStep,
00039                                    unsigned int finalTimeStep) const throw() {
00040   return local.query(queryString,initialTimeStep,finalTimeStep);
00041 }
00042 
00043 bool RemoteReasoner::updateFluents(const std::vector<actasp::AspFluent> &observations) throw() {
00044   NodeHandle n;
00045   ros::ServiceClient updateClient = n.serviceClient<bwi_kr_execution::UpdateFluents> ( "update_fluents" );
00046   updateClient.waitForExistence();
00047   
00048   bwi_kr_execution::UpdateFluents uf;
00049   
00050   transform(observations.begin(),observations.end(),back_inserter(uf.request.fluents),TranslateFluent());
00051   
00052   updateClient.call(uf);
00053   
00054   return uf.response.consistent;
00055 }
00056 
00057 actasp::AnswerSet RemoteReasoner::computePlan(const std::vector<actasp::AspRule>& goal) const throw (std::logic_error) {
00058   
00059   return local.computePlan(goal);
00060   
00061 }
00062 
00063 
00064 bool RemoteReasoner::isPlanValid(const actasp::AnswerSet& plan, const std::vector<actasp::AspRule>& goal)  const throw() {
00065   return local.isPlanValid(plan,goal);
00066   
00067 }
00068 
00069 std::vector< actasp::AnswerSet > RemoteReasoner::computeAllPlans(
00070                 const std::vector<actasp::AspRule>& goal, 
00071                 double suboptimality) const throw (std::logic_error) {
00072   
00073   return local.computeAllPlans(goal,suboptimality); 
00074   
00075                   
00076 }
00077 
00078 actasp::MultiPolicy RemoteReasoner::computePolicy(const std::vector<actasp::AspRule>& goal, 
00079                                   double suboptimality) const throw (std::logic_error) {
00080  
00081   return local.computePolicy(goal,suboptimality);
00082 }
00083 
00084 void RemoteReasoner::reset() throw() {
00085   NodeHandle n;
00086   ros::ServiceClient resetClient = n.serviceClient<std_srvs::Empty> ( "reset_state" );
00087   resetClient.waitForExistence();
00088   
00089   std_srvs::Empty empty;
00090   resetClient.call(empty);
00091 }
00092 
00093 
00094 }


bwi_kr_execution
Author(s): Matteo Leonetti, Piyush Khandelwal
autogenerated on Fri Aug 28 2015 10:14:46