Go to the documentation of this file.00001 #ifndef QT_ROS_NODE_H
00002 #define QT_ROS_NODE_H
00003
00004
00005 #include <QThread>
00006 #include <QObject>
00007 #include <QApplication>
00008
00009
00010 #include <geometry_msgs/PoseStamped.h>
00011 #include <nav_msgs/OccupancyGrid.h>
00012 #include <map_messages/PointsOfInterest.h>
00013 #include <sensor_msgs/LaserScan.h>
00014
00015 #include "Workers/PointOfInterest/PointOfInterest.h"
00016 #include "Architecture/StateMachine/StateMachine.h"
00017 #include <vector>
00018
00019
00020 #include <or_msgs/OrLearningStatus.h>
00021 #include <or_msgs/OrObjectNames.h>
00022
00023 #include <ros/ros.h>
00024
00025
00026 class MainWindow;
00027
00028 class QtRosNode : public QThread {
00029
00030 Q_OBJECT
00031
00032 public:
00036 QtRosNode(int argc, char *argv[], const char* node_name, MainWindow* mainWindow);
00037
00038 ~QtRosNode();
00039
00040 ros::NodeHandle* getNodeHandle(){ return m_NodeHandle; }
00041
00043 void run();
00044
00045 enum ModuleStateT {
00046 IDLE,
00047 WAITING,
00048 DOOR_IS_OPEN,
00049 };
00050
00051
00052 public slots:
00054 void quitNow();
00055
00056 signals:
00058 void rosShutdown();
00059 void poseUpdated(double x, double y, double theta);
00060 void mapUpdated(unsigned char * pMap, unsigned size,
00061 double resolution, geometry_msgs::Pose origin,
00062 int minX, int minY, int maxX, int maxY);
00063 void poiListUpdated(std::vector < map_messages::PointOfInterest > poiList);
00064 void pathUpdated(std::vector<geometry_msgs::PoseStamped> path);
00065 void learningStatus(std::vector<std::string> filenames, std::string objType);
00066 void objectNames(std::vector<std::string> names, std::vector<std::string> types);
00067
00068 private:
00069
00070 bool quitfromgui;
00071
00072 ros::NodeHandle* m_NodeHandle;
00073 MainWindow* m_MainWindow;
00074 QApplication* m_Application;
00075
00076 ros::Subscriber m_TextSubscriber;
00077 ros::Subscriber m_LaserSubscriber;
00078 ros::Subscriber m_RgbImageSubscriber;
00079
00080 ros::Subscriber m_PoseStampedSubscriber;
00081 ros::Subscriber m_MapDataSubscriber;
00082 ros::Subscriber m_POIsSubscriber;
00083 ros::Subscriber m_PathSubscriber;
00084
00085 ros::Subscriber m_OLPrimaryImageSubscriber;
00086 ros::Subscriber m_ORLearningStatusSubscriber;
00087 ros::Subscriber m_ORObjectNamesSubscriber;
00088
00089 void subscribeToTopics();
00090 void advertiseTopics();
00091
00092
00093 void callbackPoseStamped(const geometry_msgs::PoseStamped::ConstPtr& msg);
00094 void callbackOccupancyGrid(const nav_msgs::OccupancyGrid::ConstPtr& msg);
00095 void callbackPOIList(const map_messages::PointsOfInterest::ConstPtr& msg);
00096 void callbackLaserScan(const sensor_msgs::LaserScan::ConstPtr& msg);
00097
00098
00099
00100 void callbackLearningStatus(const or_msgs::OrLearningStatusConstPtr &msg);
00101 void callbackObjectNames(const or_msgs::OrObjectNamesConstPtr &msg);
00102
00103 StateMachine<ModuleStateT> m_ModuleMachine;
00104
00105
00106 std::string m_ExtraStatusInfo;
00107 std::vector<int> m_Ranges;
00108 unsigned int m_InitTimestamp;
00109 unsigned int m_CurrentTimestamp;
00110 unsigned int m_NewTimestamp;
00111 int m_InitRange;
00112 int m_CurrentRange;
00113 int m_NewRange;
00114 int m_GameTime;
00115 void compareRanges();
00116
00117
00118
00119 };
00120 #endif