stdr_tools.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_TOOLS
00023 #define STDR_TOOLS
00024 
00025 #include <ros/package.h>
00026 #include "ros/ros.h"
00027 #include <tf/transform_listener.h>
00028 
00029 #include <QtUiTools/QUiLoader>
00030 
00031 #include <QtCore/QDir>
00032 #include <QtCore/QFile>
00033 #include <QtCore/QObject>
00034 #include <QtCore/QString>
00035 #include <QtCore/QThread>
00036 #include <QtCore/QTimer>
00037 #include <QtCore/QTime>
00038 
00039 #include <QtGui/QMenu>
00040 #include <QtGui/QApplication>
00041 #include <QtGui/QCheckBox>
00042 #include <QtGui/QComboBox>
00043 #include <QtGui/QDoubleSpinBox>
00044 #include <QtGui/QImage>
00045 #include <QtGui/QFileDialog>
00046 #include <QtGui/QLabel>
00047 #include <QtGui/QLineEdit>
00048 #include <QtGui/QListWidget>
00049 #include <QtGui/QPainter>
00050 #include <QtGui/QPixmap>
00051 #include <QtGui/QProgressBar>
00052 #include <QtGui/QPushButton>
00053 #include <QtGui/QRadioButton>
00054 #include <QtGui/QScrollBar>
00055 #include <QtGui/QStatusBar>
00056 #include <QtGui/QTextEdit>
00057 #include <QtGui/QTreeWidget>
00058 #include <QtGui/QVBoxLayout>
00059 #include <QtGui/QWidget>
00060 #include <QtGui/QWindowsStyle>
00061 #include <QtGui/QInputDialog>
00062 #include <QtGui/QMouseEvent>
00063 #include <QtGui/QMessageBox>
00064 #include <QtGui/QTimeEdit>
00065 #include <QtGui/QInputDialog>
00066 #include <QtGui/QFont>
00067 
00068 #include <stdr_msgs/RobotIndexedVectorMsg.h>
00069 #include <stdr_msgs/RobotIndexedMsg.h>
00070 #include <stdr_msgs/RobotMsg.h>
00071 #include <stdr_msgs/Noise.h>
00072 
00073 #include <stdr_msgs/RfidTagVector.h>
00074 #include <stdr_msgs/AddRfidTag.h>
00075 #include <stdr_msgs/DeleteRfidTag.h>
00076 
00077 #include <stdr_msgs/CO2SourceVector.h>
00078 #include <stdr_msgs/AddCO2Source.h>
00079 #include <stdr_msgs/DeleteCO2Source.h>
00080 
00081 #include <stdr_msgs/ThermalSourceVector.h>
00082 #include <stdr_msgs/AddThermalSource.h>
00083 #include <stdr_msgs/DeleteThermalSource.h>
00084 
00085 #include <stdr_msgs/SoundSourceVector.h>
00086 #include <stdr_msgs/AddSoundSource.h>
00087 #include <stdr_msgs/DeleteSoundSource.h>
00088 
00089 #include <geometry_msgs/Pose2D.h>
00090 #include <geometry_msgs/Point.h>
00091 #include <geometry_msgs/Twist.h>
00092 
00093 #include <sensor_msgs/LaserScan.h>
00094 
00095 #include "stdr_server/map_loader.h"
00096 #include <stdr_msgs/LoadExternalMap.h>
00097 
00098 #include <stdr_parser/stdr_parser.h>
00099 
00100 #define STDR_PI 3.14159265359
00101 
00106 namespace stdr_gui_tools
00107 {
00113   std::string getRosPackagePath(std::string package);
00114   
00120   QString getLiteralTime(int ms);
00121   
00127   float angleRadToDegrees(float angle);
00128   
00134   float angleDegreesToRad(float angle);
00135   
00141   void printSonarMsg(stdr_msgs::SonarSensorMsg &msg);
00142   
00148   void printLaserMsg(stdr_msgs::LaserSensorMsg &msg);
00149   
00155   void printPose2D(geometry_msgs::Pose2D &msg);
00156   
00162   stdr_msgs::RobotMsg fixRobotAnglesToRad(stdr_msgs::RobotMsg rmsg);
00163   
00169   stdr_msgs::RobotMsg fixRobotAnglesToDegrees(stdr_msgs::RobotMsg rmsg);
00170   
00176   stdr_msgs::LaserSensorMsg fixLaserAnglesToRad(stdr_msgs::LaserSensorMsg rmsg);
00177   
00183   stdr_msgs::LaserSensorMsg fixLaserAnglesToDegrees(
00184     stdr_msgs::LaserSensorMsg rmsg);
00185     
00191   stdr_msgs::SonarSensorMsg fixSonarAnglesToRad(stdr_msgs::SonarSensorMsg rmsg);
00192   
00198   stdr_msgs::SonarSensorMsg fixSonarAnglesToDegrees(
00199     stdr_msgs::SonarSensorMsg rmsg);
00200     
00206   stdr_msgs::RfidSensorMsg fixRfidAnglesToRad(stdr_msgs::RfidSensorMsg rmsg);
00207   
00213   stdr_msgs::RfidSensorMsg fixRfidAnglesToDegrees(
00214     stdr_msgs::RfidSensorMsg rmsg);
00215     
00219   stdr_msgs::CO2SensorMsg fixCO2AnglesToRad(stdr_msgs::CO2SensorMsg rmsg);
00220   
00224   stdr_msgs::CO2SensorMsg fixCO2AnglesToDegrees(
00225     stdr_msgs::CO2SensorMsg rmsg);
00226     
00230   stdr_msgs::ThermalSensorMsg fixThermalAnglesToRad(stdr_msgs::ThermalSensorMsg rmsg);
00231   
00235   stdr_msgs::ThermalSensorMsg fixThermalAnglesToDegrees(
00236     stdr_msgs::ThermalSensorMsg rmsg);
00237     
00241   stdr_msgs::SoundSensorMsg fixSoundAnglesToRad(stdr_msgs::SoundSensorMsg rmsg);
00242   
00246   stdr_msgs::SoundSensorMsg fixSoundAnglesToDegrees(
00247     stdr_msgs::SoundSensorMsg rmsg);
00248 }
00249 
00250 #endif


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