QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FirmwarePlugin.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QList>
4#include <QtCore/QString>
5#include <QtCore/QVariantList>
6#include <QtPositioning/QGeoCoordinate>
7
8#include "QGCMAVLink.h"
9#include "FollowMe.h"
10#include "FactMetaData.h"
11
13class AutoPilotPlugin;
14class Vehicle;
17class Autotune;
18class LinkInterface;
19class FactGroup;
20
22{
23 FirmwareFlightMode(const QString &mName, uint32_t cMode, bool cbs = false, bool adv = false)
24 : mode_name(mName)
25 , custom_mode(cMode)
26 , canBeSet(cbs)
27 , advanced(adv)
28 {
29
30 }
31
32 FirmwareFlightMode(const QString &mName, uint8_t sMode, uint32_t cMode,
33 bool cbs = false, bool adv = false,
34 bool fWing = false, bool mRotor = true
35 )
36 : mode_name(mName)
37 , standard_mode(sMode)
38 , custom_mode(cMode)
39 , canBeSet(cbs)
40 , advanced(adv)
41 , fixedWing(fWing)
42 , multiRotor(mRotor)
43 {
44
45 }
46
47 QString mode_name = "Unknown";
48 uint8_t standard_mode = 0;
49 uint32_t custom_mode = UINT32_MAX;
50 bool canBeSet = false;
51 bool advanced = false;
52 bool fixedWing = false;
53 bool multiRotor = true;
54};
55
56/*===========================================================================*/
57
58typedef QList<FirmwareFlightMode> FlightModeList;
59typedef QMap<uint32_t,QString> FlightModeCustomModeMap;
60
65class FirmwarePlugin : public QObject
66{
67 Q_OBJECT
68
69public:
70 explicit FirmwarePlugin(QObject *parent = nullptr);
71 virtual ~FirmwarePlugin();
72
84
88 typedef QMap<QString, QString> remapParamNameMap_t;
89
93 typedef QMap<int, remapParamNameMap_t> remapParamNameMinorVersionRemapMap_t;
94
98 typedef QMap<int, remapParamNameMinorVersionRemapMap_t> remapParamNameMajorVersionMap_t;
99
101 virtual AutoPilotPlugin *autopilotPlugin(Vehicle *vehicle) const;
102
104 virtual void initializeVehicle(Vehicle* /*vehicle*/) {}
105
107 virtual bool isCapable(const Vehicle* /*vehicle*/, FirmwareCapabilities /*capabilities*/) const { return false; }
108
111 virtual QStringList flightModes(Vehicle* /*vehicle*/) const { return QStringList(); }
112
116 virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) const;
117
121 virtual bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const;
122
124 virtual bool MAV_CMD_DO_SET_MODE_is_supported() const { return false; }
125
127 virtual QString pauseFlightMode() const { return QString(); }
128
130 virtual QString missionFlightMode() const { return QString(); }
131
133 virtual QString rtlFlightMode() const { return QString(); }
134
136 virtual QString smartRTLFlightMode() const { return QString(); }
137
138 virtual bool supportsSmartRTL() const { return false; }
139
141 virtual QString landFlightMode() const { return QString(); }
142
144 virtual QString takeOffFlightMode() const { return QString(); }
145
147 virtual QString motorDetectionFlightMode() const { return QString(); }
148
150 virtual QString stabilizedFlightMode() const { return QString(); }
151
153 virtual QString takeControlFlightMode() const { return QString(); }
154
156 virtual bool isGuidedMode(const Vehicle * /*vehicle*/) const { return false; }
157
159 virtual QString gotoFlightMode() const { return QString(); }
160
162 virtual QString followFlightMode() const { return QString(); }
163
165 virtual void setGuidedMode(Vehicle *vehicle, bool guidedMode) const;
166
169 virtual void pauseVehicle(Vehicle *vehicle) const;
170
172 virtual void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const;
173
175 virtual void guidedModeLand(Vehicle *vehicle) const;
176
178 virtual void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const;
179
181 virtual void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const;
182
184 virtual double minimumTakeoffAltitudeMeters(Vehicle* /*vehicle*/) const { return 3.048; }
185
187 virtual double maximumHorizontalSpeedMultirotor(Vehicle* /*vehicle*/) const { return NAN; }
188
190 virtual double maximumEquivalentAirspeed(Vehicle* /*vehicle*/) const { return NAN; }
191
193 virtual double minimumEquivalentAirspeed(Vehicle* /*vehicle*/) const { return NAN; }
194
196 virtual bool hasGripper(const Vehicle* /*vehicle*/) const { return false; }
197
199 virtual bool mulirotorSpeedLimitsAvailable(Vehicle* /*vehicle*/) const { return false; }
200
202 virtual bool fixedWingAirSpeedLimitsAvailable(Vehicle* /*vehicle*/) const { return false; }
203
205 virtual void startTakeoff(Vehicle *vehicle) const;
206
208 virtual void startMission(Vehicle *vehicle) const;
209
211 virtual void guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius = 0.0) const;
212
216 virtual void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle);
217
220 virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const;
221
224 virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const;
225
228 virtual int defaultJoystickTXMode() const { return 2; }
229
233 virtual bool supportsThrottleModeCenterZero() const { return true; }
234
237 virtual bool supportsNegativeThrust(Vehicle* /*vehicle*/) const { return false; }
238
241 virtual bool supportsRadio() const { return true; }
242
245 virtual bool supportsJSButton() const { return false; }
246
249 virtual bool supportsMotorInterference() const { return true; }
250
257 virtual bool adjustIncomingMavlinkMessage(Vehicle* /*vehicle*/, mavlink_message_t* /*message*/) { return true; }
258
268 virtual void adjustOutgoingMavlinkMessageThreadSafe(Vehicle* /*vehicle*/, LinkInterface* /*outgoingLink*/, mavlink_message_t* /*message*/) {}
269
278 virtual bool sendHomePositionToVehicle() const { return false; }
279
283 virtual void _getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion) const;
284
287 virtual QString _internalParameterMetaDataFile(const Vehicle* /*vehicle*/) const { return QString(); }
288
293 virtual QObject *_loadParameterMetaData(const QString& /*metaDataFile*/) { return nullptr; }
294
298 virtual FactMetaData *_getMetaDataForFact(QObject* /*parameterMetaData*/, const QString& /*name*/, FactMetaData::ValueType_t /* type */, MAV_TYPE /*vehicleType*/) const { return nullptr; }
299
301 virtual QList<MAV_CMD> supportedMissionCommands(QGCMAVLink::VehicleClass_t /*vehicleClass*/) const { return QList<MAV_CMD>(); }
302
305 virtual QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const;
306
309
311 virtual int remapParamNameHigestMinorVersionNumber(int /*majorVersionNumber*/) const { return 0; }
312
314 virtual bool multiRotorCoaxialMotors(Vehicle* /*vehicle*/) const { return false; }
315
317 virtual bool multiRotorXConfig(Vehicle* /*vehicle*/) const { return false; }
318
320 virtual QString offlineEditingParamFile(Vehicle* /*vehicle*/) const { return QString(); }
321
323 virtual QString brandImageIndoor(const Vehicle* /*vehicle*/) const { return QString(); }
324
326 virtual QString brandImageOutdoor(const Vehicle* /*vehicle*/) const { return QString(); }
327
329 virtual QString vehicleImageOpaque(const Vehicle* /*vehicle*/) const { return QStringLiteral("/qmlimages/vehicleArrowOpaque.svg"); }
330
332 virtual QString vehicleImageOutline(const Vehicle* /*vehicle*/) const { return QStringLiteral("/qmlimages/vehicleArrowOutline.svg"); }
333
334 virtual QVariant expandedToolbarIndicatorSource(const Vehicle* /*vehicle*/, const QString& /*indicatorName*/) const { return QVariant(); }
335
339 virtual const QVariantList &toolIndicators(const Vehicle *vehicle);
340
342 virtual QGCCameraManager *createCameraManager(Vehicle *vehicle) const;
343
345 virtual MavlinkCameraControl *createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent = nullptr) const;
346
348 virtual QMap<QString, FactGroup*> *factGroups() { return nullptr; }
349
354 virtual void batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const;
355
356 // Returns the parameter which control auto-disarm. Assume == 0 means no auto disarm
357 virtual QString autoDisarmParameter(Vehicle* /*vehicle*/) const { return QString(); }
358
364 virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const;
365
367 virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const { return hlCustomMode; }
368
370 virtual void checkIfIsLatestStable(Vehicle *vehicle) const;
371
374 int versionCompare(const Vehicle *vehicle, const QString &compare) const;
375 int versionCompare(const Vehicle *vehicle, int major, int minor, int patch) const;
376
380 virtual void adjustMetaData(MAV_TYPE /*vehicleType*/, FactMetaData* /*metaData*/) {}
381
383 virtual void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const;
384
386 virtual QString getHobbsMeter(Vehicle *vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("Not Supported"); }
387
389 virtual Autotune *createAutotune(Vehicle *vehicle) const;
390
392 virtual void updateAvailableFlightModes(FlightModeList &flightModeList) { _updateFlightModeList(flightModeList); }
393
394signals:
396
397protected:
400 bool _armVehicleAndValidate(Vehicle *vehicle) const;
401
404 bool _setFlightModeAndValidate(Vehicle *vehicle, const QString &flightMode) const;
405
407 virtual QString _getLatestVersionFileUrl(Vehicle* /*vehicle*/) const { return QString(); }
408
410 virtual void _versionFileDownloadFinished(const QString &remoteFile, const QString &localFile, const Vehicle *vehicle) const;
411
413 virtual QString _versionRegex() const { return QString(); }
414
415 // Set Custom Mode mapping to Flight Mode String
417
418 // Convert Base enum to Derived class Enums
419 virtual uint32_t _convertToCustomFlightModeEnum(uint32_t val) const { return val; }
420
421 // Update internal mappings for a list of flight modes
422 void _updateFlightModeList(FlightModeList &flightModeList);
424
427
428 QVariantList _toolIndicatorList;
429 QVariantList _modeIndicatorList;
430};
431
432/*===========================================================================*/
433
434class FirmwarePluginInstanceData : public QObject
435{
436 Q_OBJECT
437
438public:
439 using QObject::QObject;
440
441 // support for detecting whether the firmware a vehicle is running
442 // supports a given MAV_CMD:
443 enum class CommandSupportedResult : uint8_t {
444 SUPPORTED = 23,
445 UNSUPPORTED = 24,
446 UNKNOWN = 25,
447 };
448 // anyVersionSupportsCommand returns true if any version of the
449 // firmware has supported cmd. Used so that extra round-trips to
450 // the autopilot to probe for command support are not required.
452
453 // support for detecting whether the firmware a vehicle is running
454 // supports a given MAV_CMD:
455 void setCommandSupported(MAV_CMD cmd, CommandSupportedResult status) { MAV_CMD_supported[cmd] = status; }
456
458
459private:
460 QMap<MAV_CMD, CommandSupportedResult> MAV_CMD_supported;
461};
QMap< uint32_t, QString > FlightModeCustomModeMap
QList< FirmwareFlightMode > FlightModeList
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
virtual CommandSupportedResult anyVersionSupportsCommand(MAV_CMD) const
CommandSupportedResult getCommandSupported(MAV_CMD cmd) const
void setCommandSupported(MAV_CMD cmd, CommandSupportedResult status)
virtual bool supportsNegativeThrust(Vehicle *) const
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
virtual QString motorDetectionFlightMode() const
Returns the flight mode for Motor Detection.
virtual QString pauseFlightMode() const
Returns The flight mode which indicates the vehicle is paused.
virtual QString brandImageOutdoor(const Vehicle *) const
Return the resource file which contains the brand image for the vehicle for Outdoor theme.
virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const
virtual void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle)
virtual bool supportsThrottleModeCenterZero() const
virtual void startMission(Vehicle *vehicle) const
Command the vehicle to start the mission.
virtual void checkIfIsLatestStable(Vehicle *vehicle) const
Used to check if running firmware is latest stable version.
virtual double maximumHorizontalSpeedMultirotor(Vehicle *) const
FlightModeList _flightModeList
virtual bool multiRotorCoaxialMotors(Vehicle *) const
virtual double minimumEquivalentAirspeed(Vehicle *) const
virtual const QVariantList & toolIndicators(const Vehicle *vehicle)
virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const
virtual bool supportsMotorInterference() const
virtual bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const
virtual ~FirmwarePlugin()
virtual bool supportsJSButton() const
FirmwareCapabilities
Set of optional capabilites which firmware may support.
@ ChangeHeadingCapability
Vehicle supports changing heading at current location.
@ GuidedTakeoffCapability
Vehicle supports guided takeoff.
@ TakeoffVehicleCapability
Vehicle supports taking off.
@ GuidedModeCapability
Vehicle supports guided mode commands.
@ OrbitModeCapability
Vehicle supports orbit mode.
@ SetFlightModeCapability
FirmwarePlugin::setFlightMode method is supported.
@ ROIModeCapability
Vehicle supports ROI (both in Fly guided mode and from Plan creation)
@ PauseVehicleCapability
Vehicle supports pausing at current location.
virtual QString vehicleImageOutline(const Vehicle *) const
Return the resource file which contains the vehicle icon used in the flight view when the view is lig...
virtual void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const
Command vehicle to takeoff from current location to the specified height.
virtual bool isCapable(const Vehicle *, FirmwareCapabilities) const
virtual double maximumEquivalentAirspeed(Vehicle *) const
virtual QString missionFlightMode() const
Returns the flight mode for running missions.
bool _setFlightModeAndValidate(Vehicle *vehicle, const QString &flightMode) const
virtual QString _internalParameterMetaDataFile(const Vehicle *) const
virtual uint32_t _convertToCustomFlightModeEnum(uint32_t val) const
QMap< int, remapParamNameMap_t > remapParamNameMinorVersionRemapMap_t
virtual QString _getLatestVersionFileUrl(Vehicle *) const
returns url with latest firmware release information.
void _updateFlightModeList(FlightModeList &flightModeList)
virtual void adjustMetaData(MAV_TYPE, FactMetaData *)
virtual bool adjustIncomingMavlinkMessage(Vehicle *, mavlink_message_t *)
virtual bool fixedWingAirSpeedLimitsAvailable(Vehicle *) const
virtual void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const
Command vehicle to rotate towards specified location.
virtual QString smartRTLFlightMode() const
Returns the flight mode for Smart RTL.
virtual bool multiRotorXConfig(Vehicle *) const
virtual QString takeControlFlightMode() const
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
virtual int remapParamNameHigestMinorVersionNumber(int) const
Returns the highest major version number that is known to the remap for this specified major version.
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) const
virtual QString vehicleImageOpaque(const Vehicle *) const
Return the resource file which contains the vehicle icon used in the flight view when the view is dar...
virtual void startTakeoff(Vehicle *vehicle) const
Command the vehicle to start a takeoff.
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
void _addNewFlightMode(FirmwareFlightMode &flightMode)
virtual void pauseVehicle(Vehicle *vehicle) const
virtual QVariant expandedToolbarIndicatorSource(const Vehicle *, const QString &) const
virtual bool mulirotorSpeedLimitsAvailable(Vehicle *) const
virtual FactMetaData * _getMetaDataForFact(QObject *, const QString &, FactMetaData::ValueType_t, MAV_TYPE) const
int versionCompare(const Vehicle *vehicle, const QString &compare) const
virtual bool hasGripper(const Vehicle *) const
virtual QString landFlightMode() const
Returns the flight mode for Land.
virtual QString gotoFlightMode() const
Returns the flight mode which the vehicle will be in if it is performing a goto location.
virtual Autotune * createAutotune(Vehicle *vehicle) const
Creates Autotune object.
virtual QStringList flightModes(Vehicle *) const
virtual AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const
virtual void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const
Command vehicle to return to launch.
QVariantList _modeIndicatorList
virtual QString _versionRegex() const
Returns regex QString to extract version information from text.
virtual void _getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion) const
virtual MavlinkCameraControl * createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent=nullptr) const
Camera control.
virtual QString autoDisarmParameter(Vehicle *) const
virtual QString stabilizedFlightMode() const
Returns the flight mode for Stabilized.
virtual QString brandImageIndoor(const Vehicle *) const
Return the resource file which contains the brand image for the vehicle for Indoor theme.
virtual void adjustOutgoingMavlinkMessageThreadSafe(Vehicle *, LinkInterface *, mavlink_message_t *)
bool _armVehicleAndValidate(Vehicle *vehicle) const
QVariantList _toolIndicatorList
void toolIndicatorsChanged()
virtual bool supportsRadio() const
virtual void updateAvailableFlightModes(FlightModeList &flightModeList)
Update Available flight modes recieved from vehicle.
virtual void setGuidedMode(Vehicle *vehicle, bool guidedMode) const
Set guided flight mode.
QMap< QString, QString > remapParamNameMap_t
virtual QString takeOffFlightMode() const
Returns the flight mode for TakeOff.
virtual void guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0) const
Command vehicle to move to specified location (altitude is included and relative)
FlightModeCustomModeMap _modeEnumToString
virtual QString followFlightMode() const
Returns the flight mode which the vehicle will be for follow me.
virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const
Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
virtual int defaultJoystickTXMode() const
virtual QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const
virtual void batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const
virtual QGCCameraManager * createCameraManager(Vehicle *vehicle) const
Creates vehicle camera manager.
virtual QString offlineEditingParamFile(Vehicle *) const
Return the resource file which contains the set of params loaded for offline editing.
virtual void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const
Sends the appropriate mavlink message for follow me support.
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
virtual QMap< QString, FactGroup * > * factGroups()
Returns a pointer to a dictionary of firmware-specific FactGroups.
virtual void initializeVehicle(Vehicle *)
Called when Vehicle is first created to perform any firmware specific setup.
virtual bool MAV_CMD_DO_SET_MODE_is_supported() const
returns true if this flight stack supports MAV_CMD_DO_SET_MODE
virtual QString rtlFlightMode() const
Returns the flight mode for RTL.
virtual QObject * _loadParameterMetaData(const QString &)
virtual const remapParamNameMajorVersionMap_t & paramNameRemapMajorVersionMap() const
Returns the mapping structure which is used to map from one parameter name to another based on firmwa...
virtual bool supportsSmartRTL() const
virtual void guidedModeLand(Vehicle *vehicle) const
Command vehicle to land at current location.
virtual bool sendHomePositionToVehicle() const
virtual bool isGuidedMode(const Vehicle *) const
Returns whether the vehicle is in guided mode or not.
virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const
virtual double minimumTakeoffAltitudeMeters(Vehicle *) const
virtual void _versionFileDownloadFinished(const QString &remoteFile, const QString &localFile, const Vehicle *vehicle) const
Callback to process file with latest release information.
virtual QString getHobbsMeter(Vehicle *vehicle) const
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
The link interface defines the interface for all links used to communicate with the ground station ap...
Abstract base class for all camera controls: real and simulated.
Camera Manager.
FirmwareFlightMode(const QString &mName, uint8_t sMode, uint32_t cMode, bool cbs=false, bool adv=false, bool fWing=false, bool mRotor=true)
FirmwareFlightMode(const QString &mName, uint32_t cMode, bool cbs=false, bool adv=false)