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 "ArmCircleWidget.h"
00009 #include "GripperWidget.h"
00010 #include "WristWidget.h"
00011 #include "GPS.h"
00012 #include "joystick.h"
00013 #include "Ros.h"
00014 #include "sensor_msgs/Image.h"
00015 #include "corobot_teleop/PanTilt.h"
00016 #include "Hokuyo.h"
00017 #include "MyQGraphicsView.h"
00018 
00019 
00020 
00021 //***************************************************
00022 //Speed control values, need to be determined on tests
00023 #define FORWARD_SPEED_a 800
00024 #define FORWARD_SPEED_b 700
00025 #define FORWARD_SPEED_c 600
00026 #define FORWARD_SPEED_d 500
00027 
00028 #define BACKWARD_SPEED_a 1400
00029 #define BACKWARD_SPEED_b 1700
00030 #define BACKWARD_SPEED_c 2000
00031 #define BACKWARD_SPEED_d 2300
00032 
00033 #define TURN_LEFT_SPEED_a_l 1100
00034 #define TURN_LEFT_SPEED_a_r 700
00035 
00036 #define TURN_LEFT_SPEED_b_l 1100
00037 #define TURN_LEFT_SPEED_b_r 500
00038 
00039 #define TURN_RIGHT_SPEED_a_l 700
00040 #define TURN_RIGHT_SPEED_a_r 1100
00041 
00042 #define TURN_RIGHT_SPEED_b_l 500
00043 #define TURN_RIGHT_SPEED_b_r 1100
00044 //**********************************************
00045 
00046 
00047 namespace Ui {
00048     class MainWindow;
00049 }
00050 
00051 class MainWindow : public QMainWindow
00052 {
00053     Q_OBJECT
00054 
00055 public:
00056     explicit MainWindow(QWidget *parent = 0);
00057     ~MainWindow();
00058     void resizeEvent(QResizeEvent *); //execute this function when the window size changes
00059 
00060 //#ifdef Q_WS_WIN
00061 //    bool winEvent(MSG*,long int *); // event windows used to receive joystick messages, only compiled for the windows version
00062 //#endif
00063 
00064 protected:
00065     void keyPressEvent(QKeyEvent *event);//executed each time a keyboard key is pushed
00066     void keyReleaseEvent(QKeyEvent *event);//executed each time a keyboard key is release
00067     signals :
00068           void size_changed(); //emited when the size of the window changes
00069 
00070 private:
00071     Ui::MainWindow *ui;
00072     ArmWidget arm;
00073     ArmRotationWidget arm_rotation;
00074     ArmCircleWidget armCircle;
00075     GripperWidget gripper;
00076     WristWidget wrist;
00077     Gps gps;
00078     //Joystick j;
00079     Ros r;
00080     Hokuyo hokuyo;
00081     bool next_gripper_state; //false open, true close
00082     bool LRF_lines_show;
00083     bool IR_data_show;
00084     QMessageBox msgBox;
00085     QElapsedTimer gpsUrlTImer;
00086 
00087 
00088 
00089     public slots:
00090             void change_url(QUrl url); //set url to the web viewer
00091             void connect_clicked(); // executed when the connect button is pushed
00092             void update_ptz(QImage image); //order the ptz camera scene to update
00093             void update_map(QImage image); //order the map image scene to update
00094             void update_rear(QImage image); //order the rear camera scene to update
00095             void update_kinectRGB(QImage image); //order the kinect RGB camera scene to update
00096             void update_kinectDepth(QImage image); //order the kinect Depth camera scene to update
00097             void bumper_update_slot(int bumper1, int bumper2, int bumper3, int bumper4);
00098             void Pan_control(int value);
00099             void Tilt_control(int value);
00100             void Pan_Tilt_reset();
00101             void encoder_info_update(double linearVelocity,double angularVelocity);
00102             void move_speed_select(int x);
00103             void turning_speed_select(int x);
00104             void motor_control_toggle(int value);
00105             void irdata_update_slot(double ir01,double ir02);
00106             void spatial_update_slot(double acc_x,double acc_y, double acc_z, double ang_x, double ang_y, double ang_z, double mag_x, double mag_y, double mag_z);
00107             void showLRFlines();
00108             void showIRdata(int);
00109             void showLRFdata(int);
00110 };
00111 
00112 #endif // MAINWINDOW_H


corobot_teleop
Author(s): Morgan Cormier/Gang Li/mcormier@coroware.com
autogenerated on Tue Jan 7 2014 11:39:41