CallElevator.cpp
Go to the documentation of this file.
00001 #include "CallElevator.h"
00002 
00003 #include <boost/foreach.hpp>
00004 
00005 #include "ActionFactory.h"
00006 #include "../StaticFacts.h"
00007 
00008 #include "bwi_kr_execution/CurrentStateQuery.h"
00009 #include "bwi_kr_execution/UpdateFluents.h"
00010 #include "ros/console.h"
00011 #include "ros/ros.h"
00012 
00013 namespace bwi_krexec {
00014 
00015 CallElevator::CallElevator() :
00016             done(false),
00017             asked(false),
00018             failed(false) {}
00019 
00020 struct IsFluentFacing {
00021  
00022  bool operator() (const bwi_kr_execution::AspFluent& fluent) {
00023    return fluent.name == "facing";
00024  }
00025  
00026 };
00027 
00028 void CallElevator::run() {
00029   
00030   if(!asked && !done) {
00031     std::string direction_text = (going_up) ? "up" : "down";
00032 
00033     // Get the doors for this elevator.
00034     std::vector<std::string> doors;
00035     std::list<actasp::AspAtom> static_facts = StaticFacts::staticFacts(); 
00036     BOOST_FOREACH(const actasp::AspAtom fact, static_facts) {
00037       if (fact.getName() == "elevhasdoor") {
00038         std::vector<std::string> params = fact.getParameters();
00039         if (params[0] == elevator) {
00040           doors.push_back(params[1]);
00041         }
00042       }
00043     }
00044 
00045     if (doors.size() == 0) {
00046       ROS_ERROR_STREAM("Unable to retrieve doors for elevator " << elevator << ". Cannot complete action!");
00047       done = true;
00048       failed = true;
00049     } else {
00050 
00051       // Figure out which of the doors we're facing.
00052       ros::NodeHandle n;
00053       ros::ServiceClient krClient = n.serviceClient<bwi_kr_execution::CurrentStateQuery> ( "current_state_query" );
00054       krClient.waitForExistence();
00055 
00056       bwi_kr_execution::CurrentStateQuery csq;
00057 
00058       krClient.call(csq);
00059   
00060       std::vector<bwi_kr_execution::AspFluent>::const_iterator facingDoorIt = 
00061         find_if(csq.response.answer.fluents.begin(), csq.response.answer.fluents.end(), IsFluentFacing());
00062 
00063       if (facingDoorIt == csq.response.answer.fluents.end()) {
00064         ROS_ERROR("CallElevator: Unable to ascertain which elevator door the robot is facing!");
00065         done = true;
00066         failed = true;
00067       } else {
00068         facing_door = facingDoorIt->variables[0]; 
00069         if (std::find(doors.begin(), doors.end(), facing_door) == doors.end()) {
00070           ROS_ERROR("CallElevator: Unable to ascertain which elevator door the robot is facing!");
00071           done = true;
00072           failed = true;
00073         } else {
00074           // Make sure that this is one of the elevator doors.
00075           std::vector<std::string> door_is_open;
00076           door_is_open.push_back("Door is open");
00077           askToCallElevator.reset(new CallGUI("askToCallElevator", 
00078                                               CallGUI::CHOICE_QUESTION,  
00079                                               "Could you call the elevator to go " + direction_text + 
00080                                               ", and then let me know when the door in front of me opens?", 
00081                                               120.0f, 
00082                                               door_is_open));
00083           askToCallElevator->run();
00084         }
00085       }
00086     }
00087     asked = true;
00088   } else if(!done) {
00089     if (askToCallElevator->hasFinished()) {
00090       // Check response to see it's not a timeout.
00091       int response_idx = askToCallElevator->getResponseIndex();
00092       if (response_idx == 0) {
00093 
00094         ros::NodeHandle n;
00095         ros::ServiceClient krClient = n.serviceClient<bwi_kr_execution::UpdateFluents> ( "update_fluents" );
00096         krClient.waitForExistence();
00097         bwi_kr_execution::UpdateFluents uf;
00098         bwi_kr_execution::AspFluent open_door;
00099         open_door.name = "open";
00100         open_door.variables.push_back(facing_door);
00101         uf.request.fluents.push_back(open_door);
00102 
00103         krClient.call(uf);
00104 
00105         CallGUI thanks("thanks", CallGUI::DISPLAY,  "Thanks! Would you mind helping me inside the elevator as well?");
00106         thanks.run();
00107       } else {
00108         // A door didn't open in the timeout specified.
00109         failed = true;
00110       }
00111       done = true;
00112     }
00113   }
00114  
00115   
00116 }
00117 
00118 bool CallElevator::hasFinished() const {
00119   return done;
00120 }
00121 
00122 bool CallElevator::hasFailed() const {
00123   return failed;
00124 }
00125 
00126 actasp::Action *CallElevator::cloneAndInit(const actasp::AspFluent & fluent) const {
00127   CallElevator *other = new CallElevator();
00128   other->elevator = fluent.getParameters().at(0);
00129   other->going_up = fluent.getParameters().at(1) == "up"; //throws an exception if the parameter doesn't exist
00130   return other;
00131 }
00132 
00133 std::vector<std::string> CallElevator::getParameters() const {
00134   std::vector<std::string> params;
00135   params.reserve(2);
00136   params.push_back(elevator);
00137   params.push_back(going_up? "up" : "down");
00138   return params;
00139 }
00140 
00141 //if you want the action to be available only in simulation, or only
00142 //on the robot, use the constructor that also takes a boolean.
00143 ActionFactory callElevator(new CallElevator(), false);
00144 
00145 }


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