16 #include <QHostAddress> 40 return check(m_debug & DebugMode::DEBUG_RC);
45 return check(m_debug & DebugMode::DEBUG_DATA);
50 return check(m_debug & DebugMode::DEBUG_SERIAL);
60 float logRateMs(
void)
const {
return m_logRateMs; };
92 bool useRIO(
void)
const {
return m_useRIO; };
98 bool useUADC(
void)
const {
return m_useUADC; };
150 const QString m_sysRC{
"/etc/dftirc"};
153 QSettings* m_settings{
nullptr};
156 DebugMode m_debug{DebugMode::DEBUG_NONE};
159 float m_logRateMs{10};
162 float m_flushRateMs{1e4};
165 bool m_serverEnabled{
false};
168 float m_sendRateMs{20};
171 QHostAddress m_serverAddress{QHostAddress::LocalHost};
174 quint16 m_serverPort{2701};
177 bool m_useMessageInterval{
false};
180 quint32 m_streamRate{10};
183 bool m_useMavlink{
false};
186 bool m_useRIO{
false};
189 bool m_useUADC{
false};
192 bool m_useVN200{
false};
195 bool m_setSystemTime{
false};
198 bool m_waitForMavInit{
false};
201 bool m_waitForRIO{
false};
204 bool m_waitForVN200GPS{
false};
207 bool m_waitForAllSensors{
false};
210 bool m_waitForUpdate{
true};
213 QString m_autopilotSerialPort{
""};
216 QString m_rioSerialPort{
""};
219 QString m_uADCSerialPort{
""};
222 QString m_vn200SerialPort{
""};
225 quint32 m_autopilotBaudRate{0};
228 quint32 m_rioBaudRate{0};
231 quint32 m_uADCBaudRate{0};
234 quint32 m_vn200BaudRate{0};
quint32 rioBaudRate(void) const
Overridden RIO baud rate.
Definition: settings.hh:134
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
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