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")
100#ifdef QGC_UNITTEST_BUILD
101 friend class SendMavCommandWithSignallingTest;
102 friend class SendMavCommandWithHandlerTest;
103 friend class RequestMessageTest;
104 friend class RetryableRequestMessageStateTest;
111 int defaultComponentId,
112 MAV_AUTOPILOT firmwareType,
113 MAV_TYPE vehicleType,
114 QObject* parent =
nullptr);
119 static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK = MAV_AUTOPILOT_ENUM_END;
120 static const MAV_TYPE MAV_TYPE_TRACK = MAV_TYPE_ENUM_END;
123 Vehicle(MAV_AUTOPILOT firmwareType,
124 MAV_TYPE vehicleType,
125 QObject* parent =
nullptr);
130 CheckListNotSetup = 0,
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)
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)
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)
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)
218 Q_PROPERTY(
bool orbitActive READ orbitActive NOTIFY orbitActiveChanged)
219 Q_PROPERTY(
QGCMapCircle* orbitMapCircle READ orbitMapCircle CONSTANT)
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)
229 Q_PROPERTY(
ParameterManager* parameterManager READ parameterManager CONSTANT)
232 Q_PROPERTY(
Autotune* autotune READ autotune CONSTANT)
233 Q_PROPERTY(
RemoteIDManager* remoteIDManager READ remoteIDManager CONSTANT)
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)
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)
273 Q_PROPERTY(
bool mavlinkSigning READ mavlinkSigning NOTIFY mavlinkSigningChanged)
276 Q_INVOKABLE
void resetCounters ();
278 Q_INVOKABLE
void virtualTabletJoystickValue(
double roll,
double pitch,
double yaw,
double thrust);
281 Q_INVOKABLE
void guidedModeRTL(
bool smartRTL);
284 Q_INVOKABLE
void guidedModeLand();
287 Q_INVOKABLE
void guidedModeTakeoff(
double altitudeRelative);
290 Q_INVOKABLE
double minimumTakeoffAltitudeMeters();
293 Q_INVOKABLE
double maximumHorizontalSpeedMultirotor();
296 Q_INVOKABLE
double maximumEquivalentAirspeed();
299 Q_INVOKABLE
double minimumEquivalentAirspeed();
302 Q_INVOKABLE
void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord,
double forwardFlightLoiterRadius = 0.0f);
307 Q_INVOKABLE
void guidedModeChangeAltitude(
double altitudeChange,
bool pauseVehicle);
311 Q_INVOKABLE
void guidedModeChangeHeading(const QGeoCoordinate &headingCoord);
315 Q_INVOKABLE
void guidedModeChangeGroundSpeedMetersSecond(
double groundspeed);
318 Q_INVOKABLE
void guidedModeChangeEquivalentAirspeedMetersSecond(
double airspeed);
324 Q_INVOKABLE
void guidedModeOrbit(const QGeoCoordinate& centerCoord,
double radius,
double amslAltitude);
328 Q_INVOKABLE
void guidedModeROI(const QGeoCoordinate& centerCoord);
329 Q_INVOKABLE
void stopGuidedModeROI();
333 Q_INVOKABLE
void pauseVehicle();
336 Q_INVOKABLE
void emergencyStop();
339 Q_INVOKABLE
void abortLanding(
double climbOutAltitude);
342 Q_INVOKABLE
void landingGearDeploy();
345 Q_INVOKABLE
void landingGearRetract();
347 Q_INVOKABLE
void startTakeoff();
349 Q_INVOKABLE
void startMission();
352 Q_INVOKABLE
void setCurrentMissionSequence(
int seq);
355 Q_INVOKABLE
void rebootVehicle();
357 Q_INVOKABLE
void sendPlan(QString planFile);
358 Q_INVOKABLE
void setEstimatorOrigin(const QGeoCoordinate& centerCoord);
362 Q_INVOKABLE
int versionCompare(const QString& compare) const;
363 Q_INVOKABLE
int versionCompare(
int major,
int minor,
int patch) const;
369 Q_INVOKABLE
void motorTest(
int motor,
int percent,
int timeoutSecs,
bool showError);
377 Q_ENUM(PIDTuningTelemetryMode)
379 Q_INVOKABLE
void setPIDTuningTelemetryMode(PIDTuningTelemetryMode mode);
381 Q_INVOKABLE
void forceArm ();
384 Q_INVOKABLE
void sendParamMapRC(
const QString& paramName,
double scale,
double centerValue,
int tuningID,
double minValue,
double maxValue);
387 Q_INVOKABLE
void clearAllParamMapRC(
void);
390 Q_INVOKABLE
void closeVehicle(
void) { _vehicleLinkManager->closeVehicle(); }
393 Q_INVOKABLE
void triggerSimpleCamera(
void);
396 Q_INVOKABLE
void doSetHome(
const QGeoCoordinate& coord);
398 Q_INVOKABLE
void sendSetupSigning();
400 Q_INVOKABLE QVariant expandedToolbarIndicatorSource(
const QString& indicatorName);
402 bool isInitialConnectComplete()
const;
403 QString gotoFlightMode ()
const;
406 bool hasGripper ()
const;
420 void updateFlightDistance(
double distance);
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);
425 int id()
const{
return _systemID; }
430 Q_INVOKABLE QString vehicleClassInternalName()
const;
447 QGeoCoordinate homePosition();
449 bool armed ()
const{
return _armed; }
450 void setArmed (
bool armed,
bool showError);
453 bool flightModeSetAvailable ();
454 QStringList flightModes ();
455 QString flightMode ()
const;
456 void setFlightMode (
const QString& flightMode);
458 bool airship()
const;
460 void pairRX(
int rxType,
int rxSubType);
462 bool fixedWing()
const;
463 bool multiRotor()
const;
467 bool spacecraft()
const;
471 void setGuidedMode(
bool guidedMode);
474 void setPrearmError(
const QString& prearmError);
479 void startMavlinkLog();
480 void stopMavlinkLog();
486 void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate,
bool sendMultiple =
true);
489 void trackFirmwareVehicleTypeChanges(
void);
490 void stopTrackingFirmwareVehicleTypeChanges(
void);
492 float latitude () {
return static_cast<float>(_coordinate.latitude()); }
493 float longitude () {
return static_cast<float>(_coordinate.longitude()); }
495 bool px4Firmware ()
const {
return _firmwareType == MAV_AUTOPILOT_PX4; }
496 bool apmFirmware ()
const {
return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
503 bool guidedMode ()
const;
504 bool inFwdFlight ()
const;
509 QString brandImageIndoor ()
const;
510 QString brandImageOutdoor ()
const;
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;
526 QString firmwareTypeString ()
const;
527 QString vehicleTypeString ()
const;
543 bool hilMode ()
const {
return _base_mode & MAV_MODE_FLAG_HIL_ENABLED; }
548 void stopCalibration (
bool showError);
550 void startUAVCANBusConfig(
void);
551 void stopUAVCANBusConfig(
void);
587 static void showCommandAckError(
const mavlink_command_ack_t& ack);
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);
613 bool isMavCommandPending(
int targetCompId, MAV_CMD command);
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);
622 } MavCmdResultFailureCode_t;
624 static QString mavCmdResultFailureCodeToString(MavCmdResultFailureCode_t failureCode);
629 typedef void (*MavCmdProgressHandler)(
void* progressHandlerData,
int compId,
const mavlink_command_ack_t& ack);
635 typedef void (*MavCmdResultHandler)(
void* resultHandlerData,
int compId,
const mavlink_command_ack_t& ack,
MavCmdResultFailureCode_t failureCode);
643 } MavCmdAckHandlerInfo_t;
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);
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);
661 void sendMavCommandWithLambdaFallback(
662 std::function<
void()> lambda,
663 int compId, MAV_CMD command,
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);
674 } RequestMessageResultHandlerFailureCode_t;
676 static QString requestMessageResultHandlerFailureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode);
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);
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;
706 QString vehicleUIDStr();
709 void setSoloFirmware(
bool soloFirmware);
714 void setOfflineEditingDefaultComponentId(
int defaultComponentId);
720 bool coaxialMotors();
723 bool xConfigMotors();
732 QString vehicleImageOpaque ()
const;
733 QString vehicleImageOutline ()
const;
735 const QVariantList& toolIndicators();
740 QString hobbsMeter ();
746 void forceInitialPlanRequestComplete();
748 void _setFlying(
bool flying);
749 void _setLanding(
bool landing);
750 void _setHomePosition(QGeoCoordinate& homeCoord);
770 void setEventsMetadata(uint8_t compid,
const QString& metadataJsonFileName);
771 void setActuatorsMetadata(uint8_t compid,
const QString& metadataJsonFileName);
778 void setVtolInFwdFlight (
bool vtolInFwdFlight);
779 void _offlineFirmwareTypeSettingChanged (QVariant varFirmwareType);
780 void _offlineVehicleTypeSettingChanged (QVariant varVehicleType);
847 void mavlinkLogData (
Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data,
bool acked);
855 void mavCommandResult (
int vehicleId,
int targetComponent,
int command,
int ackResult,
int failureCode);
858 void mavlinkSerialControl (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
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);
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);
907void _activeVehicleChanged (
Vehicle* newActiveVehicle);
926 void _handleEvent(uint8_t comp_id, std::unique_ptr<events::parser::ParsedEvent> event);
928#if !defined(QGC_NO_ARDUPILOT_DIALECT)
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 ();
940 void _ackMavlinkLogData (uint16_t sequence);
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);
952 bool setFlightModeCustom (
const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
953 QString _formatMavCommand (MAV_CMD command,
float param1);
955 static void _rebootCommandResultHandler(
void* resultHandlerData,
int compId,
const mavlink_command_ack_t& ack,
MavCmdResultFailureCode_t failureCode);
958 void _deleteGimbalController();
959 void _deleteCameraManager();
963 void _stopCommandProcessing();
966 int _defaultComponentId;
967 bool _offlineEditingVehicle =
false;
969 MAV_AUTOPILOT _firmwareType;
970 MAV_TYPE _vehicleType;
974 bool _soloFirmware =
false;
979 bool _isActiveVehicle =
false;
981 QGeoCoordinate _coordinate;
982 QGeoCoordinate _homePosition;
983 QGeoCoordinate _armedPosition;
985 qreal _initialGCSPressure = 0.;
986 qreal _initialGCSTemperature = 0.;
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;
1020 QString _prearmError;
1021 QTimer _prearmErrorTimer;
1022 static const int _prearmErrorTimeoutMSecs = 35 * 1000;
1024 bool _initialPlanRequestComplete =
false;
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;
1043 } SendMessageMultipleInfo_t;
1045 QList<SendMessageMultipleInfo_t> _sendMessageMultipleList;
1047 static const int _sendMessageMultipleRetries = 5;
1048 static const int _sendMessageMultipleIntraMessageDelay = 500;
1050 QTimer _sendMultipleTimer;
1051 int _nextSendMessageMultipleIndex = 0;
1053 QElapsedTimer _flightTimer;
1054 QTimer _flightTimeUpdater;
1059 bool _allLinksRemovedSent =
false;
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;
1068 bool _isROIEnabled =
false;
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;
1082 uint16_t _firmwareBoardVendorId = 0;
1083 uint16_t _firmwareBoardProductId = 0;
1089 uint64_t _mavlinkSentCount = 0;
1090 uint64_t _mavlinkReceivedCount = 0;
1091 uint64_t _mavlinkLossCount = 0;
1092 float _mavlinkLossPercent = 0.0f;
1094 float _loadProgress = 0.0f;
1096 QMap<QString, QTime> _noisySpokenPrearmMap;
1099 bool _orbitActive =
false;
1101 QTimer _orbitTelemetryTimer;
1102 static const int _orbitTelemetryTimeoutMsecs = 3000;
1104 QMap<uint8_t, QSharedPointer<EventHandler>> _events;
1113 typedef void (*WaitForMavlinkMessageResultHandler)(
void* resultHandlerData,
bool noResponsefromVehicle,
const mavlink_message_t& message);
1115 void _waitForMavlinkMessageMessageReceivedHandler(
const mavlink_message_t& message);
1119 typedef struct RequestMessageInfo {
1120 QPointer<Vehicle> vehicle;
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;
1131 bool messageReceived =
false;
1132 QElapsedTimer messageWaitElapsedTimer;
1134 } RequestMessageInfo_t;
1136 QMap<
int , QMap<
int , RequestMessageInfo_t*>> _requestMessageInfoMap;
1137 QMap<
int , QList<RequestMessageInfo_t*>> _requestMessageQueueMap;
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);
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);
1147 typedef struct MavCommandListEntry {
1148 int targetCompId = MAV_COMP_ID_AUTOPILOT1;
1149 bool useCommandInt =
false;
1156 double rgParam5 = 0;
1157 double rgParam6 = 0;
1159 bool showError =
true;
1160 MavCmdAckHandlerInfo_t ackHandlerInfo;
1161 int maxTries = _mavCommandMaxRetryCount;
1163 QElapsedTimer elapsedTimer;
1164 int ackTimeoutMSecs = 0;
1165 } MavCommandListEntry_t;
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;
1177 static constexpr int kTestMavCommandAckTimeoutMs = 500;
1179 static constexpr int kTestMavCommandMaxWaitMs = kTestMavCommandAckTimeoutMs * _mavCommandMaxRetryCount * 2;
1181 void _sendMavCommandWorker (
1182 bool commandInt,
bool showError,
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);
1193 float _altitudeTuningOffset = qQNaN();
1196 bool _multirotor_speed_limits_available =
false;
1197 bool _fixed_wing_airspeed_limits_available =
false;
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");
1268 float _altitudeAboveTerrLastRelAlt = qQNaN();
1271 int32_t getMessageRate(uint8_t compId, uint16_t msgId);
1272 void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate);
1281 void _requestMessageInterval(uint8_t compId, uint16_t msgId);
1283 static void _setMessageRateCommandResultHandler(
void* resultHandlerData,
int compId,
const mavlink_command_ack_t& ack,
MavCmdResultFailureCode_t failureCode);
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;
1295 Q_INVOKABLE
void flashBootloader();
1298 Q_INVOKABLE
void motorInterlock(
bool enable);
1305 Q_INVOKABLE
void startTimerRevertAllowTakeover();
1306 Q_INVOKABLE
void requestOperatorControl(
bool allowOverride,
int requestTimeoutSecs = 0);
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);
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)
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);
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;
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)
1358 Q_INVOKABLE
void resetAllMessages();
1359 Q_INVOKABLE
void resetErrorLevelMessages();
1360 Q_INVOKABLE
void clearMessages();
1362 bool messageTypeNone()
const;
1363 bool messageTypeNormal()
const;
1364 bool messageTypeWarning()
const;
1365 bool messageTypeError()
const;
1366 int messageCount()
const;
1367 QString formattedMessages()
const;
1385 void _textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description);
1386 void _errorMessageReceived(QString message);
1389 void _createStatusTextHandler();
1398 Q_PROPERTY(uint flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged)
1401 uint32_t flowImageIndex()
const;
1407 void _createImageProtocolManager();
1416 Q_PROPERTY(
MAVLinkLogManager *mavlinkLogManager READ mavlinkLogManager NOTIFY mavlinkLogManagerChanged)
1425 void _createMAVLinkLogManager();
1434 Q_MOC_INCLUDE(
"QGCCameraManager.h")
1435 Q_PROPERTY(
QGCCameraManager *cameraManager READ cameraManager NOTIFY cameraManagerChanged)
1436 Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT)
1440 const QVariantList &staticCameraList()
const;
1446 void _createCameraManager();