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 linear_speed_y_;
00066       float angular_speed_;
00067       
00069       float radius_;
00071       float resolution_;
00072       
00074       std::vector<CGuiLaser*>   lasers_;
00076       std::vector<CGuiSonar*>   sonars_;
00078       std::vector<CGuiRfid*>    rfids_;
00080       std::vector<CGuiCO2*>     co2_sensors_;
00082       std::vector<CGuiThermal*> thermal_sensors_;
00084       std::vector<CGuiSound*>   sound_sensors_;
00085       
00087       std::string frame_id_;
00089       geometry_msgs::Pose2D initial_pose_;
00091       geometry_msgs::Pose2D current_pose_;
00092       
00094       stdr_msgs::FootprintMsg footprint_;
00095       
00097       QImage visualization;
00098       
00104       void drawSelf(QImage *m);
00105       
00107       char visualization_status_;
00108     //------------------------------------------------------------------------//
00109     public:
00110     
00116       CGuiRobot(const stdr_msgs::RobotIndexedMsg& msg);
00117       
00122       ~CGuiRobot(void);
00123       
00128       std::string getFrameId(void);
00129       
00137       void draw(QImage *m,float ocgd,tf::TransformListener *listener);
00138       
00145       void drawLabel(QImage *m,float ocgd);
00146       
00152       bool checkEventProximity(QPoint p);
00153       
00159       void setShowLabel(bool b);
00160       
00165       void toggleShowLabel(void);
00166       
00171       bool getShowLabel(void);
00172       
00177       void toggleShowCircles(void);
00178       
00183       QPoint getCurrentPose(void);
00184       
00189       void destroy(void);
00190       
00195       int getLasersNumber(void);
00196       
00201       int getSonarsNumber(void);
00202       
00207       char getVisualizationStatus(void);
00208       
00213       void toggleVisualizationStatus(void);
00214       
00220       char getLaserVisualizationStatus(std::string frame_id);
00221       
00227       void toggleLaserVisualizationStatus(std::string frame_id);
00228       
00234       char getRfidReaderVisualizationStatus(std::string frame_id);
00240       char getCO2SensorVisualizationStatus(std::string frame_id);
00246       char getThermalSensorVisualizationStatus(std::string frame_id);
00252       char getSoundSensorVisualizationStatus(std::string frame_id);
00253       
00259       void toggleRfidReaderVisualizationStatus(std::string frame_id);
00265       void toggleCO2SensorVisualizationStatus(std::string frame_id);
00271       void toggleThermalSensorVisualizationStatus(std::string frame_id);
00277       void toggleSoundSensorVisualizationStatus(std::string frame_id);
00278       
00284       char getSonarVisualizationStatus(std::string frame_id);
00285       
00291       void toggleSonarVisualizationStatus(std::string frame_id);
00292       
00298       QImage getVisualization(float ocgd);
00299       
00304       geometry_msgs::Pose2D getCurrentPoseM(void);
00305       
00311       void speedsCallback(const geometry_msgs::Twist& msg);
00312       
00317       std::vector<float> getSpeeds(void);
00318       
00324       void setEnvironmentalTags(stdr_msgs::RfidTagVector env_tags);
00330       void setEnvironmentalCO2Sources(stdr_msgs::CO2SourceVector env_co2_sources);
00331       void setEnvironmentalThermalSources(stdr_msgs::ThermalSourceVector env_thermal_sources);
00332       void setEnvironmentalSoundSources(stdr_msgs::SoundSourceVector env_sound_sources);
00333   };  
00334 }
00335 
00336 #endif


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Thu Jun 6 2019 18:57:38