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(actasp::FilteringQueryGenerator *actualReasoner,unsigned int max_n,const actasp::ActionSet& allActions) :
00025   local(actualReasoner,max_n,allActions) {}
00026 
00027 actasp::AnswerSet RemoteReasoner::currentStateQuery(const std::vector<actasp::AspRule>& query) const throw() {
00028   return local.currentStateQuery(query);
00029 }
00030 
00031 actasp::ActionSet RemoteReasoner::availableActions() const throw() {
00032   return local.availableActions();
00033 }
00034 
00035 std::list< std::list<actasp::AspAtom> > RemoteReasoner::query(const std::string &queryString, unsigned int timeStep) const throw() {
00036   return local.query(queryString,timeStep);
00037 }
00038 
00039 bool RemoteReasoner::updateFluents(const std::vector<actasp::AspFluent> &observations) throw() {
00040   NodeHandle n;
00041   ros::ServiceClient updateClient = n.serviceClient<bwi_kr_execution::UpdateFluents> ("update_fluents");
00042   updateClient.waitForExistence();
00043 
00044   bwi_kr_execution::UpdateFluents uf;
00045 
00046   transform(observations.begin(),observations.end(),back_inserter(uf.request.fluents),TranslateFluent());
00047 
00048   updateClient.call(uf);
00049 
00050   return uf.response.consistent;
00051 }
00052 
00053 actasp::AnswerSet RemoteReasoner::computePlan(const std::vector<actasp::AspRule>& goal) const throw (std::logic_error) {
00054 
00055   return local.computePlan(goal);
00056 
00057 }
00058 
00059 
00060 bool RemoteReasoner::isPlanValid(const actasp::AnswerSet& plan, const std::vector<actasp::AspRule>& goal)  const throw() {
00061   return local.isPlanValid(plan,goal);
00062 
00063 }
00064 
00065 std::vector< actasp::AnswerSet > RemoteReasoner::computeAllPlans(
00066   const std::vector<actasp::AspRule>& goal,
00067   double suboptimality) const throw (std::logic_error) {
00068 
00069   return local.computeAllPlans(goal,suboptimality);
00070 
00071 
00072 }
00073 
00074 actasp::GraphPolicy* RemoteReasoner::computePolicy(const std::vector<actasp::AspRule>& goal, double suboptimality) const throw (std::logic_error) {
00075  return local.computePolicy(goal,suboptimality);
00076 }
00077   
00078   
00079 actasp::AnswerSet RemoteReasoner::filterState(const std::vector<actasp::AnswerSet>& plans, const std::vector<actasp::AspRule>& goals) {
00080   return local.filterState(plans,goals);
00081 }
00082 
00083 
00084 
00085 void RemoteReasoner::resetCurrentState() throw() {
00086   NodeHandle n;
00087   ros::ServiceClient resetClient = n.serviceClient<std_srvs::Empty> ("reset_state");
00088   resetClient.waitForExistence();
00089 
00090   std_srvs::Empty empty;
00091   resetClient.call(empty);
00092 }
00093 
00094 
00095 }


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