QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
Vehicle.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QElapsedTimer>
4#include <QtCore/QFile>
5#include <QtCore/QObject>
6#include <QtCore/QPointer>
7#include <QtCore/QSharedPointer>
8#include <QtCore/QTime>
9#include <QtCore/QTimer>
10#include <QtCore/QVariantList>
11#include <QtPositioning/QGeoCoordinate>
12#include <QtQmlIntegration/QtQmlIntegration>
13
15#include "MAVLinkStreamConfig.h"
16#include "QGCMapCircle.h"
17#include "QGCMAVLink.h"
18#include "QmlObjectListModel.h"
19#include "SysStatusSensorInfo.h"
20#include "VehicleLinkManager.h"
21
22#include "TerrainFactGroup.h"
23#include "VehicleFactGroup.h"
26#include "VehicleEFIFactGroup.h"
30#include "VehicleGPSFactGroup.h"
35#include "VehicleRPMFactGroup.h"
40#include "GimbalController.h"
43
44class Actuators;
45class AutoPilotPlugin;
46class Autotune;
48class EventHandler;
49class FirmwarePlugin;
50class FTPManager;
51class GeoFenceManager;
55class LinkInterface;
57class MissionManager;
61class RemoteIDManager;
62class RequestMessageTest;
63class RetryableRequestMessageStateTest;
64class SendMavCommandWithHandlerTest;
65class SendMavCommandWithSignallingTest;
66class StandardModes;
71class VehicleSupports;
72
73namespace events {
74namespace parser {
75class ParsedEvent;
76}
77}
78
80
82{
83 Q_OBJECT
84 QML_ELEMENT
85 QML_UNCREATABLE("")
86 Q_MOC_INCLUDE("AutoPilotPlugin.h")
87 Q_MOC_INCLUDE("TrajectoryPoints.h")
88 Q_MOC_INCLUDE("ParameterManager.h")
89 Q_MOC_INCLUDE("VehicleObjectAvoidance.h")
90 Q_MOC_INCLUDE("Autotune.h")
91 Q_MOC_INCLUDE("RemoteIDManager.h")
92 Q_MOC_INCLUDE("Actuators.h")
93 Q_MOC_INCLUDE("MAVLinkLogManager.h")
94 Q_MOC_INCLUDE("LinkInterface.h")
95 Q_MOC_INCLUDE("VehicleSupports.h")
96
98 friend class VehicleLinkManager;
99 friend class FactGroupListModel; // Allow call _addFactGroup
100#ifdef QGC_UNITTEST_BUILD
101 friend class SendMavCommandWithSignallingTest; // Unit test
102 friend class SendMavCommandWithHandlerTest; // Unit test
103 friend class RequestMessageTest; // Unit test
104 friend class RetryableRequestMessageStateTest; // Unit test
105#endif
106 friend class GimbalController; // Allow GimbalController to call _addFactGroup
107
108public:
110 int vehicleId,
111 int defaultComponentId,
112 MAV_AUTOPILOT firmwareType,
113 MAV_TYPE vehicleType,
114 QObject* parent = nullptr);
115
116 // Pass these into the offline constructor to create an offline vehicle which tracks the offline vehicle settings.
117 // Keep these as valid enum values to avoid UBSan failures on enum loads/comparisons.
118 // Use ENUM_END sentinels — no real component should report these values.
119 static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK = MAV_AUTOPILOT_ENUM_END;
120 static const MAV_TYPE MAV_TYPE_TRACK = MAV_TYPE_ENUM_END;
121
122 // The following is used to create a disconnected Vehicle for use while offline editing.
123 Vehicle(MAV_AUTOPILOT firmwareType,
124 MAV_TYPE vehicleType,
125 QObject* parent = nullptr);
126
127 ~Vehicle();
128
130 CheckListNotSetup = 0,
133 };
134 Q_ENUM(CheckList)
135
136 Q_PROPERTY(int id READ id CONSTANT)
137 Q_PROPERTY(AutoPilotPlugin* autopilotPlugin MEMBER _autopilotPlugin CONSTANT)
138 Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
139 Q_PROPERTY(QGeoCoordinate homePosition READ homePosition NOTIFY homePositionChanged)
140 Q_PROPERTY(QGeoCoordinate armedPosition READ armedPosition NOTIFY armedPositionChanged)
141 Q_PROPERTY(bool armed READ armed WRITE setArmedShowError NOTIFY armedChanged)
142 Q_PROPERTY(bool autoDisarm READ autoDisarm NOTIFY autoDisarmChanged)
143 Q_PROPERTY(bool flightModeSetAvailable READ flightModeSetAvailable CONSTANT)
144 Q_PROPERTY(QStringList flightModes READ flightModes NOTIFY flightModesChanged)
145 Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged)
146 Q_PROPERTY(TrajectoryPoints* trajectoryPoints MEMBER _trajectoryPoints CONSTANT)
147 Q_PROPERTY(QmlObjectListModel* cameraTriggerPoints READ cameraTriggerPoints CONSTANT)
148 Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged)
149 Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged)
150 Q_PROPERTY(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged)
151 Q_PROPERTY(bool px4Firmware READ px4Firmware NOTIFY firmwareTypeChanged)
152 Q_PROPERTY(bool apmFirmware READ apmFirmware NOTIFY firmwareTypeChanged)
153 Q_PROPERTY(bool soloFirmware READ soloFirmware WRITE setSoloFirmware NOTIFY soloFirmwareChanged)
154 Q_PROPERTY(bool genericFirmware READ genericFirmware CONSTANT)
155 Q_PROPERTY(uint messagesReceived READ messagesReceived NOTIFY messagesReceivedChanged)
156 Q_PROPERTY(uint messagesSent READ messagesSent NOTIFY messagesSentChanged)
157 Q_PROPERTY(uint messagesLost READ messagesLost NOTIFY messagesLostChanged)
158 Q_PROPERTY(bool airship READ airship NOTIFY vehicleTypeChanged)
159 Q_PROPERTY(bool fixedWing READ fixedWing NOTIFY vehicleTypeChanged)
160 Q_PROPERTY(bool multiRotor READ multiRotor NOTIFY vehicleTypeChanged)
161 Q_PROPERTY(bool vtol READ vtol NOTIFY vehicleTypeChanged)
162 Q_PROPERTY(bool rover READ rover NOTIFY vehicleTypeChanged)
163 Q_PROPERTY(bool sub READ sub NOTIFY vehicleTypeChanged)
164 Q_PROPERTY(VehicleSupports* supports READ supports CONSTANT)
165 Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged)
166 Q_PROPERTY(int motorCount READ motorCount CONSTANT)
167 Q_PROPERTY(bool coaxialMotors READ coaxialMotors CONSTANT)
168 Q_PROPERTY(bool xConfigMotors READ xConfigMotors CONSTANT)
169 Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT)
170 Q_PROPERTY(QString brandImageIndoor READ brandImageIndoor NOTIFY firmwareTypeChanged)
171 Q_PROPERTY(QString brandImageOutdoor READ brandImageOutdoor NOTIFY firmwareTypeChanged)
172 Q_PROPERTY(int sensorsPresentBits READ sensorsPresentBits NOTIFY sensorsPresentBitsChanged)
173 Q_PROPERTY(int sensorsEnabledBits READ sensorsEnabledBits NOTIFY sensorsEnabledBitsChanged)
174 Q_PROPERTY(int sensorsHealthBits READ sensorsHealthBits NOTIFY sensorsHealthBitsChanged)
175 Q_PROPERTY(int sensorsUnhealthyBits READ sensorsUnhealthyBits NOTIFY sensorsUnhealthyBitsChanged)
176 Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT)
177 Q_PROPERTY(QString pauseFlightMode READ pauseFlightMode CONSTANT)
178 Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT)
179 Q_PROPERTY(QString smartRTLFlightMode READ smartRTLFlightMode CONSTANT)
180 Q_PROPERTY(QString landFlightMode READ landFlightMode CONSTANT)
181 Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT)
182 Q_PROPERTY(QString followFlightMode READ followFlightMode CONSTANT)
183 Q_PROPERTY(QString motorDetectionFlightMode READ motorDetectionFlightMode CONSTANT)
184 Q_PROPERTY(QString stabilizedFlightMode READ stabilizedFlightMode CONSTANT)
185 Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged)
186 Q_PROPERTY(QString vehicleTypeString READ vehicleTypeString NOTIFY vehicleTypeChanged)
187 Q_PROPERTY(QString vehicleImageOpaque READ vehicleImageOpaque CONSTANT)
188 Q_PROPERTY(QString vehicleImageOutline READ vehicleImageOutline CONSTANT)
189 Q_PROPERTY(int telemetryRRSSI READ telemetryRRSSI NOTIFY telemetryRRSSIChanged)
190 Q_PROPERTY(int telemetryLRSSI READ telemetryLRSSI NOTIFY telemetryLRSSIChanged)
191 Q_PROPERTY(unsigned int telemetryRXErrors READ telemetryRXErrors NOTIFY telemetryRXErrorsChanged)
192 Q_PROPERTY(unsigned int telemetryFixed READ telemetryFixed NOTIFY telemetryFixedChanged)
193 Q_PROPERTY(unsigned int telemetryTXBuffer READ telemetryTXBuffer NOTIFY telemetryTXBufferChanged)
194 Q_PROPERTY(int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged)
195 Q_PROPERTY(int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged)
196 Q_PROPERTY(QVariantList toolIndicators READ toolIndicators NOTIFY toolIndicatorsChanged)
197 Q_PROPERTY(bool initialPlanRequestComplete READ initialPlanRequestComplete NOTIFY initialPlanRequestCompleteChanged)
198 Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
199 Q_PROPERTY(bool inFwdFlight READ inFwdFlight NOTIFY inFwdFlightChanged)
200 Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged)
201 Q_PROPERTY(quint64 mavlinkSentCount READ mavlinkSentCount NOTIFY mavlinkStatusChanged)
202 Q_PROPERTY(quint64 mavlinkReceivedCount READ mavlinkReceivedCount NOTIFY mavlinkStatusChanged)
203 Q_PROPERTY(quint64 mavlinkLossCount READ mavlinkLossCount NOTIFY mavlinkStatusChanged)
204 Q_PROPERTY(float mavlinkLossPercent READ mavlinkLossPercent NOTIFY mavlinkStatusChanged)
205 Q_PROPERTY(GimbalController* gimbalController READ gimbalController CONSTANT)
206 Q_PROPERTY(bool hasGripper READ hasGripper NOTIFY hasGripperChanged)
207 Q_PROPERTY(bool isROIEnabled READ isROIEnabled NOTIFY isROIEnabledChanged)
208 Q_PROPERTY(CheckList checkListState READ checkListState WRITE setCheckListState NOTIFY checkListStateChanged)
209 Q_PROPERTY(bool readyToFlyAvailable READ readyToFlyAvailable NOTIFY readyToFlyAvailableChanged)
210 Q_PROPERTY(bool readyToFly READ readyToFly NOTIFY readyToFlyChanged)
211 Q_PROPERTY(QObject* sysStatusSensorInfo READ sysStatusSensorInfo CONSTANT)
212 Q_PROPERTY(bool allSensorsHealthy READ allSensorsHealthy NOTIFY allSensorsHealthyChanged) //< true: all sensors in SYS_STATUS reported as healthy
213 Q_PROPERTY(bool requiresGpsFix READ requiresGpsFix NOTIFY requiresGpsFixChanged)
214 Q_PROPERTY(double loadProgress READ loadProgress NOTIFY loadProgressChanged)
215 Q_PROPERTY(bool initialConnectComplete READ isInitialConnectComplete NOTIFY initialConnectComplete)
216
217 // The following properties relate to Orbit status
218 Q_PROPERTY(bool orbitActive READ orbitActive NOTIFY orbitActiveChanged)
219 Q_PROPERTY(QGCMapCircle* orbitMapCircle READ orbitMapCircle CONSTANT)
220
221 // Vehicle state used for guided control
222 Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged)
223 Q_PROPERTY(bool landing READ landing NOTIFY landingChanged)
224 Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged)
225 Q_PROPERTY(QString gotoFlightMode READ gotoFlightMode CONSTANT)
226 Q_PROPERTY(bool haveMRSpeedLimits READ haveMRSpeedLimits NOTIFY haveMRSpeedLimChanged)
227 Q_PROPERTY(bool haveFWSpeedLimits READ haveFWSpeedLimits NOTIFY haveFWSpeedLimChanged)
228
229 Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
230 Q_PROPERTY(VehicleLinkManager* vehicleLinkManager READ vehicleLinkManager CONSTANT)
231 Q_PROPERTY(VehicleObjectAvoidance* objectAvoidance READ objectAvoidance CONSTANT)
232 Q_PROPERTY(Autotune* autotune READ autotune CONSTANT)
233 Q_PROPERTY(RemoteIDManager* remoteIDManager READ remoteIDManager CONSTANT)
234
235 // FactGroup object model properties
236
237 Q_PROPERTY(FactGroup* vehicle READ vehicleFactGroup CONSTANT)
238 Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
239 Q_PROPERTY(FactGroup* gps2 READ gps2FactGroup CONSTANT)
240 Q_PROPERTY(FactGroup* gpsAggregate READ gpsAggregateFactGroup CONSTANT)
241 Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
242 Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
243 Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
244 Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT)
245 Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT)
246 Q_PROPERTY(FactGroup* estimatorStatus READ estimatorStatusFactGroup CONSTANT)
247 Q_PROPERTY(FactGroup* terrain READ terrainFactGroup CONSTANT)
248 Q_PROPERTY(FactGroup* distanceSensors READ distanceSensorFactGroup CONSTANT)
249 Q_PROPERTY(FactGroup* localPosition READ localPositionFactGroup CONSTANT)
250 Q_PROPERTY(FactGroup* localPositionSetpoint READ localPositionSetpointFactGroup CONSTANT)
251 Q_PROPERTY(FactGroup* hygrometer READ hygrometerFactGroup CONSTANT)
252 Q_PROPERTY(FactGroup* generator READ generatorFactGroup CONSTANT)
253 Q_PROPERTY(FactGroup* efi READ efiFactGroup CONSTANT)
254 Q_PROPERTY(Actuators* actuators READ actuators CONSTANT)
255 Q_PROPERTY(HealthAndArmingCheckReport* healthAndArmingCheckReport READ healthAndArmingCheckReport CONSTANT)
256
257 // Dynamic FactGroupListModel properties
258 Q_PROPERTY(QmlObjectListModel* batteries READ batteries CONSTANT)
259 Q_PROPERTY(QmlObjectListModel* escs READ escs CONSTANT)
260
261 Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged)
262 Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged)
263 Q_PROPERTY(int firmwarePatchVersion READ firmwarePatchVersion NOTIFY firmwareVersionChanged)
264 Q_PROPERTY(int firmwareVersionType READ firmwareVersionType NOTIFY firmwareVersionChanged)
265 Q_PROPERTY(QString firmwareVersionTypeString READ firmwareVersionTypeString NOTIFY firmwareVersionChanged)
266 Q_PROPERTY(int firmwareCustomMajorVersion READ firmwareCustomMajorVersion NOTIFY firmwareCustomVersionChanged)
267 Q_PROPERTY(int firmwareCustomMinorVersion READ firmwareCustomMinorVersion NOTIFY firmwareCustomVersionChanged)
268 Q_PROPERTY(int firmwareCustomPatchVersion READ firmwareCustomPatchVersion NOTIFY firmwareCustomVersionChanged)
269 Q_PROPERTY(QString gitHash READ gitHash NOTIFY gitHashChanged)
270 Q_PROPERTY(quint64 vehicleUID READ vehicleUID NOTIFY vehicleUIDChanged)
271 Q_PROPERTY(QString vehicleUIDStr READ vehicleUIDStr NOTIFY vehicleUIDChanged)
272
273 Q_PROPERTY(bool mavlinkSigning READ mavlinkSigning NOTIFY mavlinkSigningChanged)
274
276 Q_INVOKABLE void resetCounters ();
277
278 Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
279
281 Q_INVOKABLE void guidedModeRTL(bool smartRTL);
282
284 Q_INVOKABLE void guidedModeLand();
285
287 Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative);
288
290 Q_INVOKABLE double minimumTakeoffAltitudeMeters();
291
293 Q_INVOKABLE double maximumHorizontalSpeedMultirotor();
294
296 Q_INVOKABLE double maximumEquivalentAirspeed();
297
299 Q_INVOKABLE double minimumEquivalentAirspeed();
300
302 Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord, double forwardFlightLoiterRadius = 0.0f);
303
307 Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle);
308
311 Q_INVOKABLE void guidedModeChangeHeading(const QGeoCoordinate &headingCoord);
312
315 Q_INVOKABLE void guidedModeChangeGroundSpeedMetersSecond(double groundspeed);
318 Q_INVOKABLE void guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed);
319
324 Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
325
328 Q_INVOKABLE void guidedModeROI(const QGeoCoordinate& centerCoord);
329 Q_INVOKABLE void stopGuidedModeROI();
330
333 Q_INVOKABLE void pauseVehicle();
334
336 Q_INVOKABLE void emergencyStop();
337
339 Q_INVOKABLE void abortLanding(double climbOutAltitude);
340
342 Q_INVOKABLE void landingGearDeploy();
343
345 Q_INVOKABLE void landingGearRetract();
346
347 Q_INVOKABLE void startTakeoff();
348
349 Q_INVOKABLE void startMission();
350
352 Q_INVOKABLE void setCurrentMissionSequence(int seq);
353
355 Q_INVOKABLE void rebootVehicle();
356
357 Q_INVOKABLE void sendPlan(QString planFile);
358 Q_INVOKABLE void setEstimatorOrigin(const QGeoCoordinate& centerCoord);
359
361 // returns 1 if current > compare, 0 if current == compare, -1 if current < compare
362 Q_INVOKABLE int versionCompare(const QString& compare) const;
363 Q_INVOKABLE int versionCompare(int major, int minor, int patch) const;
364
369 Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs, bool showError);
370
377 Q_ENUM(PIDTuningTelemetryMode)
378
379 Q_INVOKABLE void setPIDTuningTelemetryMode(PIDTuningTelemetryMode mode);
380
381 Q_INVOKABLE void forceArm ();
382
384 Q_INVOKABLE void sendParamMapRC(const QString& paramName, double scale, double centerValue, int tuningID, double minValue, double maxValue);
385
387 Q_INVOKABLE void clearAllParamMapRC(void);
388
390 Q_INVOKABLE void closeVehicle(void) { _vehicleLinkManager->closeVehicle(); }
391
393 Q_INVOKABLE void triggerSimpleCamera(void);
394
396 Q_INVOKABLE void doSetHome(const QGeoCoordinate& coord);
397
398 Q_INVOKABLE void sendSetupSigning();
399
400 Q_INVOKABLE QVariant expandedToolbarIndicatorSource(const QString& indicatorName);
401
402 bool isInitialConnectComplete() const;
403 QString gotoFlightMode () const;
404
405 VehicleSupports* supports() { return _vehicleSupports; }
406 bool hasGripper () const;
407 bool haveMRSpeedLimits() const { return _multirotor_speed_limits_available; }
408 bool haveFWSpeedLimits() const { return _fixed_wing_airspeed_limits_available; }
409
410 // Property accessors
411
412 QGeoCoordinate coordinate() { return _coordinate; }
413 QGeoCoordinate armedPosition () { return _armedPosition; }
414
415 qreal getInitialGCSPressure() const { return _initialGCSPressure; }
416 qreal getInitialGCSTemperature() const { return _initialGCSTemperature; }
417 void setInitialGCSPressure(qreal pressure) { _initialGCSPressure = pressure; }
418 void setInitialGCSTemperature(qreal temperature) { _initialGCSTemperature = temperature; }
419
420 void updateFlightDistance(double distance);
421
422 void sendJoystickDataThreadSafe (float roll, float pitch, float yaw, float thrust, quint16 buttons, quint16 buttons2, float pitchExtension, float rollExtension, float aux1, float aux2, float aux3, float aux4, float aux5, float aux6);
423
424 // Property accesors
425 int id() const{ return _systemID; }
426 int compId() const{ return _compID; }
427 MAV_AUTOPILOT firmwareType() const { return _firmwareType; }
428 MAV_TYPE vehicleType() const { return _vehicleType; }
430 Q_INVOKABLE QString vehicleClassInternalName() const;
431
434 bool sendMessageOnLinkThreadSafe(LinkInterface* link, mavlink_message_t message);
435
438 void sendMessageMultiple(mavlink_message_t message);
439
441 AutoPilotPlugin* autopilotPlugin() { return _autopilotPlugin; }
442
444 FirmwarePlugin* firmwarePlugin() { return _firmwarePlugin; }
445
446
447 QGeoCoordinate homePosition();
448
449 bool armed () const{ return _armed; }
450 void setArmed (bool armed, bool showError);
451 void setArmedShowError (bool armed) { setArmed(armed, true); }
452
453 bool flightModeSetAvailable ();
454 QStringList flightModes ();
455 QString flightMode () const;
456 void setFlightMode (const QString& flightMode);
457
458 bool airship() const;
459
460 void pairRX(int rxType, int rxSubType);
461
462 bool fixedWing() const;
463 bool multiRotor() const;
464 bool vtol() const;
465 bool rover() const;
466 bool sub() const;
467 bool spacecraft() const;
468
469
470
471 void setGuidedMode(bool guidedMode);
472
473 QString prearmError() const { return _prearmError; }
474 void setPrearmError(const QString& prearmError);
475
476 QmlObjectListModel* cameraTriggerPoints () { return &_cameraTriggerPoints; }
477
478 //-- Mavlink Logging
479 void startMavlinkLog();
480 void stopMavlinkLog();
481
486 void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true);
487
488 // The follow method are used to turn on/off the tracking of settings updates for firmware/vehicle type on offline vehicles.
489 void trackFirmwareVehicleTypeChanges(void);
490 void stopTrackingFirmwareVehicleTypeChanges(void);
491
492 float latitude () { return static_cast<float>(_coordinate.latitude()); }
493 float longitude () { return static_cast<float>(_coordinate.longitude()); }
494 int rcRSSI () const{ return _rcRSSI; }
495 bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
496 bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
497 bool genericFirmware () const { return !px4Firmware() && !apmFirmware(); }
498 uint messagesReceived () const{ return _messagesReceived; }
499 uint messagesSent () const{ return _messagesSent; }
500 uint messagesLost () const{ return _messagesLost; }
501 bool flying () const { return _flying; }
502 bool landing () const { return _landing; }
503 bool guidedMode () const;
504 bool inFwdFlight () const;
505 bool vtolInFwdFlight () const { return _vtolInFwdFlight; }
506 uint8_t baseMode () const { return _base_mode; }
507 uint32_t customMode () const { return _custom_mode; }
508 bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
509 QString brandImageIndoor () const;
510 QString brandImageOutdoor () const;
511 int sensorsPresentBits () const { return static_cast<int>(_onboardControlSensorsPresent); }
512 int sensorsEnabledBits () const { return static_cast<int>(_onboardControlSensorsEnabled); }
513 int sensorsHealthBits () const { return static_cast<int>(_onboardControlSensorsHealth); }
514 int sensorsUnhealthyBits () const { return static_cast<int>(_onboardControlSensorsUnhealthy); }
515 QString missionFlightMode () const;
516 QString pauseFlightMode () const;
517 QString rtlFlightMode () const;
518 QString smartRTLFlightMode () const;
519 QString landFlightMode () const;
520 QString takeControlFlightMode () const;
521 QString followFlightMode () const;
522 QString motorDetectionFlightMode () const;
523 QString stabilizedFlightMode () const;
524 double defaultCruiseSpeed () const { return _defaultCruiseSpeed; }
525 double defaultHoverSpeed () const { return _defaultHoverSpeed; }
526 QString firmwareTypeString () const;
527 QString vehicleTypeString () const;
528 int telemetryRRSSI () const{ return _telemetryRRSSI; }
529 int telemetryLRSSI () const{ return _telemetryLRSSI; }
530 unsigned int telemetryRXErrors () const{ return _telemetryRXErrors; }
531 unsigned int telemetryFixed () const{ return _telemetryFixed; }
532 unsigned int telemetryTXBuffer () const{ return _telemetryTXBuffer; }
533 int telemetryLNoise () const{ return _telemetryLNoise; }
534 int telemetryRNoise () const{ return _telemetryRNoise; }
535 bool autoDisarm ();
536 bool orbitActive () const { return _orbitActive; }
537 QGCMapCircle* orbitMapCircle () { return &_orbitMapCircle; }
538 bool readyToFlyAvailable () const{ return _readyToFlyAvailable; }
539 bool readyToFly () const{ return _readyToFly; }
540 bool allSensorsHealthy () const{ return _allSensorsHealthy; }
541 QObject* sysStatusSensorInfo () { return &_sysStatusSensorInfo; }
542 bool requiresGpsFix () const { return static_cast<bool>(_onboardControlSensorsPresent & QGCMAVLink::SysStatusSensorGPS); }
543 bool hilMode () const { return _base_mode & MAV_MODE_FLAG_HIL_ENABLED; }
544 Actuators* actuators () const { return _actuators; }
545 bool mavlinkSigning () const { return _mavlinkSigning; }
546
547 void startCalibration (QGCMAVLink::CalibrationType calType);
548 void stopCalibration (bool showError);
549
550 void startUAVCANBusConfig(void);
551 void stopUAVCANBusConfig(void);
552
553 FactGroup* vehicleFactGroup () { return _vehicleFactGroup; }
554 FactGroup* gpsFactGroup () { return &_gpsFactGroup; }
555 FactGroup* gps2FactGroup () { return &_gps2FactGroup; }
556 FactGroup* gpsAggregateFactGroup () { return &_gpsAggregateFactGroup; }
557 FactGroup* windFactGroup () { return &_windFactGroup; }
558 FactGroup* vibrationFactGroup () { return &_vibrationFactGroup; }
559 FactGroup* temperatureFactGroup () { return &_temperatureFactGroup; }
560 FactGroup* clockFactGroup () { return &_clockFactGroup; }
561 FactGroup* setpointFactGroup () { return &_setpointFactGroup; }
562 FactGroup* distanceSensorFactGroup () { return &_distanceSensorFactGroup; }
563 FactGroup* localPositionFactGroup () { return &_localPositionFactGroup; }
564 FactGroup* localPositionSetpointFactGroup() { return &_localPositionSetpointFactGroup; }
565 FactGroup* estimatorStatusFactGroup () { return &_estimatorStatusFactGroup; }
566 FactGroup* terrainFactGroup () { return &_terrainFactGroup; }
567 FactGroup* hygrometerFactGroup () { return &_hygrometerFactGroup; }
568 FactGroup* generatorFactGroup () { return &_generatorFactGroup; }
569 FactGroup* efiFactGroup () { return &_efiFactGroup; }
570 FactGroup* rpmFactGroup () { return &_rpmFactGroup; }
571
572 QmlObjectListModel* batteries () { return &_batteryFactGroupListModel; }
573 QmlObjectListModel* escs () { return &_escStatusFactGroupListModel; }
574
575 MissionManager* missionManager () { return _missionManager; }
576 GeoFenceManager* geoFenceManager () { return _geoFenceManager; }
577 RallyPointManager* rallyPointManager () { return _rallyPointManager; }
578 ParameterManager* parameterManager () { return _parameterManager; }
579 ParameterManager* parameterManager () const { return _parameterManager; }
580 VehicleLinkManager* vehicleLinkManager () { return _vehicleLinkManager; }
581 FTPManager* ftpManager () { return _ftpManager; }
582 ComponentInformationManager* compInfoManager () { return _componentInformationManager; }
583 VehicleObjectAvoidance* objectAvoidance () { return _objectAvoidance; }
584 Autotune* autotune () const { return _autotune; }
585 RemoteIDManager* remoteIDManager () { return _remoteIDManager; }
586
587 static void showCommandAckError(const mavlink_command_ack_t& ack);
588
595 void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
596 void sendMavCommandDelayed(int compId, MAV_CMD command, bool showError, int milliseconds, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
597 void sendMavCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7);
598
613 bool isMavCommandPending(int targetCompId, MAV_CMD command);
614
616 Q_INVOKABLE void sendCommand(int compId, int command, bool showError, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0, double param5 = 0.0, double param6 = 0.0, double param7 = 0.0);
617
623
624 static QString mavCmdResultFailureCodeToString(MavCmdResultFailureCode_t failureCode);
625
629 typedef void (*MavCmdProgressHandler)(void* progressHandlerData, int compId, const mavlink_command_ack_t& ack);
630
635 typedef void (*MavCmdResultHandler)(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
636
637 // Callback info for sendMavCommandWithHandler
638 typedef struct MavCmdAckHandlerInfo_s {
639 MavCmdResultHandler resultHandler;
641 MavCmdProgressHandler progressHandler;
643 } MavCmdAckHandlerInfo_t;
644
646 void sendMavCommandWithHandler(
647 const MavCmdAckHandlerInfo_t* ackHandlerInfo,
648 int compId, MAV_CMD command,
649 float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
650
654 void sendMavCommandIntWithHandler(
655 const MavCmdAckHandlerInfo_t* ackHandlerInfo,
656 int compId, MAV_CMD command, MAV_FRAME frame,
657 float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, float param7 = 0.0f);
658
661 void sendMavCommandWithLambdaFallback(
662 std::function<void()> lambda,
663 int compId, MAV_CMD command,
664 bool showError,
665 float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
666
667
675
676 static QString requestMessageResultHandlerFailureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode);
677
683 typedef void (*RequestMessageResultHandler)(void* resultHandlerData, MAV_RESULT commandResult, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message);
684
688 void requestMessage(RequestMessageResultHandler resultHandler, void* resultHandlerData, int compId, int messageId, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f);
689
690 int firmwareMajorVersion() const { return _firmwareMajorVersion; }
691 int firmwareMinorVersion() const { return _firmwareMinorVersion; }
692 int firmwarePatchVersion() const { return _firmwarePatchVersion; }
693 int firmwareVersionType() const { return _firmwareVersionType; }
694 int firmwareCustomMajorVersion() const { return _firmwareCustomMajorVersion; }
695 int firmwareCustomMinorVersion() const { return _firmwareCustomMinorVersion; }
696 int firmwareCustomPatchVersion() const { return _firmwareCustomPatchVersion; }
697 int firmwareBoardVendorId() const { return _firmwareBoardVendorId; }
698 int firmwareBoardProductId() const { return _firmwareBoardProductId; }
699 QString firmwareVersionTypeString() const;
700 void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
701 void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
702 static const int versionNotSetValue = -1;
703
704 QString gitHash() const { return _gitHash; }
705 quint64 vehicleUID() const { return _uid; }
706 QString vehicleUIDStr();
707
708 bool soloFirmware() const { return _soloFirmware; }
709 void setSoloFirmware(bool soloFirmware);
710
711 int defaultComponentId() const{ return _defaultComponentId; }
712
714 void setOfflineEditingDefaultComponentId(int defaultComponentId);
715
717 int motorCount();
718
720 bool coaxialMotors();
721
723 bool xConfigMotors();
724
726 class FirmwarePluginInstanceData* firmwarePluginInstanceData() { return _firmwarePluginInstanceData; }
727
730 void setFirmwarePluginInstanceData(FirmwarePluginInstanceData* firmwarePluginInstanceData);
731
732 QString vehicleImageOpaque () const;
733 QString vehicleImageOutline () const;
734
735 const QVariantList& toolIndicators();
736
737 bool capabilitiesKnown () const { return _capabilityBitsKnown; }
738 uint64_t capabilityBits () const { return _capabilityBits; } // Change signalled by capabilityBitsChanged
739
740 QString hobbsMeter ();
741
744 bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
745
746 void forceInitialPlanRequestComplete();
747
748 void _setFlying(bool flying);
749 void _setLanding(bool landing);
750 void _setHomePosition(QGeoCoordinate& homeCoord);
751
754
757
758 quint64 mavlinkSentCount () const{ return _mavlinkSentCount; }
759 quint64 mavlinkReceivedCount () const{ return _mavlinkReceivedCount; }
760 quint64 mavlinkLossCount () const{ return _mavlinkLossCount; }
761 float mavlinkLossPercent () const{ return _mavlinkLossPercent; }
762
763 bool isROIEnabled () const{ return _isROIEnabled; }
764
765 CheckList checkListState () { return _checkListState; }
766 void setCheckListState (CheckList cl) { _checkListState = cl; emit checkListStateChanged(); }
767
768 double loadProgress () const { return _loadProgress; }
769
770 void setEventsMetadata(uint8_t compid, const QString& metadataJsonFileName);
771 void setActuatorsMetadata(uint8_t compid, const QString& metadataJsonFileName);
772
773 HealthAndArmingCheckReport* healthAndArmingCheckReport() { return &_healthAndArmingCheckReport; }
774
775 GimbalController* gimbalController () { return _gimbalController; }
776
777public slots:
778 void setVtolInFwdFlight (bool vtolInFwdFlight);
779 void _offlineFirmwareTypeSettingChanged (QVariant varFirmwareType); // Should only be used by MissionControler to set firmware from Plan file
780 void _offlineVehicleTypeSettingChanged (QVariant varVehicleType); // Should only be used by MissionController to set vehicle type from Plan file
781 Q_INVOKABLE void sendGripperAction(QGCMAVLink::GripperActions gripperOption);
782
783signals:
784 void coordinateChanged (QGeoCoordinate coordinate);
786 void homePositionChanged (const QGeoCoordinate& homePosition);
788 void armedChanged (bool armed);
789 void flightModeChanged (const QString& flightMode);
790 void flyingChanged (bool flying);
791 void landingChanged (bool landing);
792 void guidedModeChanged (bool guidedMode);
794 void vtolInFwdFlightChanged (bool vtolInFwdFlight);
795 void prearmErrorChanged (const QString& prearmError);
796 void soloFirmwareChanged (bool soloFirmware);
797 void defaultCruiseSpeedChanged (double cruiseSpeed);
798 void defaultHoverSpeedChanged (double hoverSpeed);
802 void capabilitiesKnownChanged (bool capabilitiesKnown);
803 void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
804 void capabilityBitsChanged (uint64_t capabilityBits);
806 void calibrationEventReceived (int uasid, int componentid, int severity, QSharedPointer<events::parser::ParsedEvent> event);
810 void rcRSSIChanged (int rcRSSI);
811 void telemetryRRSSIChanged (int value);
812 void telemetryLRSSIChanged (int value);
813 void telemetryRXErrorsChanged (unsigned int value);
814 void telemetryFixedChanged (unsigned int value);
815 void telemetryTXBufferChanged (unsigned int value);
816 void telemetryLNoiseChanged (int value);
817 void telemetryRNoiseChanged (int value);
820 void sensorsPresentBitsChanged (int sensorsPresentBits);
821 void sensorsEnabledBitsChanged (int sensorsEnabledBits);
822 void sensorsHealthBitsChanged (int sensorsHealthBits);
823 void sensorsUnhealthyBitsChanged (int sensorsUnhealthyBits);
824 void orbitActiveChanged (bool orbitActive);
825 void readyToFlyAvailableChanged (bool readyToFlyAvailable);
826 void readyToFlyChanged (bool readyToFy);
827 void allSensorsHealthyChanged (bool allSensorsHealthy);
832
835 void gitHashChanged (QString hash);
837 void loadProgressChanged (float value);
838
841 void rcChannelsChanged(QVector<int> channelValues);
842
844 void remoteControlRSSIChanged (uint8_t rssi);
845
846 // Mavlink Log Download
847 void mavlinkLogData (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
848
855 void mavCommandResult (int vehicleId, int targetComponent, int command, int ackResult, int failureCode);
856
857 // MAVlink Serial Data
858 void mavlinkSerialControl (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
859
862
864 void roiCoordChanged (const QGeoCoordinate& centerCoord);
866
867 void sensorsParametersResetAck (bool success);
868
869 void logEntry (uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num);
870 void logData (uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data);
871
872private slots:
873 void _mavlinkMessageReceived (LinkInterface* link, mavlink_message_t message);
874 void _sendMessageMultipleNext ();
875 void _parametersReady (bool parametersReady);
876 void _remoteControlRSSIChanged (uint8_t rssi);
877 void _handleFlightModeChanged (const QString& flightMode);
878 void _announceArmedChanged (bool armed);
879 void _offlineCruiseSpeedSettingChanged (QVariant value);
880 void _offlineHoverSpeedSettingChanged (QVariant value);
881 void _prearmErrorTimeout ();
882 void _firstMissionLoadComplete ();
883 void _firstGeoFenceLoadComplete ();
884 void _firstRallyPointLoadComplete ();
885 void _sendMavCommandResponseTimeoutCheck();
886 void _clearCameraTriggerPoints ();
887 void _updateDistanceHeadingHome ();
888 void _updateMissionItemIndex ();
889 void _updateHeadingToNextWP ();
890 void _updateDistanceHeadingGCS ();
891 void _updateHomepoint ();
892 void _updateHobbsMeter ();
893 void _vehicleParamLoaded (bool ready);
894 void _sendQGCTimeToVehicle ();
895 void _mavlinkMessageStatus (int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
896 void _orbitTelemetryTimeout ();
897 void _updateFlightTime ();
898 void _gotProgressUpdate (float progressValue);
899 void _doSetHomeTerrainReceived (bool success, QList<double> heights);
900 void _roiTerrainReceived (bool success, QList<double> heights);
901 void _sendROICommand (const QGeoCoordinate& coord, MAV_FRAME frame, float altitude);
902 void _updateAltAboveTerrain ();
903 void _altitudeAboveTerrainReceived (bool sucess, QList<double> heights);
904
905private:
906
907void _activeVehicleChanged (Vehicle* newActiveVehicle);
908 void _handlePing (LinkInterface* link, mavlink_message_t& message);
909 void _handleHomePosition (mavlink_message_t& message);
910 void _handleHeartbeat (mavlink_message_t& message);
911 void _handleCurrentMode (mavlink_message_t& message);
912 void _handleRadioStatus (mavlink_message_t& message);
913 void _handleRCChannels (mavlink_message_t& message);
914 void _handleBatteryStatus (mavlink_message_t& message);
915 void _handleSysStatus (mavlink_message_t& message);
916 void _handleExtendedSysState (mavlink_message_t& message);
917 void _handleCommandAck (mavlink_message_t& message);
918 void _handleGpsRawInt (mavlink_message_t& message);
919 void _handleGlobalPositionInt (mavlink_message_t& message);
920 void _handleHighLatency (mavlink_message_t& message);
921 void _handleHighLatency2 (mavlink_message_t& message);
922 void _handleOrbitExecutionStatus (const mavlink_message_t& message);
923 void _handleGimbalOrientation (const mavlink_message_t& message);
924 void _handleObstacleDistance (const mavlink_message_t& message);
925 void _handleFenceStatus (const mavlink_message_t& message);
926 void _handleEvent(uint8_t comp_id, std::unique_ptr<events::parser::ParsedEvent> event);
927 // ArduPilot dialect messages
928#if !defined(QGC_NO_ARDUPILOT_DIALECT)
929 void _handleCameraFeedback (const mavlink_message_t& message);
930#endif
931 void _handleCameraImageCaptured (const mavlink_message_t& message);
932 void _handleCommandLong (const mavlink_message_t& message);
933 void _missionManagerError (int errorCode, const QString& errorMsg);
934 void _geoFenceManagerError (int errorCode, const QString& errorMsg);
935 void _rallyPointManagerError (int errorCode, const QString& errorMsg);
936 void _say (const QString& text);
937 QString _vehicleIdSpeech ();
938 void _handleMavlinkLoggingData (mavlink_message_t& message);
939 void _handleMavlinkLoggingDataAcked (mavlink_message_t& message);
940 void _ackMavlinkLogData (uint16_t sequence);
941 void _commonInit (LinkInterface* link);
942 void _setupAutoDisarmSignalling ();
943 void _setCapabilities (uint64_t capabilityBits);
944 void _updateArmed (bool armed);
945 bool _apmArmingNotRequired ();
946 void _initializeCsv ();
947 void _writeCsvLine ();
948 void _flightTimerStart ();
949 void _flightTimerStop ();
950 void _setMessageInterval (int messageId, int rate);
951 EventHandler& _eventHandler (uint8_t compid);
952 bool setFlightModeCustom (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
953 QString _formatMavCommand (MAV_CMD command, float param1);
954
955 static void _rebootCommandResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
956
957 // The following methods should only be called by unit tests
958 void _deleteGimbalController();
959 void _deleteCameraManager();
960
963 void _stopCommandProcessing();
964
965 int _systemID;
966 int _defaultComponentId;
967 bool _offlineEditingVehicle = false;
968
969 MAV_AUTOPILOT _firmwareType;
970 MAV_TYPE _vehicleType;
971 FirmwarePlugin* _firmwarePlugin = nullptr;
972 class FirmwarePluginInstanceData* _firmwarePluginInstanceData = nullptr;
973 AutoPilotPlugin* _autopilotPlugin = nullptr;
974 bool _soloFirmware = false;
975
976 QTimer _csvLogTimer;
977 QFile _csvLogFile;
978
979 bool _isActiveVehicle = false;
980
981 QGeoCoordinate _coordinate;
982 QGeoCoordinate _homePosition;
983 QGeoCoordinate _armedPosition;
984
985 qreal _initialGCSPressure = 0.;
986 qreal _initialGCSTemperature = 0.;
987
988 int _rcRSSI = 255;
989 double _rcRSSIstore = 255;
990 bool _flying = false;
991 bool _landing = false;
992 bool _vtolInFwdFlight = false;
993 uint32_t _onboardControlSensorsPresent = 0;
994 uint32_t _onboardControlSensorsEnabled = 0;
995 uint32_t _onboardControlSensorsHealth = 0;
996 uint32_t _onboardControlSensorsUnhealthy = 0;
997 bool _gpsRawIntMessageAvailable = false;
998 bool _gps2RawMessageAvailable = false;
999 bool _globalPositionIntMessageAvailable = false;
1000 double _defaultCruiseSpeed = qQNaN();
1001 double _defaultHoverSpeed = qQNaN();
1002 int _telemetryRRSSI = 0;
1003 int _telemetryLRSSI = 0;
1004 uint32_t _telemetryRXErrors = 0;
1005 uint32_t _telemetryFixed = 0;
1006 uint32_t _telemetryTXBuffer = 0;
1007 int _telemetryLNoise = 0;
1008 int _telemetryRNoise = 0;
1009 bool _capabilityBitsKnown = false;
1010 uint64_t _capabilityBits = 0;
1011 CheckList _checkListState = CheckListNotSetup;
1012 bool _readyToFlyAvailable = false;
1013 bool _readyToFly = false;
1014 bool _allSensorsHealthy = true;
1015 bool _mavlinkSigning = false;
1016
1017 SysStatusSensorInfo _sysStatusSensorInfo;
1018
1019
1020 QString _prearmError;
1021 QTimer _prearmErrorTimer;
1022 static const int _prearmErrorTimeoutMSecs = 35 * 1000;
1023
1024 bool _initialPlanRequestComplete = false;
1025
1026 ParameterManager* _parameterManager = nullptr;
1027 ComponentInformationManager* _componentInformationManager = nullptr;
1028 VehicleObjectAvoidance* _objectAvoidance = nullptr;
1029 Autotune* _autotune = nullptr;
1030 GimbalController* _gimbalController = nullptr;
1031 VehicleSupports* _vehicleSupports = nullptr;
1032
1033 bool _armed = false;
1034 uint8_t _base_mode = 0;
1035 uint32_t _custom_mode = 0;
1036 uint32_t _custom_mode_user_intention = 0;
1037 bool _has_custom_mode_user_intention = false;
1038
1040 typedef struct {
1041 mavlink_message_t message;
1042 int retryCount;
1043 } SendMessageMultipleInfo_t;
1044
1045 QList<SendMessageMultipleInfo_t> _sendMessageMultipleList;
1046
1047 static const int _sendMessageMultipleRetries = 5;
1048 static const int _sendMessageMultipleIntraMessageDelay = 500;
1049
1050 QTimer _sendMultipleTimer;
1051 int _nextSendMessageMultipleIndex = 0;
1052
1053 QElapsedTimer _flightTimer;
1054 QTimer _flightTimeUpdater;
1055 TrajectoryPoints* _trajectoryPoints = nullptr;
1056 QmlObjectListModel _cameraTriggerPoints;
1057 //QMap<QString, ADSBVehicle*> _trafficVehicleMap;
1058
1059 bool _allLinksRemovedSent = false;
1060
1061 uint _messagesReceived = 0;
1062 uint _messagesSent = 0;
1063 uint _messagesLost = 0;
1064 uint8_t _messageSeq = 0;
1065 uint8_t _compID = 0;
1066 bool _heardFrom = false;
1067
1068 bool _isROIEnabled = false;
1069\
1070 bool _checkLatestStableFWDone = false;
1071 int _firmwareMajorVersion = versionNotSetValue;
1072 int _firmwareMinorVersion = versionNotSetValue;
1073 int _firmwarePatchVersion = versionNotSetValue;
1074 int _firmwareCustomMajorVersion = versionNotSetValue;
1075 int _firmwareCustomMinorVersion = versionNotSetValue;
1076 int _firmwareCustomPatchVersion = versionNotSetValue;
1077 FIRMWARE_VERSION_TYPE _firmwareVersionType = FIRMWARE_VERSION_TYPE_OFFICIAL;
1078
1079 // Vendor and Product as reported from the first autopilot version message
1080 // during the initial connect. They may be zero eg ArduPilot SITL reports 0
1081 // by default.
1082 uint16_t _firmwareBoardVendorId = 0;
1083 uint16_t _firmwareBoardProductId = 0;
1084
1085
1086 QString _gitHash;
1087 quint64 _uid = 0;
1088
1089 uint64_t _mavlinkSentCount = 0;
1090 uint64_t _mavlinkReceivedCount = 0;
1091 uint64_t _mavlinkLossCount = 0;
1092 float _mavlinkLossPercent = 0.0f;
1093
1094 float _loadProgress = 0.0f;
1095
1096 QMap<QString, QTime> _noisySpokenPrearmMap;
1097
1098 // Orbit status values
1099 bool _orbitActive = false;
1100 QGCMapCircle _orbitMapCircle;
1101 QTimer _orbitTelemetryTimer;
1102 static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive
1103
1104 QMap<uint8_t, QSharedPointer<EventHandler>> _events;
1105 HealthAndArmingCheckReport _healthAndArmingCheckReport;
1106
1107 MAVLinkStreamConfig _mavlinkStreamConfig;
1108
1113 typedef void (*WaitForMavlinkMessageResultHandler)(void* resultHandlerData, bool noResponsefromVehicle, const mavlink_message_t& message);
1114
1115 void _waitForMavlinkMessageMessageReceivedHandler(const mavlink_message_t& message);
1116
1117 // requestMessage handling
1118
1119 typedef struct RequestMessageInfo {
1120 QPointer<Vehicle> vehicle; // QPointer automatically becomes null when Vehicle is destroyed
1121 int compId;
1122 int msgId;
1123 float param1 = 0.0f;
1124 float param2 = 0.0f;
1125 float param3 = 0.0f;
1126 float param4 = 0.0f;
1127 float param5 = 0.0f;
1128 RequestMessageResultHandler resultHandler = nullptr;
1129 void* resultHandlerData = nullptr;
1130 bool commandAckReceived = false; // We keep track of the ack/message being received since the order in which this will come in is random
1131 bool messageReceived = false; // We only delete the allocated RequestMessageInfo_t when both the message is received and we get the ack
1132 QElapsedTimer messageWaitElapsedTimer; // Elapsed time since we started waiting message to show up
1133 mavlink_message_t message;
1134 } RequestMessageInfo_t;
1135
1136 QMap<int /* compId */, QMap<int /* msgId */, RequestMessageInfo_t*>> _requestMessageInfoMap; // Map of all request message calls currently waiting on a response
1137 QMap<int /* compId */, QList<RequestMessageInfo_t*>> _requestMessageQueueMap; // Queue of requestMessage calls waiting for active request to finish per component
1138
1139 void _removeRequestMessageInfo(int compId, int msgId);
1140 bool _requestMessageDuplicate(int compId, int msgId) const;
1141 void _requestMessageSendNow(RequestMessageInfo_t* requestMessageInfo);
1142 void _requestMessageSendNextFromQueue(int compId);
1143
1144 static void _requestMessageCmdResultHandler (void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
1145 static void _requestMessageWaitForMessageResultHandler (void* resultHandlerData, bool noResponsefromVehicle, const mavlink_message_t& message);
1146
1147 typedef struct MavCommandListEntry {
1148 int targetCompId = MAV_COMP_ID_AUTOPILOT1;
1149 bool useCommandInt = false;
1150 MAV_CMD command;
1151 MAV_FRAME frame;
1152 float rgParam1 = 0;
1153 float rgParam2 = 0;
1154 float rgParam3 = 0;
1155 float rgParam4 = 0;
1156 double rgParam5 = 0;
1157 double rgParam6 = 0;
1158 float rgParam7 = 0;
1159 bool showError = true;
1160 MavCmdAckHandlerInfo_t ackHandlerInfo;
1161 int maxTries = _mavCommandMaxRetryCount;
1162 int tryCount = 0;
1163 QElapsedTimer elapsedTimer;
1164 int ackTimeoutMSecs = 0;
1165 } MavCommandListEntry_t;
1166
1167 QList<MavCommandListEntry_t> _mavCommandList;
1168 QTimer _mavCommandResponseCheckTimer;
1169 static constexpr int _mavCommandMaxRetryCount = 3;
1170 static int _mavCommandResponseCheckTimeoutMSecs();
1171 static int _mavCommandAckTimeoutMSecs();
1172 static constexpr int _mavCommandAckTimeoutMSecsHighLatency = 120000;
1173
1174public:
1177 static constexpr int kTestMavCommandAckTimeoutMs = 500;
1179 static constexpr int kTestMavCommandMaxWaitMs = kTestMavCommandAckTimeoutMs * _mavCommandMaxRetryCount * 2;
1180
1181 void _sendMavCommandWorker (
1182 bool commandInt, bool showError,
1183 const MavCmdAckHandlerInfo_t* ackHandlerInfo,
1184 int compId, MAV_CMD command, MAV_FRAME frame,
1185 float param1, float param2, float param3, float param4, double param5, double param6, float param7);
1186 void _sendMavCommandFromList(int index);
1187 int _findMavCommandListEntryIndex(int targetCompId, MAV_CMD command);
1188 bool _sendMavCommandShouldRetry(MAV_CMD command);
1189 bool _commandCanBeDuplicated(MAV_CMD command);
1190
1191 QMap<uint8_t /* batteryId */, uint8_t /* MAV_BATTERY_CHARGE_STATE_OK */> _lowestBatteryChargeStateAnnouncedMap;
1192
1193 float _altitudeTuningOffset = qQNaN(); // altitude offset, so the plotted value is around 0
1194
1195 // these flags are used to determine if the speed change action from fly view should be shown
1196 bool _multirotor_speed_limits_available = false;
1197 bool _fixed_wing_airspeed_limits_available = false;
1198
1199 // FactGroup facts
1200
1201 const QString _vehicleFactGroupName = QStringLiteral("vehicle");
1202 const QString _gpsFactGroupName = QStringLiteral("gps");
1203 const QString _gps2FactGroupName = QStringLiteral("gps2");
1204 const QString _gpsAggregateFactGroupName = QStringLiteral("gpsAggregate");
1205 const QString _windFactGroupName = QStringLiteral("wind");
1206 const QString _vibrationFactGroupName = QStringLiteral("vibration");
1207 const QString _temperatureFactGroupName = QStringLiteral("temperature");
1208 const QString _clockFactGroupName = QStringLiteral("clock");
1209 const QString _setpointFactGroupName = QStringLiteral("setpoint");
1210 const QString _distanceSensorFactGroupName = QStringLiteral("distanceSensor");
1211 const QString _localPositionFactGroupName = QStringLiteral("localPosition");
1212 const QString _localPositionSetpointFactGroupName = QStringLiteral("localPositionSetpoint");
1213 const QString _estimatorStatusFactGroupName = QStringLiteral("estimatorStatus");
1214 const QString _terrainFactGroupName = QStringLiteral("terrain");
1215 const QString _hygrometerFactGroupName = QStringLiteral("hygrometer");
1216 const QString _generatorFactGroupName = QStringLiteral("generator");
1217 const QString _efiFactGroupName = QStringLiteral("efi");
1218 const QString _rpmFactGroupName = QStringLiteral("rpm");
1219
1238
1239 // Dynamic FactGroups
1242
1243 TerrainProtocolHandler* _terrainProtocolHandler = nullptr;
1244
1245 MissionManager* _missionManager = nullptr;
1246 GeoFenceManager* _geoFenceManager = nullptr;
1247 RallyPointManager* _rallyPointManager = nullptr;
1248 VehicleLinkManager* _vehicleLinkManager = nullptr;
1249 FTPManager* _ftpManager = nullptr;
1250 InitialConnectStateMachine* _initialConnectStateMachine = nullptr;
1251 Actuators* _actuators = nullptr;
1252 RemoteIDManager* _remoteIDManager = nullptr;
1253 StandardModes* _standardModes = nullptr;
1254
1255 // Terrain query members, used to get terrain altitude for doSetHome()
1256 TerrainAtCoordinateQuery* _currentDoSetHomeTerrainAtCoordinateQuery = nullptr;
1257 QGeoCoordinate _doSetHomeCoordinate;
1258
1259 // Terrain query members, used to get terrain altitude for guidedModeROI()
1260 TerrainAtCoordinateQuery* _roiTerrainAtCoordinateQuery = nullptr;
1261 QGeoCoordinate _roiCoordinate;
1262
1263 // Terrain query members, used to get altitude above terrain Fact
1265 TerrainAtCoordinateQuery* _altitudeAboveTerrTerrainAtCoordinateQuery = nullptr;
1266 // We use this to limit above terrain altitude queries based on distance and altitude change
1268 float _altitudeAboveTerrLastRelAlt = qQNaN();
1269
1270public:
1271 int32_t getMessageRate(uint8_t compId, uint16_t msgId);
1272 void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate);
1273
1274signals:
1275 void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate);
1276
1277private:
1278 void _handleMessageInterval(const mavlink_message_t& message);
1279
1280 static void _requestMessageMessageIntervalResultHandler(void* resultHandlerData, MAV_RESULT result, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message);
1281 void _requestMessageInterval(uint8_t compId, uint16_t msgId);
1282
1283 static void _setMessageRateCommandResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
1284
1285 typedef QPair<uint8_t, uint16_t> MavCompMsgId;
1286 QHash<MavCompMsgId, int32_t> _mavlinkMsgIntervals;
1287 QMultiHash<uint8_t, uint16_t> _unsupportedMessageIds;
1288 uint16_t _lastSetMsgIntervalMsgId = 0;
1289
1290/*---------------------------------------------------------------------------*/
1291/*===========================================================================*/
1292/* ardupilotmega Dialect */
1293/*===========================================================================*/
1294public:
1295 Q_INVOKABLE void flashBootloader();
1296
1298 Q_INVOKABLE void motorInterlock(bool enable);
1299
1300/*---------------------------------------------------------------------------*/
1301/*===========================================================================*/
1302/* CONTROL STATUS HANDLER */
1303/*===========================================================================*/
1304public:
1305 Q_INVOKABLE void startTimerRevertAllowTakeover();
1306 Q_INVOKABLE void requestOperatorControl(bool allowOverride, int requestTimeoutSecs = 0);
1307
1308private:
1309 void _handleControlStatus(const mavlink_message_t& message);
1310 void _handleCommandRequestOperatorControl(const mavlink_command_long_t commandLong);
1311 static void _requestOperatorControlAckHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
1312
1313 Q_PROPERTY(uint8_t sysidInControl READ sysidInControl NOTIFY gcsControlStatusChanged)
1314 Q_PROPERTY(bool gcsControlStatusFlags_SystemManager READ gcsControlStatusFlags_SystemManager NOTIFY gcsControlStatusChanged)
1315 Q_PROPERTY(bool gcsControlStatusFlags_TakeoverAllowed READ gcsControlStatusFlags_TakeoverAllowed NOTIFY gcsControlStatusChanged)
1316 Q_PROPERTY(bool firstControlStatusReceived READ firstControlStatusReceived NOTIFY gcsControlStatusChanged)
1317 Q_PROPERTY(int operatorControlTakeoverTimeoutMsecs READ operatorControlTakeoverTimeoutMsecs CONSTANT)
1318 Q_PROPERTY(int requestOperatorControlRemainingMsecs READ requestOperatorControlRemainingMsecs CONSTANT)
1319 Q_PROPERTY(bool sendControlRequestAllowed READ sendControlRequestAllowed NOTIFY sendControlRequestAllowedChanged)
1320
1321 uint8_t sysidInControl() const { return _sysid_in_control; }
1322 bool gcsControlStatusFlags_SystemManager() const { return _gcsControlStatusFlags_SystemManager; }
1323 bool gcsControlStatusFlags_TakeoverAllowed() const { return _gcsControlStatusFlags_TakeoverAllowed; }
1324 bool firstControlStatusReceived() const { return _firstControlStatusReceived; }
1325 int operatorControlTakeoverTimeoutMsecs() const;
1326 int requestOperatorControlRemainingMsecs() const { return _timerRequestOperatorControl.remainingTime(); }
1327 bool sendControlRequestAllowed() const { return _sendControlRequestAllowed; }
1328 void requestOperatorControlStartTimer(int requestTimeoutMsecs);
1329
1330 uint8_t _sysid_in_control = 0;
1331 uint8_t _gcsControlStatusFlags = 0;
1332 bool _gcsControlStatusFlags_SystemManager = 0;
1333 bool _gcsControlStatusFlags_TakeoverAllowed = 0;
1334 bool _firstControlStatusReceived = false;
1335 QTimer _timerRevertAllowTakeover;
1336 QTimer _timerRequestOperatorControl;
1337 bool _sendControlRequestAllowed = true;
1338
1339signals:
1341 void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs);
1342 void sendControlRequestAllowedChanged(bool sendControlRequestAllowed);
1343
1344/*===========================================================================*/
1345/* STATUS TEXT HANDLER */
1346/*===========================================================================*/
1347private:
1348 Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged)
1349 Q_PROPERTY(bool messageTypeNormal READ messageTypeNormal NOTIFY messageTypeChanged)
1350 Q_PROPERTY(bool messageTypeWarning READ messageTypeWarning NOTIFY messageTypeChanged)
1351 Q_PROPERTY(bool messageTypeError READ messageTypeError NOTIFY messageTypeChanged)
1352 Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged)
1353 Q_PROPERTY(QString formattedMessages READ formattedMessages NOTIFY formattedMessagesChanged)
1354
1355 // Q_PROPERTY(StatusTextHandler *statusTextHandler READ statusTextHandler NOTIFY statusTextHandlerChanged)
1356
1357public:
1358 Q_INVOKABLE void resetAllMessages();
1359 Q_INVOKABLE void resetErrorLevelMessages();
1360 Q_INVOKABLE void clearMessages();
1361
1362 bool messageTypeNone() const;
1363 bool messageTypeNormal() const;
1364 bool messageTypeWarning() const;
1365 bool messageTypeError() const;
1366 int messageCount() const;
1367 QString formattedMessages() const;
1368
1369 // StatusTextHandler* statusTextHandler() { return m_statusTextHandler; }
1370
1371signals:
1372 void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description);
1373
1380 void newFormattedMessage(QString formattedMessage);
1381
1382 // void statusTextHandlerChanged();
1383
1384private slots:
1385 void _textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description);
1386 void _errorMessageReceived(QString message);
1387
1388private:
1389 void _createStatusTextHandler();
1390
1391 StatusTextHandler *m_statusTextHandler = nullptr;
1392
1393/*---------------------------------------------------------------------------*/
1394/*===========================================================================*/
1395/* Image Protocol Manager */
1396/*===========================================================================*/
1397private:
1398 Q_PROPERTY(uint flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged)
1399
1400public:
1401 uint32_t flowImageIndex() const;
1402
1403signals:
1405
1406private:
1407 void _createImageProtocolManager();
1408
1409 ImageProtocolManager *_imageProtocolManager = nullptr;
1410
1411/*---------------------------------------------------------------------------*/
1412/*===========================================================================*/
1413/* MAVLink Log Manager */
1414/*===========================================================================*/
1415private:
1416 Q_PROPERTY(MAVLinkLogManager *mavlinkLogManager READ mavlinkLogManager NOTIFY mavlinkLogManagerChanged)
1417
1418public:
1419 MAVLinkLogManager *mavlinkLogManager() const;
1420
1421signals:
1423
1424private:
1425 void _createMAVLinkLogManager();
1426
1427 MAVLinkLogManager *_mavlinkLogManager = nullptr;
1428
1429/*---------------------------------------------------------------------------*/
1430/*===========================================================================*/
1431/* Camera Manager */
1432/*===========================================================================*/
1433private:
1434 Q_MOC_INCLUDE("QGCCameraManager.h")
1435 Q_PROPERTY(QGCCameraManager *cameraManager READ cameraManager NOTIFY cameraManagerChanged)
1436 Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT)
1437
1438public:
1439 QGCCameraManager *cameraManager() { return _cameraManager; }
1440 const QVariantList &staticCameraList() const;
1441
1442signals:
1444
1445private:
1446 void _createCameraManager();
1447
1448 QGCCameraManager *_cameraManager = nullptr;
1449
1450/*---------------------------------------------------------------------------*/
1451};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
Dynamically manages FactGroupWithIds based on incoming messages.
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
The link interface defines the interface for all links used to communicate with the ground station ap...
Camera Manager.
The QGCMapCircle represents a circular area which can be displayed on a Map control.
Class which represents sensor info from the SYS_STATUS mavlink message.
NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be o...
int telemetryRNoise() const
Definition Vehicle.h:534
bool readyToFly() const
Definition Vehicle.h:539
VehicleGPSAggregateFactGroup _gpsAggregateFactGroup
Definition Vehicle.h:1223
void autoDisarmChanged()
QGeoCoordinate _roiCoordinate
Definition Vehicle.h:1261
bool px4Firmware() const
Definition Vehicle.h:495
void firmwareTypeChanged()
bool hilMode() const
Definition Vehicle.h:543
QGCMAVLink::VehicleClass_t vehicleClass(void) const
Definition Vehicle.h:429
void setInitialGCSPressure(qreal pressure)
Definition Vehicle.h:417
uint messagesReceived() const
Definition Vehicle.h:498
void sensorsPresentBitsChanged(int sensorsPresentBits)
void defaultHoverSpeedChanged(double hoverSpeed)
void gcsControlStatusChanged()
void defaultCruiseSpeedChanged(double cruiseSpeed)
FactGroup * localPositionFactGroup()
Definition Vehicle.h:563
VehicleVibrationFactGroup _vibrationFactGroup
Definition Vehicle.h:1225
void haveMRSpeedLimChanged()
FactGroup * vibrationFactGroup()
Definition Vehicle.h:558
void messagesLostChanged()
FactGroup * gpsAggregateFactGroup()
Definition Vehicle.h:556
void vtolInFwdFlightChanged(bool vtolInFwdFlight)
qreal getInitialGCSPressure() const
Definition Vehicle.h:415
void readyToFlyAvailableChanged(bool readyToFlyAvailable)
void isROIEnabledChanged()
Actuators * actuators() const
Definition Vehicle.h:544
Autotune * autotune() const
Definition Vehicle.h:584
void deleteGimbalController()
Delete gimbal controller, handy for RequestMessageTest.cc, otherwise gimbal controller message reques...
bool haveMRSpeedLimits() const
Definition Vehicle.h:407
bool orbitActive() const
Definition Vehicle.h:536
int firmwareCustomMajorVersion() const
Definition Vehicle.h:694
void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs)
uint messagesLost() const
Definition Vehicle.h:500
void mavlinkLogManagerChanged()
FactGroup * rpmFactGroup()
Definition Vehicle.h:570
void initialConnectComplete()
void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description)
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete)
int telemetryLRSSI() const
Definition Vehicle.h:529
TerrainFactGroup _terrainFactGroup
Definition Vehicle.h:1237
bool flying() const
Definition Vehicle.h:501
void firmwareCustomVersionChanged()
QString prearmError() const
Definition Vehicle.h:473
int sensorsEnabledBits() const
Definition Vehicle.h:512
float latitude()
Definition Vehicle.h:492
void inFwdFlightChanged()
void flyingChanged(bool flying)
void remoteControlRSSIChanged(uint8_t rssi)
Remote control RSSI changed (0% - 100%)
void capabilityBitsChanged(uint64_t capabilityBits)
bool haveFWSpeedLimits() const
Definition Vehicle.h:408
int sensorsUnhealthyBits() const
Definition Vehicle.h:514
void hobbsMeterChanged()
uint64_t capabilityBits() const
Definition Vehicle.h:738
VehicleTemperatureFactGroup _temperatureFactGroup
Definition Vehicle.h:1226
void readyToFlyChanged(bool readyToFy)
void formattedMessagesChanged()
void newFormattedMessage(QString formattedMessage)
MAV_TYPE vehicleType() const
Definition Vehicle.h:428
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
uint32_t customMode() const
Definition Vehicle.h:507
void cameraManagerChanged()
HealthAndArmingCheckReport * healthAndArmingCheckReport()
Definition Vehicle.h:773
void armedChanged(bool armed)
void firmwareVersionChanged()
FactGroup * distanceSensorFactGroup()
Definition Vehicle.h:562
void logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num)
CheckList checkListState()
Definition Vehicle.h:765
void sendControlRequestAllowedChanged(bool sendControlRequestAllowed)
void hasGripperChanged()
FactGroup * generatorFactGroup()
Definition Vehicle.h:568
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
quint64 mavlinkSentCount() const
Definition Vehicle.h:758
unsigned int telemetryTXBuffer() const
Definition Vehicle.h:532
void sensorsParametersResetAck(bool success)
int firmwareBoardProductId() const
Definition Vehicle.h:698
ComponentInformationManager * compInfoManager()
Definition Vehicle.h:582
MavCmdResultFailureCode_t
Definition Vehicle.h:618
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
Definition Vehicle.h:620
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
Definition Vehicle.h:619
@ MavCmdResultFailureDuplicateCommand
Unable to send command since duplicate is already being waited on for response.
Definition Vehicle.h:621
void telemetryLNoiseChanged(int value)
PIDTuningTelemetryMode
Definition Vehicle.h:371
@ ModeDisabled
Definition Vehicle.h:372
@ ModeAltitudeAndAirspeed
Definition Vehicle.h:375
@ ModeVelocityAndPosition
Definition Vehicle.h:374
@ ModeRateAndAttitude
Definition Vehicle.h:373
bool landing() const
Definition Vehicle.h:502
qreal getInitialGCSTemperature() const
Definition Vehicle.h:416
void checkListStateChanged()
int firmwareMinorVersion() const
Definition Vehicle.h:691
QElapsedTimer _altitudeAboveTerrQueryTimer
Definition Vehicle.h:1264
bool isOfflineEditingVehicle() const
Definition Vehicle.h:508
void messagesSentChanged()
VehicleDistanceSensorFactGroup _distanceSensorFactGroup
Definition Vehicle.h:1229
quint64 mavlinkLossCount() const
Total number of sucessful messages received.
Definition Vehicle.h:760
bool vtolInFwdFlight() const
Definition Vehicle.h:505
void capabilitiesKnownChanged(bool capabilitiesKnown)
int rcRSSI() const
Definition Vehicle.h:494
MAV_AUTOPILOT firmwareType() const
Definition Vehicle.h:427
QGeoCoordinate _altitudeAboveTerrLastCoord
Definition Vehicle.h:1267
void setCheckListState(CheckList cl)
Definition Vehicle.h:766
bool soloFirmware() const
Definition Vehicle.h:708
void coordinateChanged(QGeoCoordinate coordinate)
void currentConfigChanged()
void mavlinkLogData(Vehicle *vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked)
int firmwareCustomPatchVersion() const
Definition Vehicle.h:696
int id() const
Definition Vehicle.h:425
FactGroup * gps2FactGroup()
Definition Vehicle.h:555
void toolIndicatorsChanged()
void sensorsUnhealthyBitsChanged(int sensorsUnhealthyBits)
void landingChanged(bool landing)
VehicleLocalPositionSetpointFactGroup _localPositionSetpointFactGroup
Definition Vehicle.h:1231
FactGroup * hygrometerFactGroup()
Definition Vehicle.h:567
VehicleGPS2FactGroup _gps2FactGroup
Definition Vehicle.h:1222
unsigned int telemetryFixed() const
Definition Vehicle.h:531
VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup
Definition Vehicle.h:1232
float mavlinkLossPercent() const
Total number of lost messages.
Definition Vehicle.h:761
void loadProgressChanged(float value)
GeoFenceManager * geoFenceManager()
Definition Vehicle.h:576
void mavlinkMessageReceived(const mavlink_message_t &message)
bool requiresGpsFix() const
Definition Vehicle.h:542
VehicleRPMFactGroup _rpmFactGroup
Definition Vehicle.h:1236
FactGroup * localPositionSetpointFactGroup()
Definition Vehicle.h:564
QmlObjectListModel * escs()
Definition Vehicle.h:573
void guidedModeChanged(bool guidedMode)
FactGroup * efiFactGroup()
Definition Vehicle.h:569
void vehicleUIDChanged()
quint64 vehicleUID() const
Definition Vehicle.h:705
QGeoCoordinate armedPosition()
Definition Vehicle.h:413
void longitudeChanged()
double loadProgress() const
Definition Vehicle.h:768
RemoteIDManager * remoteIDManager()
Definition Vehicle.h:585
QObject * sysStatusSensorInfo()
Definition Vehicle.h:541
uint8_t baseMode() const
Definition Vehicle.h:506
VehicleFactGroup * _vehicleFactGroup
Definition Vehicle.h:1220
unsigned int telemetryRXErrors() const
Definition Vehicle.h:530
RequestMessageResultHandlerFailureCode_t
Definition Vehicle.h:668
@ RequestMessageFailureMessageNotReceived
Definition Vehicle.h:672
@ RequestMessageNoFailure
Definition Vehicle.h:669
@ RequestMessageFailureCommandNotAcked
Definition Vehicle.h:671
@ RequestMessageFailureCommandError
Definition Vehicle.h:670
@ RequestMessageFailureDuplicate
Exact duplicate request already active or queued for this component/message id.
Definition Vehicle.h:673
void orbitActiveChanged(bool orbitActive)
void allSensorsHealthyChanged(bool allSensorsHealthy)
FactGroup * vehicleFactGroup()
Definition Vehicle.h:553
void mavlinkSigningChanged()
int telemetryRRSSI() const
Definition Vehicle.h:528
VehicleSetpointFactGroup _setpointFactGroup
Definition Vehicle.h:1228
void armedPositionChanged()
void rcRSSIChanged(int rcRSSI)
EscStatusFactGroupListModel _escStatusFactGroupListModel
Definition Vehicle.h:1241
void soloFirmwareChanged(bool soloFirmware)
ParameterManager * parameterManager() const
Definition Vehicle.h:579
int firmwareVersionType() const
Definition Vehicle.h:693
int compId() const
Definition Vehicle.h:426
void homePositionChanged(const QGeoCoordinate &homePosition)
QMap< uint8_t, uint8_t > _lowestBatteryChargeStateAnnouncedMap
Definition Vehicle.h:1191
VehicleHygrometerFactGroup _hygrometerFactGroup
Definition Vehicle.h:1233
double defaultHoverSpeed() const
Definition Vehicle.h:525
FactGroup * windFactGroup()
Definition Vehicle.h:557
VehicleClockFactGroup _clockFactGroup
Definition Vehicle.h:1227
void flightModesChanged()
int sensorsHealthBits() const
Definition Vehicle.h:513
FactGroup * temperatureFactGroup()
Definition Vehicle.h:559
GimbalController * gimbalController()
Definition Vehicle.h:775
int telemetryLNoise() const
Definition Vehicle.h:533
bool apmFirmware() const
Definition Vehicle.h:496
int sensorsPresentBits() const
Definition Vehicle.h:511
void flightModeChanged(const QString &flightMode)
bool allSensorsHealthy() const
Definition Vehicle.h:540
QString gitHash() const
Definition Vehicle.h:704
void telemetryLRSSIChanged(int value)
void flowImageIndexChanged()
void roiCoordChanged(const QGeoCoordinate &centerCoord)
VehicleObjectAvoidance * objectAvoidance()
Definition Vehicle.h:583
void messageTypeChanged()
FactGroup * estimatorStatusFactGroup()
Definition Vehicle.h:565
int defaultComponentId() const
Definition Vehicle.h:711
void setInitialGCSTemperature(qreal temperature)
Definition Vehicle.h:418
void mavlinkStatusChanged()
quint64 mavlinkReceivedCount() const
Calculated total number of messages sent to us.
Definition Vehicle.h:759
RallyPointManager * rallyPointManager()
Definition Vehicle.h:577
bool genericFirmware() const
Definition Vehicle.h:497
FactGroup * setpointFactGroup()
Definition Vehicle.h:561
QmlObjectListModel * cameraTriggerPoints()
Definition Vehicle.h:476
float longitude()
Definition Vehicle.h:493
QGCMapCircle * orbitMapCircle()
Definition Vehicle.h:537
ParameterManager * parameterManager()
Definition Vehicle.h:578
void gitHashChanged(QString hash)
int firmwareBoardVendorId() const
Definition Vehicle.h:697
void sensorsHealthBitsChanged(int sensorsHealthBits)
VehicleLocalPositionFactGroup _localPositionFactGroup
Definition Vehicle.h:1230
QGeoCoordinate _doSetHomeCoordinate
Definition Vehicle.h:1257
void prepareDelete()
Vehicle is about to be deleted.
AutoPilotPlugin * autopilotPlugin()
Provides access to AutoPilotPlugin for this vehicle.
Definition Vehicle.h:441
bool initialPlanRequestComplete() const
Definition Vehicle.h:744
bool mavlinkSigning() const
Definition Vehicle.h:545
void messagesReceivedChanged()
VehicleGeneratorFactGroup _generatorFactGroup
Definition Vehicle.h:1234
VehicleEFIFactGroup _efiFactGroup
Definition Vehicle.h:1235
int firmwarePatchVersion() const
Definition Vehicle.h:692
QGeoCoordinate coordinate()
Definition Vehicle.h:412
FTPManager * ftpManager()
Definition Vehicle.h:581
FactGroup * clockFactGroup()
Definition Vehicle.h:560
void messageCountChanged()
void rcChannelsChanged(QVector< int > channelValues)
bool isROIEnabled() const
Running loss rate.
Definition Vehicle.h:763
BatteryFactGroupListModel _batteryFactGroupListModel
Definition Vehicle.h:1240
void telemetryTXBufferChanged(unsigned int value)
@ CheckListFailed
Definition Vehicle.h:132
@ CheckListPassed
Definition Vehicle.h:131
QmlObjectListModel * batteries()
Definition Vehicle.h:572
void haveFWSpeedLimChanged()
double defaultCruiseSpeed() const
Definition Vehicle.h:524
void telemetryRRSSIChanged(int value)
bool armed() const
Definition Vehicle.h:449
VehicleSupports * supports()
Definition Vehicle.h:405
void telemetryFixedChanged(unsigned int value)
bool capabilitiesKnown() const
Definition Vehicle.h:737
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
FactGroup * gpsFactGroup()
Definition Vehicle.h:554
void calibrationEventReceived(int uasid, int componentid, int severity, QSharedPointer< events::parser::ParsedEvent > event)
int firmwareCustomMinorVersion() const
Definition Vehicle.h:695
void sensorsEnabledBitsChanged(int sensorsEnabledBits)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
Definition Vehicle.h:726
int firmwareMajorVersion() const
Definition Vehicle.h:690
void requiresGpsFixChanged()
void closeVehicle(void)
Removes the vehicle from the system.
Definition Vehicle.h:390
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
FactGroup * terrainFactGroup()
Definition Vehicle.h:566
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data)
VehicleWindFactGroup _windFactGroup
Definition Vehicle.h:1224
VehicleGPSFactGroup _gpsFactGroup
Definition Vehicle.h:1221
MissionManager * missionManager()
Definition Vehicle.h:575
void prearmErrorChanged(const QString &prearmError)
void vehicleTypeChanged()
uint messagesSent() const
Definition Vehicle.h:499
void setArmedShowError(bool armed)
Definition Vehicle.h:451
void telemetryRNoiseChanged(int value)
bool readyToFlyAvailable() const
Definition Vehicle.h:538
void logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
void telemetryRXErrorsChanged(unsigned int value)
Q_DECLARE_METATYPE(satellite_info_s)
MavCmdResultHandler resultHandler
Definition Vehicle.h:639
void * resultHandlerData
‍nullptr for no handler
Definition Vehicle.h:640
MavCmdProgressHandler progressHandler
Definition Vehicle.h:641