Go to the documentation of this file.00001 #include "CallGUI.h"
00002
00003 #include <boost/foreach.hpp>
00004 #include <ros/ros.h>
00005
00006 #include <stdexcept>
00007
00008 using namespace std;
00009
00010 namespace bwi_krexec {
00011
00012 CallGUI::CallGUI ( const std::string &name, const TYPE type, const std::string& message,
00013 float timeOut,
00014 const std::vector<std::string> &options ) :
00015 name ( name ),
00016 type ( type ),
00017 message ( message ),
00018 timeOut ( timeOut ),
00019 options ( options ),
00020 done ( false ) {}
00021
00022
00023 void CallGUI::run() {
00024
00025
00026 ros::NodeHandle n;
00027 ros::ServiceClient client = n.serviceClient<bwi_msgs::QuestionDialog> ( "question_dialog" );
00028
00029 client.waitForExistence();
00030
00031 req.request.type = type;
00032 req.request.message = message;
00033 req.request.options = options;
00034 req.request.timeout = timeOut;
00035
00036 client.waitForExistence();
00037
00038
00039
00040
00041
00042
00043 client.call ( req );
00044
00045 done = true;
00046
00047 }
00048
00049 string CallGUI::getResponse() {
00050 if ((done) && (req.response.index == bwi_msgs::QuestionDialogRequest::TEXT_RESPONSE)) {
00051 return req.response.text;
00052 }
00053 else {
00054 return "";
00055 }
00056 }
00057
00058 int CallGUI::getResponseIndex() {
00059 if (done) {
00060 return req.response.index;
00061 }
00062 else {
00063 return bwi_msgs::QuestionDialogRequest::NO_RESPONSE;
00064 }
00065 }
00066
00067 actasp::Action *CallGUI::cloneAndInit(const actasp::AspFluent & fluent) const {
00068 throw runtime_error("CallGUI: initilization from fluent not supported");
00069 }
00070
00071 }