#include <ros/package.h>
#include "ros/ros.h"
#include <tf/transform_listener.h>
#include <QtUiTools/QUiLoader>
#include <QtCore/QDir>
#include <QtCore/QFile>
#include <QtCore/QObject>
#include <QtCore/QString>
#include <QtCore/QThread>
#include <QtCore/QTimer>
#include <QtCore/QTime>
#include <QtGui/QMenu>
#include <QtGui/QApplication>
#include <QtGui/QCheckBox>
#include <QtGui/QComboBox>
#include <QtGui/QDoubleSpinBox>
#include <QtGui/QImage>
#include <QtGui/QFileDialog>
#include <QtGui/QLabel>
#include <QtGui/QLineEdit>
#include <QtGui/QListWidget>
#include <QtGui/QPainter>
#include <QtGui/QPixmap>
#include <QtGui/QProgressBar>
#include <QtGui/QPushButton>
#include <QtGui/QRadioButton>
#include <QtGui/QScrollBar>
#include <QtGui/QStatusBar>
#include <QtGui/QTextEdit>
#include <QtGui/QTreeWidget>
#include <QtGui/QVBoxLayout>
#include <QtGui/QWidget>
#include <QtGui/QWindowsStyle>
#include <QtGui/QInputDialog>
#include <QtGui/QMouseEvent>
#include <QtGui/QMessageBox>
#include <QtGui/QTimeEdit>
#include <QtGui/QFont>
#include <stdr_msgs/RobotIndexedVectorMsg.h>
#include <stdr_msgs/RobotIndexedMsg.h>
#include <stdr_msgs/RobotMsg.h>
#include <stdr_msgs/Noise.h>
#include <stdr_msgs/RfidTagVector.h>
#include <stdr_msgs/AddRfidTag.h>
#include <stdr_msgs/DeleteRfidTag.h>
#include <stdr_msgs/CO2SourceVector.h>
#include <stdr_msgs/AddCO2Source.h>
#include <stdr_msgs/DeleteCO2Source.h>
#include <stdr_msgs/ThermalSourceVector.h>
#include <stdr_msgs/AddThermalSource.h>
#include <stdr_msgs/DeleteThermalSource.h>
#include <stdr_msgs/SoundSourceVector.h>
#include <stdr_msgs/AddSoundSource.h>
#include <stdr_msgs/DeleteSoundSource.h>
#include <geometry_msgs/Pose2D.h>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/LaserScan.h>
#include "stdr_server/map_loader.h"
#include <stdr_msgs/LoadExternalMap.h>
#include <stdr_parser/stdr_parser.h>
Go to the source code of this file.
Namespaces | |
namespace | stdr_gui_tools |
The namespace for STDR GUI tools. | |
Defines | |
#define | STDR_PI 3.14159265359 |
Functions | |
float | stdr_gui_tools::angleDegreesToRad (float angle) |
Converts an angle from degrees to rads. | |
float | stdr_gui_tools::angleRadToDegrees (float angle) |
Converts an angle from rads to degrees. | |
stdr_msgs::CO2SensorMsg | stdr_gui_tools::fixCO2AnglesToDegrees (stdr_msgs::CO2SensorMsg rmsg) |
Angle conversion. | |
stdr_msgs::CO2SensorMsg | stdr_gui_tools::fixCO2AnglesToRad (stdr_msgs::CO2SensorMsg rmsg) |
Angle conversion. | |
stdr_msgs::LaserSensorMsg | stdr_gui_tools::fixLaserAnglesToDegrees (stdr_msgs::LaserSensorMsg rmsg) |
Takes a stdr_msgs::LaserSensorMsg and converts its angles to degrees. | |
stdr_msgs::LaserSensorMsg | stdr_gui_tools::fixLaserAnglesToRad (stdr_msgs::LaserSensorMsg rmsg) |
Takes a stdr_msgs::LaserSensorMsg and converts its angles to rads. | |
stdr_msgs::RfidSensorMsg | stdr_gui_tools::fixRfidAnglesToDegrees (stdr_msgs::RfidSensorMsg rmsg) |
Takes a stdr_msgs::RfidSensorMsg and converts its angles to degrees. | |
stdr_msgs::RfidSensorMsg | stdr_gui_tools::fixRfidAnglesToRad (stdr_msgs::RfidSensorMsg rmsg) |
Takes a stdr_msgs::RfidSensorMsg and converts its angles to rads. | |
stdr_msgs::RobotMsg | stdr_gui_tools::fixRobotAnglesToDegrees (stdr_msgs::RobotMsg rmsg) |
Takes a stdr_msgs::RobotMsg and converts its angles to degrees. | |
stdr_msgs::RobotMsg | stdr_gui_tools::fixRobotAnglesToRad (stdr_msgs::RobotMsg rmsg) |
Takes a stdr_msgs::RobotMsg and converts its angles to rads. | |
stdr_msgs::SonarSensorMsg | stdr_gui_tools::fixSonarAnglesToDegrees (stdr_msgs::SonarSensorMsg rmsg) |
Takes a stdr_msgs::SonarSensorMsg and converts its angles to degrees. | |
stdr_msgs::SonarSensorMsg | stdr_gui_tools::fixSonarAnglesToRad (stdr_msgs::SonarSensorMsg rmsg) |
Takes a stdr_msgs::SonarSensorMsg and converts its angles to rads. | |
stdr_msgs::SoundSensorMsg | stdr_gui_tools::fixSoundAnglesToDegrees (stdr_msgs::SoundSensorMsg rmsg) |
Angle conversion. | |
stdr_msgs::SoundSensorMsg | stdr_gui_tools::fixSoundAnglesToRad (stdr_msgs::SoundSensorMsg rmsg) |
Angle conversion. | |
stdr_msgs::ThermalSensorMsg | stdr_gui_tools::fixThermalAnglesToDegrees (stdr_msgs::ThermalSensorMsg rmsg) |
Angle conversion. | |
stdr_msgs::ThermalSensorMsg | stdr_gui_tools::fixThermalAnglesToRad (stdr_msgs::ThermalSensorMsg rmsg) |
Angle conversion. | |
QString | stdr_gui_tools::getLiteralTime (int ms) |
Transforms the milliseconds in literal representation. | |
std::string | stdr_gui_tools::getRosPackagePath (std::string package) |
Returns the global path of the ROS package provided. | |
void | stdr_gui_tools::printLaserMsg (stdr_msgs::LaserSensorMsg &msg) |
Prints a laser msg. | |
void | stdr_gui_tools::printPose2D (geometry_msgs::Pose2D &msg) |
Prints a ROS pose2d msg. | |
void | stdr_gui_tools::printSonarMsg (stdr_msgs::SonarSensorMsg &msg) |
Prints a sonar msg. |
#define STDR_PI 3.14159265359 |
Definition at line 100 of file stdr_tools.h.