Developmental Flight Test Instrumentation
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 #include "util/util.hh"
21 
22 
23 namespace dfti {
24 
25 
27 
33 struct APData
34 {
36  quint32 rcInTime;
38  quint16 rcIn1;
40  quint16 rcIn2;
42  quint16 rcIn3;
44  quint16 rcIn4;
46  quint16 rcIn5;
48  quint16 rcIn6;
50  quint16 rcIn7;
52  quint16 rcIn8;
54  quint32 rcOutTime;
56  quint16 rcOut1;
58  quint16 rcOut2;
60  quint16 rcOut3;
62  quint16 rcOut4;
64  quint16 rcOut5;
66  quint16 rcOut6;
68  quint16 rcOut7;
70  quint16 rcOut8;
71 };
72 
73 
75 class Autopilot : public SerialSensor
76 {
77  Q_OBJECT;
78 
79 public:
81 
85  explicit Autopilot(Settings *_settings, QObject* _parent = nullptr);
86 
88 
91  void open(void);
92 
93 
95 
105  void requestStream(quint8 streamId, quint16 streamRate, quint8 enabled);
106 
108 
114  void getDataRate(quint16 msgId);
115 
117 
123  void setDataRate(quint8 msgId, float msgRate);
124 
125 public slots:
127  void readData(void);
128 
129 signals:
131  void measurementUpdate(APData data);
132 
133 private:
135  bool gotMsg{false};
136 
138  quint8 systemId{0};
139 
141  quint8 compId{0};
142 
144  quint8 thisId{255};
145 
147  mavlink_message_t message;
148 
150 
154  mavlink_status_t lastStatus;
155 
157  struct MavlinkTimestamps {
159  MavlinkTimestamps() { reset(); }
161  quint64 rcChannelsRaw;
163  quint64 servoOutputRaw;
165  void reset(void) { rcChannelsRaw = 0; servoOutputRaw = 0; }
166  };
167 
169  MavlinkTimestamps timestamps;
170 
172  APData data;
173 };
174 
175 
176 }; // namespace dfti
quint16 rcIn2
RC input channel 2 PPM value.
Definition: autopilot.hh:40
Serial IO Sensor interface.
quint16 rcIn1
RC input channel 1 PPM value.
Definition: autopilot.hh:38
Base class for interfacing with sensors over a serial port (UART/RS-232).
Definition: serialsensor.hh:28
quint16 rcIn3
RC input channel 3 PPM value.
Definition: autopilot.hh:42
quint16 rcOut3
RC output channel 3 PPM value.
Definition: autopilot.hh:60
quint16 rcOut6
RC output channel 6 PPM value.
Definition: autopilot.hh:66
quint16 rcOut5
RC output channel 5 PPM value.
Definition: autopilot.hh:64
Definition: autopilot.cc:12
quint16 rcOut4
RC output channel 4 PPM value.
Definition: autopilot.hh:62
quint32 rcInTime
RC input timestamp.
Definition: autopilot.hh:36
Settings manager.
Definition: settings.hh:30
quint16 rcIn5
RC input channel 5 PPM value.
Definition: autopilot.hh:46
quint16 rcIn6
RC input channel 6 PPM value.
Definition: autopilot.hh:48
quint16 rcOut7
RC Output channel 7 PPM value.
Definition: autopilot.hh:68
quint16 rcIn8
RC input channel 8 PPM value.
Definition: autopilot.hh:52
Structure to hold autopilot data.
Definition: autopilot.hh:33
quint16 rcIn4
RC input channel 4 PPM value.
Definition: autopilot.hh:44
quint32 rcOutTime
RC output timestamp.
Definition: autopilot.hh:54
DFTI settings manager interface.
Serial driver to acquire data from a MAVLink-based autopilot.
Definition: autopilot.hh:75
quint16 rcOut8
RC Output channel 8 PPM value.
Definition: autopilot.hh:70
quint16 rcOut2
RC output channel 2 PPM value.
Definition: autopilot.hh:58
Utility functions.
quint16 rcIn7
RC input channel 7 PPM value.
Definition: autopilot.hh:50
quint16 rcOut1
RC output channel 1 PPM value.
Definition: autopilot.hh:56