00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #include "stdr_gui/stdr_gui_connector.h"
00023
00024 namespace stdr_gui
00025 {
00026
00033 CGuiConnector::CGuiConnector(int argc, char **argv):
00034 QObject(),
00035 loader_(argc,argv),
00036 robotCreatorConn(argc,argv),
00037 argc_(argc),
00038 argv_(argv)
00039 {
00040
00041 bool map_initialized_ = false;
00042
00043 QObject::connect(
00044 loader_.actionProperties,SIGNAL(triggered(bool)),
00045 this,SLOT(actionPropertiesTriggered()));
00046
00047 QObject::connect(
00048 loader_.actionAbout_STDR_Simulator,SIGNAL(triggered(bool)),
00049 this,SLOT(actionAboutTriggered()));
00050
00051 QObject::connect(
00052 loader_.actionExit,SIGNAL(triggered(bool)),
00053 this,SLOT(actionExitTriggered()));
00054
00055 QObject::connect(
00056 loader_.actionLoadMap,SIGNAL(triggered(bool)),
00057 this,SLOT(actionLoadMapTriggered()));
00058
00059 QObject::connect(
00060 loader_.actionNewRobot,SIGNAL(triggered(bool)),
00061 this,SLOT(actionNewRobotTriggered()));
00062
00063 QObject::connect(
00064 loader_.actionAddRobot,SIGNAL(triggered(bool)),
00065 this,SLOT(actionAddRobotTriggered()));
00066
00067 QObject::connect(
00068 loader_.actionZoomIn,SIGNAL(triggered(bool)),
00069 this,SLOT(actionZoomInTriggered()));
00070
00071 QObject::connect(
00072 loader_.actionZoomOut,SIGNAL(triggered(bool)),
00073 this,SLOT(actionZoomOutTriggered()));
00074
00075 QObject::connect(
00076 loader_.actionAdjusted,SIGNAL(triggered(bool)),
00077 this,SLOT(actionAdjustedTriggered()));
00078
00079 QObject::connect(
00080 loader_.actionGrid,SIGNAL(triggered(bool)),
00081 this,SLOT(actionGridTriggered()));
00082
00083 QObject::connect(
00084 loader_.actionNewRfid,SIGNAL(triggered(bool)),
00085 this,SLOT(actionNewRfidTriggered()));
00086
00087 QObject::connect(
00088 loader_.actionNewThermal,SIGNAL(triggered(bool)),
00089 this,SLOT(actionNewThermalTriggered()));
00090
00091 QObject::connect(
00092 loader_.actionNewCo2,SIGNAL(triggered(bool)),
00093 this,SLOT(actionNewCo2Triggered()));
00094
00095 QObject::connect(
00096 loader_.actionNewSound,SIGNAL(triggered(bool)),
00097 this,SLOT(actionNewSoundTriggered()));
00098
00099 grid_enabled_ = false;
00100 }
00101
00106 void CGuiConnector::actionExitTriggered(void)
00107 {
00108 ROS_INFO("Exiting GUI...");
00109 exit(0);
00110 }
00111
00116 void CGuiConnector::actionPropertiesTriggered(void)
00117 {
00118 QMessageBox msg(static_cast<QMainWindow *>(&this->loader_));
00119 msg.setWindowTitle(QString("Not finished yet :/"));
00120 msg.exec();
00121 }
00122
00127 void CGuiConnector::actionLoadMapTriggered(void)
00128 {
00129 QString file_name = QFileDialog::getOpenFileName(
00130 &loader_,
00131 tr("Load map"),
00132 QString().fromStdString(
00133 stdr_gui_tools::getRosPackagePath("stdr_resources") +
00134 std::string("/maps")),
00135 tr("Yaml map files (*.yaml)"));
00136 if(file_name.isEmpty() || file_name.isNull())
00137 {
00138 return;
00139 }
00140
00141 ros::NodeHandle nh;
00142
00143 nav_msgs::OccupancyGrid map;
00144
00145 map = stdr_server::map_loader::loadMap(file_name.toStdString().c_str());
00146
00147 ros::ServiceClient client;
00148
00149 while (!ros::service::waitForService
00150 ("/stdr_server/load_static_map_external", ros::Duration(.1)) &&
00151 ros::ok())
00152 {
00153 ROS_WARN
00154 ("Trying to register to /stdr_server/load_static_map_external...");
00155 }
00156
00157 client = nh.serviceClient<stdr_msgs::LoadExternalMap>
00158 ("/stdr_server/load_static_map_external", true);
00159
00160 stdr_msgs::LoadExternalMap srv;
00161
00162 srv.request.map = map;
00163
00164 if (client.call(srv)) {
00165 ROS_INFO("Map successfully loaded");
00166 }
00167 else {
00168 ROS_ERROR("Could not load map, maybe already loaded...");
00169 }
00170 }
00171
00176 void CGuiConnector::actionAboutTriggered(void)
00177 {
00178 QMessageBox msg(static_cast<QMainWindow *>(&this->loader_));
00179 msg.setWindowTitle(QString("STDR Simulator - About"));
00180 msg.setText(QString("Simple Two Dimentional Robot Simulator\
00181 (STDR Simulator) is a multi-robot simulator created in QT4. Its goals\
00182 are : \n\n1) to simulate easily a single robot or a swarm in a 2D\
00183 environment, \n2) to be totally parameterizable \n3) to be ROS\
00184 compliant.\n\nDevelopers:\nManos Tsardoulias, etsardou@gmail.com\
00185 \nChris Zalidis,zalidis@gmail.com\nAris Thallas, aris.thallas@gmail.com"));
00186 msg.exec();
00187 }
00188
00193 void CGuiConnector::actionNewRobotTriggered(void)
00194 {
00195 robotCreatorConn.initialise();
00196 }
00197
00202 void CGuiConnector::actionAddRobotTriggered(void)
00203 {
00204 if ( ! map_initialized_ )
00205 {
00206 return;
00207 }
00208 QString file_name = QFileDialog::getOpenFileName(
00209 &loader_,
00210 tr("Load robot"),
00211 QString().fromStdString(
00212 stdr_gui_tools::getRosPackagePath("stdr_resources")) +
00213 QString("/resources/"),
00214 tr("Robot Files (*.yaml *xml)"));
00215
00216 if (file_name.isEmpty()) {
00217 return;
00218 }
00219
00220 try {
00221 stdr_msgs::RobotMsg new_robot_msg =
00222 stdr_parser::Parser::createMessage<stdr_msgs::RobotMsg>
00223 (file_name.toStdString());
00224
00225 Q_EMIT robotFromFile(new_robot_msg);
00226 }
00227 catch(stdr_parser::ParserException ex)
00228 {
00229 QMessageBox msg(static_cast<QMainWindow *>(&this->loader_));
00230 msg.setWindowTitle(QString("STDR Parser - Error"));
00231 msg.setText(QString(ex.what()));
00232 msg.exec();
00233 return;
00234 }
00235 }
00236
00241 void CGuiConnector::actionNewRfidTriggered(void)
00242 {
00243 if ( ! map_initialized_ )
00244 {
00245 return;
00246 }
00247 Q_EMIT loadRfidPressed();
00248 }
00249
00254 void CGuiConnector::actionNewThermalTriggered(void)
00255 {
00256 if ( ! map_initialized_ )
00257 {
00258 return;
00259 }
00260 Q_EMIT loadThermalPressed();
00261 }
00262
00267 void CGuiConnector::actionNewCo2Triggered(void)
00268 {
00269 if ( ! map_initialized_ )
00270 {
00271 return;
00272 }
00273 Q_EMIT loadCo2Pressed();
00274 }
00275
00280 void CGuiConnector::actionNewSoundTriggered(void)
00281 {
00282 if ( ! map_initialized_ )
00283 {
00284 return;
00285 }
00286 Q_EMIT loadSoundPressed();
00287 }
00288
00293 void CGuiConnector::actionZoomInTriggered(void)
00294 {
00295 if ( ! map_initialized_ )
00296 {
00297 return;
00298 }
00299 Q_EMIT setZoomInCursor(loader_.actionZoomIn->isChecked());
00300 loader_.actionZoomOut->setChecked(false);
00301 loader_.actionAdjusted->setChecked(false);
00302 }
00303
00308 void CGuiConnector::actionZoomOutTriggered(void)
00309 {
00310 if ( ! map_initialized_ )
00311 {
00312 return;
00313 }
00314 Q_EMIT setZoomOutCursor(loader_.actionZoomOut->isChecked());
00315 loader_.actionZoomIn->setChecked(false);
00316 loader_.actionAdjusted->setChecked(false);
00317 }
00318
00323 void CGuiConnector::actionAdjustedTriggered(void)
00324 {
00325 if ( ! map_initialized_ )
00326 {
00327 return;
00328 }
00329 Q_EMIT setAdjustedCursor(loader_.actionAdjusted->isChecked());
00330 loader_.actionZoomIn->setChecked(false);
00331 loader_.actionZoomOut->setChecked(false);
00332 }
00333
00338 void CGuiConnector::actionGridTriggered(void)
00339 {
00340 if ( ! map_initialized_ )
00341 {
00342 return;
00343 }
00344 grid_enabled_ =! grid_enabled_;
00345 }
00346
00351 bool CGuiConnector::isGridEnabled(void)
00352 {
00353 return grid_enabled_;
00354 }
00355
00363 void CGuiConnector::addToGrid(QWidget *w,int row,int column)
00364 {
00365 loader_.gridLayout->addWidget(w,row,column,0);
00366 }
00367
00374 void CGuiConnector::setGridColumnStretch(int cell,int stretch)
00375 {
00376 loader_.gridLayout->setColumnStretch(cell,stretch);
00377 }
00378
00383 void CGuiConnector::show(void)
00384 {
00385 loader_.show();
00386 loader_.showMaximized();
00387 }
00388
00394 void CGuiConnector::setStatusBarMessage(QString s)
00395 {
00396 loader_.statusbar->showMessage(s,0);
00397 }
00398
00403 QEvent* CGuiConnector::getCloseEvent(void)
00404 {
00405 return loader_.getCloseEvent();
00406 }
00407
00412 bool CGuiConnector::closeTriggered(void)
00413 {
00414 return loader_.closeTriggered();
00415 }
00416
00421 void CGuiConnector::shutdown(void)
00422 {
00423 loader_.shutdown();
00424 }
00425
00431 void CGuiConnector::setMapInitialized(bool mi)
00432 {
00433 map_initialized_ = mi;
00434 }
00435
00440 void CGuiConnector::uncheckZoomButtons(void)
00441 {
00442 loader_.actionZoomIn->setChecked(false);
00443 loader_.actionZoomOut->setChecked(false);
00444 }
00445
00452 void CGuiConnector::raiseMessage(QString title, QString s)
00453 {
00454 QMessageBox msg(static_cast<QMainWindow *>(&this->loader_));
00455 msg.setWindowTitle(title);
00456 msg.setText(s);
00457 msg.exec();
00458 }
00459 }