qnode.hpp
Go to the documentation of this file.
00001 
00008 /*****************************************************************************
00009 ** Ifdefs
00010 *****************************************************************************/
00011 
00012 #ifndef segbot_controller_QNODE_HPP_
00013 #define segbot_controller_QNODE_HPP_
00014 
00015 /*****************************************************************************
00016 ** Includes
00017 *****************************************************************************/
00018 
00019 #include <ros/ros.h>
00020 #include <string>
00021 #include <QThread>
00022 #include <QStringListModel>
00023 #include <geometry_msgs/PoseStamped.h>
00024 #include <actionlib_msgs/GoalID.h>
00025 #include <move_base_msgs/MoveBaseAction.h>
00026 #include <actionlib/client/simple_action_client.h>
00027 /*****************************************************************************
00028 ** Namespaces
00029 *****************************************************************************/
00030 
00031 namespace segbot_controller {
00032 
00033 /*****************************************************************************
00034 ** Class
00035 *****************************************************************************/
00036 
00037 class QNode : public QThread {
00038 Q_OBJECT
00039 public:
00040         QNode(int argc, char** argv );
00041         virtual ~QNode();
00042         bool init();
00043         bool init(const std::string &master_url, const std::string &host_url);
00044         void run();
00045         void stopmsg(const geometry_msgs::PoseStamped::ConstPtr msg);
00046   void goalpub(const geometry_msgs::PoseStamped::ConstPtr msg);
00047 
00048         /*********************
00049         ** Logging
00050         **********************/
00051         enum LogLevel {
00052     Debug,
00053     Info,
00054     Warn,
00055     Error,
00056     Fatal
00057   };
00058 
00059         QStringListModel* loggingModel() { return &logging_model; }
00060         void log( const LogLevel &level, const std::string &msg);
00061 public slots:
00062   void stop();
00063   void cont();
00064 
00065 
00066 signals:
00067   void loggingUpdated();
00068   void rosShutdown();
00069 
00070 public:
00071   int init_argc;
00072   char** init_argv;
00073   boost::shared_ptr<ros::Subscriber> sub;
00074   QStringListModel logging_model;
00075   boost::shared_ptr<actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> > client; 
00076   boost::shared_ptr<move_base_msgs::MoveBaseGoal> mostRecentGoal;
00077 };
00078 
00079 }  // namespace segbot_controller
00080 
00081 #endif /* segbot_controller_QNODE_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


segbot_controller
Author(s): lab
autogenerated on Sun Mar 24 2013 17:17:27