stdr_gui_controller.h
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 
22 #ifndef STDR_GUI_CONTROLLER
23 #define STDR_GUI_CONTROLLER
24 
25 #include <iostream>
26 #include <cstdlib>
27 #include <boost/thread.hpp>
28 
29 #include "nav_msgs/OccupancyGrid.h"
30 
42 
44 
49 namespace stdr_gui
50 {
51 
56  class CGuiController :
57  public QThread
58  {
59  Q_OBJECT
60 
61  //------------------------------------------------------------------------//
62  private:
63 
64  typedef std::map<QString,CLaserVisualisation *>::iterator
66  typedef std::map<QString,CSonarVisualisation *>::iterator
68  typedef std::map<QString,CRobotVisualisation *>::iterator
70  typedef std::map<QString,CGuiRfidTag>::iterator RfidTagIterator;
71  typedef std::map<QString,CGuiCo2Source>::iterator Co2SourcesIterator;
72  typedef std::map<QString,CGuiSoundSource>::iterator SoundSourcesIterator;
73  typedef std::map<QString,CGuiThermalSource>::iterator
75 
77  int argc_;
79  char** argv_;
80 
82  bool map_lock_;
85 
87  std::vector<CGuiRobot> registered_robots_;
89  std::set<std::string> my_robots_;
90 
92  std::map<QString,CLaserVisualisation *> laser_visualizers_;
94  std::map<QString,CSonarVisualisation *> sonar_visualizers_;
96  std::map<QString,CRobotVisualisation *> robot_visualizers_;
97 
99  std::map<QString,CGuiRfidTag> rfid_tags_;
101  stdr_msgs::RfidTagVector rfid_tag_pure_;
103  stdr_msgs::ThermalSourceVector thermal_source_pure_;
105  std::map<QString,CGuiThermalSource> thermal_sources_;
107  stdr_msgs::CO2SourceVector co2_source_pure_;
109  std::map<QString,CGuiCo2Source> co2_sources_;
111  stdr_msgs::SoundSourceVector sound_source_pure_;
113  std::map<QString,CGuiSoundSource> sound_sources_;
114 
131 
133  nav_msgs::OccupancyGrid map_msg_;
134 
138  stdr_msgs::RobotIndexedVectorMsg all_robots_;
139 
141  QTimer* timer_;
144 
146  QIcon icon_move_;
149 
151  QImage initial_map_;
153  QImage running_map_;
154 
161 
168  stdr_msgs::LaserSensorMsg getLaserDescription(
169  QString robotName,
170  QString laserName);
171 
178  stdr_msgs::SonarSensorMsg getSonarDescription(
179  QString robotName,
180  QString sonarName);
181 
183  std::string robot_following_;
184 
189 
194 
199 
204 
205  //------------------------------------------------------------------------//
206  public:
207 
214  CGuiController(int argc,char **argv);
215 
220  ~CGuiController(void);
221 
226  void setupWidgets(void);
227 
232  void initializeCommunications(void);
233 
239  void receiveMap(const nav_msgs::OccupancyGrid& msg);
240 
246  void receiveRfids(const stdr_msgs::RfidTagVector& msg);
247 
253  void receiveCO2Sources(const stdr_msgs::CO2SourceVector& msg);
254 
260  void receiveThermalSources(const stdr_msgs::ThermalSourceVector& msg);
261 
267  void receiveSoundSources(const stdr_msgs::SoundSourceVector& msg);
268 
274  void receiveRobots(const stdr_msgs::RobotIndexedVectorMsg& msg);
275 
280  bool init();
281 
287  void cleanupVisualizers(const stdr_msgs::RobotIndexedVectorMsg& msg);
288 
289  //------------------------------------------------------------------------//
290  public Q_SLOTS:
291 
298  void saveRobotPressed(stdr_msgs::RobotMsg newRobotMsg,QString file_name);
299 
305  void loadRobotPressed(stdr_msgs::RobotMsg newRobotMsg);
306 
312  void loadRobotFromFilePressed(stdr_msgs::RobotMsg newRobotMsg);
313 
318  void loadRfidPressed(void);
319 
324  void loadCo2Pressed(void);
325 
330  void loadSoundPressed(void);
331 
336  void loadThermalPressed(void);
337 
343  void zoomInPressed(QPoint p);
344 
350  void zoomOutPressed(QPoint p);
351 
357  void robotPlaceSet(QPoint p);
358 
364  void rfidPlaceSet(QPoint p);
365 
371  void thermalPlaceSet(QPoint p);
372 
378  void co2PlaceSet(QPoint p);
379 
385  void soundPlaceSet(QPoint p);
386 
391  void updateMapInternal(void);
392 
399  void laserVisualizerClicked(QString robotName,QString laserName);
400 
407  void sonarVisualizerClicked(QString robotName,QString sonarName);
408 
414  void robotVisualizerClicked(QString robotName);
415 
422  void itemClicked(QPoint p,Qt::MouseButton b);
423 
430  void robotReplaceSet(QPoint p,std::string robotName);
431 
438  void laserVisibilityClicked(QString robotName,QString laserName);
439 
446  void sonarVisibilityClicked(QString robotName,QString sonarName);
447 
456  void rfidReaderVisibilityClicked(QString robotName,QString rfidReaderName);
457 
466  void co2SensorVisibilityClicked(QString robotName,QString co2SensorName);
467 
476  void thermalSensorVisibilityClicked(QString robotName,QString thermalSensorName);
477 
486  void soundSensorVisibilityClicked(QString robotName,QString soundSensorName);
487 
493  void robotVisibilityClicked(QString robotName);
494 
495  //------------------------------------------------------------------------//
496  Q_SIGNALS:
497 
502  void waitForRobotPose(void);
503 
508  void waitForThermalPose(void);
509 
514  void waitForCo2Pose(void);
515 
520  void waitForSoundPose(void);
521 
526  void waitForRfidPose(void);
527 
533  void replaceRobot(std::string robotFrameId);
534 
542  void setLaserVisibility(QString robotName,QString laserName,char vs);
543 
551  void setSonarVisibility(QString robotName,QString sonarName,char vs);
552 
561  void setRfidReaderVisibility(QString robotName,
562  QString rfidReaderName, char vs);
563 
572  void setCO2SensorVisibility(QString robotName,
573  QString co2SensorName, char vs);
574 
583  void setThermalSensorVisibility(QString robotName,
584  QString thermalSensorName, char vs);
585 
594  void setSoundSensorVisibility(QString robotName,
595  QString soundSensorName, char vs);
596 
603  void setRobotVisibility(QString robotName,char vs);
604  };
605 }
606 
607 #endif
608 
void thermalSensorVisibilityClicked(QString robotName, QString thermalSensorName)
Informs CGuiController that a Thermal Sensor visibility status has \ been clicked. Connects to the CInfoConnector::thermalSensorVisibilityClicked\ signal.
void setLaserVisibility(QString robotName, QString laserName, char vs)
Is emitted when a laser&#39;s visibility status is going to be changed. Connects to the CInfoConnector::s...
void saveRobotPressed(stdr_msgs::RobotMsg newRobotMsg, QString file_name)
Saves the robot in a yaml file. Connects to the CGuiConnector::CRobotCreatorConnector::saveRobotPress...
void sonarVisualizerClicked(QString robotName, QString sonarName)
Informs CGuiController that a sonar visualizer has been clicked. Connects to the CInfoConnector::sona...
int argc_
Input arguments.
void setThermalSensorVisibility(QString robotName, QString thermalSensorName, char vs)
Is emitted when a thermal sensor&#39;s visibility status is going to be \ changed. Connects to the CInfoC...
nav_msgs::OccupancyGrid map_msg_
Robot handler from stdr_robot.
void thermalPlaceSet(QPoint p)
Gets the point at which the new thermal source is placed. Connects to the CMapConnector::thermalPlace...
void setRfidReaderVisibility(QString robotName, QString rfidReaderName, char vs)
Is emitted when a rfid sensor&#39;s visibility status is going to be \ changed. Connects to the CInfoConn...
void rfidPlaceSet(QPoint p)
Gets the point at which the new RFID tag is placed. Connects to the CMapConnector::robotPlaceSet sign...
void robotVisualizerClicked(QString robotName)
Informs CGuiController that a robot visualizer has been clicked. Connects to the CInfoConnector::robo...
void setSoundSensorVisibility(QString robotName, QString soundSensorName, char vs)
Is emitted when a sound sensor&#39;s visibility status is going to be \ changed. Connects to the CInfoCon...
std::map< QString, CSonarVisualisation * > sonar_visualizers_
Robot visualizers.
void zoomOutPressed(QPoint p)
Performs zoom out when the button is pressed. Connects to the CMapConnector::zoomOutPressed signal...
void loadRfidPressed(void)
Informs CGuiController that an RFID is going to be placed in the environment. Connects to the CGuiCon...
std::map< QString, CGuiSoundSource > sound_sources_
ROS subscriber for occupancy grid map.
char ** argv_
Prevents concurrent map writing.
void loadSoundPressed(void)
Informs CGuiController that a sound source is going to be placed in the environment. Connects to the CGuiConnector::loadSoundPressed signal.
std::map< QString, CLaserVisualisation * > laser_visualizers_
Sonar visualizers.
void initializeCommunications(void)
Initializes the Qt event connections and ROS subscribers and publishers.
void receiveRobots(const stdr_msgs::RobotIndexedVectorMsg &msg)
Receives the robots from stdr_server. Connects to "stdr_server/active_robots" ROS topic...
ros::NodeHandle n_
ROS tf transform listener.
void waitForRfidPose(void)
Is emitted when a new rfid tag is going to be placed. Connects to the CMapConnector::waitForRfidPose ...
void loadThermalPressed(void)
Informs CGuiController that a thermal source is going to be placed in the environment. Connects to the CGuiConnector::loadThermalPressed signal.
void waitForRobotPose(void)
Is emitted when a new robot is going to be placed. Connects to the CMapConnector::waitForPlace slot...
void rfidReaderVisibilityClicked(QString robotName, QString rfidReaderName)
Informs CGuiController that a rfidReader visibility status has \ been clicked. Connects to the CInfoC...
ros::ServiceClient new_thermal_source_client_
Service client for deleting a thermal source.
~CGuiController(void)
Default destructor.
QIcon icon_delete_
QImage created one time, containing the OGM.
QIcon icon_move_
QIcon for delete robot (pop-up menu)
QTime elapsed_time_
QIcon for move robot (pop-up menu)
void receiveMap(const nav_msgs::OccupancyGrid &msg)
Receives the occupancy grid map from stdr_server. Connects to "map" ROS topic.
ros::ServiceClient delete_thermal_source_client_
Service client for inserting a new sound source.
std::map< QString, CGuiSoundSource >::iterator SoundSourcesIterator
void replaceRobot(std::string robotFrameId)
Is emitted when a robot is going to be re-placed. Connects to the CMapConnector::waitForReplace slot...
ros::Subscriber rfids_subscriber_
ROS subscriber for co2 sources.
QImage running_map_
Object of CGuiConnector.
ros::ServiceClient delete_rfid_tag_client_
Service client for inserting a new co2 source.
std::map< QString, CRobotVisualisation * >::iterator RobotVisIterator
stdr_msgs::SoundSourceVector sound_source_pure_
Sound sources in the environment.
void laserVisibilityClicked(QString robotName, QString laserName)
Informs CGuiController that a laser visibility status has been clicked. Connects to the CInfoConnecto...
ros::Subscriber sound_sources_subscriber_
The ROS node handle.
std::map< QString, CLaserVisualisation * >::iterator LaserVisIterator
stdr_msgs::LaserSensorMsg getLaserDescription(QString robotName, QString laserName)
Returns a stdr_msgs::LaserSensorMsg message from robot and laser name.
void robotReplaceSet(QPoint p, std::string robotName)
Informs CGuiController about the new pose of a robot. Connects to the CMapConnector::robotReplaceSet ...
void waitForThermalPose(void)
Is emitted when a new thermal source is going to be placed. Connects to the CMapConnector::waitForThe...
Serves the Qt events of the main GUI window. Inherits from QObject.
ros::Subscriber co2_sources_subscriber_
ROS subscriber for thermal sources.
void loadRobotFromFilePressed(stdr_msgs::RobotMsg newRobotMsg)
Informs CGuiController that a robot is loaded from a yaml file. Connects to the CGuiConnector::robotF...
QTimer * timer_
Elapsed time from the experiment&#39;s start.
stdr_robot::HandleRobot robot_handler_
All robots in "raw" form.
void setCO2SensorVisibility(QString robotName, QString co2SensorName, char vs)
Is emitted when a CO2 sensor&#39;s visibility status is going to be \ changed. Connects to the CInfoConne...
std::map< QString, CRobotVisualisation * > robot_visualizers_
RFID tags in the environment.
void waitForCo2Pose(void)
Is emitted when a new CO2 source is going to be placed. Connects to the CMapConnector::waitForCo2Pose...
ros::ServiceClient new_sound_source_client_
Service client for deleting a sound source.
void receiveRfids(const stdr_msgs::RfidTagVector &msg)
Receives the existent rfid tags.
ros::ServiceClient delete_co2_source_client_
Service client for inserting a new thermal source.
QImage initial_map_
QImage that initiates as initial_map and the elements are painted on it.
std::map< QString, CSonarVisualisation * >::iterator SonarVisIterator
stdr_msgs::RfidTagVector rfid_tag_pure_
Thermal sources in the environment.
std::map< QString, CGuiThermalSource >::iterator ThermalSourcesIterator
Number of input arguments.
CGuiConnector gui_connector_
Object of CInfoConnector.
void laserVisualizerClicked(QString robotName, QString laserName)
Informs CGuiController that a laser visualizer has been clicked. Connects to the CInfoConnector::lase...
void loadCo2Pressed(void)
Informs CGuiController that a CO2 source is going to be placed in the environment. Connects to the CGuiConnector::loadCo2Pressed signal.
void receiveThermalSources(const stdr_msgs::ThermalSourceVector &msg)
Receives the existent thermal sources.
CInfoConnector info_connector_
Object of CMapConnector.
tf::TransformListener listener_
The occypancy grid map.
void waitForSoundPose(void)
Is emitted when a new sound source is going to be placed. Connects to the CMapConnector::waitForSOund...
ros::ServiceClient delete_sound_source_client_
void co2PlaceSet(QPoint p)
Gets the point at which the new CO2 source is placed. Connects to the CMapConnector::co2PlaceSet sign...
void zoomInPressed(QPoint p)
Performs zoom in when the button is pressed. Connects to the CMapConnector::zoomInPressed signal...
void receiveSoundSources(const stdr_msgs::SoundSourceVector &msg)
Receives the existent sound sources.
std::map< QString, CGuiRfidTag >::iterator RfidTagIterator
void sonarVisibilityClicked(QString robotName, QString sonarName)
Informs CGuiController that a sonar visibility status has been clicked. Connects to the CInfoConnecto...
void receiveCO2Sources(const stdr_msgs::CO2SourceVector &msg)
Receives the existent co2 sources.
void soundPlaceSet(QPoint p)
Gets the point at which the new sound source is placed. Connects to the CMapConnector::soundPlaceSet ...
The main namespace for STDR GUI.
void loadRobotPressed(stdr_msgs::RobotMsg newRobotMsg)
Loads a robot from robot creator into map. Connects to the CGuiConnector::CRobotCreatorConnector::loa...
ros::Subscriber robot_subscriber_
ROS subscriber for rfids.
void cleanupVisualizers(const stdr_msgs::RobotIndexedVectorMsg &msg)
Dumps all visualizers that connect to robots not existent in the input argument message.
void updateMapInternal(void)
Updates the map to be shown in GUI. Connects to the timeout signal of timer_.
Serves the Qt events of the map-holding widget. Inherits from QObject.
stdr_msgs::RobotIndexedVectorMsg all_robots_
Timer for the drawing event.
bool map_lock_
Prevents actions before map initializes.
std::map< QString, CGuiCo2Source > co2_sources_
Sound sources in the environment.
std::set< std::string > my_robots_
Laser visualizers.
bool init()
Initializes the ROS spin and Qt threads.
CGuiController(int argc, char **argv)
Default contructor.
std::string robot_following_
Service client for inserting a new rfid tag.
ros::Subscriber map_subscriber_
ROS subscriber to get all robots.
stdr_msgs::CO2SourceVector co2_source_pure_
CO2 sources in the environment.
std::vector< CGuiRobot > registered_robots_
Robots created from the specific GUI instance.
std::map< QString, CGuiThermalSource > thermal_sources_
The original vector.
void setupWidgets(void)
Sets up the main window widgets.
void robotPlaceSet(QPoint p)
Gets the point at which the new robot is placed. Connects to the CMapConnector::robotPlaceSet signal...
ros::ServiceClient new_rfid_tag_client_
Service client for deleting a rfid tag.
Serves the Qt events of the tree-like information widget. Inherits from QObject.
void setRobotVisibility(QString robotName, char vs)
Is emitted when a robot&#39;s visibility status is going to be changed. Connects to the CInfoConnector::s...
void setSonarVisibility(QString robotName, QString sonarName, char vs)
Is emitted when a sonar&#39;s visibility status is going to be changed. Connects to the CInfoConnector::s...
stdr_msgs::ThermalSourceVector thermal_source_pure_
CO2 sources in the environment.
void co2SensorVisibilityClicked(QString robotName, QString co2SensorName)
Informs CGuiController that a CO2Sensor visibility status has \ been clicked. Connects to the CInfoCo...
stdr_msgs::SonarSensorMsg getSonarDescription(QString robotName, QString sonarName)
Returns a stdr_msgs::SonarSensorMsg message from robot and sonar name.
void itemClicked(QPoint p, Qt::MouseButton b)
Informs CGuiController that click has performed in the map. Connects to the CMapConnector::itemClicke...
void robotVisibilityClicked(QString robotName)
Informs CGuiController that a robot visibility status has been clicked. Connects to the CInfoConnecto...
ros::ServiceClient new_co2_source_client_
Service client for deleting a co2 source.
std::map< QString, CGuiCo2Source >::iterator Co2SourcesIterator
std::map< QString, CGuiRfidTag > rfid_tags_
The original rfid vector.
bool map_initialized_
All the robots server has.
void soundSensorVisibilityClicked(QString robotName, QString soundSensorName)
Informs CGuiController that a sound Sensor visibility status has \ been clicked. Connects to the CInf...
ros::Subscriber thermal_sources_subscriber_
ROS subscriber for sound sources.


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