Go to the documentation of this file.00001 #include "SearchRoom.h"
00002
00003 #include "ActionFactory.h"
00004
00005 #include "CallGUI.h"
00006
00007 #include "bwi_kr_execution/AspFluent.h"
00008
00009 #include "bwi_kr_execution/CurrentStateQuery.h"
00010 #include <bwi_kr_execution/UpdateFluents.h>
00011
00012 #include <ros/ros.h>
00013 #include <sound_play/sound_play.h>
00014
00015 #include <string>
00016 #include <iostream>
00017
00018 using namespace std;
00019
00020 namespace bwi_krexec {
00021
00022 SearchRoom::SearchRoom() :
00023 person(),
00024 room(),
00025 done(false){
00026 }
00027
00028 ros::Publisher SearchRoom::ask_pub;
00029 bool SearchRoom::pub_set(false);
00030
00031 void SearchRoom::run() {
00032
00033 ros::NodeHandle n;
00034 if (!pub_set) {
00035 ask_pub = n.advertise<sound_play::SoundRequest>("robotsound", 1000);
00036 pub_set = true;
00037 }
00038
00039
00040 ros::ServiceClient currentClient = n.serviceClient<bwi_kr_execution::CurrentStateQuery> ( "current_state_query" );
00041 currentClient.waitForExistence();
00042
00043 bwi_kr_execution::AspFluent atFluent;
00044 atFluent.name = "at";
00045 atFluent.timeStep = 0;
00046 atFluent.variables.push_back(room);
00047
00048 bwi_kr_execution::AspRule rule;
00049 rule.head.push_back(atFluent);
00050
00051 bwi_kr_execution::CurrentStateQuery csq;
00052 csq.request.query.push_back(rule);
00053
00054 currentClient.call(csq);
00055
00056 bool at = csq.response.answer.satisfied;
00057
00058 if (at) {
00059
00060 if (ask_pub.getNumSubscribers() == 0) return;
00061
00062
00063 sound_play::SoundRequest sound_req;
00064 sound_req.sound = sound_play::SoundRequest::SAY;
00065 sound_req.command = sound_play::SoundRequest::PLAY_ONCE;
00066 std::stringstream ss;
00067 ss << "Is " << person << " in the room?";
00068 sound_req.arg = ss.str();
00069
00070 ask_pub.publish(sound_req);
00071 }
00072
00073 vector<string> options;
00074 options.push_back("yes");
00075 options.push_back("no");
00076
00077 CallGUI searchRoom("searchRoom", CallGUI::CHOICE_QUESTION, "Is " + person + " in the room " + room + "?", 60.0, options);
00078 searchRoom.run();
00079
00080 int response = searchRoom.getResponseIndex();
00081
00082 if (response >= 0) {
00083 CallGUI thank("thank", CallGUI::DISPLAY, "Thank you!");
00084 thank.run();
00085
00086
00087
00088
00089
00090
00091
00092 }
00093
00094 ros::ServiceClient krClient = n.serviceClient<bwi_kr_execution::UpdateFluents> ( "update_fluents" );
00095 krClient.waitForExistence();
00096
00097 bwi_kr_execution::UpdateFluents uf;
00098 bwi_kr_execution::AspFluent fluent;
00099 fluent.timeStep = 0;
00100 fluent.variables.push_back(person);
00101 fluent.variables.push_back(room);
00102
00103 fluent.name = ((response == 0) ? "inroom" : "-inroom");
00104
00105 uf.request.fluents.push_back(fluent);
00106 krClient.call(uf);
00107
00108 done = true;
00109
00110 }
00111
00112 actasp::Action* SearchRoom::cloneAndInit(const actasp::AspFluent& fluent) const {
00113 SearchRoom *newAction = new SearchRoom();
00114 newAction->person = fluent.getParameters().at(0);
00115 newAction->room = fluent.getParameters().at(1);
00116
00117 return newAction;
00118 }
00119
00120 std::vector<std::string> SearchRoom::getParameters() const {
00121 vector<string> param;
00122 param.push_back(person);
00123 param.push_back(room);
00124 return param;
00125 }
00126
00127
00128 ActionFactory SearchRoomFactory(new SearchRoom());
00129
00130 }