QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
QGCMAVLink.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QList>
4#include <QtCore/QLoggingCategory>
5#include <QtCore/QObject>
6#include <QtCore/QString>
7#include <QtQmlIntegration/QtQmlIntegration>
8
9#include "MAVLinkLib.h"
10
11Q_DECLARE_LOGGING_CATEGORY(QGCMAVLinkLog)
12// Q_DECLARE_METATYPE(mavlink_message_t)
13Q_DECLARE_METATYPE(MAV_TYPE)
14Q_DECLARE_METATYPE(MAV_AUTOPILOT)
15
16class QGCMAVLink : public QObject
17{
18 Q_OBJECT
19 QML_NAMED_ELEMENT(MAVLink)
20 QML_SINGLETON
21
22public:
23 // Creating an instance of QGCMAVLink is only meant to be used for the Qml Singleton
24 QGCMAVLink(QObject *parent = nullptr);
26
27 typedef int FirmwareClass_t;
28 typedef int VehicleClass_t;
29
30 static constexpr const FirmwareClass_t FirmwareClassPX4 = MAV_AUTOPILOT_PX4;
31 static constexpr const FirmwareClass_t FirmwareClassArduPilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
32 static constexpr const FirmwareClass_t FirmwareClassGeneric = MAV_AUTOPILOT_GENERIC;
33
34 static constexpr const VehicleClass_t VehicleClassAirship = MAV_TYPE_AIRSHIP;
35 static constexpr const VehicleClass_t VehicleClassFixedWing = MAV_TYPE_FIXED_WING;
36 static constexpr const VehicleClass_t VehicleClassRoverBoat = MAV_TYPE_GROUND_ROVER;
37 static constexpr const VehicleClass_t VehicleClassSub = MAV_TYPE_SUBMARINE;
38 static constexpr const VehicleClass_t VehicleClassSpacecraft = MAV_TYPE_SPACECRAFT_ORBITER;
39 static constexpr const VehicleClass_t VehicleClassMultiRotor = MAV_TYPE_QUADROTOR;
40 static constexpr const VehicleClass_t VehicleClassVTOL = MAV_TYPE_VTOL_TAILSITTER_QUADROTOR;
41 static constexpr const VehicleClass_t VehicleClassGeneric = MAV_TYPE_GENERIC;
42
43 static constexpr const uint8_t maxRcChannels = 18; // mavlink_rc_channels_t->chancount
44
45 static bool isPX4FirmwareClass (MAV_AUTOPILOT autopilot) { return autopilot == MAV_AUTOPILOT_PX4; }
46 static bool isArduPilotFirmwareClass (MAV_AUTOPILOT autopilot) { return autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA; }
47 static bool isGenericFirmwareClass (MAV_AUTOPILOT autopilot) { return !isPX4FirmwareClass(autopilot) && ! isArduPilotFirmwareClass(autopilot); }
48 static FirmwareClass_t firmwareClass (MAV_AUTOPILOT autopilot);
49 static MAV_AUTOPILOT firmwareClassToAutopilot (FirmwareClass_t firmwareClass) { return static_cast<MAV_AUTOPILOT>(firmwareClass); }
50 static QString firmwareClassToString (FirmwareClass_t firmwareClass);
51 static MAV_AUTOPILOT firmwareTypeFromString (const QString &firmwareTypeStr);
52 static QList<FirmwareClass_t> allFirmwareClasses ();
53
54 static bool isAirship (MAV_TYPE mavType);
55 static bool isFixedWing (MAV_TYPE mavType);
56 static bool isRoverBoat (MAV_TYPE mavType);
57 static bool isSub (MAV_TYPE mavType);
58 static bool isSpacecraft (MAV_TYPE mavType);
59 static bool isMultiRotor (MAV_TYPE mavType);
60 static bool isVTOL (MAV_TYPE mavType);
61 static VehicleClass_t vehicleClass (MAV_TYPE mavType);
62 static MAV_TYPE vehicleClassToMavType (VehicleClass_t vehicleClass) { return static_cast<MAV_TYPE>(vehicleClass); }
63 static QString vehicleClassToUserVisibleString(VehicleClass_t vehicleClass);
64 static QString vehicleClassToInternalString(VehicleClass_t vehicleClass);
65 static MAV_TYPE vehicleTypeFromString(const QString &vehicleStr);
66 static QList<VehicleClass_t> allVehicleClasses (void);
67
68 static QString mavResultToString (uint8_t result);
69 static QString mavResultToString (MAV_RESULT result) { return mavResultToString(static_cast<uint8_t>(result)); }
70 static QString mavSysStatusSensorToString (MAV_SYS_STATUS_SENSOR sysStatusSensor);
71 static QString mavTypeToString (MAV_TYPE mavType);
72 static QString firmwareVersionTypeToString (FIRMWARE_VERSION_TYPE firmwareVersionType);
73 static FIRMWARE_VERSION_TYPE firmwareVersionTypeFromString(const QString &typeStr);
74 static int motorCount (MAV_TYPE mavType, uint8_t frameType = 0);
75 static uint32_t highLatencyFailuresToMavSysStatus(mavlink_high_latency2_t& highLatency2);
76 static QString compIdToString (uint8_t compId);
77
78 // Expose mavlink enums to Qml. I've tried various way to make this work without duping, but haven't found anything that works.
79
80#if defined(__clang__) || defined(__GNUC__)
81#pragma GCC diagnostic push
82#pragma GCC diagnostic ignored "-Wshadow"
83#endif
84#if defined(_MSC_VER)
85#pragma warning(push)
86#pragma warning(disable: 4456)
87#endif
88
90 MAV_BATTERY_FUNCTION_UNKNOWN=0, /* Battery function is unknown | */
91 MAV_BATTERY_FUNCTION_ALL=1, /* Battery supports all flight systems | */
92 MAV_BATTERY_FUNCTION_PROPULSION=2, /* Battery for the propulsion system | */
93 MAV_BATTERY_FUNCTION_AVIONICS=3, /* Avionics battery | */
94 MAV_BATTERY_TYPE_PAYLOAD=4, /* Payload battery | */
95 };
96 Q_ENUM(MAV_BATTERY_FUNCTION)
97
99 {
100 MAV_BATTERY_CHARGE_STATE_UNDEFINED=0, /* Low battery state is not provided | */
101 MAV_BATTERY_CHARGE_STATE_OK=1, /* Battery is not in low state. Normal operation. | */
102 MAV_BATTERY_CHARGE_STATE_LOW=2, /* Battery state is low, warn and monitor close. | */
103 MAV_BATTERY_CHARGE_STATE_CRITICAL=3, /* Battery state is critical, return or abort immediately. | */
104 MAV_BATTERY_CHARGE_STATE_EMERGENCY=4, /* Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage. | */
105 MAV_BATTERY_CHARGE_STATE_FAILED=5, /* Battery failed, damage unavoidable. | */
106 MAV_BATTERY_CHARGE_STATE_UNHEALTHY=6, /* Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. | */
107 MAV_BATTERY_CHARGE_STATE_CHARGING=7, /* Battery is charging. | */
108 };
109 Q_ENUM(MAV_BATTERY_CHARGE_STATE)
110
111#if defined(__clang__) || defined(__GNUC__)
112#pragma GCC diagnostic pop
113#endif
114#if defined(_MSC_VER)
115#pragma warning(pop)
116#endif
117
120 SysStatusSensor3dGyro = MAV_SYS_STATUS_SENSOR_3D_GYRO,
121 SysStatusSensor3dAccel = MAV_SYS_STATUS_SENSOR_3D_ACCEL,
122 SysStatusSensor3dMag = MAV_SYS_STATUS_SENSOR_3D_MAG,
123 SysStatusSensorAbsolutePressure = MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE,
124 SysStatusSensorDifferentialPressure = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
125 SysStatusSensorGPS = MAV_SYS_STATUS_SENSOR_GPS,
126 SysStatusSensorOpticalFlow = MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW,
127 SysStatusSensorVisionPosition = MAV_SYS_STATUS_SENSOR_VISION_POSITION,
128 SysStatusSensorLaserPosition = MAV_SYS_STATUS_SENSOR_LASER_POSITION,
129 SysStatusSensorExternalGroundTruth = MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH,
130 SysStatusSensorAngularRateControl = MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL,
131 SysStatusSensorAttitudeStabilization = MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION,
132 SysStatusSensorYawPosition = MAV_SYS_STATUS_SENSOR_YAW_POSITION,
133 SysStatusSensorZAltitudeControl = MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL,
134 SysStatusSensorXYPositionControl = MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL,
135 SysStatusSensorMotorOutputs = MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS,
136 SysStatusSensorRCReceiver = MAV_SYS_STATUS_SENSOR_RC_RECEIVER,
137 SysStatusSensor3dGyro2 = MAV_SYS_STATUS_SENSOR_3D_GYRO2,
138 SysStatusSensor3dAccel2 = MAV_SYS_STATUS_SENSOR_3D_ACCEL2,
139 SysStatusSensor3dMag2 = MAV_SYS_STATUS_SENSOR_3D_MAG2,
140 SysStatusSensorGeoFence = MAV_SYS_STATUS_GEOFENCE,
141 SysStatusSensorAHRS = MAV_SYS_STATUS_AHRS,
142 SysStatusSensorTerrain = MAV_SYS_STATUS_TERRAIN,
143 SysStatusSensorReverseMotor = MAV_SYS_STATUS_REVERSE_MOTOR,
144 SysStatusSensorLogging = MAV_SYS_STATUS_LOGGING,
145 SysStatusSensorBattery = MAV_SYS_STATUS_SENSOR_BATTERY,
146 };
147 Q_ENUM(MavlinkSysStatus)
148
150 GripperActionRelease = GRIPPER_ACTION_RELEASE,
151 GripperActionGrab = GRIPPER_ACTION_GRAB,
152 GripperActionHold = GRIPPER_ACTION_HOLD,
153 GripperOptionInvalid = GRIPPER_ACTIONS_ENUM_END,
154 };
155 Q_ENUM(GripperActions)
156
173 Q_ENUM(CalibrationType)
174
175 MAVPACKED(
176 typedef struct param_ext_union {
177 union {
178 float param_float;
179 double param_double;
180 int64_t param_int64;
181 uint64_t param_uint64;
182 int32_t param_int32;
183 uint32_t param_uint32;
184 int16_t param_int16;
185 uint16_t param_uint16;
186 int8_t param_int8;
187 uint8_t param_uint8;
188 uint8_t bytes[MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN];
189 };
190 uint8_t type;
191 }) param_ext_union_t;
192
193 static bool isValidChannel(uint8_t channel) { return (channel < MAVLINK_COMM_NUM_BUFFERS); }
194 static bool isValidChannel(mavlink_channel_t channel) { return isValidChannel(static_cast<uint8_t>(channel)); }
195
196 static mavlink_status_t* getChannelStatus(mavlink_channel_t channel) { return mavlink_get_channel_status(static_cast<uint8_t>(channel)); }
197
198 static const QHash<int, QString> mavlinkCompIdHash;
199};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
mavlink_channel_t
Definition MAVLinkLib.h:7
mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
Definition QGCMAVLink.cc:50
#define MAVLINK_COMM_NUM_BUFFERS
Definition MAVLinkLib.h:27
Q_DECLARE_METATYPE(satellite_info_s)