stdr_gui_connector.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 
23 
24 namespace stdr_gui
25 {
26 
33  CGuiConnector::CGuiConnector(int argc, char **argv):
34  QObject(),
35  loader_(argc,argv),
36  robotCreatorConn(argc,argv),
37  argc_(argc),
38  argv_(argv)
39  {
40 
41  bool map_initialized_ = false;
42 
43  QObject::connect(
44  loader_.actionProperties,SIGNAL(triggered(bool)),
45  this,SLOT(actionPropertiesTriggered()));
46 
47  QObject::connect(
48  loader_.actionAbout_STDR_Simulator,SIGNAL(triggered(bool)),
49  this,SLOT(actionAboutTriggered()));
50 
51  QObject::connect(
52  loader_.actionExit,SIGNAL(triggered(bool)),
53  this,SLOT(actionExitTriggered()));
54 
55  QObject::connect(
56  loader_.actionLoadMap,SIGNAL(triggered(bool)),
57  this,SLOT(actionLoadMapTriggered()));
58 
59  QObject::connect(
60  loader_.actionNewRobot,SIGNAL(triggered(bool)),
61  this,SLOT(actionNewRobotTriggered()));
62 
63  QObject::connect(
64  loader_.actionAddRobot,SIGNAL(triggered(bool)),
65  this,SLOT(actionAddRobotTriggered()));
66 
67  QObject::connect(
68  loader_.actionZoomIn,SIGNAL(triggered(bool)),
69  this,SLOT(actionZoomInTriggered()));
70 
71  QObject::connect(
72  loader_.actionZoomOut,SIGNAL(triggered(bool)),
73  this,SLOT(actionZoomOutTriggered()));
74 
75  QObject::connect(
76  loader_.actionAdjusted,SIGNAL(triggered(bool)),
77  this,SLOT(actionAdjustedTriggered()));
78 
79  QObject::connect(
80  loader_.actionGrid,SIGNAL(triggered(bool)),
81  this,SLOT(actionGridTriggered()));
82 
83  QObject::connect(
84  loader_.actionNewRfid,SIGNAL(triggered(bool)),
85  this,SLOT(actionNewRfidTriggered()));
86 
87  QObject::connect(
88  loader_.actionNewThermal,SIGNAL(triggered(bool)),
89  this,SLOT(actionNewThermalTriggered()));
90 
91  QObject::connect(
92  loader_.actionNewCo2,SIGNAL(triggered(bool)),
93  this,SLOT(actionNewCo2Triggered()));
94 
95  QObject::connect(
96  loader_.actionNewSound,SIGNAL(triggered(bool)),
97  this,SLOT(actionNewSoundTriggered()));
98 
99  grid_enabled_ = false;
100  }
101 
107  {
108  ROS_INFO("Exiting GUI...");
109  exit(0);
110  }
111 
117  {
118  QMessageBox msg(static_cast<QMainWindow *>(&this->loader_));
119  msg.setWindowTitle(QString("Not finished yet :/"));
120  msg.exec();
121  }
122 
128  {
129  QString file_name = QFileDialog::getOpenFileName(
130  &loader_,
131  tr("Load map"),
132  QString().fromStdString(
133  stdr_gui_tools::getRosPackagePath("stdr_resources") +
134  std::string("/maps")),
135  tr("Yaml map files (*.yaml)"));
136  if(file_name.isEmpty() || file_name.isNull())
137  {
138  return;
139  }
140 
141  ros::NodeHandle nh;
142 
143  nav_msgs::OccupancyGrid map;
144 
145  map = stdr_server::map_loader::loadMap(file_name.toStdString().c_str());
146 
147  ros::ServiceClient client;
148 
150  ("/stdr_server/load_static_map_external", ros::Duration(.1)) &&
151  ros::ok())
152  {
153  ROS_WARN
154  ("Trying to register to /stdr_server/load_static_map_external...");
155  }
156 
157  client = nh.serviceClient<stdr_msgs::LoadExternalMap>
158  ("/stdr_server/load_static_map_external", true);
159 
160  stdr_msgs::LoadExternalMap srv;
161 
162  srv.request.map = map;
163 
164  if (client.call(srv)) {
165  ROS_INFO("Map successfully loaded");
166  }
167  else {
168  ROS_ERROR("Could not load map, maybe already loaded...");
169  }
170  }
171 
177  {
178  QMessageBox msg(static_cast<QMainWindow *>(&this->loader_));
179  msg.setWindowTitle(QString("STDR Simulator - About"));
180  msg.setText(QString("Simple Two Dimentional Robot Simulator\
181  (STDR Simulator) is a multi-robot simulator created in QT4. Its goals\
182  are : \n\n1) to simulate easily a single robot or a swarm in a 2D\
183  environment, \n2) to be totally parameterizable \n3) to be ROS\
184  compliant.\n\nDevelopers:\nManos Tsardoulias, etsardou@gmail.com\
185  \nChris Zalidis,zalidis@gmail.com\nAris Thallas, aris.thallas@gmail.com"));
186  msg.exec();
187  }
188 
194  {
196  }
197 
203  {
204  if ( ! map_initialized_ )
205  {
206  return;
207  }
208  QString file_name = QFileDialog::getOpenFileName(
209  &loader_,
210  tr("Load robot"),
211  QString().fromStdString(
212  stdr_gui_tools::getRosPackagePath("stdr_resources")) +
213  QString("/resources/"),
214  tr("Robot Files (*.yaml *xml)"));
215 
216  if (file_name.isEmpty()) {
217  return;
218  }
219 
220  try {
221  stdr_msgs::RobotMsg new_robot_msg =
222  stdr_parser::Parser::createMessage<stdr_msgs::RobotMsg>
223  (file_name.toStdString());
224 
225  Q_EMIT robotFromFile(new_robot_msg);
226  }
228  {
229  QMessageBox msg(static_cast<QMainWindow *>(&this->loader_));
230  msg.setWindowTitle(QString("STDR Parser - Error"));
231  msg.setText(QString(ex.what()));
232  msg.exec();
233  return;
234  }
235  }
236 
242  {
243  if ( ! map_initialized_ )
244  {
245  return;
246  }
247  Q_EMIT loadRfidPressed();
248  }
249 
255  {
256  if ( ! map_initialized_ )
257  {
258  return;
259  }
260  Q_EMIT loadThermalPressed();
261  }
262 
268  {
269  if ( ! map_initialized_ )
270  {
271  return;
272  }
273  Q_EMIT loadCo2Pressed();
274  }
275 
281  {
282  if ( ! map_initialized_ )
283  {
284  return;
285  }
286  Q_EMIT loadSoundPressed();
287  }
288 
294  {
295  if ( ! map_initialized_ )
296  {
297  return;
298  }
299  Q_EMIT setZoomInCursor(loader_.actionZoomIn->isChecked());
300  loader_.actionZoomOut->setChecked(false);
301  loader_.actionAdjusted->setChecked(false);
302  }
303 
309  {
310  if ( ! map_initialized_ )
311  {
312  return;
313  }
314  Q_EMIT setZoomOutCursor(loader_.actionZoomOut->isChecked());
315  loader_.actionZoomIn->setChecked(false);
316  loader_.actionAdjusted->setChecked(false);
317  }
318 
324  {
325  if ( ! map_initialized_ )
326  {
327  return;
328  }
329  Q_EMIT setAdjustedCursor(loader_.actionAdjusted->isChecked());
330  loader_.actionZoomIn->setChecked(false);
331  loader_.actionZoomOut->setChecked(false);
332  }
333 
339  {
340  if ( ! map_initialized_ )
341  {
342  return;
343  }
345  }
346 
352  {
353  return grid_enabled_;
354  }
355 
363  void CGuiConnector::addToGrid(QWidget *w,int row,int column)
364  {
365  loader_.gridLayout->addWidget(w,row,column,0);
366  }
367 
374  void CGuiConnector::setGridColumnStretch(int cell,int stretch)
375  {
376  loader_.gridLayout->setColumnStretch(cell,stretch);
377  }
378 
384  {
385  loader_.show();
386  loader_.showMaximized();
387  }
388 
395  {
396  loader_.statusbar->showMessage(s,0);
397  }
398 
404  {
405  return loader_.getCloseEvent();
406  }
407 
413  {
414  return loader_.closeTriggered();
415  }
416 
422  {
423  loader_.shutdown();
424  }
425 
432  {
433  map_initialized_ = mi;
434  }
435 
441  {
442  loader_.actionZoomIn->setChecked(false);
443  loader_.actionZoomOut->setChecked(false);
444  }
445 
452  void CGuiConnector::raiseMessage(QString title, QString s)
453  {
454  QMessageBox msg(static_cast<QMainWindow *>(&this->loader_));
455  msg.setWindowTitle(title);
456  msg.setText(s);
457  msg.exec();
458  }
459 }
void loadCo2Pressed(void)
Signal emmited on load CO2 source pressed.
QAction * actionZoomOut
The action of map adjusted button.
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
CRobotCreatorConnector robotCreatorConn
< Serves the Qt events of the RobotCreator Widget
void setGridColumnStretch(int cell, int stretch)
Wraps the Qt gridColumnStretch function.
std::string getRosPackagePath(std::string package)
Returns the global path of the ROS package provided.
Definition: stdr_tools.cpp:31
void setMapInitialized(bool mi)
Sets the map_initialized_ private variable.
void actionZoomOutTriggered(void)
Qt slot that is called when the zoom out tool button is pressed.
QAction * actionNewRobot
The action of adding a new robot button.
void robotFromFile(stdr_msgs::RobotMsg msg)
Signal emmited on load robot from file pressed.
void initialise(void)
Initializes the robot creator.
void show(void)
Shows the main window.
void setAdjustedCursor(bool state)
Qt signal that is emmited when the Adjust map button is pressed.
QEvent * getCloseEvent(void)
Returns the exit event.
bool map_initialized_
True if grid is enabled.
void shutdown(void)
Shuts down the main window.
void shutdown(void)
Shuts down the main window.
QAction * actionAddRobot
The action of new RFID tag button.
void actionNewRobotTriggered(void)
Qt slot that is called when the NewRobot tool button is pressed.
QAction * actionZoomIn
The action of zooming out button.
#define ROS_WARN(...)
void setZoomInCursor(bool state)
Qt signal that is emmited in GuiConnector::actionZoomInTriggered and connects to MapLoader::setCursor...
nav_msgs::OccupancyGrid loadMap(const std::string &fname)
void raiseMessage(QString title, QString s)
Raises a message box with a specific message.
void addToGrid(QWidget *w, int row, int column)
Adds a widget to the main window Qt grid.
void loadSoundPressed(void)
Signal emmited on load sound source pressed.
bool closeTriggered(void)
Returns the exit triggered status.
void actionAddRobotTriggered(void)
Qt slot that is called when the AddRobot tool button is pressed.
QEvent * getCloseEvent(void)
Returns the exit event captured.
void setZoomOutCursor(bool state)
Qt signal that is emmited in GuiConnector::actionZoomOutTriggered and connects to MapLoader::setCurso...
QAction * actionGrid
The action of creating new robot button.
#define ROS_INFO(...)
void actionGridTriggered(void)
Qt slot that is called when the grid status has changed.
void actionAdjustedTriggered(void)
Qt slot that is called when the adjusted map visualization tool button is pressed.
void loadRfidPressed(void)
Signal emmited on load RFID tag pressed.
ROSCPP_DECL bool ok()
void setStatusBarMessage(QString s)
Displays a message in the QMainWindow status bar.
void actionNewSoundTriggered(void)
Qt slot that is called when the NewSound tool button is pressed.
QAction * actionNewSound
The action of loading a map button.
QAction * actionLoadMap
The action of zooming in button.
CGuiConnector(int argc, char **argv)
Default contructor.
The main namespace for STDR GUI.
void actionNewCo2Triggered(void)
Qt slot that is called when the NewCO2 tool button is pressed.
QAction * actionProperties
< The action of properties button
void loadThermalPressed(void)
Signal emmited on load thermal source pressed.
bool grid_enabled_
The loader of main GUI QWidget.
void actionLoadMapTriggered(void)
Qt slot that is called when the LoadMap tool button is pressed.
QAction * actionNewRfid
The action of new thermal source button.
void actionExitTriggered(void)
Qt slot that is called when the Exit action is triggered.
QAction * actionNewThermal
The action of new CO2 source button.
void actionAboutTriggered(void)
Qt slot that is called when the About tool button is pressed.
void actionNewThermalTriggered(void)
Qt slot that is called when the NewThermal tool button is pressed.
void actionPropertiesTriggered(void)
Qt slot that is called when the Properties tool button is pressed.
void uncheckZoomButtons(void)
Unchecks the zoom in & out buttons when right click in map is pushed.
QAction * actionNewCo2
The action of new sound source button.
#define ROS_ERROR(...)
void actionZoomInTriggered(void)
Qt slot that is called when the zoom in tool button is pressed.
bool isGridEnabled(void)
Returns the grid enabled state.
void actionNewRfidTriggered(void)
Qt slot that is called when the NewRfid tool button is pressed.
bool closeTriggered(void)
Returns true if a close event was triggered.
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Mon Jun 10 2019 15:15:16