meeting_experiment.cpp
Go to the documentation of this file.
00001 
00002 #include "bwi_kr_execution/ExecutePlanAction.h"
00003 
00004 #include <actionlib/client/simple_action_client.h>
00005 
00006 #include <ros/ros.h>
00007 
00008 typedef actionlib::SimpleActionClient<bwi_kr_execution::ExecutePlanAction> Client;
00009 
00010 using namespace std;
00011 
00012 int main(int argc, char**argv) {
00013   ros::init(argc, argv, "meeting_experiment");
00014   ros::NodeHandle n;
00015   
00016   ros::NodeHandle privateNode("~");
00017   string meeting;
00018   privateNode.param<string>("meeting",meeting,"bwi_meeting");
00019   
00020   ROS_INFO_STREAM("getting ready for meeting " << meeting);
00021   
00022   Client client("/action_executor/execute_plan", true);
00023   client.waitForServer();
00024   
00025   bwi_kr_execution::ExecutePlanGoal goal;
00026   
00027   bwi_kr_execution::AspRule rule;
00028   bwi_kr_execution::AspFluent fluent;
00029   fluent.name = "not allinmeeting";
00030   
00031   fluent.variables.push_back(meeting);
00032  
00033   rule.body.push_back(fluent);
00034   goal.aspGoal.push_back(rule);
00035   
00036   ROS_INFO("sending goal");
00037   client.sendGoalAndWait(goal);
00038   
00039   if (client.getState() == actionlib::SimpleClientGoalState::ABORTED) {
00040     ROS_INFO("Aborted");
00041   }
00042   else if (client.getState() == actionlib::SimpleClientGoalState::PREEMPTED) {
00043     ROS_INFO("Preempted");
00044   }
00045   
00046   else if (client.getState() == actionlib::SimpleClientGoalState::SUCCEEDED) {
00047     ROS_INFO("Succeeded!");
00048   }
00049   else
00050      ROS_INFO("Terminated");
00051     
00052   return 0;
00053 }


bwi_tasks
Author(s): Matteo Leonetti, Shiqi Zhang
autogenerated on Fri Aug 28 2015 10:14:58