6#include <QtCore/QElapsedTimer>
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>
73class RequestMessageTest;
74class RetryableRequestMessageStateTest;
75class SendMavCommandWithHandlerTest;
76class SendMavCommandWithSignallingTest;
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")
108#ifdef QGC_UNITTEST_BUILD
109 friend class SendMavCommandWithSignallingTest;
110 friend class SendMavCommandWithHandlerTest;
111 friend class RequestMessageTest;
112 friend class RetryableRequestMessageStateTest;
122 QObject* parent =
nullptr);
133 QObject* parent =
nullptr);
144 Q_PROPERTY(
int id READ
id CONSTANT)
154 Q_PROPERTY(
TrajectoryPoints* trajectoryPoints MEMBER _trajectoryPoints CONSTANT)
301 Q_INVOKABLE
bool guidedModeGotoLocation(
const QGeoCoordinate& gotoCoord,
double forwardFlightLoiterRadius = 0.0f);
323 Q_INVOKABLE
void guidedModeOrbit(
const QGeoCoordinate& centerCoord,
double radius,
double amslAltitude);
327 Q_INVOKABLE
void guidedModeROI(
const QGeoCoordinate& centerCoord);
356 Q_INVOKABLE
void sendPlan(QString planFile);
362 Q_INVOKABLE
int versionCompare(
int major,
int minor,
int patch)
const;
368 Q_INVOKABLE
void motorTest(
int motor,
int percent,
int timeoutSecs,
bool showError);
383 Q_INVOKABLE
void sendParamMapRC(
const QString& paramName,
double scale,
double centerValue,
int tuningID,
double minValue,
double maxValue);
395 Q_INVOKABLE
void doSetHome(
const QGeoCoordinate& coord);
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);
422 void sendJoystickAuxRcOverrideThreadSafe(
const std::array<uint16_t, kAuxRcOverrideChannelCount> &channelValues,
const std::array<bool, kAuxRcOverrideChannelCount> &channelEnabled,
bool useRcOverride);
425 int id()
const{
return _systemID; }
449 bool armed ()
const{
return _armed; }
460 void pairRX(
int rxType,
int rxSubType);
486 void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate,
bool sendMultiple =
true);
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; }
509 uint32_t
effectiveCustomMode ()
const {
return _has_custom_mode_user_intention ? _custom_mode_user_intention : _custom_mode; }
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; }
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);
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);
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);
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);
634 std::function<
void()> lambda,
635 int compId, MAV_CMD command,
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);
659 void setFirmwareVersion(
int majorVersion,
int minorVersion,
int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
799 void mavlinkLogData (
Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data,
bool acked);
807 void mavCommandResult (
int vehicleId,
int targetComponent,
int command,
int ackResult,
int failureCode);
810 void mavlinkSerialControl (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
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);
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);
850 void _activeVehicleChanged (
Vehicle* newActiveVehicle);
870#if !defined(QGC_NO_ARDUPILOT_DIALECT)
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 ();
882 void _ackMavlinkLogData (uint16_t sequence);
884 void _setupAutoDisarmSignalling ();
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);
899 void _deleteGimbalController();
900 void _deleteCameraManager();
904 void _stopCommandProcessing();
907 int _defaultComponentId;
908 bool _offlineEditingVehicle =
false;
910 MAV_AUTOPILOT _firmwareType;
911 MAV_TYPE _vehicleType;
915 bool _soloFirmware =
false;
920 bool _isActiveVehicle =
false;
922 QGeoCoordinate _coordinate;
923 QGeoCoordinate _homePosition;
924 QGeoCoordinate _armedPosition;
926 qreal _initialGCSPressure = 0.;
927 qreal _initialGCSTemperature = 0.;
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;
945 bool _readyToFlyAvailable =
false;
946 bool _readyToFly =
false;
947 bool _allSensorsHealthy =
true;
949 std::atomic<bool> _joystickAuxRcOverrideActive =
false;
951 std::unique_ptr<SysStatusSensorInfo> _sysStatusSensorInfo;
954 QString _prearmError;
955 QTimer _prearmErrorTimer;
956 static const int _prearmErrorTimeoutMSecs = 35 * 1000;
958 bool _initialPlanRequestComplete =
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;
978 } SendMessageMultipleInfo_t;
980 QList<SendMessageMultipleInfo_t> _sendMessageMultipleList;
982 static const int _sendMessageMultipleRetries = 5;
983 static const int _sendMessageMultipleIntraMessageDelay = 500;
985 QTimer _sendMultipleTimer;
986 int _nextSendMessageMultipleIndex = 0;
988 QElapsedTimer _flightTimer;
989 QTimer _flightTimeUpdater;
991 std::unique_ptr<QmlObjectListModel> _cameraTriggerPoints;
994 bool _allLinksRemovedSent =
false;
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;
1003 bool _isROIEnabled =
false;
1005 bool _checkLatestStableFWDone =
false;
1012 FIRMWARE_VERSION_TYPE _firmwareVersionType = FIRMWARE_VERSION_TYPE_OFFICIAL;
1017 uint16_t _firmwareBoardVendorId = 0;
1018 uint16_t _firmwareBoardProductId = 0;
1024 uint64_t _mavlinkSentCount = 0;
1025 uint64_t _mavlinkReceivedCount = 0;
1026 uint64_t _mavlinkLossCount = 0;
1027 float _mavlinkLossPercent = 0.0f;
1029 float _loadProgress = 0.0f;
1031 QMap<QString, QTime> _noisySpokenPrearmMap;
1034 bool _orbitActive =
false;
1035 std::unique_ptr<QGCMapCircle> _orbitMapCircle;
1036 QTimer _orbitTelemetryTimer;
1037 static const int _orbitTelemetryTimeoutMsecs = 3000;
1039 std::unique_ptr<MAVLinkStreamConfig> _mavlinkStreamConfig;
1161 Q_PROPERTY(
bool gcsControlStatusFlags_SystemManager READ gcsControlStatusFlags_SystemManager NOTIFY
gcsControlStatusChanged)
1162 Q_PROPERTY(
bool gcsControlStatusFlags_TakeoverAllowed READ gcsControlStatusFlags_TakeoverAllowed NOTIFY
gcsControlStatusChanged)
1164 Q_PROPERTY(
int operatorControlTakeoverTimeoutMsecs READ operatorControlTakeoverTimeoutMsecs CONSTANT)
1165 Q_PROPERTY(
int requestOperatorControlRemainingMsecs READ requestOperatorControlRemainingMsecs CONSTANT)
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);
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;
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);
1237 void _createStatusTextHandler();
1255 void _createImageProtocolManager();
1256 void _createSigningController();
1274 void _createMAVLinkLogManager();
1283 Q_MOC_INCLUDE(
"QGCCameraManager.h")
1295 void _createCameraManager();
1304 Q_MOC_INCLUDE(
"HealthAndArmingCheckReport.h")
1313 void _createMAVLinkEventManager();
1315 bool _healthAndArmingChecksSupported(uint8_t compid);
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.
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...
static VehicleClass_t vehicleClass(MAV_TYPE mavType)
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:
Fact * altitudeRelative()
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.
bool isInitialConnectComplete() const
Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle)
void _setLanding(bool landing)
QGCCameraManager * cameraManager()
Q_INVOKABLE void motorInterlock(bool enable)
Command vehicle to Enable/Disable Motor Interlock.
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
int32_t getMessageRate(uint8_t compId, uint16_t msgId)
VehicleDistanceSensorFactGroup * _distanceSensorFactGroup
TerrainProtocolHandler * _terrainProtocolHandler
void firmwareTypeChanged()
QGCMAVLink::VehicleClass_t vehicleClass(void) const
uint32_t effectiveCustomMode() const
void setInitialGCSPressure(qreal pressure)
Q_INVOKABLE void flashBootloader()
uint messagesReceived() const
void sensorsPresentBitsChanged(int sensorsPresentBits)
void defaultHoverSpeedChanged(double hoverSpeed)
const QString _vibrationFactGroupName
bool _multirotor_speed_limits_available
void gcsControlStatusChanged()
void defaultCruiseSpeedChanged(double cruiseSpeed)
bool messageTypeError() const
const QString _gpsFactGroupName
FactGroup * localPositionFactGroup()
void haveMRSpeedLimChanged()
FactGroup * vibrationFactGroup()
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)
BatteryFactGroupListModel * _batteryFactGroupListModel
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)
VehicleLocalPositionFactGroup * _localPositionFactGroup
const QString _hygrometerFactGroupName
void messagesLostChanged()
Q_INVOKABLE void rebootVehicle()
Reboot vehicle.
FactGroup * gpsAggregateFactGroup()
VehicleRPMFactGroup * _rpmFactGroup
const QString _localPositionFactGroupName
void vtolInFwdFlightChanged(bool vtolInFwdFlight)
qreal getInitialGCSPressure() const
QString missionFlightMode() const
void readyToFlyAvailableChanged(bool readyToFlyAvailable)
void forceInitialPlanRequestComplete()
void isROIEnabledChanged()
Actuators * actuators() const
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate ¢erCoord, double radius, double amslAltitude)
const QString _terrainFactGroupName
Autotune * autotune() const
const QString _temperatureFactGroupName
void deleteGimbalController()
Delete gimbal controller, handy for RequestMessageTest.cc, otherwise gimbal controller message reques...
void _offlineVehicleTypeSettingChanged(QVariant varVehicleType)
Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative)
Command vehicle to takeoff from current location.
Q_INVOKABLE void sendGripperAction(GRIPPER_ACTIONS gripperOption)
bool haveMRSpeedLimits() const
QString flightMode() const
static QString mavCmdResultFailureCodeToString(MavCmdResultFailureCode_t failureCode)
QString stabilizedFlightMode() const
int firmwareCustomMajorVersion() const
const QVariantList & staticCameraList() const
void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs)
Q_INVOKABLE QVariant expandedToolbarIndicatorSource(const QString &indicatorName)
uint messagesLost() const
void sendJoystickAuxRcOverrideThreadSafe(const std::array< uint16_t, kAuxRcOverrideChannelCount > &channelValues, const std::array< bool, kAuxRcOverrideChannelCount > &channelEnabled, bool useRcOverride)
void setActuatorsMetadata(uint8_t compid, const QString &metadataJsonFileName)
void setSoloFirmware(bool soloFirmware)
void mavlinkLogManagerChanged()
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple=true)
FactGroup * rpmFactGroup()
QGeoCoordinate homePosition()
const QString _estimatorStatusFactGroupName
const QString _radioStatusFactGroupName
QString vehicleImageOutline() const
MissionManager * _missionManager
void initialConnectComplete()
VehicleLocalPositionSetpointFactGroup * _localPositionSetpointFactGroup
void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description)
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete)
Q_INVOKABLE double minimumEquivalentAirspeed()
const QString _clockFactGroupName
Q_INVOKABLE void stopGuidedModeROI()
void firmwareCustomVersionChanged()
QString pauseFlightMode() const
QString prearmError() const
int sensorsEnabledBits() const
EscStatusFactGroupListModel * _escStatusFactGroupListModel
Q_INVOKABLE void guidedModeROI(const QGeoCoordinate ¢erCoord)
const QString _efiFactGroupName
void inFwdFlightChanged()
void flyingChanged(bool flying)
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
Q_INVOKABLE double maximumHorizontalSpeedMultirotorMetersSecond()
void sendMessageMultiple(mavlink_message_t message)
void capabilityBitsChanged(uint64_t capabilityBits)
bool messageTypeNone() const
bool haveFWSpeedLimits() const
int sensorsUnhealthyBits() const
void _setHomePosition(QGeoCoordinate &homeCoord)
VehicleClockFactGroup * _clockFactGroup
uint64_t capabilityBits() const
Q_INVOKABLE void abortLanding(double climbOutAltitude)
Command vehicle to abort landing.
void setGuidedMode(bool guidedMode)
void readyToFlyChanged(bool readyToFy)
QString firmwareVersionTypeString() const
QString landFlightMode() const
static void showCommandAckError(const mavlink_command_ack_t &ack)
void formattedMessagesChanged()
void newFormattedMessage(QString formattedMessage)
MAV_TYPE vehicleType() const
VehicleLinkManager * vehicleLinkManager()
uint32_t customMode() const
void cameraManagerChanged()
VehicleSigningController * signingController()
Q_INVOKABLE void sendParamMapRC(const QString ¶mName, double scale, double centerValue, int tuningID, double minValue, double maxValue)
Sends PARAM_MAP_RC message to vehicle.
HealthAndArmingCheckReport * healthAndArmingCheckReport()
void armedChanged(bool armed)
void firmwareVersionChanged()
FactGroup * distanceSensorFactGroup()
void logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num)
CheckList checkListState()
void sendControlRequestAllowedChanged(bool sendControlRequestAllowed)
FactGroup * generatorFactGroup()
void rcChannelsRawChanged(QVector< int > channelValues)
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
quint64 mavlinkSentCount() const
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)
Q_INVOKABLE double minimumTakeoffAltitudeMeters()
InitialConnectStateMachine * _initialConnectStateMachine
void sensorsParametersResetAck(bool success)
int firmwareBoardProductId() const
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)
ComponentInformationManager * compInfoManager()
const QString _distanceSensorFactGroupName
Q_INVOKABLE double maximumEquivalentAirspeed()
@ ModeAltitudeAndAirspeed
@ ModeVelocityAndPosition
void setPrearmError(const QString &prearmError)
VehicleVibrationFactGroup * _vibrationFactGroup
qreal getInitialGCSTemperature() const
void checkListStateChanged()
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
Q_INVOKABLE void startTimerRevertAllowTakeover()
VehicleGeneratorFactGroup * _generatorFactGroup
const QString _generatorFactGroupName
int firmwareMinorVersion() const
bool isOfflineEditingVehicle() const
void messagesSentChanged()
quint64 mavlinkLossCount() const
Total number of sucessful messages received.
Q_INVOKABLE void sendPlan(QString planFile)
bool vtolInFwdFlight() const
Q_INVOKABLE void startMission()
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...
void capabilitiesKnownChanged(bool capabilitiesKnown)
MAV_AUTOPILOT firmwareType() const
Q_INVOKABLE void requestOperatorControl(bool allowOverride, int requestTimeoutSecs=0)
void rcChannelsClampedChanged(QVector< int > channelValues)
VehicleEstimatorStatusFactGroup * _estimatorStatusFactGroup
VehicleTemperatureFactGroup * _temperatureFactGroup
void setCheckListState(CheckList cl)
bool soloFirmware() const
void coordinateChanged(QGeoCoordinate coordinate)
QString vehicleImageOpaque() const
float _altitudeTuningOffset
Q_INVOKABLE void setPIDTuningTelemetryMode(PIDTuningTelemetryMode mode)
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.
void updateFlightDistance(double distance)
int firmwareCustomPatchVersion() const
const QString _gpsAggregateFactGroupName
Q_INVOKABLE bool guidedModeGotoLocation(const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0f)
void pairRX(int rxType, int rxSubType)
const QString _setpointFactGroupName
Q_INVOKABLE void setCurrentMissionSequence(int seq)
Alter the current mission item on the vehicle.
FactGroup * gps2FactGroup()
void toolIndicatorsChanged()
void sensorsUnhealthyBitsChanged(int sensorsUnhealthyBits)
void landingChanged(bool landing)
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
VehicleWindFactGroup * _windFactGroup
const QString _rpmFactGroupName
FactGroup * hygrometerFactGroup()
static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK
Q_INVOKABLE void startTakeoff()
Q_INVOKABLE void resetAllMessages()
VehicleHygrometerFactGroup * _hygrometerFactGroup
void setFlightMode(const QString &flightMode)
bool messageTypeWarning() const
static constexpr int kTestMavCommandMaxWaitMs
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.
float mavlinkLossPercent() const
Total number of lost messages.
void loadProgressChanged(float value)
QString smartRTLFlightMode() const
static const MAV_TYPE MAV_TYPE_TRACK
QString followFlightMode() const
bool _fixed_wing_airspeed_limits_available
GeoFenceManager * geoFenceManager()
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs, bool showError)
void mavlinkMessageReceived(const mavlink_message_t &message)
bool requiresGpsFix() const
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
Q_INVOKABLE void resetCounters()
< Flight mode vehicle is in while performing goto
const QVariantList & toolIndicators()
void _offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
FactGroup * localPositionSetpointFactGroup()
Q_INVOKABLE void guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed)
QmlObjectListModel * escs()
void guidedModeChanged(bool guidedMode)
FactGroup * efiFactGroup()
void setEventsMetadata(uint8_t compid, const QString &metadataJsonFileName)
QString formattedMessages() const
int _findMavCommandListEntryIndex(int targetCompId, MAV_CMD command)
Test-only helper: forwards to MavCommandQueue::findEntryIndex.
quint64 vehicleUID() const
QGeoCoordinate armedPosition()
double loadProgress() const
RemoteIDManager * remoteIDManager()
QObject * sysStatusSensorInfo()
const QString _vehicleFactGroupName
QString motorDetectionFlightMode() const
Q_INVOKABLE void resetErrorLevelMessages()
VehicleFactGroup * _vehicleFactGroup
void orbitActiveChanged(bool orbitActive)
bool messageTypeNormal() const
void allSensorsHealthyChanged(bool allSensorsHealthy)
FactGroup * vehicleFactGroup()
static constexpr int kAuxRcOverrideChannelCount
Sends RC_CHANNELS_OVERRIDE for joystick aux axes mapped to RC channels 5–10 only.
Q_INVOKABLE void guidedModeRTL(bool smartRTL)
Command vehicle to return to launch.
VehicleGPS2FactGroup * _gps2FactGroup
void trackFirmwareVehicleTypeChanges(void)
Q_INVOKABLE void landingGearDeploy()
Command vichecle to deploy landing gear.
static constexpr int kTestMavCommandAckTimeoutMs
void armedPositionChanged()
VehicleEFIFactGroup * _efiFactGroup
static QString requestMessageResultHandlerFailureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
RemoteIDManager * _remoteIDManager
Q_INVOKABLE void doSetHome(const QGeoCoordinate &coord)
Set home from flight map coordinate.
void stopUAVCANBusConfig(void)
void soloFirmwareChanged(bool soloFirmware)
ParameterManager * parameterManager() const
int firmwareVersionType() const
uint32_t flowImageIndex() const
void homePositionChanged(const QGeoCoordinate &homePosition)
const VehicleSigningController * signingController() const
QMap< uint8_t, uint8_t > _lowestBatteryChargeStateAnnouncedMap
FactGroup * radioStatusFactGroup()
Q_INVOKABLE void pauseVehicle()
double defaultHoverSpeed() const
void stopTrackingFirmwareVehicleTypeChanges(void)
FactGroup * windFactGroup()
void flightModesChanged()
const QString _gps2FactGroupName
int sensorsHealthBits() const
FactGroup * temperatureFactGroup()
GimbalController * gimbalController()
Q_INVOKABLE void closeVehicle()
Removes the vehicle from the system.
int sensorsPresentBits() const
void flightModeChanged(const QString &flightMode)
bool allSensorsHealthy() const
void flowImageIndexChanged()
void roiCoordChanged(const QGeoCoordinate ¢erCoord)
VehicleObjectAvoidance * objectAvoidance()
Q_INVOKABLE void clearAllParamMapRC(void)
Clears all PARAM_MAP_RC settings from vehicle.
void messageTypeChanged()
FactGroup * estimatorStatusFactGroup()
Q_INVOKABLE void setEstimatorOrigin(const QGeoCoordinate ¢erCoord)
void setVtolInFwdFlight(bool vtolInFwdFlight)
Q_INVOKABLE void guidedModeChangeGroundSpeedMetersSecond(double groundspeed)
int defaultComponentId() const
void setInitialGCSTemperature(qreal temperature)
void mavlinkStatusChanged()
quint64 mavlinkReceivedCount() const
Calculated total number of messages sent to us.
MAVLinkLogManager * mavlinkLogManager() const
RallyPointManager * rallyPointManager()
Q_INVOKABLE void clearMessages()
bool genericFirmware() const
FactGroup * setpointFactGroup()
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)
QmlObjectListModel * cameraTriggerPoints()
GeoFenceManager * _geoFenceManager
QGCMapCircle * orbitMapCircle()
bool flightModeSetAvailable()
ParameterManager * parameterManager()
VehicleGPSFactGroup * _gpsFactGroup
void gitHashChanged(QString hash)
int firmwareBoardVendorId() const
void sensorsHealthBitsChanged(int sensorsHealthBits)
void _setFlying(bool flying)
Q_INVOKABLE void guidedModeChangeHeading(const QGeoCoordinate &headingCoord)
QString takeControlFlightMode() const
void prepareDelete()
Vehicle is about to be deleted.
AutoPilotPlugin * autopilotPlugin()
Provides access to AutoPilotPlugin for this vehicle.
bool initialPlanRequestComplete() const
void messagesReceivedChanged()
const QString _localPositionSetpointFactGroupName
void setOfflineEditingDefaultComponentId(int defaultComponentId)
Sets the default component id for an offline editing vehicle.
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType=FIRMWARE_VERSION_TYPE_OFFICIAL)
QString rtlFlightMode() const
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)
int firmwarePatchVersion() const
QGeoCoordinate coordinate()
void startCalibration(QGCMAVLink::CalibrationType calType)
QVector< int > _servoOutputRawValues
QString firmwareTypeString() const
static constexpr int _mavCommandMaxRetryCount
FTPManager * ftpManager()
FactGroup * clockFactGroup()
void stopCalibration(bool showError)
void messageCountChanged()
bool isROIEnabled() const
Running loss rate.
QmlObjectListModel * batteries()
void haveFWSpeedLimChanged()
RallyPointManager * _rallyPointManager
double defaultCruiseSpeed() const
void startUAVCANBusConfig(void)
RadioStatusFactGroup * _radioStatusFactGroup
QString gotoFlightMode() const
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)
Q_INVOKABLE void landingGearRetract()
Command vichecle to retract landing gear.
VehicleSupports * supports()
bool capabilitiesKnown() const
const QString _windFactGroupName
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
VehicleGPSAggregateFactGroup * _gpsAggregateFactGroup
FactGroup * gpsFactGroup()
int firmwareCustomMinorVersion() const
void sensorsEnabledBitsChanged(int sensorsEnabledBits)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
VehicleSetpointFactGroup * _setpointFactGroup
Q_INVOKABLE int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.
int firmwareMajorVersion() const
TerrainFactGroup * _terrainFactGroup
Q_INVOKABLE void forceArm()
void requiresGpsFixChanged()
void setArmed(bool armed, bool showError)
QStringList flightModes()
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
FactGroup * terrainFactGroup()
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data)
Q_INVOKABLE QString vehicleClassInternalName() const
VehicleLinkManager * _vehicleLinkManager
void servoOutputsChanged(QVector< int > servoValues)
TerrainQueryCoordinator * _terrainQueryCoordinator
MissionManager * missionManager()
void prearmErrorChanged(const QString &prearmError)
void vehicleTypeChanged()
Q_INVOKABLE void guidedModeLand()
Command vehicle to land at current location.
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.
uint messagesSent() const
void setArmedShowError(bool armed)
StandardModes * _standardModes
bool readyToFlyAvailable() const
QString vehicleTypeString() const
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.
MavCmdResultFailureCode_t
RequestMessageResultHandlerFailureCode_t
static const int versionNotSetValue