settings.hh
Go to the documentation of this file.
1 
9 #pragma once
10 
11 
12 // 3rd party
13 #include <QDebug>
14 #include <QDir>
15 #include <QFile>
16 #include <QHostAddress>
17 #include <QObject>
18 #include <QSettings>
19 #include <QString>
20 #include <QVector>
21 // project
22 #include "core/consts.hh"
23 #include "util/util.hh"
24 
25 
26 namespace dfti {
27 
28 
30 class Settings : public QObject
31 {
32  Q_OBJECT;
33 
34 public:
36  Settings(QString _rcfile, DebugMode _debug);
37 
39  bool debugRC() const {
40  return check(m_debug & DebugMode::DEBUG_RC);
41  };
42 
44  bool debugData() const {
45  return check(m_debug & DebugMode::DEBUG_DATA);
46  };
47 
49  bool debugSerial() const {
50  return check(m_debug & DebugMode::DEBUG_SERIAL);
51  };
52 
54 
57  void loadRCFile(QString _fn);
58 
60  float logRateMs(void) const { return m_logRateMs; };
61 
63  float flushRateMs(void) const { return m_flushRateMs; };
64 
66  float sendRateMs(void) const { return m_sendRateMs; };
67 
69  bool serverEnabled(void) const { return m_serverEnabled; };
70 
72  QHostAddress serverAddress(void) const { return m_serverAddress; };
73 
75  quint16 serverPort(void) const { return m_serverPort; };
76 
78 
83  bool useMessageInterval(void) const { return m_useMessageInterval; };
84 
86  quint32 streamRate(void) const { return m_streamRate; };
87 
89  bool setSystemTime(void) const { return m_setSystemTime; };
90 
92  bool useRIO(void) const { return m_useRIO; };
93 
95  bool useMavlink(void) const { return m_useMavlink; };
96 
98  bool useUADC(void) const { return m_useUADC; };
99 
101  bool useVN200(void) const { return m_useVN200; };
102 
104  bool waitForRIO(void) const { return m_waitForRIO; };
105 
107  bool waitForMavInit(void) const { return m_waitForMavInit; };
108 
110  bool waitForVN200GPS(void) const { return m_waitForVN200GPS; };
111 
113  bool waitForAllSensors(void) const { return m_waitForAllSensors; };
114 
116  bool waitForUpdate(void) const { return m_waitForUpdate; };
117 
119  QString autopilotSerialPort(void) const { return m_autopilotSerialPort; };
120 
122  QString rioSerialPort(void) const { return m_rioSerialPort; };
123 
125  QString uADCSerialPort(void) const { return m_uADCSerialPort; };
126 
128  QString vn200SerialPort(void) const { return m_vn200SerialPort; };
129 
131  quint32 autopilotBaudRate(void) const { return m_autopilotBaudRate; };
132 
134  quint32 rioBaudRate(void) const { return m_rioBaudRate; };
135 
137  quint32 uADCBaudRate(void) const { return m_uADCBaudRate; };
138 
140  quint32 vn200BaudRate(void) const { return m_vn200BaudRate; };
141 
142 private:
144  QString m_rcfile;
145 
147  QString m_userRC;
148 
150  const QString m_sysRC{"/etc/dftirc"};
151 
153  QSettings* m_settings{nullptr};
154 
156  DebugMode m_debug{DebugMode::DEBUG_NONE};
157 
159  float m_logRateMs{10};
160 
162  float m_flushRateMs{1e4};
163 
165  bool m_serverEnabled{false};
166 
168  float m_sendRateMs{20};
169 
171  QHostAddress m_serverAddress{QHostAddress::LocalHost};
172 
174  quint16 m_serverPort{2701};
175 
177  bool m_useMessageInterval{false};
178 
180  quint32 m_streamRate{10};
181 
183  bool m_useMavlink{false};
184 
186  bool m_useRIO{false};
187 
189  bool m_useUADC{false};
190 
192  bool m_useVN200{false};
193 
195  bool m_setSystemTime{false};
196 
198  bool m_waitForMavInit{false};
199 
201  bool m_waitForRIO{false};
202 
204  bool m_waitForVN200GPS{false};
205 
207  bool m_waitForAllSensors{false};
208 
210  bool m_waitForUpdate{true};
211 
213  QString m_autopilotSerialPort{""};
214 
216  QString m_rioSerialPort{""};
217 
219  QString m_uADCSerialPort{""};
220 
222  QString m_vn200SerialPort{""};
223 
225  quint32 m_autopilotBaudRate{0};
226 
228  quint32 m_rioBaudRate{0};
229 
231  quint32 m_uADCBaudRate{0};
232 
234  quint32 m_vn200BaudRate{0};
235 };
236 
237 }; // namespace dfti
quint32 rioBaudRate(void) const
Overridden RIO baud rate.
Definition: settings.hh:134
DFTI constants.
quint32 vn200BaudRate(void) const
Overridden VN-200 baud rate.
Definition: settings.hh:140
bool debugRC() const
Returns true if settings debug messages are enabled.
Definition: settings.hh:39
QString uADCSerialPort(void) const
Overridden uADC serial port.
Definition: settings.hh:125
Settings(QString _rcfile, DebugMode _debug)
Ctor.
Definition: settings.cc:18
QHostAddress serverAddress(void) const
Return the server address.
Definition: settings.hh:72
float logRateMs(void) const
Return the log sampling time in ms.
Definition: settings.hh:60
quint32 autopilotBaudRate(void) const
Overridden Autopilot baud rate.
Definition: settings.hh:131
bool debugData() const
Returns true if sensor data debug messages are enabled.
Definition: settings.hh:44
Definition: autopilot.cc:12
QString rioSerialPort(void) const
Overridden RIO serial port.
Definition: settings.hh:122
quint32 uADCBaudRate(void) const
Overridden uADC baud rate.
Definition: settings.hh:137
Settings manager.
Definition: settings.hh:30
QString autopilotSerialPort(void) const
Overridden Autopilot serial port.
Definition: settings.hh:119
DebugMode
Debugging Mode enumeration.
Definition: consts.hh:35
bool check(AvailableSensors x)
Check an AvailableSensors value.
Definition: consts.hh:82
quint16 serverPort(void) const
Return the server port.
Definition: settings.hh:75
QString vn200SerialPort(void) const
Overridden VN-200 serial port.
Definition: settings.hh:128
bool serverEnabled(void) const
Return the server status.
Definition: settings.hh:69
bool useMavlink(void) const
Do we have a MAVLink-based autopilot?
Definition: settings.hh:95
bool useUADC(void) const
Do we have a Micro Air Data Computer?
Definition: settings.hh:98
bool waitForMavInit(void) const
Should we wait for the MAVLink init message before logging?
Definition: settings.hh:107
void loadRCFile(QString _fn)
Load a settings file.
Definition: settings.cc:57
bool waitForAllSensors(void) const
Should we wait for all sensors to get data before writing?
Definition: settings.hh:113
float sendRateMs(void) const
Return the server sampling time in ms.
Definition: settings.hh:66
bool waitForRIO(void) const
Should we wait for the RIO values before logging?
Definition: settings.hh:104
bool debugSerial() const
Returns true if serial i/o debug messages are enabled.
Definition: settings.hh:49
bool useRIO(void) const
Do we have RIO logging?
Definition: settings.hh:92
float flushRateMs(void) const
Return the log flush timer period in ms.
Definition: settings.hh:63
Utility functions.
bool useMessageInterval(void) const
Should we prefer the MESSAGE_INTERVAL interface?
Definition: settings.hh:83
bool waitForVN200GPS(void) const
Should we wait for VN200 GPS before logging?
Definition: settings.hh:110
quint32 streamRate(void) const
Return the desired MAVLink stream rate in Hz.
Definition: settings.hh:86
bool waitForUpdate(void) const
Should we wait for a data update to write to the log?
Definition: settings.hh:116
bool setSystemTime(void) const
Should we set the system time from GPS?
Definition: settings.hh:89
bool useVN200(void) const
Do we have a VN-200 INS?
Definition: settings.hh:101