36 robotCreatorConn(argc,argv),
48 loader_.actionAbout_STDR_Simulator,SIGNAL(triggered(
bool)),
52 loader_.actionExit,SIGNAL(triggered(
bool)),
118 QMessageBox msg(static_cast<QMainWindow *>(&this->
loader_));
119 msg.setWindowTitle(QString(
"Not finished yet :/"));
129 QString file_name = QFileDialog::getOpenFileName(
132 QString().fromStdString(
134 std::string(
"/maps")),
135 tr(
"Yaml map files (*.yaml)"));
136 if(file_name.isEmpty() || file_name.isNull())
143 nav_msgs::OccupancyGrid map;
150 (
"/stdr_server/load_static_map_external",
ros::Duration(.1)) &&
154 (
"Trying to register to /stdr_server/load_static_map_external...");
158 (
"/stdr_server/load_static_map_external",
true);
160 stdr_msgs::LoadExternalMap srv;
162 srv.request.map = map;
164 if (client.call(srv)) {
165 ROS_INFO(
"Map successfully loaded");
168 ROS_ERROR(
"Could not load map, maybe already loaded...");
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"));
208 QString file_name = QFileDialog::getOpenFileName(
211 QString().fromStdString(
213 QString(
"/resources/"),
214 tr(
"Robot Files (*.yaml *xml)"));
216 if (file_name.isEmpty()) {
221 stdr_msgs::RobotMsg new_robot_msg =
222 stdr_parser::Parser::createMessage<stdr_msgs::RobotMsg>
223 (file_name.toStdString());
229 QMessageBox msg(static_cast<QMainWindow *>(&this->
loader_));
230 msg.setWindowTitle(QString(
"STDR Parser - Error"));
231 msg.setText(QString(ex.what()));
365 loader_.gridLayout->addWidget(w,row,column,0);
376 loader_.gridLayout->setColumnStretch(cell,stretch);
396 loader_.statusbar->showMessage(s,0);
454 QMessageBox msg(static_cast<QMainWindow *>(&this->
loader_));
455 msg.setWindowTitle(title);
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.
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.
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.
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.
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.
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)