44 Q_INVOKABLE
void setCommLost(
bool commLost) { _commLost = commLost; }
62 void setArmed(
bool armed) {
if (
armed) _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
else _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED; }
63 bool armed()
const {
return (_mavBaseMode & MAV_MODE_FLAG_SAFETY_ARMED) != 0; }
87 void clearReceivedMavCommandCounts() { _receivedMavCommandCountMap.clear(); _receivedMavCommandByCompCountMap.clear(); _receivedRequestMessageByCompAndMsgCountMap.clear(); }
89 int receivedMavCommandCount(MAV_CMD command,
int compId)
const {
return _receivedMavCommandByCompCountMap.value(command).value(compId, 0); }
90 int receivedRequestMessageCount(
int compId,
int messageId)
const {
return _receivedRequestMessageByCompAndMsgCountMap.value(compId).value(messageId, 0); }
108 QMutexLocker locker(&_requestMessageNoResponseMutex);
110 _requestMessageNoResponseIds.insert(messageId);
112 _requestMessageNoResponseIds.remove(messageId);
123 _paramSetFailureMode = mode;
134 _paramRequestReadFailureMode = mode;
171 void _writeBytes(
const QByteArray &bytes)
final;
172 void _writeBytesQueued(
const QByteArray &bytes);
177 uint8_t standard_mode;
178 uint32_t custom_mode;
183 bool _connect() final;
184 bool _allocateMavlinkChannel() final;
185 void _freeMavlinkChannel() final;
187 uint8_t _getMavlinkAuxChannel()
const {
return _mavlinkAuxChannel; }
188 bool _mavlinkAuxChannelIsSet()
const;
189 uint8_t _getMavlinkVehicleChannel()
const {
return _mavlinkVehicleChannel; }
190 bool _mavlinkVehicleChannelIsSet()
const;
195 float _floatUnionForParam(
int componentId,
const QString ¶mName);
196 uint32_t _computeParamHash(
int componentId)
const;
197 void _setParamFloatUnionIntoMap(
int componentId,
const QString ¶mName,
float paramFloat);
200 void _handleIncomingNSHBytes(
const char *bytes,
int cBytes);
202 void _handleIncomingMavlinkBytes(
const uint8_t *bytes,
int cBytes);
223 void _sendParamError(
int componentId,
const char *paramId, int16_t paramIndex, uint8_t errorCode);
229 void _sendHeartBeat();
230 void _sendHighLatency2();
231 void _sendHomePosition();
232 void _sendGpsRawInt();
233 void _sendGlobalPositionInt();
234 void _sendExtendedSysState();
235 void _sendVibration();
236 void _sendSysStatus();
237 void _sendBatteryStatus();
238 void _sendNamedValueFloats();
239 void _sendChunkedStatusText(uint16_t chunkId,
bool missingChunks);
240 void _sendStatusTextMessages();
241 void _respondWithAutopilotVersion();
242 void _sendRCChannels();
243 void _sendADSBVehicles();
244 void _sendGeneralMetaData();
245 void _sendRemoteIDArmStatus();
246 void _sendAvailableModesMonitor();
248 void _paramRequestListWorker();
249 void _logDownloadWorker();
250 void _availableModesWorker();
251 void _sendAvailableMode(uint8_t modeIndexOneBased);
252 int _availableModesCount()
const;
253 void _moveADSBVehicle(
int vehicleIndex);
255 static MockLink *_startMockLinkWorker(
const QString &configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType,
bool sendStatusText,
bool enableCamera,
bool enableGimbal,
MockConfiguration::FailureMode_t failureMode);
260 static QString _createRandomFile(uint32_t byteCount);
262 QThread *_workerThread =
nullptr;
266 const MAV_AUTOPILOT _firmwareType = MAV_AUTOPILOT_PX4;
267 const MAV_TYPE _vehicleType = MAV_TYPE_QUADROTOR;
268 const bool _sendStatusText =
false;
269 const bool _enableCamera =
false;
270 const bool _enableGimbal =
false;
272 const uint8_t _vehicleSystemId = 0;
273 const double _vehicleLatitude = 0.0;
274 const double _vehicleLongitude = 0.0;
278 const uint16_t _boardVendorId = 0;
279 const uint16_t _boardProductId = 0;
285 uint8_t _mavlinkAuxChannel = std::numeric_limits<uint8_t>::max();
286 QMutex _mavlinkAuxMutex;
288 uint8_t _mavlinkVehicleChannel = std::numeric_limits<uint8_t>::max();
290 mavlink_signing_t _mockSigning{};
291 mavlink_signing_streams_t _mockSigningStreams{};
293 bool _connected =
false;
296 uint8_t _mavBaseMode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
298 uint8_t _mavState = MAV_STATE_STANDBY;
300 QElapsedTimer _runningTime;
301 static constexpr int32_t _batteryMaxTimeRemaining = 15 * 60;
302 int8_t _battery1PctRemaining = 100;
303 int32_t _battery1TimeRemaining = _batteryMaxTimeRemaining;
304 MAV_BATTERY_CHARGE_STATE _battery1ChargeState = MAV_BATTERY_CHARGE_STATE_OK;
305 int8_t _battery2PctRemaining = 100;
306 int32_t _battery2TimeRemaining = _batteryMaxTimeRemaining;
307 MAV_BATTERY_CHARGE_STATE _battery2ChargeState = MAV_BATTERY_CHARGE_STATE_OK;
309 double _vehicleAltitudeAMSL = _defaultVehicleHomeAltitude;
310 bool _commLost =
false;
311 bool _signingEnabled =
false;
312 bool _highLatencyTransmissionEnabled =
true;
314 int _sendHomePositionDelayCount = 10;
315 int _sendGPSPositionDelayCount = 100;
317 int _currentParamRequestListComponentIndex = -1;
318 int _currentParamRequestListParamIndex = -1;
319 QList<int> _paramRequestListComponentIds;
320 QStringList _paramRequestListParamNames;
324 QMutex _paramRequestListMutex;
327 int _availableModesWorkerNextModeIndex = 0;
331 QMutex _availableModesWorkerMutex;
332 uint8_t _availableModesMonitorSeqNumber = 0;
334 QString _logDownloadFilename;
335 uint32_t _logDownloadCurrentOffset = 0;
336 uint32_t _logDownloadBytesRemaining = 0;
340 QMutex _logDownloadMutex;
343 mutable QMutex _requestMessageNoResponseMutex;
344 QSet<uint32_t> _requestMessageNoResponseIds;
346 bool _paramSetFailureFirstAttemptPending =
false;
348 bool _paramRequestReadFailureFirstAttemptPending =
false;
349 bool _hashCheckNoResponse =
false;
350 int _hashCheckRequestCount = 0;
351 bool _paramRequestListHashCheckSent =
false;
353 struct RCChannelOverride {
354 enum class State { Ignore, Overridden, Released } state = State::Ignore;
357 static constexpr int kRcChannelOverrideChannelCount = 18;
358 std::array<RCChannelOverride, kRcChannelOverrideChannelCount> _rcChannelOverrides;
360 QMap<MAV_CMD, int> _receivedMavCommandCountMap;
361 QMap<MAV_CMD, QMap<int, int>> _receivedMavCommandByCompCountMap;
362 QMap<uint32_t, int> _receivedRequestMessageCountMap;
363 QMap<int, QMap<int, int>> _receivedRequestMessageByCompAndMsgCountMap;
364 QMap<uint32_t, int> _receivedMavlinkMessageCountMap;
365 QMap<int, QMap<QString, QVariant>> _mapParamName2Value;
366 QMap<int, QMap<QString, MAV_PARAM_TYPE>> _mapParamName2MavParamType;
369 QGeoCoordinate coordinate;
371 double altitude = 0.0;
373 QList<ADSBVehicle> _adsbVehicles;
374 QList<QGeoCoordinate> _adsbVehicleCoordinates;
375 static constexpr int _numberOfVehicles = 5;
376 double _adsbAngles[_numberOfVehicles]{};
378 static std::atomic<int> _nextVehicleSystemId;
382 static constexpr double _defaultVehicleLatitude = 47.397;
383 static constexpr double _defaultVehicleLongitude = 8.5455;
384 static constexpr double _defaultVehicleHomeAltitude = 488.056;
386 static constexpr const char *_failParam =
"COM_FLTMODE6";
388 static constexpr uint8_t _vehicleComponentId = MAV_COMP_ID_AUTOPILOT1;
390 static constexpr uint16_t _logDownloadLogId = 0;
391 static constexpr uint32_t _logDownloadFileSize = 1000;
393 static constexpr bool _mavlinkStarted =
true;
395 static QList<FlightMode_t> _availableFlightModes;
397 std::atomic<bool> _disconnectedEmitted{
false};