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