mainwindow.h
Go to the documentation of this file.
00001 #ifndef MAINWINDOW_H
00002 #define MAINWINDOW_H
00003 
00004 #include <QMainWindow>
00005 #include <QMessageBox>
00006 #include "ArmWidget.h"
00007 #include "ArmRotationWidget.h"
00008 #include "GripperWidget.h"
00009 #include "WristWidget.h"
00010 #include "GPS.h"
00011 #include "Ros.h"
00012 #include "Image.h"
00013 #include "sensor_msgs/Image.h"
00014 #include "corobot_msgs/PanTilt.h"
00015 #include "Hokuyo.h"
00016 
00017 namespace Ui {
00018     class MainWindow;
00019 }
00020 
00021 class MainWindow : public QMainWindow
00022 {
00023     Q_OBJECT
00024 
00025 public:
00026     explicit MainWindow(QWidget *parent = 0);
00027     ~MainWindow();
00028     void resizeEvent(QResizeEvent *); //execute this function when the window size changes
00029     void setArguments(int argc_, char *argv_[]);
00030 
00031 protected:
00032     void keyPressEvent(QKeyEvent *event);//executed each time a keyboard key is pushed
00033     void keyReleaseEvent(QKeyEvent *event);//executed each time a keyboard key is release
00034     signals :
00035           void size_changed(); //emited when the size of the window changes
00036 
00037 private:
00038     Ui::MainWindow *ui;
00039     ArmWidget arm;
00040     ArmRotationWidget arm_rotation;
00041     GripperWidget gripper;
00042     WristWidget wrist;
00043     Gps gps;
00044     Ros r;
00045     Hokuyo hokuyo;
00046     bool next_gripper_state; //false open, true close
00047     bool LRF_lines_show;
00048     bool IR_data_show;
00049     QMessageBox msgBox;
00050     QElapsedTimer gpsUrlTImer;
00051     int argc;
00052     char **argv;
00053 
00054     // Object Image representing the camera steam that is displayed on the graphicsview
00055     Image image_kinect_depth;// allcamera scene : bottom right image
00056     Image image_kinect_rgb;// allcamera scene : bottom right image
00057     Image image_rear_cam;
00058     Image image_ptz_cam;
00059     Image image_front_cam;
00060     Image image_map_image;
00061 
00062 
00063 
00064     public slots:
00065     void change_url(QUrl url); //set url to the web viewer
00066     void connect_clicked(); // executed when the connect button is pushed
00067     void update_ptz(QImage image); //order the ptz camera scene to update
00068     void update_map(QImage image); //order the map image scene to update
00069     void update_rear(QImage image); //order the rear camera scene to update
00070     void update_kinectRGB(QImage image); //order the kinect RGB camera scene to update
00071     void update_kinectDepth(QImage image); //order the kinect Depth camera scene to update
00072     void bumper_update_slot(int bumper1, int bumper2, int bumper3, int bumper4); // update bumper data
00073     void Pan_Tilt_reset(); // ask the ros node to reset the pan and tilt position of the camera
00074     void encoder_info_update(double linearVelocity,double angularVelocity); // update the encoder info on the interface
00075     void motor_control_toggle(int value); // interface the toggle button "Motor Control Disable"
00076     void irdata_update_slot(double ir01,double ir02); //update the onscreen value of the infrared sensor
00077     void imu_update_slot(double acc_x,double acc_y, double acc_z, double ang_x, double ang_y, double ang_z); //update the imu values on the interface
00078     void magnetic_update_slot(double mag_x, double mag_y, double mag_z); //update the imu values on the interface
00079     void showLRFlines(); // Interface the show line button in the rangefinding interface
00080     void showIRdata(int); // Interface the show ir data button in the rangefinder interface
00081     void showLRFdata(int); // Interface the show LRF button in the rangefinder interface
00082 };
00083 
00084 #endif // MAINWINDOW_H


corobot_teleop
Author(s):
autogenerated on Sun Oct 5 2014 23:18:16