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 <functional>
4#include <memory>
5
6#include <QtCore/QElapsedTimer>
7#include <QtCore/QFile>
8#include <QtCore/QObject>
9#include <QtCore/QPointer>
10#include <QtCore/QSharedPointer>
11#include <QtCore/QTime>
12#include <QtCore/QTimer>
13#include <QtCore/QVariantList>
14#include <QtPositioning/QGeoCoordinate>
15#include <QtQmlIntegration/QtQmlIntegration>
16
17#include <array>
18#include <atomic>
19
20#include "QGCMAVLink.h"
21#include "VehicleFactGroup.h"
22#include "VehicleSigningController.h" // Q_PROPERTY needs the full QObject type for moc/QML metatype registration
23#include "VehicleTypes.h"
24
25class Actuators;
28class QGCMapCircle;
32class AutoPilotPlugin;
54class Autotune;
57class FirmwarePlugin;
58class FTPManager;
59class GeoFenceManager;
63class LinkInterface;
65class MavCommandQueue;
67class MissionManager;
72class RemoteIDManager;
73class RequestMessageTest;
74class RetryableRequestMessageStateTest;
75class SendMavCommandWithHandlerTest;
76class SendMavCommandWithSignallingTest;
77class StandardModes;
83class VehicleSupports;
84
86{
87 Q_OBJECT
88 QML_ELEMENT
89 QML_UNCREATABLE("")
90 Q_MOC_INCLUDE("Actuators.h")
91 Q_MOC_INCLUDE("AutoPilotPlugin.h")
92 Q_MOC_INCLUDE("Autotune.h")
93 Q_MOC_INCLUDE("GimbalController.h")
94 Q_MOC_INCLUDE("LinkInterface.h")
95 Q_MOC_INCLUDE("MAVLinkLogManager.h")
96 Q_MOC_INCLUDE("ParameterManager.h")
97 Q_MOC_INCLUDE("QGCMapCircle.h")
98 Q_MOC_INCLUDE("QmlObjectListModel.h")
99 Q_MOC_INCLUDE("RemoteIDManager.h")
100 Q_MOC_INCLUDE("TrajectoryPoints.h")
101 Q_MOC_INCLUDE("VehicleLinkManager.h")
102 Q_MOC_INCLUDE("VehicleObjectAvoidance.h")
103 Q_MOC_INCLUDE("VehicleSupports.h")
104
106 friend class VehicleLinkManager;
107 friend class FactGroupListModel; // Allow call _addFactGroup
108#ifdef QGC_UNITTEST_BUILD
109 friend class SendMavCommandWithSignallingTest; // Unit test
110 friend class SendMavCommandWithHandlerTest; // Unit test
111 friend class RequestMessageTest; // Unit test
112 friend class RetryableRequestMessageStateTest; // Unit test
113#endif
114 friend class GimbalController; // Allow GimbalController to call _addFactGroup
115
116public:
118 int vehicleId,
120 MAV_AUTOPILOT firmwareType,
121 MAV_TYPE vehicleType,
122 QObject* parent = nullptr);
123
124 // Pass these into the offline constructor to create an offline vehicle which tracks the offline vehicle settings.
125 // Keep these as valid enum values to avoid UBSan failures on enum loads/comparisons.
126 // Use ENUM_END sentinels — no real component should report these values.
127 static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK = MAV_AUTOPILOT_ENUM_END;
128 static const MAV_TYPE MAV_TYPE_TRACK = MAV_TYPE_ENUM_END;
129
130 // The following is used to create a disconnected Vehicle for use while offline editing.
131 Vehicle(MAV_AUTOPILOT firmwareType,
132 MAV_TYPE vehicleType,
133 QObject* parent = nullptr);
134
135 ~Vehicle();
136
142 Q_ENUM(CheckList)
143
144 Q_PROPERTY(int id READ id CONSTANT)
145 Q_PROPERTY(AutoPilotPlugin* autopilotPlugin MEMBER _autopilotPlugin CONSTANT)
146 Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
147 Q_PROPERTY(QGeoCoordinate homePosition READ homePosition NOTIFY homePositionChanged)
148 Q_PROPERTY(QGeoCoordinate armedPosition READ armedPosition NOTIFY armedPositionChanged)
149 Q_PROPERTY(bool armed READ armed WRITE setArmedShowError NOTIFY armedChanged)
150 Q_PROPERTY(bool autoDisarm READ autoDisarm NOTIFY autoDisarmChanged)
151 Q_PROPERTY(bool flightModeSetAvailable READ flightModeSetAvailable CONSTANT)
152 Q_PROPERTY(QStringList flightModes READ flightModes NOTIFY flightModesChanged)
153 Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged)
154 Q_PROPERTY(TrajectoryPoints* trajectoryPoints MEMBER _trajectoryPoints CONSTANT)
156 Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged)
157 Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged)
158 Q_PROPERTY(bool px4Firmware READ px4Firmware NOTIFY firmwareTypeChanged)
159 Q_PROPERTY(bool apmFirmware READ apmFirmware NOTIFY firmwareTypeChanged)
160 Q_PROPERTY(bool soloFirmware READ soloFirmware WRITE setSoloFirmware NOTIFY soloFirmwareChanged)
161 Q_PROPERTY(bool genericFirmware READ genericFirmware CONSTANT)
163 Q_PROPERTY(uint messagesSent READ messagesSent NOTIFY messagesSentChanged)
164 Q_PROPERTY(uint messagesLost READ messagesLost NOTIFY messagesLostChanged)
165 Q_PROPERTY(bool airship READ airship NOTIFY vehicleTypeChanged)
166 Q_PROPERTY(bool fixedWing READ fixedWing NOTIFY vehicleTypeChanged)
167 Q_PROPERTY(bool multiRotor READ multiRotor NOTIFY vehicleTypeChanged)
168 Q_PROPERTY(bool vtol READ vtol NOTIFY vehicleTypeChanged)
169 Q_PROPERTY(bool rover READ rover NOTIFY vehicleTypeChanged)
170 Q_PROPERTY(bool sub READ sub NOTIFY vehicleTypeChanged)
171 Q_PROPERTY(VehicleSupports* supports READ supports CONSTANT)
172 Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged)
173 Q_PROPERTY(int motorCount READ motorCount CONSTANT)
174 Q_PROPERTY(bool coaxialMotors READ coaxialMotors CONSTANT)
175 Q_PROPERTY(bool xConfigMotors READ xConfigMotors CONSTANT)
176 Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT)
181 Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT)
182 Q_PROPERTY(QString pauseFlightMode READ pauseFlightMode CONSTANT)
183 Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT)
184 Q_PROPERTY(QString smartRTLFlightMode READ smartRTLFlightMode CONSTANT)
185 Q_PROPERTY(QString landFlightMode READ landFlightMode CONSTANT)
186 Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT)
187 Q_PROPERTY(QString followFlightMode READ followFlightMode CONSTANT)
188 Q_PROPERTY(QString motorDetectionFlightMode READ motorDetectionFlightMode CONSTANT)
189 Q_PROPERTY(QString stabilizedFlightMode READ stabilizedFlightMode CONSTANT)
190 Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged)
191 Q_PROPERTY(QString vehicleTypeString READ vehicleTypeString NOTIFY vehicleTypeChanged)
192 Q_PROPERTY(QString vehicleImageOpaque READ vehicleImageOpaque CONSTANT)
193 Q_PROPERTY(QString vehicleImageOutline READ vehicleImageOutline CONSTANT)
194 Q_PROPERTY(QVariantList toolIndicators READ toolIndicators NOTIFY toolIndicatorsChanged)
196 Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
197 Q_PROPERTY(bool inFwdFlight READ inFwdFlight NOTIFY inFwdFlightChanged)
199 Q_PROPERTY(quint64 mavlinkSentCount READ mavlinkSentCount NOTIFY mavlinkStatusChanged)
201 Q_PROPERTY(quint64 mavlinkLossCount READ mavlinkLossCount NOTIFY mavlinkStatusChanged)
203 Q_PROPERTY(GimbalController* gimbalController READ gimbalController CONSTANT)
204 Q_PROPERTY(bool hasGripper READ hasGripper NOTIFY hasGripperChanged)
205 Q_PROPERTY(bool isROIEnabled READ isROIEnabled NOTIFY isROIEnabledChanged)
208 Q_PROPERTY(bool readyToFly READ readyToFly NOTIFY readyToFlyChanged)
209 Q_PROPERTY(QObject* sysStatusSensorInfo READ sysStatusSensorInfo CONSTANT)
210 Q_PROPERTY(bool allSensorsHealthy READ allSensorsHealthy NOTIFY allSensorsHealthyChanged) //< true: all sensors in SYS_STATUS reported as healthy
211 Q_PROPERTY(bool requiresGpsFix READ requiresGpsFix NOTIFY requiresGpsFixChanged)
212 Q_PROPERTY(double loadProgress READ loadProgress NOTIFY loadProgressChanged)
214
215 // The following properties relate to Orbit status
216 Q_PROPERTY(bool orbitActive READ orbitActive NOTIFY orbitActiveChanged)
217 Q_PROPERTY(QGCMapCircle* orbitMapCircle READ orbitMapCircle CONSTANT)
218
219 // Vehicle state used for guided control
220 Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged)
221 Q_PROPERTY(bool landing READ landing NOTIFY landingChanged)
222 Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged)
223 Q_PROPERTY(QString gotoFlightMode READ gotoFlightMode CONSTANT)
226
227 Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
230 Q_PROPERTY(Autotune* autotune READ autotune CONSTANT)
231 Q_PROPERTY(RemoteIDManager* remoteIDManager READ remoteIDManager CONSTANT)
232
233 // FactGroup object model properties
234
235 Q_PROPERTY(FactGroup* vehicle READ vehicleFactGroup CONSTANT)
236 Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
237 Q_PROPERTY(FactGroup* gps2 READ gps2FactGroup CONSTANT)
238 Q_PROPERTY(FactGroup* gpsAggregate READ gpsAggregateFactGroup CONSTANT)
239 Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
240 Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
241 Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
242 Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT)
243 Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT)
244 Q_PROPERTY(FactGroup* estimatorStatus READ estimatorStatusFactGroup CONSTANT)
245 Q_PROPERTY(FactGroup* terrain READ terrainFactGroup CONSTANT)
246 Q_PROPERTY(FactGroup* distanceSensors READ distanceSensorFactGroup CONSTANT)
247 Q_PROPERTY(FactGroup* localPosition READ localPositionFactGroup CONSTANT)
248 Q_PROPERTY(FactGroup* localPositionSetpoint READ localPositionSetpointFactGroup CONSTANT)
249 Q_PROPERTY(FactGroup* hygrometer READ hygrometerFactGroup CONSTANT)
250 Q_PROPERTY(FactGroup* generator READ generatorFactGroup CONSTANT)
251 Q_PROPERTY(FactGroup* efi READ efiFactGroup CONSTANT)
252 Q_PROPERTY(FactGroup* radioStatus READ radioStatusFactGroup CONSTANT)
253 Q_PROPERTY(Actuators* actuators READ actuators CONSTANT)
254
255 // Dynamic FactGroupListModel properties
256 Q_PROPERTY(QmlObjectListModel* batteries READ batteries CONSTANT)
257 Q_PROPERTY(QmlObjectListModel* escs READ escs CONSTANT)
258
267 Q_PROPERTY(QString gitHash READ gitHash NOTIFY gitHashChanged)
268 Q_PROPERTY(quint64 vehicleUID READ vehicleUID NOTIFY vehicleUIDChanged)
269 Q_PROPERTY(QString vehicleUIDStr READ vehicleUIDStr NOTIFY vehicleUIDChanged)
270
272
273
274 Q_INVOKABLE void resetCounters ();
275
276 Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
277
279 Q_INVOKABLE void guidedModeRTL(bool smartRTL);
280
282 Q_INVOKABLE void guidedModeLand();
283
285 Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative);
286
288 Q_INVOKABLE double minimumTakeoffAltitudeMeters();
289
292
294 Q_INVOKABLE double maximumEquivalentAirspeed();
295
297 Q_INVOKABLE double minimumEquivalentAirspeed();
298
301 Q_INVOKABLE bool guidedModeGotoLocation(const QGeoCoordinate& gotoCoord, double forwardFlightLoiterRadius = 0.0f);
302
306 Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle);
307
310 Q_INVOKABLE void guidedModeChangeHeading(const QGeoCoordinate &headingCoord);
311
314 Q_INVOKABLE void guidedModeChangeGroundSpeedMetersSecond(double groundspeed);
317 Q_INVOKABLE void guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed);
318
323 Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
324
327 Q_INVOKABLE void guidedModeROI(const QGeoCoordinate& centerCoord);
328 Q_INVOKABLE void stopGuidedModeROI();
329
332 Q_INVOKABLE void pauseVehicle();
333
335 Q_INVOKABLE void emergencyStop();
336
338 Q_INVOKABLE void abortLanding(double climbOutAltitude);
339
341 Q_INVOKABLE void landingGearDeploy();
342
344 Q_INVOKABLE void landingGearRetract();
345
346 Q_INVOKABLE void startTakeoff();
347
348 Q_INVOKABLE void startMission();
349
351 Q_INVOKABLE void setCurrentMissionSequence(int seq);
352
354 Q_INVOKABLE void rebootVehicle();
355
356 Q_INVOKABLE void sendPlan(QString planFile);
357 Q_INVOKABLE void setEstimatorOrigin(const QGeoCoordinate& centerCoord);
358
360 // returns 1 if current > compare, 0 if current == compare, -1 if current < compare
361 Q_INVOKABLE int versionCompare(const QString& compare) const;
362 Q_INVOKABLE int versionCompare(int major, int minor, int patch) const;
363
368 Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs, bool showError);
369
377
379
380 Q_INVOKABLE void forceArm ();
381
383 Q_INVOKABLE void sendParamMapRC(const QString& paramName, double scale, double centerValue, int tuningID, double minValue, double maxValue);
384
386 Q_INVOKABLE void clearAllParamMapRC(void);
387
389 Q_INVOKABLE void closeVehicle();
390
392 Q_INVOKABLE void triggerSimpleCamera(void);
393
395 Q_INVOKABLE void doSetHome(const QGeoCoordinate& coord);
396
397 Q_INVOKABLE QVariant expandedToolbarIndicatorSource(const QString& indicatorName);
398
399 bool isInitialConnectComplete() const;
400 QString gotoFlightMode () const;
401
402 VehicleSupports* supports() { return _vehicleSupports; }
403 bool hasGripper () const;
406
407 // Property accessors
408
409 QGeoCoordinate coordinate() { return _coordinate; }
410 QGeoCoordinate armedPosition () { return _armedPosition; }
411
412 qreal getInitialGCSPressure() const { return _initialGCSPressure; }
413 qreal getInitialGCSTemperature() const { return _initialGCSTemperature; }
414 void setInitialGCSPressure(qreal pressure) { _initialGCSPressure = pressure; }
415 void setInitialGCSTemperature(qreal temperature) { _initialGCSTemperature = temperature; }
416
417 void updateFlightDistance(double distance);
418
419 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);
421 static constexpr int kAuxRcOverrideChannelCount = 6;
422 void sendJoystickAuxRcOverrideThreadSafe(const std::array<uint16_t, kAuxRcOverrideChannelCount> &channelValues, const std::array<bool, kAuxRcOverrideChannelCount> &channelEnabled, bool useRcOverride);
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
435
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
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
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.
491
492 float latitude () { return static_cast<float>(_coordinate.latitude()); }
493 float longitude () { return static_cast<float>(_coordinate.longitude()); }
494 bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
495 bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
496 bool genericFirmware () const { return !px4Firmware() && !apmFirmware(); }
497 uint messagesReceived () const{ return _messagesReceived; }
498 uint messagesSent () const{ return _messagesSent; }
499 uint messagesLost () const{ return _messagesLost; }
500 bool flying () const { return _flying; }
501 bool landing () const { return _landing; }
502 bool guidedMode () const;
503 bool inFwdFlight () const;
504 bool vtolInFwdFlight () const { return _vtolInFwdFlight; }
505 uint8_t baseMode () const { return _base_mode; }
506 uint32_t customMode () const { return _custom_mode; }
509 uint32_t effectiveCustomMode () const { return _has_custom_mode_user_intention ? _custom_mode_user_intention : _custom_mode; }
510 bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
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 bool autoDisarm ();
529 bool orbitActive () const { return _orbitActive; }
530 QGCMapCircle* orbitMapCircle () { return _orbitMapCircle.get(); }
531 bool readyToFlyAvailable () const{ return _readyToFlyAvailable; }
532 bool readyToFly () const{ return _readyToFly; }
533 bool allSensorsHealthy () const{ return _allSensorsHealthy; }
534 QObject* sysStatusSensorInfo ();
535 bool requiresGpsFix () const { return static_cast<bool>(_onboardControlSensorsPresent & MAV_SYS_STATUS_SENSOR_GPS); }
536 bool hilMode () const { return _base_mode & MAV_MODE_FLAG_HIL_ENABLED; }
537 Actuators* actuators () const { return _actuators; }
538 VehicleSigningController* signingController() { return _signingController; }
539 const VehicleSigningController* signingController() const { return _signingController; }
540
542 void stopCalibration (bool showError);
543
544 void startUAVCANBusConfig(void);
545 void stopUAVCANBusConfig(void);
546
566
569
573 ParameterManager* parameterManager () { return _parameterManager; }
574 ParameterManager* parameterManager () const { return _parameterManager; }
577 ComponentInformationManager* compInfoManager () { return _componentInformationManager; }
578 VehicleObjectAvoidance* objectAvoidance () { return _objectAvoidance; }
579 Autotune* autotune () const { return _autotune; }
581
582 static void showCommandAckError(const mavlink_command_ack_t& ack);
583
590 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);
591 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);
592 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);
593
608 bool isMavCommandPending(int targetCompId, MAV_CMD command);
609
611 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);
612
614
615 // MavCmdProgressHandler, MavCmdResultHandler, MavCmdAckHandlerInfo_t are inherited from VehicleTypes.
616
619 const MavCmdAckHandlerInfo_t* ackHandlerInfo,
620 int compId, MAV_CMD command,
621 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);
622
627 const MavCmdAckHandlerInfo_t* ackHandlerInfo,
628 int compId, MAV_CMD command, MAV_FRAME frame,
629 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);
630
634 std::function<void()> lambda,
635 int compId, MAV_CMD command,
636 bool showError,
637 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);
638
639
641
642 // RequestMessageResultHandler is inherited from VehicleTypes.
643
647 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);
648
649 int firmwareMajorVersion() const { return _firmwareMajorVersion; }
650 int firmwareMinorVersion() const { return _firmwareMinorVersion; }
651 int firmwarePatchVersion() const { return _firmwarePatchVersion; }
652 int firmwareVersionType() const { return _firmwareVersionType; }
653 int firmwareCustomMajorVersion() const { return _firmwareCustomMajorVersion; }
654 int firmwareCustomMinorVersion() const { return _firmwareCustomMinorVersion; }
655 int firmwareCustomPatchVersion() const { return _firmwareCustomPatchVersion; }
656 int firmwareBoardVendorId() const { return _firmwareBoardVendorId; }
657 int firmwareBoardProductId() const { return _firmwareBoardProductId; }
658 QString firmwareVersionTypeString() const;
659 void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
660 void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
661 // versionNotSetValue inherited from VehicleTypes
662
663 QString gitHash() const { return _gitHash; }
664 quint64 vehicleUID() const { return _uid; }
665 QString vehicleUIDStr();
666
667 bool soloFirmware() const { return _soloFirmware; }
668 void setSoloFirmware(bool soloFirmware);
669
670 int defaultComponentId() const{ return _defaultComponentId; }
671
674
676 int motorCount();
677
679 bool coaxialMotors();
680
682 bool xConfigMotors();
683
685 class FirmwarePluginInstanceData* firmwarePluginInstanceData() { return _firmwarePluginInstanceData; }
686
690
691 QString vehicleImageOpaque () const;
692 QString vehicleImageOutline () const;
693
694 const QVariantList& toolIndicators();
695
696 bool capabilitiesKnown () const { return _capabilityBitsKnown; }
697 uint64_t capabilityBits () const { return _capabilityBits; } // Change signalled by capabilityBitsChanged
698
699 QString hobbsMeter ();
700
703 bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
704
706
707 void _setFlying(bool flying);
708 void _setLanding(bool landing);
709 void _setHomePosition(QGeoCoordinate& homeCoord);
710
713
716
717 quint64 mavlinkSentCount () const{ return _mavlinkSentCount; }
718 quint64 mavlinkReceivedCount () const{ return _mavlinkReceivedCount; }
719 quint64 mavlinkLossCount () const{ return _mavlinkLossCount; }
720 float mavlinkLossPercent () const{ return _mavlinkLossPercent; }
721
722 bool isROIEnabled () const{ return _isROIEnabled; }
723
724 CheckList checkListState () { return _checkListState; }
725 void setCheckListState (CheckList cl) { _checkListState = cl; emit checkListStateChanged(); }
726
727 double loadProgress () const { return _loadProgress; }
728
729 void setActuatorsMetadata(uint8_t compid, const QString& metadataJsonFileName);
730
731 GimbalController* gimbalController () { return _gimbalController; }
732
733public slots:
735 void _offlineFirmwareTypeSettingChanged (QVariant varFirmwareType); // Should only be used by MissionControler to set firmware from Plan file
736 void _offlineVehicleTypeSettingChanged (QVariant varVehicleType); // Should only be used by MissionController to set vehicle type from Plan file
737 Q_INVOKABLE void sendGripperAction(GRIPPER_ACTIONS gripperOption);
738
739signals:
740 void coordinateChanged (QGeoCoordinate coordinate);
742 void homePositionChanged (const QGeoCoordinate& homePosition);
744 void armedChanged (bool armed);
745 void flightModeChanged (const QString& flightMode);
751 void prearmErrorChanged (const QString& prearmError);
753 void defaultCruiseSpeedChanged (double cruiseSpeed);
754 void defaultHoverSpeedChanged (double hoverSpeed);
773 void readyToFlyChanged (bool readyToFy);
779
782 void gitHashChanged (QString hash);
784 void loadProgressChanged (float value);
785
788 void rcChannelsRawChanged(QVector<int> channelValues);
789
792 void rcChannelsClampedChanged(QVector<int> channelValues);
793
796 void servoOutputsChanged(QVector<int> servoValues);
797
798 // Mavlink Log Download
799 void mavlinkLogData (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
800
807 void mavCommandResult (int vehicleId, int targetComponent, int command, int ackResult, int failureCode);
808
809 // MAVlink Serial Data
810 void mavlinkSerialControl (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
811
813
815 void roiCoordChanged (const QGeoCoordinate& centerCoord);
817
818 void sensorsParametersResetAck (bool success);
819
820 void logEntry (uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num);
821 void logData (uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data);
822
823private slots:
824 void _mavlinkMessageReceived (LinkInterface* link, mavlink_message_t message);
825 void _sendMessageMultipleNext ();
826 void _parametersReady (bool parametersReady);
827 void _handleFlightModeChanged (const QString& flightMode);
828 void _announceArmedChanged (bool armed);
829 void _offlineCruiseSpeedSettingChanged (QVariant value);
830 void _offlineHoverSpeedSettingChanged (QVariant value);
831 void _prearmErrorTimeout ();
832 void _firstMissionLoadComplete ();
833 void _firstGeoFenceLoadComplete ();
834 void _firstRallyPointLoadComplete ();
835 void _clearCameraTriggerPoints ();
836 void _updateDistanceHeadingHome ();
837 void _updateMissionItemIndex ();
838 void _updateHeadingToNextWP ();
839 void _updateDistanceHeadingGCS ();
840 void _updateHomepoint ();
841 void _updateHobbsMeter ();
842 void _vehicleParamLoaded (bool ready);
843 void _sendQGCTimeToVehicle ();
844 void _mavlinkMessageStatus (int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
845 void _orbitTelemetryTimeout ();
846 void _updateFlightTime ();
847 void _gotProgressUpdate (float progressValue);
848
849private:
850 void _activeVehicleChanged (Vehicle* newActiveVehicle);
851 void _handlePing (LinkInterface* link, mavlink_message_t& message);
852 void _handleHomePosition (mavlink_message_t& message);
853 void _handleHeartbeat (mavlink_message_t& message);
854 void _handleCurrentMode (mavlink_message_t& message);
855 void _handleRCChannels (mavlink_message_t& message);
856 void _handleBatteryStatus (mavlink_message_t& message);
857 void _handleSysStatus (mavlink_message_t& message);
858 void _handleExtendedSysState (mavlink_message_t& message);
859 void _handleCommandAck (mavlink_message_t& message);
860 void _handleGpsRawInt (mavlink_message_t& message);
861 void _handleGlobalPositionInt (mavlink_message_t& message);
862 void _handleHighLatency (mavlink_message_t& message);
863 void _handleHighLatency2 (mavlink_message_t& message);
864 void _handleOrbitExecutionStatus (const mavlink_message_t& message);
865 void _handleGimbalOrientation (const mavlink_message_t& message);
866 void _handleObstacleDistance (const mavlink_message_t& message);
867 void _handleFenceStatus (const mavlink_message_t& message);
868
869 // ArduPilot dialect messages
870#if !defined(QGC_NO_ARDUPILOT_DIALECT)
871 void _handleCameraFeedback (const mavlink_message_t& message);
872#endif
873 void _handleCameraImageCaptured (const mavlink_message_t& message);
874 void _handleCommandLong (const mavlink_message_t& message);
875 void _missionManagerError (int errorCode, const QString& errorMsg);
876 void _geoFenceManagerError (int errorCode, const QString& errorMsg);
877 void _rallyPointManagerError (int errorCode, const QString& errorMsg);
878 void _say (const QString& text);
879 QString _vehicleIdSpeech ();
880 void _handleMavlinkLoggingData (mavlink_message_t& message);
881 void _handleMavlinkLoggingDataAcked (mavlink_message_t& message);
882 void _ackMavlinkLogData (uint16_t sequence);
883 void _commonInit (LinkInterface* link);
884 void _setupAutoDisarmSignalling ();
885 void _setCapabilities (uint64_t capabilityBits);
886 void _updateArmed (bool armed);
887 bool _apmArmingNotRequired ();
888 void _initializeCsv ();
889 void _writeCsvLine ();
890 void _flightTimerStart ();
891 void _flightTimerStop ();
892 void _setMessageInterval (int messageId, int rate);
893 bool setFlightModeCustom (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
894 QString _formatMavCommand (MAV_CMD command, float param1);
895
896 static void _rebootCommandResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
897
898 // The following methods should only be called by unit tests
899 void _deleteGimbalController();
900 void _deleteCameraManager();
901
904 void _stopCommandProcessing();
905
906 int _systemID;
907 int _defaultComponentId;
908 bool _offlineEditingVehicle = false;
909
910 MAV_AUTOPILOT _firmwareType;
911 MAV_TYPE _vehicleType;
912 FirmwarePlugin* _firmwarePlugin = nullptr;
913 class FirmwarePluginInstanceData* _firmwarePluginInstanceData = nullptr;
914 AutoPilotPlugin* _autopilotPlugin = nullptr;
915 bool _soloFirmware = false;
916
917 QTimer _csvLogTimer;
918 QFile _csvLogFile;
919
920 bool _isActiveVehicle = false;
921
922 QGeoCoordinate _coordinate;
923 QGeoCoordinate _homePosition;
924 QGeoCoordinate _armedPosition;
925
926 qreal _initialGCSPressure = 0.;
927 qreal _initialGCSTemperature = 0.;
928
929 bool _flying = false;
930 bool _landing = false;
931 bool _vtolInFwdFlight = false;
932 uint32_t _onboardControlSensorsPresent = 0;
933 uint32_t _onboardControlSensorsEnabled = 0;
934 uint32_t _onboardControlSensorsHealth = 0;
935 uint32_t _onboardControlSensorsUnhealthy = 0;
936 bool _gpsRawIntMessageAvailable = false;
937 bool _gps2RawMessageAvailable = false;
938 bool _globalPositionIntMessageAvailable = false;
939 bool _cameraImageCapturedMessageAvailable = false;
940 double _defaultCruiseSpeed = qQNaN();
941 double _defaultHoverSpeed = qQNaN();
942 bool _capabilityBitsKnown = false;
943 uint64_t _capabilityBits = 0;
944 CheckList _checkListState = CheckListNotSetup;
945 bool _readyToFlyAvailable = false;
946 bool _readyToFly = false;
947 bool _allSensorsHealthy = true;
948 VehicleSigningController* _signingController = nullptr;
949 std::atomic<bool> _joystickAuxRcOverrideActive = false;
950
951 std::unique_ptr<SysStatusSensorInfo> _sysStatusSensorInfo;
952
953
954 QString _prearmError;
955 QTimer _prearmErrorTimer;
956 static const int _prearmErrorTimeoutMSecs = 35 * 1000;
957
958 bool _initialPlanRequestComplete = false;
959
960 ParameterManager* _parameterManager = nullptr;
961 ComponentInformationManager* _componentInformationManager = nullptr;
962 VehicleObjectAvoidance* _objectAvoidance = nullptr;
963 Autotune* _autotune = nullptr;
964 GimbalController* _gimbalController = nullptr;
965 VehicleSupports* _vehicleSupports = nullptr;
966
967 bool _armed = false;
968 uint8_t _base_mode = 0;
969 uint32_t _custom_mode = 0;
970 uint32_t _custom_mode_user_intention = 0;
971 bool _has_custom_mode_user_intention = false;
972 QString _lastAnnouncedFlightMode;
973
975 typedef struct {
976 mavlink_message_t message;
977 int retryCount;
978 } SendMessageMultipleInfo_t;
979
980 QList<SendMessageMultipleInfo_t> _sendMessageMultipleList;
981
982 static const int _sendMessageMultipleRetries = 5;
983 static const int _sendMessageMultipleIntraMessageDelay = 500;
984
985 QTimer _sendMultipleTimer;
986 int _nextSendMessageMultipleIndex = 0;
987
988 QElapsedTimer _flightTimer;
989 QTimer _flightTimeUpdater;
990 TrajectoryPoints* _trajectoryPoints = nullptr;
991 std::unique_ptr<QmlObjectListModel> _cameraTriggerPoints;
992 //QMap<QString, ADSBVehicle*> _trafficVehicleMap;
993
994 bool _allLinksRemovedSent = false;
995
996 uint _messagesReceived = 0;
997 uint _messagesSent = 0;
998 uint _messagesLost = 0;
999 uint8_t _messageSeq = 0;
1000 uint8_t _compID = 0;
1001 bool _heardFrom = false;
1002
1003 bool _isROIEnabled = false;
1004\
1005 bool _checkLatestStableFWDone = false;
1006 int _firmwareMajorVersion = versionNotSetValue;
1007 int _firmwareMinorVersion = versionNotSetValue;
1008 int _firmwarePatchVersion = versionNotSetValue;
1009 int _firmwareCustomMajorVersion = versionNotSetValue;
1010 int _firmwareCustomMinorVersion = versionNotSetValue;
1011 int _firmwareCustomPatchVersion = versionNotSetValue;
1012 FIRMWARE_VERSION_TYPE _firmwareVersionType = FIRMWARE_VERSION_TYPE_OFFICIAL;
1013
1014 // Vendor and Product as reported from the first autopilot version message
1015 // during the initial connect. They may be zero eg ArduPilot SITL reports 0
1016 // by default.
1017 uint16_t _firmwareBoardVendorId = 0;
1018 uint16_t _firmwareBoardProductId = 0;
1019
1020
1021 QString _gitHash;
1022 quint64 _uid = 0;
1023
1024 uint64_t _mavlinkSentCount = 0;
1025 uint64_t _mavlinkReceivedCount = 0;
1026 uint64_t _mavlinkLossCount = 0;
1027 float _mavlinkLossPercent = 0.0f;
1028
1029 float _loadProgress = 0.0f;
1030
1031 QMap<QString, QTime> _noisySpokenPrearmMap;
1032
1033 // Orbit status values
1034 bool _orbitActive = false;
1035 std::unique_ptr<QGCMapCircle> _orbitMapCircle;
1036 QTimer _orbitTelemetryTimer;
1037 static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive
1038
1039 std::unique_ptr<MAVLinkStreamConfig> _mavlinkStreamConfig;
1040
1041 MavCommandQueue* _mavCmdQueue = nullptr;
1042 RequestMessageCoordinator* _reqMsgCoord = nullptr;
1043
1044public:
1047 static constexpr int _mavCommandMaxRetryCount = 3;
1048 static constexpr int kTestMavCommandAckTimeoutMs = 500;
1050
1052 int _findMavCommandListEntryIndex(int targetCompId, MAV_CMD command);
1053
1054 QMap<uint8_t /* batteryId */, uint8_t /* MAV_BATTERY_CHARGE_STATE_OK */> _lowestBatteryChargeStateAnnouncedMap;
1055
1056 float _altitudeTuningOffset = qQNaN(); // altitude offset, so the plotted value is around 0
1057
1058 // these flags are used to determine if the speed change action from fly view should be shown
1061
1062 // FactGroup facts
1063
1064 const QString _vehicleFactGroupName = QStringLiteral("vehicle");
1065 const QString _gpsFactGroupName = QStringLiteral("gps");
1066 const QString _gps2FactGroupName = QStringLiteral("gps2");
1067 const QString _gpsAggregateFactGroupName = QStringLiteral("gpsAggregate");
1068 const QString _windFactGroupName = QStringLiteral("wind");
1069 const QString _vibrationFactGroupName = QStringLiteral("vibration");
1070 const QString _temperatureFactGroupName = QStringLiteral("temperature");
1071 const QString _clockFactGroupName = QStringLiteral("clock");
1072 const QString _setpointFactGroupName = QStringLiteral("setpoint");
1073 const QString _distanceSensorFactGroupName = QStringLiteral("distanceSensor");
1074 const QString _localPositionFactGroupName = QStringLiteral("localPosition");
1075 const QString _localPositionSetpointFactGroupName = QStringLiteral("localPositionSetpoint");
1076 const QString _estimatorStatusFactGroupName = QStringLiteral("estimatorStatus");
1077 const QString _terrainFactGroupName = QStringLiteral("terrain");
1078 const QString _hygrometerFactGroupName = QStringLiteral("hygrometer");
1079 const QString _generatorFactGroupName = QStringLiteral("generator");
1080 const QString _efiFactGroupName = QStringLiteral("efi");
1081 const QString _rpmFactGroupName = QStringLiteral("rpm");
1082 const QString _radioStatusFactGroupName = QStringLiteral("radioStatus");
1083
1103
1104 // Live SERVO_OUTPUT_RAW values (microseconds). Indexed 0..15 -> SERVO1..SERVO16.
1105 QVector<int> _servoOutputRawValues = QVector<int>(16, -1);
1106
1107 // Dynamic FactGroups
1110
1112
1122
1123 // All terrain query workflows (doSetHome, ROI, altAboveTerrain) live in the coordinator.
1125
1126public:
1127 int32_t getMessageRate(uint8_t compId, uint16_t msgId);
1128 void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate);
1129
1130signals:
1131 // Re-emitted from MessageIntervalManager so existing consumers keep working.
1132 void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate);
1133
1134private:
1135 MessageIntervalManager* _messageIntervalManager = nullptr;
1136
1137/*---------------------------------------------------------------------------*/
1138/*===========================================================================*/
1139/* ardupilotmega Dialect */
1140/*===========================================================================*/
1141public:
1142 Q_INVOKABLE void flashBootloader();
1143
1145 Q_INVOKABLE void motorInterlock(bool enable);
1146
1147/*---------------------------------------------------------------------------*/
1148/*===========================================================================*/
1149/* CONTROL STATUS HANDLER */
1150/*===========================================================================*/
1151public:
1152 Q_INVOKABLE void startTimerRevertAllowTakeover();
1153 Q_INVOKABLE void requestOperatorControl(bool allowOverride, int requestTimeoutSecs = 0);
1154
1155private:
1156 void _handleControlStatus(const mavlink_message_t& message);
1157 void _handleCommandRequestOperatorControl(const mavlink_command_long_t commandLong);
1158 static void _requestOperatorControlAckHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
1159
1160 Q_PROPERTY(uint8_t sysidInControl READ sysidInControl NOTIFY gcsControlStatusChanged)
1161 Q_PROPERTY(bool gcsControlStatusFlags_SystemManager READ gcsControlStatusFlags_SystemManager NOTIFY gcsControlStatusChanged)
1162 Q_PROPERTY(bool gcsControlStatusFlags_TakeoverAllowed READ gcsControlStatusFlags_TakeoverAllowed NOTIFY gcsControlStatusChanged)
1163 Q_PROPERTY(bool firstControlStatusReceived READ firstControlStatusReceived NOTIFY gcsControlStatusChanged)
1164 Q_PROPERTY(int operatorControlTakeoverTimeoutMsecs READ operatorControlTakeoverTimeoutMsecs CONSTANT)
1165 Q_PROPERTY(int requestOperatorControlRemainingMsecs READ requestOperatorControlRemainingMsecs CONSTANT)
1166 Q_PROPERTY(bool sendControlRequestAllowed READ sendControlRequestAllowed NOTIFY sendControlRequestAllowedChanged)
1167
1168 uint8_t sysidInControl() const { return _sysid_in_control; }
1169 bool gcsControlStatusFlags_SystemManager() const { return _gcsControlStatusFlags_SystemManager; }
1170 bool gcsControlStatusFlags_TakeoverAllowed() const { return _gcsControlStatusFlags_TakeoverAllowed; }
1171 bool firstControlStatusReceived() const { return _firstControlStatusReceived; }
1172 int operatorControlTakeoverTimeoutMsecs() const;
1173 int requestOperatorControlRemainingMsecs() const { return _timerRequestOperatorControl.remainingTime(); }
1174 bool sendControlRequestAllowed() const { return _sendControlRequestAllowed; }
1175 void requestOperatorControlStartTimer(int requestTimeoutMsecs);
1176
1177 uint8_t _sysid_in_control = 0;
1178 uint8_t _gcsControlStatusFlags = 0;
1179 bool _gcsControlStatusFlags_SystemManager = 0;
1180 bool _gcsControlStatusFlags_TakeoverAllowed = 0;
1181 bool _firstControlStatusReceived = false;
1182 QTimer _timerRevertAllowTakeover;
1183 QTimer _timerRequestOperatorControl;
1184 bool _sendControlRequestAllowed = true;
1185
1186signals:
1188 void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs);
1189 void sendControlRequestAllowedChanged(bool sendControlRequestAllowed);
1190
1191/*===========================================================================*/
1192/* STATUS TEXT HANDLER */
1193/*===========================================================================*/
1194private:
1195 Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged)
1196 Q_PROPERTY(bool messageTypeNormal READ messageTypeNormal NOTIFY messageTypeChanged)
1197 Q_PROPERTY(bool messageTypeWarning READ messageTypeWarning NOTIFY messageTypeChanged)
1198 Q_PROPERTY(bool messageTypeError READ messageTypeError NOTIFY messageTypeChanged)
1199 Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged)
1200 Q_PROPERTY(QString formattedMessages READ formattedMessages NOTIFY formattedMessagesChanged)
1201
1202 // Q_PROPERTY(StatusTextHandler *statusTextHandler READ statusTextHandler NOTIFY statusTextHandlerChanged)
1203
1204public:
1205 Q_INVOKABLE void resetAllMessages();
1206 Q_INVOKABLE void resetErrorLevelMessages();
1207 Q_INVOKABLE void clearMessages();
1208
1209 bool messageTypeNone() const;
1210 bool messageTypeNormal() const;
1211 bool messageTypeWarning() const;
1212 bool messageTypeError() const;
1213 int messageCount() const;
1214 QString formattedMessages() const;
1215
1216 // StatusTextHandler* statusTextHandler() { return m_statusTextHandler; }
1217
1218signals:
1219 void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description);
1220
1227 void newFormattedMessage(QString formattedMessage);
1228
1229 // void statusTextHandlerChanged();
1230
1231private slots:
1232 void _onStatusTextFromEvent(uint8_t compid, int severity, const QString &text, const QString &description);
1233 void _textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description);
1234 void _errorMessageReceived(QString message);
1235
1236private:
1237 void _createStatusTextHandler();
1238
1239 StatusTextHandler *m_statusTextHandler = nullptr;
1240
1241/*---------------------------------------------------------------------------*/
1242/*===========================================================================*/
1243/* Image Protocol Manager */
1244/*===========================================================================*/
1245private:
1246 Q_PROPERTY(uint flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged)
1247
1248public:
1249 uint32_t flowImageIndex() const;
1250
1251signals:
1253
1254private:
1255 void _createImageProtocolManager();
1256 void _createSigningController();
1257
1258 ImageProtocolManager *_imageProtocolManager = nullptr;
1259
1260/*---------------------------------------------------------------------------*/
1261/*===========================================================================*/
1262/* MAVLink Log Manager */
1263/*===========================================================================*/
1264private:
1266
1267public:
1269
1270signals:
1272
1273private:
1274 void _createMAVLinkLogManager();
1275
1276 MAVLinkLogManager *_mavlinkLogManager = nullptr;
1277
1278/*---------------------------------------------------------------------------*/
1279/*===========================================================================*/
1280/* Camera Manager */
1281/*===========================================================================*/
1282private:
1283 Q_MOC_INCLUDE("QGCCameraManager.h")
1285 Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT)
1286
1287public:
1288 QGCCameraManager *cameraManager() { return _cameraManager; }
1289 const QVariantList &staticCameraList() const;
1290
1291signals:
1293
1294private:
1295 void _createCameraManager();
1296
1297 QGCCameraManager *_cameraManager = nullptr;
1298
1299/*---------------------------------------------------------------------------*/
1300/*===========================================================================*/
1301/* MAVLinkEventsManager */
1302/*===========================================================================*/
1303private:
1304 Q_MOC_INCLUDE("HealthAndArmingCheckReport.h")
1306
1307public:
1309
1310 void setEventsMetadata(uint8_t compid, const QString& metadataJsonFileName);
1311
1312private:
1313 void _createMAVLinkEventManager();
1314 void _handleEventMessage(const mavlink_message_t& msg);
1315 bool _healthAndArmingChecksSupported(uint8_t compid);
1316
1317 std::unique_ptr<MAVLinkEventManager> _eventManager;
1318};
struct __mavlink_message mavlink_message_t
struct __mavlink_command_ack_t mavlink_command_ack_t
struct __mavlink_command_long_t mavlink_command_long_t
The AutoPilotPlugin class is an abstract base class which represents the methods and objects which ar...
Dynamically manages FactGroupWithIds based on incoming messages.
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware ...
This is the base class for firmware specific geofence managers.
Supports the Mavlink image transmission protocol (https://mavlink.io/en/services/image_transmission....
State machine for initial vehicle connection sequence.
The link interface defines the interface for all links used to communicate with the ground station ap...
Owns per-component EventHandler instances and drives the Health & Arming Check report.
Allows to configure a set of mavlink streams to a specific rate, and restore back to default.
Owns the COMMAND_LONG / COMMAND_INT send/retry/ack pipeline for a single Vehicle.
Tracks per-component MAVLink message intervals and mediates SET_MESSAGE_INTERVAL commands plus MESSAG...
Camera Manager.
The QGCMapCircle represents a circular area which can be displayed on a Map control.
Radio link telemetry decoded from MAVLINK_MSG_ID_RADIO_STATUS.
This is the base class for firmware specific rally point managers. A rally point manager is responsib...
Coordinates MAV_CMD_REQUEST_MESSAGE workflows: per-component queueing, ack/message correlation,...
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...
Coordinates the three terrain-query workflows attached to a Vehicle:
Per-vehicle signing facade. Owns the wiring between Vehicle and the active SigningController (which l...
Q_INVOKABLE void triggerSimpleCamera(void)
Trigger camera using MAV_CMD_DO_DIGICAM_CONTROL command.
Definition Vehicle.cc:3128
bool sub() const
Definition Vehicle.cc:1748
bool readyToFly() const
Definition Vehicle.h:532
bool isInitialConnectComplete() const
Definition Vehicle.cc:2804
Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle)
Definition Vehicle.cc:1914
void _setLanding(bool landing)
Definition Vehicle.cc:1815
void autoDisarmChanged()
QGCCameraManager * cameraManager()
Definition Vehicle.h:1288
bool px4Firmware() const
Definition Vehicle.h:494
Q_INVOKABLE void motorInterlock(bool enable)
Command vehicle to Enable/Disable Motor Interlock.
Definition Vehicle.cc:3371
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
Definition Vehicle.cc:1712
int32_t getMessageRate(uint8_t compId, uint16_t msgId)
Definition Vehicle.cc:3330
VehicleDistanceSensorFactGroup * _distanceSensorFactGroup
Definition Vehicle.h:1093
TerrainProtocolHandler * _terrainProtocolHandler
Definition Vehicle.h:1111
void firmwareTypeChanged()
bool hilMode() const
Definition Vehicle.h:536
QGCMAVLink::VehicleClass_t vehicleClass(void) const
Definition Vehicle.h:429
uint32_t effectiveCustomMode() const
Definition Vehicle.h:509
void setInitialGCSPressure(qreal pressure)
Definition Vehicle.h:414
Q_INVOKABLE void flashBootloader()
Definition Vehicle.cc:3359
uint messagesReceived() const
Definition Vehicle.h:497
void sensorsPresentBitsChanged(int sensorsPresentBits)
void defaultHoverSpeedChanged(double hoverSpeed)
const QString _vibrationFactGroupName
Definition Vehicle.h:1069
bool _multirotor_speed_limits_available
Definition Vehicle.h:1059
void gcsControlStatusChanged()
void defaultCruiseSpeedChanged(double cruiseSpeed)
bool messageTypeError() const
Definition Vehicle.cc:3394
const QString _gpsFactGroupName
Definition Vehicle.h:1065
FactGroup * localPositionFactGroup()
Definition Vehicle.cc:420
void haveMRSpeedLimChanged()
FactGroup * vibrationFactGroup()
Definition Vehicle.cc:415
void sendMavCommandWithLambdaFallback(std::function< void()> lambda, 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)
Definition Vehicle.cc:2185
BatteryFactGroupListModel * _batteryFactGroupListModel
Definition Vehicle.h:1108
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)
Definition Vehicle.cc:2146
VehicleLocalPositionFactGroup * _localPositionFactGroup
Definition Vehicle.h:1094
const QString _hygrometerFactGroupName
Definition Vehicle.h:1078
void messagesLostChanged()
Q_INVOKABLE void rebootVehicle()
Reboot vehicle.
Definition Vehicle.cc:2316
FactGroup * gpsAggregateFactGroup()
Definition Vehicle.cc:413
VehicleRPMFactGroup * _rpmFactGroup
Definition Vehicle.h:1100
const QString _localPositionFactGroupName
Definition Vehicle.h:1074
void vtolInFwdFlightChanged(bool vtolInFwdFlight)
qreal getInitialGCSPressure() const
Definition Vehicle.h:412
QString missionFlightMode() const
Definition Vehicle.cc:2533
void readyToFlyAvailableChanged(bool readyToFlyAvailable)
void forceInitialPlanRequestComplete()
Definition Vehicle.cc:2707
void isROIEnabledChanged()
Actuators * actuators() const
Definition Vehicle.h:537
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate &centerCoord, double radius, double amslAltitude)
Definition Vehicle.cc:1943
const QString _terrainFactGroupName
Definition Vehicle.h:1077
Actuators * _actuators
Definition Vehicle.h:1119
Autotune * autotune() const
Definition Vehicle.h:579
const QString _temperatureFactGroupName
Definition Vehicle.h:1070
void deleteGimbalController()
Delete gimbal controller, handy for RequestMessageTest.cc, otherwise gimbal controller message reques...
void _offlineVehicleTypeSettingChanged(QVariant varVehicleType)
Definition Vehicle.cc:487
Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative)
Command vehicle to takeoff from current location.
Definition Vehicle.cc:1846
Q_INVOKABLE void sendGripperAction(GRIPPER_ACTIONS gripperOption)
Definition Vehicle.cc:3137
bool haveMRSpeedLimits() const
Definition Vehicle.h:404
QString flightMode() const
Definition Vehicle.cc:1468
bool orbitActive() const
Definition Vehicle.h:529
static QString mavCmdResultFailureCodeToString(MavCmdResultFailureCode_t failureCode)
Definition Vehicle.cc:3350
QString stabilizedFlightMode() const
Definition Vehicle.cc:2573
int firmwareCustomMajorVersion() const
Definition Vehicle.h:653
const QVariantList & staticCameraList() const
Definition Vehicle.cc:3524
void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs)
Q_INVOKABLE QVariant expandedToolbarIndicatorSource(const QString &indicatorName)
Definition Vehicle.cc:3340
uint messagesLost() const
Definition Vehicle.h:499
void sendJoystickAuxRcOverrideThreadSafe(const std::array< uint16_t, kAuxRcOverrideChannelCount > &channelValues, const std::array< bool, kAuxRcOverrideChannelCount > &channelEnabled, bool useRcOverride)
Definition Vehicle.cc:3041
void setActuatorsMetadata(uint8_t compid, const QString &metadataJsonFileName)
Definition Vehicle.cc:1265
bool vtol() const
Definition Vehicle.cc:1763
void setSoloFirmware(bool soloFirmware)
Definition Vehicle.cc:2435
void mavlinkLogManagerChanged()
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple=true)
Definition Vehicle.cc:1529
FactGroup * rpmFactGroup()
Definition Vehicle.cc:427
QGeoCoordinate homePosition()
Definition Vehicle.cc:1434
const QString _estimatorStatusFactGroupName
Definition Vehicle.h:1076
const QString _radioStatusFactGroupName
Definition Vehicle.h:1082
QString vehicleImageOutline() const
Definition Vehicle.cc:2586
MissionManager * _missionManager
Definition Vehicle.h:1113
void initialConnectComplete()
VehicleLocalPositionSetpointFactGroup * _localPositionSetpointFactGroup
Definition Vehicle.h:1095
void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description)
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete)
Q_INVOKABLE double minimumEquivalentAirspeed()
Definition Vehicle.cc:1872
const QString _clockFactGroupName
Definition Vehicle.h:1071
bool rover() const
Definition Vehicle.cc:1743
bool multiRotor() const
Definition Vehicle.cc:1758
bool flying() const
Definition Vehicle.h:500
Q_INVOKABLE void stopGuidedModeROI()
Definition Vehicle.cc:2003
void firmwareCustomVersionChanged()
QString pauseFlightMode() const
Definition Vehicle.cc:2538
QString prearmError() const
Definition Vehicle.h:473
int sensorsEnabledBits() const
Definition Vehicle.h:512
EscStatusFactGroupListModel * _escStatusFactGroupListModel
Definition Vehicle.h:1109
Q_INVOKABLE void guidedModeROI(const QGeoCoordinate &centerCoord)
Definition Vehicle.cc:1975
float latitude()
Definition Vehicle.h:492
const QString _efiFactGroupName
Definition Vehicle.h:1080
void inFwdFlightChanged()
void flyingChanged(bool flying)
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
Definition Vehicle.cc:2527
Q_INVOKABLE double maximumHorizontalSpeedMultirotorMetersSecond()
Definition Vehicle.cc:1860
bool hasGripper() const
Definition Vehicle.cc:1877
void sendMessageMultiple(mavlink_message_t message)
Definition Vehicle.cc:1587
void capabilityBitsChanged(uint64_t capabilityBits)
bool messageTypeNone() const
Definition Vehicle.cc:3391
bool haveFWSpeedLimits() const
Definition Vehicle.h:405
int sensorsUnhealthyBits() const
Definition Vehicle.h:514
void _setHomePosition(QGeoCoordinate &homeCoord)
Definition Vehicle.cc:1188
void hobbsMeterChanged()
VehicleClockFactGroup * _clockFactGroup
Definition Vehicle.h:1091
uint64_t capabilityBits() const
Definition Vehicle.h:697
Q_INVOKABLE void abortLanding(double climbOutAltitude)
Command vehicle to abort landing.
Definition Vehicle.cc:2056
void setGuidedMode(bool guidedMode)
Definition Vehicle.cc:2070
void readyToFlyChanged(bool readyToFy)
QString firmwareVersionTypeString() const
Definition Vehicle.cc:2289
QString landFlightMode() const
Definition Vehicle.cc:2553
static void showCommandAckError(const mavlink_command_ack_t &ack)
Definition Vehicle.cc:2200
void formattedMessagesChanged()
void newFormattedMessage(QString formattedMessage)
MAV_TYPE vehicleType() const
Definition Vehicle.h:428
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
uint32_t customMode() const
Definition Vehicle.h:506
void cameraManagerChanged()
VehicleSigningController * signingController()
Definition Vehicle.h:538
Q_INVOKABLE void sendParamMapRC(const QString &paramName, double scale, double centerValue, int tuningID, double minValue, double maxValue)
Sends PARAM_MAP_RC message to vehicle.
Definition Vehicle.cc:2921
HealthAndArmingCheckReport * healthAndArmingCheckReport()
Definition Vehicle.cc:3556
void armedChanged(bool armed)
void firmwareVersionChanged()
FactGroup * distanceSensorFactGroup()
Definition Vehicle.cc:419
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:724
void sendControlRequestAllowedChanged(bool sendControlRequestAllowed)
void hasGripperChanged()
FactGroup * generatorFactGroup()
Definition Vehicle.cc:425
void rcChannelsRawChanged(QVector< int > channelValues)
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
quint64 mavlinkSentCount() const
Definition Vehicle.h:717
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)
Definition Vehicle.cc:2175
Q_INVOKABLE double minimumTakeoffAltitudeMeters()
Definition Vehicle.cc:1855
InitialConnectStateMachine * _initialConnectStateMachine
Definition Vehicle.h:1118
void sensorsParametersResetAck(bool success)
int firmwareBoardProductId() const
Definition Vehicle.h:657
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)
Definition Vehicle.cc:2151
ComponentInformationManager * compInfoManager()
Definition Vehicle.h:577
bool guidedMode() const
Definition Vehicle.cc:2065
const QString _distanceSensorFactGroupName
Definition Vehicle.h:1073
Q_INVOKABLE double maximumEquivalentAirspeed()
Definition Vehicle.cc:1866
PIDTuningTelemetryMode
Definition Vehicle.h:370
@ ModeDisabled
Definition Vehicle.h:371
@ ModeAltitudeAndAirspeed
Definition Vehicle.h:374
@ ModeVelocityAndPosition
Definition Vehicle.h:373
@ ModeRateAndAttitude
Definition Vehicle.h:372
void setPrearmError(const QString &prearmError)
Definition Vehicle.cc:2258
bool landing() const
Definition Vehicle.h:501
VehicleVibrationFactGroup * _vibrationFactGroup
Definition Vehicle.h:1089
qreal getInitialGCSTemperature() const
Definition Vehicle.h:413
void checkListStateChanged()
~Vehicle()
Definition Vehicle.cc:388
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
Definition Vehicle.cc:2281
Q_INVOKABLE void startTimerRevertAllowTakeover()
Definition Vehicle.cc:3179
int messageCount() const
Definition Vehicle.cc:3395
VehicleGeneratorFactGroup * _generatorFactGroup
Definition Vehicle.h:1098
const QString _generatorFactGroupName
Definition Vehicle.h:1079
int firmwareMinorVersion() const
Definition Vehicle.h:650
bool isOfflineEditingVehicle() const
Definition Vehicle.h:510
void messagesSentChanged()
quint64 mavlinkLossCount() const
Total number of sucessful messages received.
Definition Vehicle.h:719
Q_INVOKABLE void sendPlan(QString planFile)
Definition Vehicle.cc:2713
bool vtolInFwdFlight() const
Definition Vehicle.h:504
Q_INVOKABLE void startMission()
Definition Vehicle.cc:1888
bool isMavCommandPending(int targetCompId, MAV_CMD command)
isMavCommandPending Query whether the specified MAV_CMD is in queue to be sent or has already been se...
Definition Vehicle.cc:2190
void capabilitiesKnownChanged(bool capabilitiesKnown)
MAV_AUTOPILOT firmwareType() const
Definition Vehicle.h:427
Q_INVOKABLE void requestOperatorControl(bool allowOverride, int requestTimeoutSecs=0)
Definition Vehicle.cc:3195
void rcChannelsClampedChanged(QVector< int > channelValues)
VehicleEstimatorStatusFactGroup * _estimatorStatusFactGroup
Definition Vehicle.h:1096
VehicleTemperatureFactGroup * _temperatureFactGroup
Definition Vehicle.h:1090
void setCheckListState(CheckList cl)
Definition Vehicle.h:725
bool soloFirmware() const
Definition Vehicle.h:667
void coordinateChanged(QGeoCoordinate coordinate)
QString vehicleImageOpaque() const
Definition Vehicle.cc:2578
float _altitudeTuningOffset
Definition Vehicle.h:1056
Q_INVOKABLE void setPIDTuningTelemetryMode(PIDTuningTelemetryMode mode)
Definition Vehicle.cc:2753
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)
Q_INVOKABLE void emergencyStop()
Command vehicle to kill all motors no matter what state.
Definition Vehicle.cc:2081
void updateFlightDistance(double distance)
Definition Vehicle.cc:2916
int firmwareCustomPatchVersion() const
Definition Vehicle.h:655
int id() const
Definition Vehicle.h:425
const QString _gpsAggregateFactGroupName
Definition Vehicle.h:1067
Q_INVOKABLE bool guidedModeGotoLocation(const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0f)
Definition Vehicle.cc:1893
void pairRX(int rxType, int rxSubType)
Definition Vehicle.cc:3170
const QString _setpointFactGroupName
Definition Vehicle.h:1072
Q_INVOKABLE void setCurrentMissionSequence(int seq)
Alter the current mission item on the vehicle.
Definition Vehicle.cc:2111
FactGroup * gps2FactGroup()
Definition Vehicle.cc:412
void toolIndicatorsChanged()
void sensorsUnhealthyBitsChanged(int sensorsUnhealthyBits)
void landingChanged(bool landing)
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
VehicleWindFactGroup * _windFactGroup
Definition Vehicle.h:1088
bool inFwdFlight() const
Definition Vehicle.cc:2075
const QString _rpmFactGroupName
Definition Vehicle.h:1081
FactGroup * hygrometerFactGroup()
Definition Vehicle.cc:424
static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK
Definition Vehicle.h:127
Q_INVOKABLE void startTakeoff()
Definition Vehicle.cc:1882
Q_INVOKABLE void resetAllMessages()
Definition Vehicle.cc:3388
VehicleHygrometerFactGroup * _hygrometerFactGroup
Definition Vehicle.h:1097
void setFlightMode(const QString &flightMode)
Definition Vehicle.cc:1478
bool messageTypeWarning() const
Definition Vehicle.cc:3393
static constexpr int kTestMavCommandMaxWaitMs
Definition Vehicle.h:1049
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)
Same as sendMavCommand but available from Qml.
Definition Vehicle.cc:2156
float mavlinkLossPercent() const
Total number of lost messages.
Definition Vehicle.h:720
void loadProgressChanged(float value)
QString smartRTLFlightMode() const
Definition Vehicle.cc:2548
static const MAV_TYPE MAV_TYPE_TRACK
Definition Vehicle.h:128
QString followFlightMode() const
Definition Vehicle.cc:2563
bool _fixed_wing_airspeed_limits_available
Definition Vehicle.h:1060
GeoFenceManager * geoFenceManager()
Definition Vehicle.h:571
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs, bool showError)
Definition Vehicle.cc:2443
void mavlinkMessageReceived(const mavlink_message_t &message)
bool requiresGpsFix() const
Definition Vehicle.h:535
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
Definition Vehicle.cc:3335
Q_INVOKABLE void resetCounters()
< Flight mode vehicle is in while performing goto
Definition Vehicle.cc:510
const QVariantList & toolIndicators()
Definition Vehicle.cc:2594
void _offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
Definition Vehicle.cc:474
FactGroup * localPositionSetpointFactGroup()
Definition Vehicle.cc:421
Q_INVOKABLE void guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed)
Definition Vehicle.cc:1934
QmlObjectListModel * escs()
Definition Vehicle.cc:431
void guidedModeChanged(bool guidedMode)
FactGroup * efiFactGroup()
Definition Vehicle.cc:426
void setEventsMetadata(uint8_t compid, const QString &metadataJsonFileName)
Definition Vehicle.cc:3561
QString formattedMessages() const
Definition Vehicle.cc:3396
int _findMavCommandListEntryIndex(int targetCompId, MAV_CMD command)
Test-only helper: forwards to MavCommandQueue::findEntryIndex.
Definition Vehicle.cc:2195
void vehicleUIDChanged()
quint64 vehicleUID() const
Definition Vehicle.h:664
bool autoDisarm()
Definition Vehicle.cc:2614
QGeoCoordinate armedPosition()
Definition Vehicle.h:410
void longitudeChanged()
double loadProgress() const
Definition Vehicle.h:727
RemoteIDManager * remoteIDManager()
Definition Vehicle.h:580
QObject * sysStatusSensorInfo()
Definition Vehicle.cc:433
const QString _vehicleFactGroupName
Definition Vehicle.h:1064
QString motorDetectionFlightMode() const
Definition Vehicle.cc:2568
Q_INVOKABLE void resetErrorLevelMessages()
Definition Vehicle.cc:3389
uint8_t baseMode() const
Definition Vehicle.h:505
VehicleFactGroup * _vehicleFactGroup
Definition Vehicle.h:1084
bool coaxialMotors()
Definition Vehicle.cc:1419
void orbitActiveChanged(bool orbitActive)
bool messageTypeNormal() const
Definition Vehicle.cc:3392
void allSensorsHealthyChanged(bool allSensorsHealthy)
FactGroup * vehicleFactGroup()
Definition Vehicle.h:547
static constexpr int kAuxRcOverrideChannelCount
Sends RC_CHANNELS_OVERRIDE for joystick aux axes mapped to RC channels 5–10 only.
Definition Vehicle.h:421
Q_INVOKABLE void guidedModeRTL(bool smartRTL)
Command vehicle to return to launch.
Definition Vehicle.cc:1828
VehicleGPS2FactGroup * _gps2FactGroup
Definition Vehicle.h:1086
bool xConfigMotors()
Definition Vehicle.cc:1424
void trackFirmwareVehicleTypeChanges(void)
Definition Vehicle.cc:212
Q_INVOKABLE void landingGearDeploy()
Command vichecle to deploy landing gear.
Definition Vehicle.cc:2091
static constexpr int kTestMavCommandAckTimeoutMs
Definition Vehicle.h:1048
void armedPositionChanged()
VehicleEFIFactGroup * _efiFactGroup
Definition Vehicle.h:1099
int motorCount()
Definition Vehicle.cc:1410
void stopMavlinkLog()
Definition Vehicle.cc:2473
static QString requestMessageResultHandlerFailureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
Definition Vehicle.cc:3345
RemoteIDManager * _remoteIDManager
Definition Vehicle.h:1120
Q_INVOKABLE void doSetHome(const QGeoCoordinate &coord)
Set home from flight map coordinate.
Definition Vehicle.cc:2867
void stopUAVCANBusConfig(void)
Definition Vehicle.cc:2427
void soloFirmwareChanged(bool soloFirmware)
ParameterManager * parameterManager() const
Definition Vehicle.h:574
int firmwareVersionType() const
Definition Vehicle.h:652
uint32_t flowImageIndex() const
Definition Vehicle.cc:3491
int compId() const
Definition Vehicle.h:426
void homePositionChanged(const QGeoCoordinate &homePosition)
const VehicleSigningController * signingController() const
Definition Vehicle.h:539
QMap< uint8_t, uint8_t > _lowestBatteryChargeStateAnnouncedMap
Definition Vehicle.h:1054
FactGroup * radioStatusFactGroup()
Definition Vehicle.cc:428
Q_INVOKABLE void pauseVehicle()
Definition Vehicle.cc:2047
double defaultHoverSpeed() const
Definition Vehicle.h:525
void stopTrackingFirmwareVehicleTypeChanges(void)
Definition Vehicle.cc:221
FactGroup * windFactGroup()
Definition Vehicle.cc:414
void flightModesChanged()
const QString _gps2FactGroupName
Definition Vehicle.h:1066
int sensorsHealthBits() const
Definition Vehicle.h:513
FactGroup * temperatureFactGroup()
Definition Vehicle.cc:416
GimbalController * gimbalController()
Definition Vehicle.h:731
bool apmFirmware() const
Definition Vehicle.h:495
Q_INVOKABLE void closeVehicle()
Removes the vehicle from the system.
Definition Vehicle.cc:435
int sensorsPresentBits() const
Definition Vehicle.h:511
void flightModeChanged(const QString &flightMode)
bool allSensorsHealthy() const
Definition Vehicle.h:533
QString gitHash() const
Definition Vehicle.h:663
void flowImageIndexChanged()
void roiCoordChanged(const QGeoCoordinate &centerCoord)
VehicleObjectAvoidance * objectAvoidance()
Definition Vehicle.h:578
Q_INVOKABLE void clearAllParamMapRC(void)
Clears all PARAM_MAP_RC settings from vehicle.
Definition Vehicle.cc:2955
void messageTypeChanged()
FactGroup * estimatorStatusFactGroup()
Definition Vehicle.cc:422
Q_INVOKABLE void setEstimatorOrigin(const QGeoCoordinate &centerCoord)
Definition Vehicle.cc:3147
void setVtolInFwdFlight(bool vtolInFwdFlight)
Definition Vehicle.cc:2457
Q_INVOKABLE void guidedModeChangeGroundSpeedMetersSecond(double groundspeed)
Definition Vehicle.cc:1924
int defaultComponentId() const
Definition Vehicle.h:670
void setInitialGCSTemperature(qreal temperature)
Definition Vehicle.h:415
void mavlinkStatusChanged()
quint64 mavlinkReceivedCount() const
Calculated total number of messages sent to us.
Definition Vehicle.h:718
MAVLinkLogManager * mavlinkLogManager() const
Definition Vehicle.cc:3506
RallyPointManager * rallyPointManager()
Definition Vehicle.h:572
Q_INVOKABLE void clearMessages()
Definition Vehicle.cc:3390
bool genericFirmware() const
Definition Vehicle.h:496
FactGroup * setpointFactGroup()
Definition Vehicle.cc:418
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)
Definition Vehicle.cc:2981
QmlObjectListModel * cameraTriggerPoints()
Definition Vehicle.cc:434
FTPManager * _ftpManager
Definition Vehicle.h:1117
GeoFenceManager * _geoFenceManager
Definition Vehicle.h:1114
float longitude()
Definition Vehicle.h:493
QGCMapCircle * orbitMapCircle()
Definition Vehicle.h:530
bool flightModeSetAvailable()
Definition Vehicle.cc:1457
ParameterManager * parameterManager()
Definition Vehicle.h:573
VehicleGPSFactGroup * _gpsFactGroup
Definition Vehicle.h:1085
void gitHashChanged(QString hash)
int firmwareBoardVendorId() const
Definition Vehicle.h:656
void sensorsHealthBitsChanged(int sensorsHealthBits)
void _setFlying(bool flying)
Definition Vehicle.cc:1807
Q_INVOKABLE void guidedModeChangeHeading(const QGeoCoordinate &headingCoord)
Definition Vehicle.cc:2037
QString takeControlFlightMode() const
Definition Vehicle.cc:2558
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:703
void messagesReceivedChanged()
const QString _localPositionSetpointFactGroupName
Definition Vehicle.h:1075
void setOfflineEditingDefaultComponentId(int defaultComponentId)
Sets the default component id for an offline editing vehicle.
Definition Vehicle.cc:2448
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType=FIRMWARE_VERSION_TYPE_OFFICIAL)
Definition Vehicle.cc:2272
QString rtlFlightMode() const
Definition Vehicle.cc:2543
bool fixedWing() const
Definition Vehicle.cc:1738
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)
Definition Vehicle.cc:2252
int firmwarePatchVersion() const
Definition Vehicle.h:651
QGeoCoordinate coordinate()
Definition Vehicle.h:409
void startCalibration(QGCMAVLink::CalibrationType calType)
Definition Vehicle.cc:2325
QVector< int > _servoOutputRawValues
Definition Vehicle.h:1105
QString firmwareTypeString() const
Definition Vehicle.cc:505
static constexpr int _mavCommandMaxRetryCount
Definition Vehicle.h:1047
FTPManager * ftpManager()
Definition Vehicle.h:576
FactGroup * clockFactGroup()
Definition Vehicle.cc:417
void stopCalibration(bool showError)
Definition Vehicle.cc:2405
void messageCountChanged()
bool isROIEnabled() const
Running loss rate.
Definition Vehicle.h:722
@ CheckListFailed
Definition Vehicle.h:140
@ CheckListNotSetup
Definition Vehicle.h:138
@ CheckListPassed
Definition Vehicle.h:139
QmlObjectListModel * batteries()
Definition Vehicle.cc:430
void haveFWSpeedLimChanged()
RallyPointManager * _rallyPointManager
Definition Vehicle.h:1115
double defaultCruiseSpeed() const
Definition Vehicle.h:524
void startUAVCANBusConfig(void)
Definition Vehicle.cc:2419
RadioStatusFactGroup * _radioStatusFactGroup
Definition Vehicle.h:1102
QString gotoFlightMode() const
Definition Vehicle.cc:1823
void sendMavCommandIntWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, 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)
Definition Vehicle.cc:2180
bool armed() const
Definition Vehicle.h:449
Q_INVOKABLE void landingGearRetract()
Command vichecle to retract landing gear.
Definition Vehicle.cc:2101
VehicleSupports * supports()
Definition Vehicle.h:402
bool capabilitiesKnown() const
Definition Vehicle.h:696
const QString _windFactGroupName
Definition Vehicle.h:1068
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
VehicleGPSAggregateFactGroup * _gpsAggregateFactGroup
Definition Vehicle.h:1087
FactGroup * gpsFactGroup()
Definition Vehicle.cc:411
int firmwareCustomMinorVersion() const
Definition Vehicle.h:654
void sensorsEnabledBitsChanged(int sensorsEnabledBits)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
Definition Vehicle.h:685
VehicleSetpointFactGroup * _setpointFactGroup
Definition Vehicle.h:1092
Q_INVOKABLE int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.
Definition Vehicle.cc:2743
int firmwareMajorVersion() const
Definition Vehicle.h:649
TerrainFactGroup * _terrainFactGroup
Definition Vehicle.h:1101
Q_INVOKABLE void forceArm()
Definition Vehicle.cc:1448
void requiresGpsFixChanged()
void setArmed(bool armed, bool showError)
Definition Vehicle.cc:1439
QStringList flightModes()
Definition Vehicle.cc:1462
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
FactGroup * terrainFactGroup()
Definition Vehicle.cc:423
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data)
Q_INVOKABLE QString vehicleClassInternalName() const
Definition Vehicle.cc:1773
VehicleLinkManager * _vehicleLinkManager
Definition Vehicle.h:1116
void servoOutputsChanged(QVector< int > servoValues)
QString hobbsMeter()
Definition Vehicle.cc:2718
TerrainQueryCoordinator * _terrainQueryCoordinator
Definition Vehicle.h:1124
MissionManager * missionManager()
Definition Vehicle.h:570
void prearmErrorChanged(const QString &prearmError)
void startMavlinkLog()
Definition Vehicle.cc:2468
void vehicleTypeChanged()
Q_INVOKABLE void guidedModeLand()
Command vehicle to land at current location.
Definition Vehicle.cc:1837
void sendMavCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, 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)
Sends the command and calls the callback with the result.
Definition Vehicle.cc:2170
uint messagesSent() const
Definition Vehicle.h:498
void setArmedShowError(bool armed)
Definition Vehicle.h:451
bool airship() const
Definition Vehicle.cc:1733
StandardModes * _standardModes
Definition Vehicle.h:1121
QString vehicleUIDStr()
Definition Vehicle.cc:1012
bool spacecraft() const
Definition Vehicle.cc:1753
bool readyToFlyAvailable() const
Definition Vehicle.h:531
QString vehicleTypeString() const
Definition Vehicle.cc:1768
void logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
void(* RequestMessageResultHandler)(void *resultHandlerData, MAV_RESULT commandResult, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t &message)
Callback for requestMessage — delivered when the ack/message pair resolves or a failure occurs.
struct VehicleTypes::MavCmdAckHandlerInfo_s MavCmdAckHandlerInfo_t
Callback info bundle for sendMavCommandWithHandler.
RequestMessageResultHandlerFailureCode_t
static const int versionNotSetValue