QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockLink.h
Go to the documentation of this file.
1#pragma once
2
4#include "LinkInterface.h"
6#include "QGCMAVLinkTypes.h"
7#include "MockConfiguration.h"
9
10#include <QtCore/QElapsedTimer>
11#include <QtCore/QMap>
12#include <QtCore/QMutex>
13#include <QtCore/QSet>
14#include <QtPositioning/QGeoCoordinate>
15
16#include <array>
17#include <atomic>
18
19class MockLinkCamera;
20class MockLinkFTP;
21class MockLinkGimbal;
22class MockLinkWorker;
23class QThread;
24
25class MockLink : public LinkInterface
26{
27 Q_OBJECT
28 friend class MockLinkFTP;
29
30public:
31 explicit MockLink(SharedLinkConfigurationPtr &config, QObject *parent = nullptr);
32 virtual ~MockLink();
33
34 void run1HzTasks();
35 void run10HzTasks();
36 void run500HzTasks();
38
39 bool shouldSendStatusText() const { return _sendStatusText; }
40
41 bool isConnected() const final { return _connected; }
42 void disconnect() final;
43
44 Q_INVOKABLE void setCommLost(bool commLost) { _commLost = commLost; }
45 Q_INVOKABLE void simulateConnectionRemoved();
46
47 int vehicleId() const { return _vehicleSystemId; }
48 MAV_AUTOPILOT getFirmwareType() const { return _firmwareType; }
49
50 double vehicleLatitude() const { return _vehicleLatitude; }
51 double vehicleLongitude() const { return _vehicleLongitude; }
52 double vehicleAltitudeAMSL() const { return _vehicleAltitudeAMSL; }
53
54 bool signingEnabled() const { return _signingEnabled; }
55
58
59 MockLinkFTP *mockLinkFTP() const;
60
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; }
64
68 void setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult) const { _missionItemHandler->setFailureMode(failureMode, failureAckResult); }
69
71 void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType) const { _missionItemHandler->sendUnexpectedMissionAck(ackType); }
72
74 void sendUnexpectedMissionItem() const { _missionItemHandler->sendUnexpectedMissionItem(); }
75
77 void sendUnexpectedMissionRequest() const { _missionItemHandler->sendUnexpectedMissionRequest(); }
78
79 void sendUnexpectedCommandAck(MAV_CMD command, MAV_RESULT ackResult);
80
82 void resetMissionItemHandler() const { _missionItemHandler->reset(); }
83
85 QString logDownloadFile() const { return _logDownloadFilename; }
86
87 void clearReceivedMavCommandCounts() { _receivedMavCommandCountMap.clear(); _receivedMavCommandByCompCountMap.clear(); _receivedRequestMessageByCompAndMsgCountMap.clear(); }
88 int receivedMavCommandCount(MAV_CMD command) const { return _receivedMavCommandCountMap.value(command, 0); }
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); }
91 void clearReceivedRequestMessageCounts() { _receivedRequestMessageCountMap.clear(); _receivedRequestMessageByCompAndMsgCountMap.clear(); }
92 int receivedRequestMessageCount(uint32_t messageId) const { return _receivedRequestMessageCountMap.value(messageId, 0); }
93 void clearReceivedMavlinkMessageCounts() { _receivedMavlinkMessageCountMap.clear(); _hashCheckRequestCount = 0; _missionItemHandler->clearRequestListCounts(); }
94 int receivedMavlinkMessageCount(uint32_t messageId) const { return _receivedMavlinkMessageCountMap.value(messageId, 0); }
95 int receivedMissionRequestListCount(MAV_MISSION_TYPE type) const { return _missionItemHandler->requestListCount(type); }
96
103 void setRequestMessageFailureMode(RequestMessageFailureMode_t failureMode) { _requestMessageFailureMode = failureMode; }
104
107 void setRequestMessageNoResponse(uint32_t messageId, bool noResponse = true) {
108 QMutexLocker locker(&_requestMessageNoResponseMutex);
109 if (noResponse) {
110 _requestMessageNoResponseIds.insert(messageId);
111 } else {
112 _requestMessageNoResponseIds.remove(messageId);
113 }
114 }
115
123 _paramSetFailureMode = mode;
124 _paramSetFailureFirstAttemptPending = (mode == FailParamSetFirstAttemptNoAck);
125 }
126
134 _paramRequestReadFailureMode = mode;
135 _paramRequestReadFailureFirstAttemptPending = (mode == FailParamRequestReadFirstAttemptNoResponse);
136 }
137
138 void setHashCheckNoResponse(bool noResponse) { _hashCheckNoResponse = noResponse; }
139
141 int hashCheckRequestCount() const { return _hashCheckRequestCount; }
142
144 void setMockParamValue(int componentId, const QString &paramName, float value);
145
146 static MockLink *startPX4MockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
147 static MockLink *startGenericMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
148 static MockLink *startNoInitialConnectMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
149 static MockLink *startAPMArduCopterMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
150 static MockLink *startAPMArduPlaneMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
151 static MockLink *startAPMArduSubMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
152 static MockLink *startAPMArduRoverMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
153
154 // Special commands for testing Vehicle::sendMavCommandWithHandler
155 static constexpr MAV_CMD MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED = MAV_CMD_USER_1;
156 static constexpr MAV_CMD MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED = MAV_CMD_USER_2;
157 static constexpr MAV_CMD MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED = MAV_CMD_USER_3;
158 static constexpr MAV_CMD MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED = MAV_CMD_USER_4;
159 static constexpr MAV_CMD MAV_CMD_MOCKLINK_NO_RESPONSE = MAV_CMD_USER_5;
160 static constexpr MAV_CMD MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY = static_cast<MAV_CMD>(MAV_CMD_USER_5 + 1);
161 static constexpr MAV_CMD MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_ACCEPTED = static_cast<MAV_CMD>(MAV_CMD_USER_5 + 2);
162 static constexpr MAV_CMD MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_FAILED = static_cast<MAV_CMD>(MAV_CMD_USER_5 + 3);
163 static constexpr MAV_CMD MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK = static_cast<MAV_CMD>(MAV_CMD_USER_5 + 4);
164
165signals:
166 void writeBytesQueuedSignal(const QByteArray &bytes);
167 void highLatencyTransmissionEnabledChanged(bool highLatencyTransmissionEnabled);
168
169private slots:
171 void _writeBytes(const QByteArray &bytes) final;
172 void _writeBytesQueued(const QByteArray &bytes);
173
174private:
175 typedef struct {
176 const char *name;
177 uint8_t standard_mode;
178 uint32_t custom_mode;
179 bool canBeSet;
180 bool advanced;
181 } FlightMode_t;
182
183 bool _connect() final;
184 bool _allocateMavlinkChannel() final;
185 void _freeMavlinkChannel() final;
186
187 uint8_t _getMavlinkAuxChannel() const { return _mavlinkAuxChannel; }
188 bool _mavlinkAuxChannelIsSet() const;
189 uint8_t _getMavlinkVehicleChannel() const { return _mavlinkVehicleChannel; }
190 bool _mavlinkVehicleChannelIsSet() const;
191
192 void _loadParams();
193
195 float _floatUnionForParam(int componentId, const QString &paramName);
196 uint32_t _computeParamHash(int componentId) const;
197 void _setParamFloatUnionIntoMap(int componentId, const QString &paramName, float paramFloat);
198
200 void _handleIncomingNSHBytes(const char *bytes, int cBytes);
202 void _handleIncomingMavlinkBytes(const uint8_t *bytes, int cBytes);
204 void _updateIncomingMessageCounts(const mavlink_message_t &msg);
205 void _handleIncomingMavlinkMsg(const mavlink_message_t &msg);
206 void _handleHeartBeat(const mavlink_message_t &msg);
207 void _handleSetMode(const mavlink_message_t &msg);
208 void _handleParamRequestList(const mavlink_message_t &msg);
209 void _handleParamSet(const mavlink_message_t &msg);
210 void _handleParamRequestRead(const mavlink_message_t &msg);
211 void _handleFTP(const mavlink_message_t &msg);
212 void _handleCommandLong(const mavlink_message_t &msg);
213 void _handleInProgressCommandLong(const mavlink_command_long_t &request);
214 void _handleCommandLongSetMessageInterval(const mavlink_command_long_t &request, bool &acccepted);
215 void _handleManualControl(const mavlink_message_t &msg);
216 void _handleRCChannelsOverride(const mavlink_message_t &msg);
217 void _handlePreFlightCalibration(const mavlink_command_long_t &request);
218 void _handleTakeoff(const mavlink_command_long_t &request);
219 void _handleLogRequestList(const mavlink_message_t &msg);
220 void _handleLogRequestData(const mavlink_message_t &msg);
221 void _handleParamMapRC(const mavlink_message_t &msg);
222 void _handleSetupSigning(const mavlink_message_t &msg);
223 void _sendParamError(int componentId, const char *paramId, int16_t paramIndex, uint8_t errorCode);
224 void _handleRequestMessage(const mavlink_command_long_t &request, bool &accepted, bool &noAck);
225 void _handleRequestMessageAutopilotVersion(const mavlink_command_long_t &request, bool &accepted);
226 void _handleRequestMessageDebug(const mavlink_command_long_t &request, bool &accepted, bool &noAck);
227 void _handleRequestMessageAvailableModes(const mavlink_command_long_t &request, bool &accepted);
228
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();
247
248 void _paramRequestListWorker();
249 void _logDownloadWorker();
250 void _availableModesWorker();
251 void _sendAvailableMode(uint8_t modeIndexOneBased);
252 int _availableModesCount() const;
253 void _moveADSBVehicle(int vehicleIndex);
254
255 static MockLink *_startMockLinkWorker(const QString &configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode);
256 static MockLink *_startMockLink(MockConfiguration *mockConfig);
257
260 static QString _createRandomFile(uint32_t byteCount);
261
262 QThread *_workerThread = nullptr;
263 MockLinkWorker *_worker = nullptr;
264
265 const MockConfiguration *_mockConfig = 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;
275 // These are just set for reporting the fields in _respondWithAutopilotVersion()
276 // and ensuring that the Vehicle reports the fields in Vehicle::firmwareBoardVendorId etc.
277 // They do not control any mock simulation (and it is up to the Custom build to do that).
278 const uint16_t _boardVendorId = 0;
279 const uint16_t _boardProductId = 0;
280 MockLinkMissionItemHandler *const _missionItemHandler = nullptr;
281 MockLinkCamera *const _mockLinkCamera = nullptr;
282 MockLinkGimbal *const _mockLinkGimbal = nullptr;
283 MockLinkFTP *const _mockLinkFTP = nullptr;
284
285 uint8_t _mavlinkAuxChannel = std::numeric_limits<uint8_t>::max();
286 QMutex _mavlinkAuxMutex;
288 uint8_t _mavlinkVehicleChannel = std::numeric_limits<uint8_t>::max();
289
290 mavlink_signing_t _mockSigning{};
291 mavlink_signing_streams_t _mockSigningStreams{};
292
293 bool _connected = false;
294 bool _inNSH = false;
295
296 uint8_t _mavBaseMode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
297 uint32_t _mavCustomMode = PX4CustomMode::MANUAL;
298 uint8_t _mavState = MAV_STATE_STANDBY;
299
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;
308
309 double _vehicleAltitudeAMSL = _defaultVehicleHomeAltitude;
310 bool _commLost = false;
311 bool _signingEnabled = false;
312 bool _highLatencyTransmissionEnabled = true;
313
314 int _sendHomePositionDelayCount = 10;
315 int _sendGPSPositionDelayCount = 100;
316
317 int _currentParamRequestListComponentIndex = -1;
318 int _currentParamRequestListParamIndex = -1;
319 QList<int> _paramRequestListComponentIds;
320 QStringList _paramRequestListParamNames;
324 QMutex _paramRequestListMutex;
325
326 // Mavlink standard modes worker information
327 int _availableModesWorkerNextModeIndex = 0;
331 QMutex _availableModesWorkerMutex;
332 uint8_t _availableModesMonitorSeqNumber = 0;
333
334 QString _logDownloadFilename;
335 uint32_t _logDownloadCurrentOffset = 0;
336 uint32_t _logDownloadBytesRemaining = 0;
340 QMutex _logDownloadMutex;
341
342 RequestMessageFailureMode_t _requestMessageFailureMode = FailRequestMessageNone;
343 mutable QMutex _requestMessageNoResponseMutex;
344 QSet<uint32_t> _requestMessageNoResponseIds;
345 ParamSetFailureMode_t _paramSetFailureMode = FailParamSetNone;
346 bool _paramSetFailureFirstAttemptPending = false;
347 ParamRequestReadFailureMode_t _paramRequestReadFailureMode = FailParamRequestReadNone;
348 bool _paramRequestReadFailureFirstAttemptPending = false;
349 bool _hashCheckNoResponse = false;
350 int _hashCheckRequestCount = 0;
351 bool _paramRequestListHashCheckSent = false;
352
353 struct RCChannelOverride {
354 enum class State { Ignore, Overridden, Released } state = State::Ignore;
355 uint16_t value = 0;
356 };
357 static constexpr int kRcChannelOverrideChannelCount = 18;
358 std::array<RCChannelOverride, kRcChannelOverrideChannelCount> _rcChannelOverrides;
359
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;
367
368 struct ADSBVehicle {
369 QGeoCoordinate coordinate;
370 double angle = 0.0;
371 double altitude = 0.0;
372 };
373 QList<ADSBVehicle> _adsbVehicles;
374 QList<QGeoCoordinate> _adsbVehicleCoordinates;
375 static constexpr int _numberOfVehicles = 5;
376 double _adsbAngles[_numberOfVehicles]{};
377
378 static std::atomic<int> _nextVehicleSystemId;
379
380 // Vehicle position is set close to default Gazebo vehicle location. This allows for multi-vehicle
381 // testing of a gazebo vehicle and a mocklink vehicle
382 static constexpr double _defaultVehicleLatitude = 47.397;
383 static constexpr double _defaultVehicleLongitude = 8.5455;
384 static constexpr double _defaultVehicleHomeAltitude = 488.056;
385
386 static constexpr const char *_failParam = "COM_FLTMODE6";
387
388 static constexpr uint8_t _vehicleComponentId = MAV_COMP_ID_AUTOPILOT1;
389
390 static constexpr uint16_t _logDownloadLogId = 0;
391 static constexpr uint32_t _logDownloadFileSize = 1000;
392
393 static constexpr bool _mavlinkStarted = true;
394
395 static QList<FlightMode_t> _availableFlightModes;
396
397 std::atomic<bool> _disconnectedEmitted{false};
398};
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
struct __mavlink_message mavlink_message_t
struct __mavlink_command_long_t mavlink_command_long_t
The link interface defines the interface for all links used to communicate with the ground station ap...
Simulates MAVLink Camera Protocol v2 components for MockLink.
Mock implementation of Mavlink FTP server.
Definition MockLinkFTP.h:16
Simulates MAVLink Gimbal Manager Protocol for MockLink.
int requestListCount(MAV_MISSION_TYPE type) const
void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType)
Called to send a MISSION_ACK message while the MissionManager is in idle state.
void reset()
Reset the state of the MissionItemHandler to no items, no transactions in progress.
void setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
void sendUnexpectedMissionRequest()
Called to send a MISSION_REQUEST message while the MissionManager is in idle state.
void sendUnexpectedMissionItem()
Called to send a MISSION_ITEM message while the MissionManager is in idle state.
Worker class that runs periodic tasks for MockLink simulation.