stdr_gui_robot.h
Go to the documentation of this file.
00001 /******************************************************************************
00002    STDR Simulator - Simple Two DImensional Robot Simulator
00003    Copyright (C) 2013 STDR Simulator
00004    This program is free software; you can redistribute it and/or modify
00005    it under the terms of the GNU General Public License as published by
00006    the Free Software Foundation; either version 3 of the License, or
00007    (at your option) any later version.
00008    This program is distributed in the hope that it will be useful,
00009    but WITHOUT ANY WARRANTY; without even the implied warranty of
00010    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011    GNU General Public License for more details.
00012    You should have received a copy of the GNU General Public License
00013    along with this program; if not, write to the Free Software Foundation,
00014    Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301  USA
00015    
00016    Authors : 
00017    * Manos Tsardoulias, etsardou@gmail.com
00018    * Aris Thallas, aris.thallas@gmail.com
00019    * Chris Zalidis, zalidis@gmail.com 
00020 ******************************************************************************/
00021 
00022 #ifndef STDR_GUI_ROBOT_CONTAINER
00023 #define STDR_GUI_ROBOT_CONTAINER
00024 
00025 #include "stdr_gui/stdr_tools.h"
00026 #include "stdr_gui/stdr_gui_sensors/stdr_gui_laser.h"
00027 #include "stdr_gui/stdr_gui_sensors/stdr_gui_rfid.h"
00028 #include "stdr_gui/stdr_gui_sensors/stdr_gui_co2.h"
00029 #include "stdr_gui/stdr_gui_sensors/stdr_gui_thermal.h"
00030 #include "stdr_gui/stdr_gui_sensors/stdr_gui_sound.h"
00031 #include "stdr_gui/stdr_gui_sensors/stdr_gui_sonar.h"
00032 
00037 namespace stdr_gui
00038 {
00043   class CGuiRobot
00044   {
00045     //------------------------------------------------------------------------//
00046     private:
00047     
00049       bool show_label_;
00051       bool show_circles_;
00053       bool robot_initialized_;
00054       
00056       bool started_;
00057       
00059       ros::Subscriber speeds_subscriber_;
00060       
00062       float linear_speed_;
00064       float angular_speed_;
00065       
00067       float radius_;
00069       float resolution_;
00070       
00072       std::vector<CGuiLaser*>   lasers_;
00074       std::vector<CGuiSonar*>   sonars_;
00076       std::vector<CGuiRfid*>    rfids_;
00078       std::vector<CGuiCO2*>     co2_sensors_;
00080       std::vector<CGuiThermal*> thermal_sensors_;
00082       std::vector<CGuiSound*>   sound_sensors_;
00083       
00085       std::string frame_id_;
00087       geometry_msgs::Pose2D initial_pose_;
00089       geometry_msgs::Pose2D current_pose_;
00090       
00092       stdr_msgs::FootprintMsg footprint_;
00093       
00095       QImage visualization;
00096       
00102       void drawSelf(QImage *m);
00103       
00105       char visualization_status_;
00106     //------------------------------------------------------------------------//
00107     public:
00108     
00114       CGuiRobot(const stdr_msgs::RobotIndexedMsg& msg);
00115       
00120       ~CGuiRobot(void);
00121       
00126       std::string getFrameId(void);
00127       
00135       void draw(QImage *m,float ocgd,tf::TransformListener *listener);
00136       
00143       void drawLabel(QImage *m,float ocgd);
00144       
00150       bool checkEventProximity(QPoint p);
00151       
00157       void setShowLabel(bool b);
00158       
00163       void toggleShowLabel(void);
00164       
00169       bool getShowLabel(void);
00170       
00175       void toggleShowCircles(void);
00176       
00181       QPoint getCurrentPose(void);
00182       
00187       void destroy(void);
00188       
00193       int getLasersNumber(void);
00194       
00199       int getSonarsNumber(void);
00200       
00205       char getVisualizationStatus(void);
00206       
00211       void toggleVisualizationStatus(void);
00212       
00218       char getLaserVisualizationStatus(std::string frame_id);
00219       
00225       void toggleLaserVisualizationStatus(std::string frame_id);
00226       
00232       char getRfidReaderVisualizationStatus(std::string frame_id);
00238       char getCO2SensorVisualizationStatus(std::string frame_id);
00244       char getThermalSensorVisualizationStatus(std::string frame_id);
00250       char getSoundSensorVisualizationStatus(std::string frame_id);
00251       
00257       void toggleRfidReaderVisualizationStatus(std::string frame_id);
00263       void toggleCO2SensorVisualizationStatus(std::string frame_id);
00269       void toggleThermalSensorVisualizationStatus(std::string frame_id);
00275       void toggleSoundSensorVisualizationStatus(std::string frame_id);
00276       
00282       char getSonarVisualizationStatus(std::string frame_id);
00283       
00289       void toggleSonarVisualizationStatus(std::string frame_id);
00290       
00296       QImage getVisualization(float ocgd);
00297       
00302       geometry_msgs::Pose2D getCurrentPoseM(void);
00303       
00309       void speedsCallback(const geometry_msgs::Twist& msg);
00310       
00315       std::pair<float,float> getSpeeds(void);
00316       
00322       void setEnvironmentalTags(stdr_msgs::RfidTagVector env_tags);
00328       void setEnvironmentalCO2Sources(stdr_msgs::CO2SourceVector env_co2_sources);
00329       void setEnvironmentalThermalSources(stdr_msgs::ThermalSourceVector env_thermal_sources);
00330       void setEnvironmentalSoundSources(stdr_msgs::SoundSourceVector env_sound_sources);
00331   };  
00332 }
00333 
00334 #endif


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Wed Sep 2 2015 03:36:44