Ros.h
Go to the documentation of this file.
00001 #ifndef ROS_H
00002 #define ROS_H
00003 
00004 #include <QThread>
00005 
00006 #include "ros/ros.h"
00007 #include "nav_msgs/Odometry.h"
00008 #include "corobot_msgs/SensorMsg.h"
00009 #include "corobot_msgs/PowerMsg.h"
00010 #include "corobot_msgs/PanTilt.h"
00011 #include "corobot_msgs/takepic.h"
00012 #include "corobot_msgs/MoveArm.h"
00013 #include "sensor_msgs/CameraInfo.h"
00014 #include "sensor_msgs/Image.h"
00015 #include "sensor_msgs/CompressedImage.h"
00016 #include "sensor_msgs/LaserScan.h"
00017 #include "sensor_msgs/MagneticField.h"
00018 #include "sensor_msgs/Imu.h"
00019 #include "std_msgs/Int32.h"
00020 
00021 #include "corobot_msgs/MotorCommand.h"
00022 
00023 
00024 #include "sensor_msgs/NavSatFix.h"
00025 
00026 #include <QGraphicsScene>
00027 
00028 
00029 #include "Point.h"
00030 #include "Image.h"
00031 #include "Hokuyo.h"
00032 
00033 const float BATTERY_EMPTY= 12* 7/10;
00034 
00035 class Ros : public QThread {
00036 
00037     Q_OBJECT
00038 
00039 private:
00040     //ros variables to call services and to get messages from a topic
00041     ros::ServiceClient setOdom_client;
00042 
00043 
00044     ros::Timer timer;
00045 
00046     ros::Subscriber velocity,ir,power,bumper,ptz,arm,cameraInfo,cameraImage,imu,magnetic,map_image;
00047     ros::Subscriber gps,scan,kinect_rgb,kinect_depth,kinect_skel;
00048     ros::Subscriber rear_cam,ptz_cam; // subsriber for rear_cam and PTZ_cam
00049 
00050 
00051     ros::Publisher driveControl_pub, velocityValue_pub, moveArm_pub;
00052     //*************************************************************************
00053     //Hardware component "ctf" subscriber
00054     ros::Subscriber ssc32_info_sub,phidget_info_sub;
00055 
00056     //*************************************************************************
00057     //Receive message from Joy stick
00058     ros::Subscriber takepic_sub;
00059 
00060 
00061 
00062     bool cameraRear_jpeg_compression, cameraFront_jpeg_compression; //True if the jpeg compression is activated
00063     bool arm_al5a, arm_pincher, arm_reactor, arm_old_ssc32, arm_old_phidget; //is there a lynxmotion al5a arm? a PhantomX pincher? a Phantom X reactor? Or maybe an old corobot_arm? 
00064 
00065     float speed_x,speed_a; //linear and angular speed
00066     int speed_value; //Maximum speed of the wheels. Between 0 and 100.
00067     bool initialized;
00068     float arm_px,arm_py; //arm position
00069     float speed_left, speed_right; //Speed of the left wheel and right wheel. Between -100 and 100
00070     bool turningLeft, turningRight; //Is the robot turning left, is the robot turning right
00071     double ir01, ir02; // range value for the small front and rear infrared sensors
00072     int bumper_data[4]; // save the information on if the bumper is hit or not
00073 
00074 
00075     bool kinect_selected; //is kinect selected?
00076 
00077 
00078     bool Corobot; //is Corobot
00079 
00080        void timerCallback(const ros::TimerEvent& event);
00081 
00082 
00083 signals :
00084        void posArmReal(double x, double y); //position of the robot arm
00085        void angleWristReal (double angle);//angle of the robot wrist
00086        void irData(double ir01, double ir02);
00087        void battery_percent(int value); //percentage of battery left
00088      //  void ptzData();
00089        void gps_lat(double lat); //robot lattitude
00090        void gps_lon(double lon); //robot longitude
00091        void gps_coord(double lat, double lon); //gps coordinate
00092        void arm_model(bool arm_al5a,bool arm_pincher,bool arm_reactor,bool arm_old_corobot); //give the model of the arm connected to the robot
00093 
00094         void update_mapimage(QImage image);
00095         void update_rearcam(QImage image);
00096         void update_ptzcam(QImage image);
00097         void update_kinectDepthcam(QImage image);
00098         void update_kinectRGBcam(QImage image);
00099        void battery_volts(double volts);
00100        void bumper_update(int bumper1, int bumper2, int bumper3, int bumper4);
00101        void velocity_info(double linear, double angular);
00102        void imu_data(double acc_x,double acc_y, double acc_z, double ang_x, double ang_y, double ang_z);
00103        void magnetic_data(double mag_x, double mag_y, double mag_z);
00104 
00105        void hokuyo_update(Hokuyo_Points* hokuyo_points);
00106         void save_image(bool save); //order to save the front camera current displayed image
00107 
00108    public slots:
00109        void turnWrist(float angle); //turn the robor wrist
00110        void moveGripper(bool state);//change gripper state
00111        bool turn_left();
00112        bool turn_right();
00113        bool motor_stop();
00114        void moveShoulderArm(double shoulder);
00115        void moveElbowArm(double elbow);
00116        void rotateArm(double angle);
00117        void ResetArm();
00118        bool decrease_speed();
00119        bool increase_speed();
00120        bool increase_backward_speed();
00121        bool stop_turn();
00122         void setSpeedFast(bool toggled);
00123         void setSpeedModerate(bool toggled);
00124         void setSpeedSlow(bool toggled);
00125         void currentCameraTabChanged(int index); //subscribe to only the camera topics we are interested in
00126         void Pan_control(int value); // get the user interaction to control the pan camera and send it to the ros node
00127         void Tilt_control(int value); // get the user interaction to control the tilt camera and send it to the ros node
00128 
00129 public:
00130         ~Ros();
00131         Ros();
00132         void run();
00133         void init(int argc, char *argv[]);
00134         void init(int argc, char *argv[], const std::string & master, const std::string & host);
00135 
00136         ros::Publisher pan_tilt_control;
00137         void subscribe(); //function that initialize every ros variables declared above.
00138 
00139 
00140         void velocityCallback(const nav_msgs::Odometry::ConstPtr& msg);//just receive position data from the robot
00141         void irCallback(const corobot_msgs::SensorMsg::ConstPtr& msg); //just received ir data from the robot
00142         void powerCallback(const corobot_msgs::PowerMsgConstPtr& msg);//just received power data from the robot
00143         void bumperCallback(const corobot_msgs::SensorMsg::ConstPtr& msg);//just received bumper data from the robot
00144         void gpsCallback(const sensor_msgs::NavSatFix::ConstPtr& msg);//just receive gps information from the robot
00145         void scanCallback(const sensor_msgs::LaserScan::ConstPtr& msg);//just receive hokuyo information from the robot
00146         void kinectdepthCallback(const sensor_msgs::Image::ConstPtr& msg);//just received kinect depth image from the robot
00147         void kinectrgbCallback(const sensor_msgs::CompressedImage::ConstPtr& msg);//just received kinect rgb image from the robot
00148         void imuCallback(const sensor_msgs::Imu::ConstPtr& msg);
00149         void magCallback(const sensor_msgs::MagneticField::ConstPtr& msg);
00150         void takepicCallback(const corobot_msgs::takepic::ConstPtr& msg);
00151 
00152 
00153         //*****************************************************************
00154         //Modified to compress image for the sake of wifi transmitting
00155         void mapCallback(const sensor_msgs::CompressedImage::ConstPtr& msg);
00156         void rear_camCallback_compressed(const sensor_msgs::CompressedImage::ConstPtr& msg);
00157         void ptz_camCallback_compressed(const sensor_msgs::CompressedImage::ConstPtr& msg);
00158         void rear_camCallback(const sensor_msgs::Image::ConstPtr& msg);
00159         void ptz_camCallback(const sensor_msgs::Image::ConstPtr& msg);
00160 
00161        bool setOdom(float x, float y);//change the encoders
00162        bool resetOdom();//reset the encoders
00163        void resetArm();//reset arm position
00164 
00165        void openGripper();//open the gripepr
00166        void closeGripper();//close the gripper
00167        int pan,tilt; //pan/tilt
00168 
00169        int move_speed_level;
00170        int turning_speed_level;
00171 
00172        Hokuyo_Points* hokuyo_points_;
00173 
00174    };
00175 
00176 
00177 #endif // ROS_H


corobot_teleop
Author(s):
autogenerated on Wed Aug 26 2015 11:09:59