057833f61ee647a37a4b3f01a72e1a76110144fc
[mardrone] / mardrone / dronecontrol.h
1 #ifndef DRONECONTROL_H
2 #define DRONECONTROL_H
3
4 #include <QGraphicsWidget>
5 #include <QGraphicsItem>
6 #include <QPainter>
7 #include <QUdpSocket>
8 #include <QTcpSocket>
9 #include <QThread>
10 #include <QTimer>
11 #include <QSettings>
12 #include <QRotationSensor>
13 #undef _GNU_SOURCE // just get rid of error message double definition
14 #include <navdata.h>
15
16 class DroneThread;
17
18 QTM_USE_NAMESPACE
19
20 class DroneControl : public QObject
21 {
22     Q_OBJECT
23     Q_PROPERTY(float pitch READ pitch WRITE setPitch NOTIFY pitchRollChanged)
24     Q_PROPERTY(float roll  READ roll  WRITE setRoll NOTIFY pitchRollChanged)
25     Q_PROPERTY(float yaw   READ yaw   WRITE setYaw NOTIFY pitchRollChanged)
26     Q_PROPERTY(float altitude  READ altitude WRITE setAltitude)
27     Q_PROPERTY(float vVelocity READ vVelocity WRITE setVVelocity NOTIFY pitchRollChanged)
28     Q_PROPERTY(int   enabled   READ enabled WRITE setEnabled)
29     Q_PROPERTY(bool  fly READ fly WRITE setFly)
30     Q_PROPERTY(bool  ctrlActive READ ctrlActive WRITE setCtrlActive)
31     Q_PROPERTY(float dronePitch READ dronePitch NOTIFY navDataChanged)
32     Q_PROPERTY(float droneRoll READ droneRoll NOTIFY navDataChanged)
33     Q_PROPERTY(float droneYaw READ droneYaw NOTIFY navDataChanged)
34     Q_PROPERTY(float droneVBat READ droneVBat NOTIFY navDataChanged)
35     Q_PROPERTY(float droneAltitude READ droneAltitude NOTIFY navDataChanged)
36     Q_PROPERTY(bool  emergency READ emergency WRITE setEmergency)
37     Q_PROPERTY(QString decodedStatus READ decodedStatus NOTIFY statusChanged)
38     Q_PROPERTY(int pwm_motor1 READ pwm_motor1 NOTIFY navDataChanged)
39     Q_PROPERTY(int pwm_motor2 READ pwm_motor1 NOTIFY navDataChanged)
40     Q_PROPERTY(int pwm_motor3 READ pwm_motor1 NOTIFY navDataChanged)
41     Q_PROPERTY(int pwm_motor4 READ pwm_motor1 NOTIFY navDataChanged)
42
43
44    // Config variables from QSettings
45     Q_PROPERTY(QString  confDroneIp   READ confDroneIp      WRITE setConfDroneIp      NOTIFY configChanged)
46     Q_PROPERTY(bool  confShowDebug    READ confShowDebug    WRITE setConfShowDebug    NOTIFY configChanged)
47     Q_PROPERTY(bool  confShowHorizon  READ confShowHorizon  WRITE setConfShowHorizon  NOTIFY configChanged)
48     Q_PROPERTY(bool  confShowGauges   READ confShowGauges   WRITE setConfShowGauges   NOTIFY configChanged)
49     Q_PROPERTY(bool  confUseAccel     READ confUseAccel     WRITE setConfUseAccel     NOTIFY configChanged)
50     Q_PROPERTY(bool  confUseJoyStick  READ confUseJoyStick  WRITE setConfUseJoyStick  NOTIFY configChanged)
51     Q_PROPERTY(bool  confFullScreen   READ confFullScreen   WRITE setConfFullScreen   NOTIFY configChanged)
52     Q_PROPERTY(float confForwardGain  READ confForwardGain  WRITE setConfForwardGain  NOTIFY configChanged)
53     Q_PROPERTY(float confBackwardGain READ confBackwardGain WRITE setConfBackwardGain NOTIFY configChanged)
54     Q_PROPERTY(float confLeftGain     READ confLeftGain     WRITE setConfLeftGain     NOTIFY configChanged)
55     Q_PROPERTY(float confRightGain    READ confRightGain    WRITE setConfRightGain    NOTIFY configChanged)
56     Q_PROPERTY(float confCtrlTrsh     READ confCtrlTrsh     WRITE setConfCtrlTrsh     NOTIFY configChanged)
57
58 public:
59     explicit DroneControl();
60
61
62     float pitch();    void setPitch(float val_);
63     float roll() ;    void setRoll(float val_);
64     float yaw() ;     void setYaw(float val_);
65     float altitude(); void setAltitude(float val_) ;
66     float vVelocity();void setVVelocity(float val_) ;
67     int   enabled() ; void setEnabled(int val_) ;
68     bool  emergency();void setEmergency(bool val_) ;
69     bool  fly() ;     void setFly(bool val_) ;
70     bool  ctrlActive();void setCtrlActive(bool val_) ;
71
72 // Read only telemetry and drone status
73     QString decodedStatus();
74     int pwm_motor1();
75     int pwm_motor2();
76     int pwm_motor3();
77     int pwm_motor4();
78     float droneAltitude();
79     float dronePitch();
80     float droneRoll();
81     float droneYaw();
82     float droneVBat();
83
84 //Config variables
85  QString confDroneIp();      void setConfDroneIp(QString ip);
86  bool    confShowDebug();    void setConfShowDebug(bool val);
87  bool    confShowHorizon();  void setConfShowHorizon(bool val);
88  bool    confShowGauges();   void setConfShowGauges(bool val);
89  bool    confUseAccel();     void setConfUseAccel(bool val);
90  bool    confFullScreen();   void setConfFullScreen(bool val);
91  bool    confUseJoyStick();  void setConfUseJoyStick(bool val);
92  float   confForwardGain();  void setConfForwardGain(float val);
93  float   confBackwardGain(); void setConfBackwardGain(float val);
94  float   confLeftGain();     void setConfLeftGain(float val);
95  float   confRightGain();    void setConfRightGain(float val);
96  float   confCtrlTrsh();     void setConfCtrlTrsh(float val);
97 signals:
98     void navDataChanged();
99     void statusChanged();
100     void configChanged();
101     void pitchRollChanged();
102 public slots:
103     void navDataUpdated();
104     void statusUpdated();
105     void rotationReadingsChanged();
106 private:
107
108     float m_pitch;     // pitch in horizon
109     float m_roll;      // Roll in horizon
110     float m_yaw;       // low value to display
111     float m_vv;        // Verticl velocity
112     float m_altitude;  // altitude
113     float m_rotRefX;   // Rotation zero reference
114     float m_rotRefY;
115     float m_rotRefZ;
116     int   m_enabled;   // Enable flag
117     bool  m_emergency; // Emergency flag
118     QString _emgReason; // Reason of emergency
119     bool  m_fly;       // Fly flag
120     bool  m_ctrlActive;
121     bool  m_useAccel;
122     float m_ctrlTrsh;  // accel controll treshold
123
124     QTcpSocket *ctlSock;  // TCP port for control/config data
125     QUdpSocket *navSock;  // Navigation data receive socket port 5554
126     QHostAddress droneHost;  // Ip address of the drone
127
128     DroneThread *droneThread;
129     QSettings *droneSettings;
130     QRotationSensor *rSensor; // used for controllind drone with device rotation
131 };
132
133
134
135 class DroneThread:public QThread {
136     Q_OBJECT
137 public:
138     DroneThread(DroneControl *parentp,QHostAddress host);
139
140  //   ~DroneThread ();
141     void run();
142     void sendNav(QString cmd);
143     void sendCmd(QString cmd);
144     NavData *navData() { return &nd; };
145
146     enum droneState {
147         notInitialized,
148         initialized,
149         ready,
150         flying
151
152     };
153 public slots:
154     void navDataReady();
155     void timer();
156     void setFly(bool fly);
157     void setEmergency(bool emg);
158     void setDroneControl(float pitch,float roll,float yaw,float vv);
159     void setDroneGain(float fgain,float bgain,float lgain,float rgain);
160
161 private:
162
163      QHostAddress droneHost;  // Ip address of the drone
164      QTimer *stateTimer;
165      volatile bool stopped;
166      DroneControl *parent;
167      QUdpSocket *navSock;  // Navigation data receive socket port 5554
168      QUdpSocket *cmdSock; // Ay command socket port 5556
169      int state;
170      int seq;           // Drone command seq number
171      bool m_fly;
172      bool m_emergency;
173      float m_pitch;
174      float m_roll;
175      float m_yaw;
176      float m_vv;
177      float m_fgain;
178      float m_bgain;
179      float m_rgain;
180      float m_lgain;
181      NavData nd;
182 };
183
184 #endif // DRONECONTROL_H