4#include <QtCore/QObject>
5#include <QtCore/QString>
6#include <QtQmlIntegration/QtQmlIntegration>
8#include "MAVLinkEnums.h"
15 QML_NAMED_ELEMENT(MAVLink)
39 static bool isPX4FirmwareClass (MAV_AUTOPILOT autopilot) {
return autopilot == MAV_AUTOPILOT_PX4; }
52 static bool isSub (MAV_TYPE mavType);
55 static bool isVTOL (MAV_TYPE mavType);
70 static int motorCount (MAV_TYPE mavType, uint8_t frameType = 0);
93 typedef struct param_ext_union {
98 uint64_t param_uint64;
100 uint32_t param_uint32;
102 uint16_t param_uint16;
108 }) param_ext_union_t;
mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
#define MAVLINK_COMM_NUM_BUFFERS
#define MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
struct __mavlink_high_latency2_t mavlink_high_latency2_t
static VehicleClass_t vehicleClass(MAV_TYPE mavType)
static QString vehicleClassToUserVisibleString(VehicleClass_t vehicleClass)
static bool isGenericFirmwareClass(MAV_AUTOPILOT autopilot)
static bool isArduPilotFirmwareClass(MAV_AUTOPILOT autopilot)
static MAV_AUTOPILOT firmwareTypeFromString(const QString &firmwareTypeStr)
static const char * vehicleClassToCanonicalString(VehicleClass_t vehicleClass)
static bool isMultiRotor(MAV_TYPE mavType)
static uint32_t highLatencyFailuresToMavSysStatus(mavlink_high_latency2_t &highLatency2)
static constexpr const VehicleClass_t VehicleClassSub
static QString mavTypeToString(MAV_TYPE mavType)
static constexpr const VehicleClass_t VehicleClassFixedWing
static int motorCount(MAV_TYPE mavType, uint8_t frameType=0)
static constexpr const VehicleClass_t VehicleClassMultiRotor
static bool isValidChannel(mavlink_channel_t channel)
static bool isAirship(MAV_TYPE mavType)
static QList< FirmwareClass_t > allFirmwareClasses()
@ CalibrationAPMPressureAirspeed
@ CalibrationAPMAccelSimple
@ CalibrationAPMCompassMot
@ CalibrationAPMPreFlight
static QString mavResultToString(MAV_RESULT result)
static bool isSpacecraft(MAV_TYPE mavType)
static QString firmwareClassToString(FirmwareClass_t firmwareClass)
static bool isVTOL(MAV_TYPE mavType)
static constexpr const FirmwareClass_t FirmwareClassPX4
static bool isPX4FirmwareClass(MAV_AUTOPILOT autopilot)
static QString firmwareVersionTypeToString(FIRMWARE_VERSION_TYPE firmwareVersionType)
static bool isFixedWing(MAV_TYPE mavType)
static MAV_TYPE vehicleClassToMavType(VehicleClass_t vehicleClass)
static QString compIdToString(uint8_t compId)
static constexpr const VehicleClass_t VehicleClassAirship
static MAV_AUTOPILOT firmwareClassToAutopilot(FirmwareClass_t firmwareClass)
static constexpr const FirmwareClass_t FirmwareClassGeneric
static bool isValidChannel(uint8_t channel)
static QString mavSysStatusSensorToString(MAV_SYS_STATUS_SENSOR sysStatusSensor)
static MAV_TYPE vehicleTypeFromString(const QString &vehicleStr)
static const QHash< int, QString > mavlinkCompIdHash
static constexpr const VehicleClass_t VehicleClassRoverBoat
static FirmwareClass_t firmwareClass(MAV_AUTOPILOT autopilot)
static const char * firmwareClassToCanonicalString(FirmwareClass_t firmwareClass)
static constexpr const VehicleClass_t VehicleClassSpacecraft
static mavlink_status_t * getChannelStatus(mavlink_channel_t channel)
static QString mavResultToString(uint8_t result)
static constexpr const VehicleClass_t VehicleClassVTOL
static bool isSub(MAV_TYPE mavType)
static FIRMWARE_VERSION_TYPE firmwareVersionTypeFromString(const QString &typeStr)
static constexpr const FirmwareClass_t FirmwareClassArduPilot
static QString vehicleClassToInternalString(VehicleClass_t vehicleClass)
MAVPACKED(typedef struct param_ext_union { union { float param_float;double param_double;int64_t param_int64;uint64_t param_uint64;int32_t param_int32;uint32_t param_uint32;int16_t param_int16;uint16_t param_uint16;int8_t param_int8;uint8_t param_uint8;uint8_t bytes[MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN];};uint8_t type;}) param_ext_union_t
static bool isRoverBoat(MAV_TYPE mavType)
static QList< VehicleClass_t > allVehicleClasses(void)
static constexpr VehicleClass_t VehicleClassGeneric