Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #ifndef STDR_GUI_CONTROLLER
00023 #define STDR_GUI_CONTROLLER
00024
00025 #include <iostream>
00026 #include <cstdlib>
00027 #include <boost/thread.hpp>
00028
00029 #include "nav_msgs/OccupancyGrid.h"
00030
00031 #include "stdr_gui/stdr_gui_connector.h"
00032 #include "stdr_gui/stdr_info_connector.h"
00033 #include "stdr_gui/stdr_map_connector.h"
00034 #include "stdr_gui/stdr_visualization/stdr_sonar_visualization.h"
00035 #include "stdr_gui/stdr_visualization/stdr_laser_visualization.h"
00036 #include "stdr_gui/stdr_visualization/stdr_robot_visualization.h"
00037 #include "stdr_gui/stdr_gui_sensors/stdr_gui_robot.h"
00038 #include "stdr_gui/stdr_map_metainformation/stdr_gui_co2_source.h"
00039 #include "stdr_gui/stdr_map_metainformation/stdr_gui_sound_source.h"
00040 #include "stdr_gui/stdr_map_metainformation/stdr_gui_thermal_source.h"
00041 #include "stdr_gui/stdr_map_metainformation/stdr_gui_rfid_tag.h"
00042
00043 #include <stdr_robot/handle_robot.h>
00044
00049 namespace stdr_gui
00050 {
00051
00056 class CGuiController :
00057 public QThread
00058 {
00059 Q_OBJECT
00060
00061
00062 private:
00063
00064 typedef std::map<QString,CLaserVisualisation *>::iterator
00065 LaserVisIterator;
00066 typedef std::map<QString,CSonarVisualisation *>::iterator
00067 SonarVisIterator;
00068 typedef std::map<QString,CRobotVisualisation *>::iterator
00069 RobotVisIterator;
00070 typedef std::map<QString,CGuiRfidTag>::iterator RfidTagIterator;
00071 typedef std::map<QString,CGuiCo2Source>::iterator Co2SourcesIterator;
00072 typedef std::map<QString,CGuiSoundSource>::iterator SoundSourcesIterator;
00073 typedef std::map<QString,CGuiThermalSource>::iterator
00074 ThermalSourcesIterator;
00075
00077 int argc_;
00079 char** argv_;
00080
00082 bool map_lock_;
00084 bool map_initialized_;
00085
00087 std::vector<CGuiRobot> registered_robots_;
00089 std::set<std::string> my_robots_;
00090
00092 std::map<QString,CLaserVisualisation *> laser_visualizers_;
00094 std::map<QString,CSonarVisualisation *> sonar_visualizers_;
00096 std::map<QString,CRobotVisualisation *> robot_visualizers_;
00097
00099 std::map<QString,CGuiRfidTag> rfid_tags_;
00101 stdr_msgs::RfidTagVector rfid_tag_pure_;
00103 stdr_msgs::ThermalSourceVector thermal_source_pure_;
00105 std::map<QString,CGuiThermalSource> thermal_sources_;
00107 stdr_msgs::CO2SourceVector co2_source_pure_;
00109 std::map<QString,CGuiCo2Source> co2_sources_;
00111 stdr_msgs::SoundSourceVector sound_source_pure_;
00113 std::map<QString,CGuiSoundSource> sound_sources_;
00114
00116 ros::Subscriber map_subscriber_;
00118 ros::Subscriber robot_subscriber_;
00120 ros::Subscriber rfids_subscriber_;
00122 ros::Subscriber co2_sources_subscriber_;
00124 ros::Subscriber thermal_sources_subscriber_;
00126 ros::Subscriber sound_sources_subscriber_;
00128 ros::NodeHandle n_;
00130 tf::TransformListener listener_;
00131
00133 nav_msgs::OccupancyGrid map_msg_;
00134
00136 stdr_robot::HandleRobot robot_handler_;
00138 stdr_msgs::RobotIndexedVectorMsg all_robots_;
00139
00141 QTimer* timer_;
00143 QTime elapsed_time_;
00144
00146 QIcon icon_move_;
00148 QIcon icon_delete_;
00149
00151 QImage initial_map_;
00153 QImage running_map_;
00154
00156 CGuiConnector gui_connector_;
00158 CInfoConnector info_connector_;
00160 CMapConnector map_connector_;
00161
00168 stdr_msgs::LaserSensorMsg getLaserDescription(
00169 QString robotName,
00170 QString laserName);
00171
00178 stdr_msgs::SonarSensorMsg getSonarDescription(
00179 QString robotName,
00180 QString sonarName);
00181
00183 std::string robot_following_;
00184
00186 ros::ServiceClient new_rfid_tag_client_;
00188 ros::ServiceClient delete_rfid_tag_client_;
00189
00191 ros::ServiceClient new_co2_source_client_;
00193 ros::ServiceClient delete_co2_source_client_;
00194
00196 ros::ServiceClient new_thermal_source_client_;
00198 ros::ServiceClient delete_thermal_source_client_;
00199
00201 ros::ServiceClient new_sound_source_client_;
00203 ros::ServiceClient delete_sound_source_client_;
00204
00205
00206 public:
00207
00214 CGuiController(int argc,char **argv);
00215
00220 ~CGuiController(void);
00221
00226 void setupWidgets(void);
00227
00232 void initializeCommunications(void);
00233
00239 void receiveMap(const nav_msgs::OccupancyGrid& msg);
00240
00246 void receiveRfids(const stdr_msgs::RfidTagVector& msg);
00247
00253 void receiveCO2Sources(const stdr_msgs::CO2SourceVector& msg);
00254
00260 void receiveThermalSources(const stdr_msgs::ThermalSourceVector& msg);
00261
00267 void receiveSoundSources(const stdr_msgs::SoundSourceVector& msg);
00268
00274 void receiveRobots(const stdr_msgs::RobotIndexedVectorMsg& msg);
00275
00280 bool init();
00281
00287 void cleanupVisualizers(const stdr_msgs::RobotIndexedVectorMsg& msg);
00288
00289
00290 public Q_SLOTS:
00291
00298 void saveRobotPressed(stdr_msgs::RobotMsg newRobotMsg,QString file_name);
00299
00305 void loadRobotPressed(stdr_msgs::RobotMsg newRobotMsg);
00306
00312 void loadRobotFromFilePressed(stdr_msgs::RobotMsg newRobotMsg);
00313
00318 void loadRfidPressed(void);
00319
00324 void loadCo2Pressed(void);
00325
00330 void loadSoundPressed(void);
00331
00336 void loadThermalPressed(void);
00337
00343 void zoomInPressed(QPoint p);
00344
00350 void zoomOutPressed(QPoint p);
00351
00357 void robotPlaceSet(QPoint p);
00358
00364 void rfidPlaceSet(QPoint p);
00365
00371 void thermalPlaceSet(QPoint p);
00372
00378 void co2PlaceSet(QPoint p);
00379
00385 void soundPlaceSet(QPoint p);
00386
00391 void updateMapInternal(void);
00392
00399 void laserVisualizerClicked(QString robotName,QString laserName);
00400
00407 void sonarVisualizerClicked(QString robotName,QString sonarName);
00408
00414 void robotVisualizerClicked(QString robotName);
00415
00422 void itemClicked(QPoint p,Qt::MouseButton b);
00423
00430 void robotReplaceSet(QPoint p,std::string robotName);
00431
00438 void laserVisibilityClicked(QString robotName,QString laserName);
00439
00446 void sonarVisibilityClicked(QString robotName,QString sonarName);
00447
00456 void rfidReaderVisibilityClicked(QString robotName,QString rfidReaderName);
00457
00466 void co2SensorVisibilityClicked(QString robotName,QString co2SensorName);
00467
00476 void thermalSensorVisibilityClicked(QString robotName,QString thermalSensorName);
00477
00486 void soundSensorVisibilityClicked(QString robotName,QString soundSensorName);
00487
00493 void robotVisibilityClicked(QString robotName);
00494
00495
00496 Q_SIGNALS:
00497
00502 void waitForRobotPose(void);
00503
00508 void waitForThermalPose(void);
00509
00514 void waitForCo2Pose(void);
00515
00520 void waitForSoundPose(void);
00521
00526 void waitForRfidPose(void);
00527
00533 void replaceRobot(std::string robotFrameId);
00534
00542 void setLaserVisibility(QString robotName,QString laserName,char vs);
00543
00551 void setSonarVisibility(QString robotName,QString sonarName,char vs);
00552
00561 void setRfidReaderVisibility(QString robotName,
00562 QString rfidReaderName, char vs);
00563
00572 void setCO2SensorVisibility(QString robotName,
00573 QString co2SensorName, char vs);
00574
00583 void setThermalSensorVisibility(QString robotName,
00584 QString thermalSensorName, char vs);
00585
00594 void setSoundSensorVisibility(QString robotName,
00595 QString soundSensorName, char vs);
00596
00603 void setRobotVisibility(QString robotName,char vs);
00604 };
00605 }
00606
00607 #endif
00608