00001
00002 #include "actions/ActionFactory.h"
00003
00004 #include "actasp/reasoners/Clingo.h"
00005 #include "actasp/action_utils.h"
00006
00007 #include "msgs_utils.h"
00008 #include "bwi_kr_execution/UpdateFluents.h"
00009 #include "bwi_kr_execution/CurrentStateQuery.h"
00010 #include "bwi_kr_execution/ComputePlan.h"
00011 #include "bwi_kr_execution/ComputeAllPlans.h"
00012 #include "bwi_kr_execution/IsPlanValid.h"
00013
00014 #include <ros/ros.h>
00015 #include <ros/package.h>
00016 #include <std_srvs/Empty.h>
00017
00018 #include <boost/filesystem.hpp>
00019
00020 using namespace actasp;
00021 using namespace std;
00022 using namespace ros;
00023 using namespace bwi_krexec;
00024
00025 const int MAX_N = 20;
00026 const std::string queryDirectory("/tmp/bwi_kr_execution/");
00027
00028
00029
00030 bool updateFluents(bwi_kr_execution::UpdateFluents::Request &req,
00031 bwi_kr_execution::UpdateFluents::Response &res) throw();
00032
00033 bool currentStateQuery(bwi_kr_execution::CurrentStateQuery::Request &req,
00034 bwi_kr_execution::CurrentStateQuery::Response &res) throw();
00035
00036 bool computePlan(bwi_kr_execution::ComputePlan::Request &req,
00037 bwi_kr_execution::ComputePlan::Response &res);
00038
00039 bool computeAllPlans(bwi_kr_execution::ComputeAllPlans::Request &req,
00040 bwi_kr_execution::ComputeAllPlans::Response &res);
00041
00042 bool isPlanvalid(bwi_kr_execution::IsPlanValid::Request &req,
00043 bwi_kr_execution::IsPlanValid::Response &res);
00044
00045 bool resetState(std_srvs::Empty::Request &,
00046 std_srvs::Empty::Response &);
00047
00048 actasp::AspKR *reasoner;
00049
00050 int main(int argc, char **argv) {
00051
00052 ros::init(argc, argv, "bwi_kr");
00053 ros::NodeHandle n;
00054
00055 if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug)) {
00056 ros::console::notifyLoggerLevelsChanged();
00057 }
00058
00059 ros::NodeHandle privateNode("~");
00060
00061 string domainDirectory;
00062 n.param<std::string>("bwi_kr_execution/domain_directory", domainDirectory, ros::package::getPath("bwi_kr_execution")+"/domain/");
00063
00064 if(domainDirectory.at(domainDirectory.size()-1) != '/')
00065 domainDirectory += '/';
00066
00067 bool simulating;
00068 privateNode.param<bool>("simulation",simulating,false);
00069
00070 ActionFactory::setSimulation(simulating);
00071
00072 boost::filesystem::create_directories(queryDirectory);
00073
00074 reasoner = new Clingo(MAX_N,"n",queryDirectory,domainDirectory,actionMapToSet(ActionFactory::actions()));
00075 reasoner->reset();
00076
00077 ros::ServiceServer update_fluents = n.advertiseService("update_fluents", updateFluents);
00078 ros::ServiceServer current_state_query = n.advertiseService("current_state_query", currentStateQuery);
00079 ros::ServiceServer compute_plan = n.advertiseService("compute_plan", computePlan);
00080 ros::ServiceServer compute_all_plans = n.advertiseService("compute_all_plans", computeAllPlans);
00081 ros::ServiceServer is_plan_valid = n.advertiseService("is_plan_valid", isPlanvalid);
00082 ros::ServiceServer reset_state = n.advertiseService("reset_state", isPlanvalid);
00083
00084
00085
00086
00087
00088 ros::spin();
00089
00090 delete reasoner;
00091
00092 return 0;
00093 }
00094
00095 bool updateFluents(bwi_kr_execution::UpdateFluents::Request &req,
00096 bwi_kr_execution::UpdateFluents::Response &res) throw() {
00097
00098 vector<AspFluent> fluents;
00099 transform(req.fluents.begin(),req.fluents.end(),back_inserter(fluents),TranslateFluent());
00100
00101 res.consistent = reasoner->updateFluents(fluents);
00102
00103 return true;
00104 }
00105
00106 bool currentStateQuery(bwi_kr_execution::CurrentStateQuery::Request &req,
00107 bwi_kr_execution::CurrentStateQuery::Response &res) throw() {
00108
00109 vector<AspRule> rules;
00110 transform(req.query.begin(),req.query.end(),back_inserter(rules),TranslateRule());
00111
00112 AnswerSet answer = reasoner->currentStateQuery(rules);
00113
00114 res.answer.satisfied = answer.isSatisfied();
00115 transform(answer.getFluents().begin(),answer.getFluents().end(),back_inserter(res.answer.fluents),TranslateFluent());
00116
00117 return true;
00118 }
00119
00120
00121 bool computePlan(bwi_kr_execution::ComputePlan::Request &req,
00122 bwi_kr_execution::ComputePlan::Response &res) {
00123 vector<AspRule> goal;
00124 transform(req.goal.begin(),req.goal.end(),back_inserter(goal),TranslateRule());
00125
00126
00127 AnswerSet answer = reasoner->computePlan(goal);
00128
00129 res.plan.satisfied = answer.isSatisfied();
00130 transform(answer.getFluents().begin(),answer.getFluents().end(),back_inserter(res.plan.fluents),TranslateFluent());
00131
00132 return true;
00133 }
00134
00135 bool computeAllPlans(bwi_kr_execution::ComputeAllPlans::Request& req, bwi_kr_execution::ComputeAllPlans::Response& res) {
00136
00137 vector<AspRule> goal;
00138 transform(req.goal.begin(),req.goal.end(),back_inserter(goal),TranslateRule());
00139
00140
00141 vector<actasp::AnswerSet> answers = reasoner->computeAllPlans(goal,req.suboptimality);
00142
00143 transform(answers.begin(),answers.end(),back_inserter(res.plans),TranslateAnswerSet());
00144
00145 return true;
00146 }
00147
00148
00149 bool isPlanvalid(bwi_kr_execution::IsPlanValid::Request& req, bwi_kr_execution::IsPlanValid::Response& res) {
00150
00151 vector<AspRule> goal;
00152 transform(req.goal.begin(),req.goal.end(),back_inserter(goal),TranslateRule());
00153
00154 res.valid = reasoner->isPlanValid(TranslateAnswerSet()(req.plan), goal);
00155
00156 return true;
00157 }
00158
00159 bool resetState(std_srvs::Empty::Request &, std_srvs::Empty::Response &) {
00160 reasoner->reset();
00161 }