RobotThread.h
Go to the documentation of this file.
00001 #ifndef ___ROBOTTHREAD_H___
00002 #define ___ROBOTTHREAD_H___
00003 
00004 #include <QThread>
00005 #include <QObject>
00006 #include <QStringList>
00007 #include <stdlib.h>
00008 #include <iostream>
00009 #include "assert.h"
00010 
00011 #include <ros/ros.h>
00012 #include <ros/network.h>
00013 #include <std_msgs/String.h>
00014 #include <sensor_msgs/LaserScan.h>
00015 #include <geometry_msgs/Twist.h>
00016 #include <turtlesim/Velocity.h>
00017 #include <turtlesim/Pose.h>
00018 #include <nav_msgs/Odometry.h>
00019 #include <actionlib/client/simple_action_client.h>
00020 #include <move_base_msgs/MoveBaseAction.h>
00021 
00022 namespace server {
00023 
00024 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00025 
00026 class RobotThread : public QThread {
00027         Q_OBJECT
00028 public:
00029     RobotThread(int argc, char **pArgv);
00030     virtual ~RobotThread();
00031 
00032     double getXPos();
00033     double getXSpeed();
00034     double getASpeed();
00035     double getYPos();
00036     double getAPos();
00037 
00038     bool init();
00039 
00040     void callback(nav_msgs::Odometry msg);
00041     //void callback(turtlesim::Pose msg);
00042     void scanCallBack(sensor_msgs::LaserScan scan);
00043 
00044         void SetSpeed(double speed, double angle);
00045     void setPose(QList<double> to_set);
00046     void goToXYZ(geometry_msgs::Point goTo);
00047     void setCommand(QString cmd);
00048     void run();
00049 
00050     Q_SIGNAL void newPose(double,double,double);
00051     Q_SIGNAL void newMidLaser(double);
00052 
00053 private:
00054     QString command;
00055         
00056     int m_Init_argc;
00057     char** m_pInit_argv;
00058 
00059     double m_speed;
00060     double m_angle;
00061 
00062     double m_xPos;
00063     double m_yPos;
00064     double m_aPos;
00065 
00066     double m_maxRange;
00067     double m_minRange;
00068 
00069     QList<double> ranges;
00070 
00071     ros::Publisher cmd_publisher;
00072     ros::Publisher sim_velocity;
00073 
00074     ros::Subscriber pose_listener;
00075     ros::Subscriber scan_listener;
00076 };
00077 }//end namespace
00078 #endif
00079 


gui_command
Author(s): Hunter Allen
autogenerated on Mon Oct 6 2014 08:35:15