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/QMap>
5#include <QtCore/QString>
6#include <QtCore/QVariantList>
7#include <QtPositioning/QGeoCoordinate>
8
9#include "MAVLinkEnums.h"
10#include "QGCMAVLinkTypes.h"
11#include "FollowMe.h"
12#include "VehicleTypes.h"
13
14class Vehicle;
15
17class AutoPilotPlugin;
18class FactMetaData;
21class Autotune;
22class LinkInterface;
23class FactGroup;
25
27{
28 FirmwareFlightMode(const QString &mName, uint32_t cMode, bool cbs = false, bool adv = false)
29 : mode_name(mName)
30 , custom_mode(cMode)
31 , canBeSet(cbs)
32 , advanced(adv)
33 {
34
35 }
36
37 FirmwareFlightMode(const QString &mName, uint8_t sMode, uint32_t cMode,
38 bool cbs = false, bool adv = false,
39 bool fWing = false, bool mRotor = true
40 )
41 : mode_name(mName)
42 , standard_mode(sMode)
43 , custom_mode(cMode)
44 , canBeSet(cbs)
45 , advanced(adv)
46 , fixedWing(fWing)
47 , multiRotor(mRotor)
48 {
49
50 }
51
52 QString mode_name = "Unknown";
53 uint8_t standard_mode = 0;
54 uint32_t custom_mode = UINT32_MAX;
55 bool canBeSet = false;
56 bool advanced = false;
57 bool fixedWing = false;
58 bool multiRotor = true;
59};
60
61/*===========================================================================*/
62
63typedef QList<FirmwareFlightMode> FlightModeList;
64typedef QMap<uint32_t,QString> FlightModeCustomModeMap;
65
72class FirmwarePlugin : public QObject
73{
74 Q_OBJECT
75
76public:
77 explicit FirmwarePlugin(QObject *parent = nullptr);
78 virtual ~FirmwarePlugin();
79
91
104
108 typedef QMap<QString, QString> remapParamNameMap_t;
109
113 typedef QMap<int, remapParamNameMap_t> remapParamNameMinorVersionRemapMap_t;
114
118 typedef QMap<int, remapParamNameMinorVersionRemapMap_t> remapParamNameMajorVersionMap_t;
119
121 virtual AutoPilotPlugin *autopilotPlugin(Vehicle *vehicle) const;
122
124 virtual void initializeVehicle(Vehicle* /*vehicle*/) {}
125
127 virtual bool isCapable(const Vehicle* /*vehicle*/, FirmwareCapabilities /*capabilities*/) const { return false; }
128
131 virtual QStringList flightModes(Vehicle* /*vehicle*/) const { return QStringList(); }
132
136 virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) const;
137
141 virtual bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const;
142
144 virtual bool MAV_CMD_DO_SET_MODE_is_supported() const { return false; }
145
147 virtual QString pauseFlightMode() const { return QString(); }
148
150 virtual QString missionFlightMode() const { return QString(); }
151
153 virtual QString rtlFlightMode() const { return QString(); }
154
156 virtual QString smartRTLFlightMode() const { return QString(); }
157
158 virtual bool supportsSmartRTL() const { return false; }
159
161 virtual QString landFlightMode() const { return QString(); }
162
164 virtual QString takeOffFlightMode() const { return QString(); }
165
167 virtual QString motorDetectionFlightMode() const { return QString(); }
168
170 virtual QString stabilizedFlightMode() const { return QString(); }
171
173 virtual QString takeControlFlightMode() const { return QString(); }
174
176 virtual bool isGuidedMode(const Vehicle * /*vehicle*/) const { return false; }
177
179 virtual QString gotoFlightMode() const { return QString(); }
180
182 virtual QString followFlightMode() const { return QString(); }
183
185 virtual void setGuidedMode(Vehicle *vehicle, bool guidedMode) const;
186
189 virtual void pauseVehicle(Vehicle *vehicle) const;
190
192 virtual void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const;
193
195 virtual void guidedModeLand(Vehicle *vehicle) const;
196
198 virtual void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const;
199
201 virtual void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const;
202
204 virtual double minimumTakeoffAltitudeMeters(Vehicle* /*vehicle*/) const { return 3.048; }
205
207 virtual double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle* /*vehicle*/) const { return NAN; }
208
210 virtual double maximumEquivalentAirspeed(Vehicle* /*vehicle*/) const { return NAN; }
211
213 virtual double minimumEquivalentAirspeed(Vehicle* /*vehicle*/) const { return NAN; }
214
216 virtual bool hasGripper(const Vehicle* /*vehicle*/) const { return false; }
217
219 virtual bool mulirotorSpeedLimitsAvailable(Vehicle* /*vehicle*/) const { return false; }
220
222 virtual bool fixedWingAirSpeedLimitsAvailable(Vehicle* /*vehicle*/) const { return false; }
223
225 virtual void startTakeoff(Vehicle *vehicle) const;
226
228 virtual void startMission(Vehicle *vehicle) const;
229
232 virtual bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius = 0.0) const;
233
237 virtual void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle);
238
241 virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const;
242
245 virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const;
246
249 virtual int defaultJoystickTXMode() const { return 2; }
250
254 virtual bool supportsThrottleModeCenterZero() const { return true; }
255
258 virtual bool supportsNegativeThrust(Vehicle* /*vehicle*/) const { return false; }
259
262 virtual bool supportsRadio() const { return true; }
263
266 virtual bool supportsJSButton() const { return false; }
267
270 virtual bool supportsMotorInterference() const { return true; }
271
278 virtual bool adjustIncomingMavlinkMessage(Vehicle* /*vehicle*/, mavlink_message_t* /*message*/) { return true; }
279
289 virtual void adjustOutgoingMavlinkMessageThreadSafe(Vehicle* /*vehicle*/, LinkInterface* /*outgoingLink*/, mavlink_message_t* /*message*/) {}
290
299 virtual bool sendHomePositionToVehicle() const { return false; }
300
302 virtual QList<MAV_CMD> supportedMissionCommands(QGCMAVLinkTypes::VehicleClass_t /*vehicleClass*/) const { return QList<MAV_CMD>(); }
303
306 virtual QString missionCommandOverrides(QGCMAVLinkTypes::VehicleClass_t vehicleClass) const;
307
311
315 virtual int remapParamNameHigestMinorVersionNumber(int /*majorVersionNumber*/) const { return VehicleTypes::versionNotSetValue; }
316
318 virtual bool multiRotorCoaxialMotors(Vehicle* /*vehicle*/) const { return false; }
319
321 virtual bool multiRotorXConfig(Vehicle* /*vehicle*/) const { return false; }
322
324 virtual QString offlineEditingParamFile(Vehicle* /*vehicle*/) const { return QString(); }
325
327 virtual QString vehicleImageOpaque(const Vehicle* /*vehicle*/) const { return QStringLiteral("/qmlimages/vehicleArrowOpaque.svg"); }
328
330 virtual QString vehicleImageOutline(const Vehicle* /*vehicle*/) const { return QStringLiteral("/qmlimages/vehicleArrowOutline.svg"); }
331
332 virtual QVariant expandedToolbarIndicatorSource(const Vehicle* /*vehicle*/, const QString& /*indicatorName*/) const { return QVariant(); }
333
337 virtual const QVariantList &toolIndicators(const Vehicle *vehicle);
338
340 virtual QGCCameraManager *createCameraManager(Vehicle *vehicle) const;
341
343 virtual MavlinkCameraControlInterface *createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent = nullptr) const;
344
346 virtual QMap<QString, FactGroup*> *factGroups() { return nullptr; }
347
352 virtual void batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const;
353
354 // Returns the parameter which control auto-disarm. Assume == 0 means no auto disarm
355 virtual QString autoDisarmParameter(Vehicle* /*vehicle*/) const { return QString(); }
356
362 virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const;
363
365 virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const { return hlCustomMode; }
366
368 virtual void checkIfIsLatestStable(Vehicle *vehicle) const;
369
372 int versionCompare(const Vehicle *vehicle, const QString &compare) const;
373 int versionCompare(const Vehicle *vehicle, int major, int minor, int patch) const;
374
378 virtual void adjustMetaData(MAV_TYPE /*vehicleType*/, FactMetaData* /*metaData*/) {}
379
381 virtual void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const;
382
384 virtual QString getHobbsMeter(Vehicle *vehicle) const { Q_UNUSED(vehicle); return QStringLiteral("Not Supported"); }
385
387 virtual Autotune *createAutotune(Vehicle *vehicle) const;
388
390 virtual void updateAvailableFlightModes(FlightModeList &flightModeList) { _updateFlightModeList(flightModeList); }
391
393 void cacheParameterMetaDataFile(const QString &metaDataFile);
394
395signals:
397
398protected:
401 bool _armVehicleAndValidate(Vehicle *vehicle) const;
402
405 bool _setFlightModeAndValidate(Vehicle *vehicle, const QString &flightMode) const;
406
407 virtual QString _internalParameterMetaDataFile(const Vehicle* /*vehicle*/) const { return QString(); }
408 virtual MAV_AUTOPILOT _autopilotType() const { return MAV_AUTOPILOT_GENERIC; }
409 virtual ParameterMetaData *_createParameterMetaData() { return nullptr; }
410 QString _cachedParameterMetaDataFile(const Vehicle *vehicle) const;
411
413 virtual QString _getLatestVersionFileUrl(Vehicle* /*vehicle*/) const { return QString(); }
414
416 virtual void _versionFileDownloadFinished(const QString &remoteFile, const QString &localFile, const Vehicle *vehicle) const;
417
419 virtual QString _versionRegex() const { return QString(); }
420
421 // Set Custom Mode mapping to Flight Mode String
423
424 // Convert Base enum to Derived class Enums
425 virtual uint32_t _convertToCustomFlightModeEnum(uint32_t val) const { return val; }
426
427 // Update internal mappings for a list of flight modes
428 void _updateFlightModeList(FlightModeList &flightModeList);
430
433
434 QVariantList _toolIndicatorList;
435 QVariantList _modeIndicatorList;
436};
437
438/*===========================================================================*/
439
440class FirmwarePluginInstanceData : public QObject
441{
442 Q_OBJECT
443
444public:
445 using QObject::QObject;
446
447 // support for detecting whether the firmware a vehicle is running
448 // supports a given MAV_CMD:
449 enum class CommandSupportedResult : uint8_t {
450 SUPPORTED = 23,
451 UNSUPPORTED = 24,
452 UNKNOWN = 25,
453 };
454 // anyVersionSupportsCommand returns true if any version of the
455 // firmware has supported cmd. Used so that extra round-trips to
456 // the autopilot to probe for command support are not required.
458
459 // support for detecting whether the firmware a vehicle is running
460 // supports a given MAV_CMD:
461 void setCommandSupported(MAV_CMD cmd, CommandSupportedResult status) { MAV_CMD_supported[cmd] = status; }
462
464
465private:
466 QMap<MAV_CMD, CommandSupportedResult> MAV_CMD_supported;
467};
QMap< uint32_t, QString > FlightModeCustomModeMap
QList< FirmwareFlightMode > FlightModeList
struct __mavlink_message mavlink_message_t
struct __mavlink_camera_information_t mavlink_camera_information_t
The AutoPilotPlugin class is an abstract base class which represents the methods and objects which ar...
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
Holds the meta data associated with a Fact.
virtual CommandSupportedResult anyVersionSupportsCommand(MAV_CMD) const
CommandSupportedResult getCommandSupported(MAV_CMD cmd) const
void setCommandSupported(MAV_CMD cmd, CommandSupportedResult status)
The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware ...
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 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.
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
void cacheParameterMetaDataFile(const QString &metaDataFile)
virtual double maximumEquivalentAirspeed(Vehicle *) const
virtual QString missionFlightMode() const
Returns the flight mode for running missions.
virtual QString missionCommandOverrides(QGCMAVLinkTypes::VehicleClass_t vehicleClass) const
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 guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0) const
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
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.
void _addNewFlightMode(FirmwareFlightMode &flightMode)
virtual void pauseVehicle(Vehicle *vehicle) const
virtual QVariant expandedToolbarIndicatorSource(const Vehicle *, const QString &) const
virtual MAV_AUTOPILOT _autopilotType() const
virtual bool mulirotorSpeedLimitsAvailable(Vehicle *) 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
ParameterMetaData * loadParameterMetaData(const Vehicle *vehicle)
virtual AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const
virtual void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const
Command vehicle to return to launch.
virtual ParameterMetaData * _createParameterMetaData()
QVariantList _modeIndicatorList
virtual QString _versionRegex() const
Returns regex QString to extract version information from text.
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLinkTypes::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
virtual QString autoDisarmParameter(Vehicle *) const
virtual QString stabilizedFlightMode() const
Returns the flight mode for Stabilized.
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.
QString _cachedParameterMetaDataFile(const Vehicle *vehicle) const
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.
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 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 double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *) const
virtual const remapParamNameMajorVersionMap_t & paramNameRemapMajorVersionMap() const
virtual bool supportsSmartRTL() const
virtual void guidedModeLand(Vehicle *vehicle) const
Command vehicle to land at current location.
virtual bool sendHomePositionToVehicle() const
virtual MavlinkCameraControlInterface * createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent=nullptr) const
Camera control.
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.
A vehicle component is an object which abstracts the physical portion of a vehicle into a set of conf...
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)
static const int versionNotSetValue