any_plan_executor.cpp
Go to the documentation of this file.
00001 
00002 #include "msgs_utils.h"
00003 #include "RemoteReasoner.h"
00004 #include "StaticFacts.h"
00005 
00006 #include "actasp/action_utils.h"
00007 #include "actasp/executors/ReplanningActionExecutor.h"
00008 #include "actasp/planners/AnyPlan.h"
00009 #include "actasp/ExecutionObserver.h"
00010 #include "actasp/PlanningObserver.h"
00011 #include "actasp/AnswerSet.h"
00012 
00013 
00014 #include "bwi_kr_execution/ExecutePlanAction.h"
00015 
00016 #include "actions/ActionFactory.h"
00017 #include "actions/LogicalNavigation.h"
00018 
00019 #include <actionlib/server/simple_action_server.h>
00020 
00021 #include <ros/ros.h>
00022 #include <ros/package.h>
00023 #include <ros/console.h>
00024 
00025 #include <boost/filesystem.hpp>
00026 
00027 #include <string>
00028 
00029 const int MAX_N = 20;
00030 const std::string queryDirectory("/tmp/bwi_action_execution/");
00031 
00032 
00033 using namespace std;
00034 using namespace bwi_krexec;
00035 using namespace actasp;
00036 
00037 typedef actionlib::SimpleActionServer<bwi_kr_execution::ExecutePlanAction> Server;
00038 
00039 
00040 ActionExecutor *executor;
00041 
00042 struct PrintFluent {
00043   
00044   PrintFluent(ostream& stream) : stream(stream) {}
00045   
00046   string operator()(const AspFluent& fluent) {
00047     stream << fluent.toString() << " ";
00048   }
00049   
00050   ostream &stream;
00051   
00052 };
00053 
00054 struct Observer : public ExecutionObserver, public PlanningObserver {
00055   
00056   void actionStarted(const AspFluent& action) throw() {
00057     ROS_INFO_STREAM("Starting execution: " << action.toString());
00058   }
00059   
00060   void actionTerminated(const AspFluent& action) throw() {
00061     ROS_INFO_STREAM("Terminating execution: " << action.toString());
00062   }
00063   
00064   
00065   void planChanged(const AnswerSet& newPlan) throw() {
00066    stringstream planStream;
00067    
00068    ROS_INFO_STREAM("plan size: " << newPlan.getFluents().size());
00069    
00070    copy(newPlan.getFluents().begin(),newPlan.getFluents().end(),ostream_iterator<string>(planStream," "));
00071    
00072    ROS_INFO_STREAM(planStream.str());
00073   }
00074   
00075   
00076 };
00077 
00078 void executePlan(const bwi_kr_execution::ExecutePlanGoalConstPtr& plan, Server* as) {
00079 
00080   vector<AspRule> goalRules;
00081 
00082   transform(plan->aspGoal.begin(),plan->aspGoal.end(),back_inserter(goalRules),TranslateRule());
00083 
00084   executor->setGoal(goalRules);
00085 
00086   ros::Rate loop(10);
00087 
00088   while (!executor->goalReached() && !executor->failed() && ros::ok()) {
00089 
00090     if (!as->isPreemptRequested()) {
00091       executor->executeActionStep();
00092     }
00093     else {
00094       if(as->isNewGoalAvailable()) {
00095         goalRules.clear();
00096         const bwi_kr_execution::ExecutePlanGoalConstPtr& newGoal = as->acceptNewGoal();
00097         transform(newGoal->aspGoal.begin(),newGoal->aspGoal.end(),back_inserter(goalRules),TranslateRule());
00098         executor->setGoal(goalRules);
00099       }
00100     }
00101          loop.sleep();
00102   }
00103 
00104 
00105   if (executor->goalReached()) {
00106     ROS_INFO("Execution succeded");
00107     as->setSucceeded();
00108   }
00109   else {
00110     ROS_INFO("Execution failed");
00111     as->setAborted();
00112   }
00113 }
00114 
00115 int main(int argc, char**argv) {
00116   ros::init(argc, argv, "action_executor");
00117   ros::NodeHandle n;
00118 
00119 //   if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug)) {
00120 //     ros::console::notifyLoggerLevelsChanged();
00121 //   }
00122   
00123   ros::NodeHandle privateNode("~");
00124   string domainDirectory;
00125   n.param<std::string>("bwi_kr_execution/domain_directory", domainDirectory, ros::package::getPath("bwi_kr_execution")+"/domain/");
00126   
00127   if(domainDirectory.at(domainDirectory.size()-1) != '/')
00128     domainDirectory += '/';
00129 
00130 //  create initial state
00131   LogicalNavigation setInitialState("noop");
00132   setInitialState.run();
00133 
00134 
00135   bool simulating;
00136   privateNode.param<bool>("simulation",simulating,false);
00137   ActionFactory::setSimulation(simulating); 
00138   
00139   boost::filesystem::create_directories(queryDirectory);
00140 
00141   AspKR *reasoner = new RemoteReasoner(MAX_N,queryDirectory,domainDirectory,actionMapToSet(ActionFactory::actions()));
00142   StaticFacts::retrieveStaticFacts(reasoner, domainDirectory);
00143   Planner *planner = new AnyPlan(reasoner,1.);
00144   
00145   //need a pointer to the specific type for the observer
00146   ReplanningActionExecutor *replanner = new ReplanningActionExecutor(reasoner,planner,ActionFactory::actions());
00147   executor = replanner;
00148   
00149   Observer observer;
00150   executor->addExecutionObserver(&observer);
00151   replanner->addPlanningObserver(&observer);
00152 
00153   Server server(privateNode, "execute_plan", boost::bind(&executePlan, _1, &server), false);
00154   server.start();
00155 
00156   ros::spin();
00157 
00158   
00159   return 0;
00160 }


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