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