autopilot.hh
Go to the documentation of this file.
1 
9 #pragma once
10 
11 
12 // 3rd party
13 #include <QDebug>
14 #include <QObject>
15 #include <mavlink/v1/common/mavlink.h>
16 // dfti
17 #include "mavlink_info.hh"
18 #include "sensor/serialsensor.hh"
19 #include "settings/settings.hh"
20 
21 
22 namespace dfti {
23 
24 
26 
32 struct APData
33 {
35  quint32 rcInTime;
37  quint16 rcIn1;
39  quint16 rcIn2;
41  quint16 rcIn3;
43  quint16 rcIn4;
45  quint16 rcIn5;
47  quint16 rcIn6;
49  quint16 rcIn7;
51  quint16 rcIn8;
53  quint32 rcOutTime;
55  quint16 rcOut1;
57  quint16 rcOut2;
59  quint16 rcOut3;
61  quint16 rcOut4;
63  quint16 rcOut5;
65  quint16 rcOut6;
67  quint16 rcOut7;
69  quint16 rcOut8;
70 };
71 
72 
74 class Autopilot : public SerialSensor
75 {
76  Q_OBJECT;
77 
78 public:
80 
84  explicit Autopilot(Settings *_settings, QObject* _parent = nullptr);
85 
87 
90  void open(void);
91 
92 
94 
104  void requestStream(quint8 streamId, quint16 streamRate, quint8 enabled);
105 
107 
113  void getDataRate(quint16 msgId);
114 
116 
122  void setDataRate(quint8 msgId, float msgRate);
123 
124 public slots:
126  void readData(void);
127 
128 signals:
130  void measurementUpdate(APData data);
131 
132 private:
134  bool gotMsg{false};
135 
137  quint8 systemId{0};
138 
140  quint8 compId{0};
141 
143  quint8 thisId{255};
144 
146  mavlink_message_t message;
147 
149 
153  mavlink_status_t lastStatus;
154 
156  struct MavlinkTimestamps {
158  MavlinkTimestamps() { reset(); }
160  quint64 rcChannelsRaw;
162  quint64 servoOutputRaw;
164  void reset(void) { rcChannelsRaw = 0; servoOutputRaw = 0; }
165  };
166 
168  MavlinkTimestamps timestamps;
169 
171  APData data;
172 };
173 
174 
175 }; // namespace dfti
quint16 rcIn2
RC input channel 2 PPM value.
Definition: autopilot.hh:39
Serial IO Sensor interface.
quint16 rcIn1
RC input channel 1 PPM value.
Definition: autopilot.hh:37
Base class for interfacing with sensors over a serial port (UART/RS-232).
Definition: serialsensor.hh:30
quint16 rcIn3
RC input channel 3 PPM value.
Definition: autopilot.hh:41
quint16 rcOut3
RC output channel 3 PPM value.
Definition: autopilot.hh:59
quint16 rcOut6
RC output channel 6 PPM value.
Definition: autopilot.hh:65
quint16 rcOut5
RC output channel 5 PPM value.
Definition: autopilot.hh:63
Definition: autopilot.cc:12
quint16 rcOut4
RC output channel 4 PPM value.
Definition: autopilot.hh:61
quint32 rcInTime
RC input timestamp.
Definition: autopilot.hh:35
Settings manager.
Definition: settings.hh:30
quint16 rcIn5
RC input channel 5 PPM value.
Definition: autopilot.hh:45
quint16 rcIn6
RC input channel 6 PPM value.
Definition: autopilot.hh:47
quint16 rcOut7
RC Output channel 7 PPM value.
Definition: autopilot.hh:67
quint16 rcIn8
RC input channel 8 PPM value.
Definition: autopilot.hh:51
Structure to hold autopilot data.
Definition: autopilot.hh:32
quint16 rcIn4
RC input channel 4 PPM value.
Definition: autopilot.hh:43
quint32 rcOutTime
RC output timestamp.
Definition: autopilot.hh:53
DFTI settings manager interface.
Serial driver to acquire data from a MAVLink-based autopilot.
Definition: autopilot.hh:74
quint16 rcOut8
RC Output channel 8 PPM value.
Definition: autopilot.hh:69
quint16 rcOut2
RC output channel 2 PPM value.
Definition: autopilot.hh:57
quint16 rcIn7
RC input channel 7 PPM value.
Definition: autopilot.hh:49
quint16 rcOut1
RC output channel 1 PPM value.
Definition: autopilot.hh:55