QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
PX4FirmwarePlugin.h
Go to the documentation of this file.
1#pragma once
2
3#include "FirmwarePlugin.h"
4#include "QGCMAVLink.h"
5
7{
8 Q_OBJECT
9
10public:
12 virtual ~PX4FirmwarePlugin ();
13
14 // Called internally only
15 void _changeAltAfterPause(void* resultHandlerData, bool pauseSucceeded);
16
17 // Overrides from FirmwarePlugin
18
19 QList<MAV_CMD> supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass) const override;
20
21 AutoPilotPlugin* autopilotPlugin (Vehicle* vehicle) const override;
22 bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities) const override;
23 QStringList flightModes (Vehicle* vehicle) const override;
24 QString flightMode (uint8_t base_mode, uint32_t custom_mode) const override;
25 bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) const override;
26 void setGuidedMode (Vehicle* vehicle, bool guidedMode) const override;
27 QString pauseFlightMode (void) const override;
28 QString missionFlightMode (void) const override;
29 QString rtlFlightMode (void) const override;
30 QString landFlightMode (void) const override;
31 QString takeControlFlightMode (void) const override;
32 QString gotoFlightMode (void) const override;
33 QString followFlightMode (void) const override;
34 QString takeOffFlightMode (void) const override;
35 QString stabilizedFlightMode (void) const override;
36 void pauseVehicle (Vehicle* vehicle) const override;
37 void guidedModeRTL (Vehicle* vehicle, bool smartRTL) const override;
38 void guidedModeLand (Vehicle* vehicle) const override;
39 void guidedModeTakeoff (Vehicle* vehicle, double takeoffAltRel) const override;
40 double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle* vehicle) const override;
41 double maximumEquivalentAirspeed(Vehicle* vehicle) const override;
42 double minimumEquivalentAirspeed(Vehicle* vehicle) const override;
43 bool mulirotorSpeedLimitsAvailable(Vehicle* vehicle) const override;
44 bool fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) const override;
45 bool guidedModeGotoLocation (Vehicle* vehicle, const QGeoCoordinate& gotoCoord, double forwardFlightLoiterRadius) const override;
46 void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeRel, bool pauseVehicle) override;
47 void guidedModeChangeGroundSpeedMetersSecond(Vehicle* vehicle, double groundspeed) const override;
48 void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv) const override;
49 void guidedModeChangeHeading (Vehicle* vehicle, const QGeoCoordinate &headingCoord) const override;
50 void startTakeoff (Vehicle* vehicle) const override;
51 void startMission (Vehicle* vehicle) const override;
52 bool isGuidedMode (const Vehicle* vehicle) const override;
53 void initializeVehicle (Vehicle* vehicle) override;
54 bool sendHomePositionToVehicle (void) const override;
55 QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override;
56 QString _internalParameterMetaDataFile (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.json"); }
57 MAV_AUTOPILOT _autopilotType () const override { return MAV_AUTOPILOT_PX4; }
59 bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override;
60 QString offlineEditingParamFile (Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); }
61 QString autoDisarmParameter (Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); }
62 uint32_t highLatencyCustomModeTo32Bits (uint16_t hlCustomMode) const override;
63 bool supportsNegativeThrust (Vehicle* vehicle) const override;
64 QString getHobbsMeter (Vehicle* vehicle) const override;
65 bool hasGripper (const Vehicle* vehicle) const override;
66 QVariant expandedToolbarIndicatorSource (const Vehicle* vehicle, const QString& indicatorName) const override;
67
68 void updateAvailableFlightModes (FlightModeList &modeList) override;
69
70private slots:
71 void _mavCommandResult(int vehicleId, int component, int command, int result, int failureCode);
72
73private:
74 void _handleAutopilotVersion (Vehicle* vehicle, mavlink_message_t* message);
75
76 QString _getLatestVersionFileUrl (Vehicle* vehicle) const override;
77 QString _versionRegex () const override;
78
79 // Any instance data here must be global to all vehicles
80 // Vehicle specific data should go into PX4FirmwarePluginInstanceData
81};
82
84{
85 Q_OBJECT
86
87public:
88 PX4FirmwarePluginInstanceData(QObject* parent = nullptr);
89
90 // anyVersionSupportsCommand returns
91 // CommandSupportedResult::SUPPORTED if any version of the
92 // firmware has supported cmd. It return UNSUPPORTED if no
93 // version ever has. It returns UNKNOWN if that information is
94 // not known.
96 switch (cmd) {
97 case MAV_CMD_DO_SET_MISSION_CURRENT:
99 default:
101 }
102 }
103
105};
QList< FirmwareFlightMode > FlightModeList
struct __mavlink_message mavlink_message_t
The AutoPilotPlugin class is an abstract base class which represents the methods and objects which ar...
The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware ...
FirmwareCapabilities
Set of optional capabilites which firmware may support.
bool versionNotified
true: user notified over version issue
CommandSupportedResult anyVersionSupportsCommand(MAV_CMD cmd) const override
void initializeVehicle(Vehicle *vehicle) override
Called when Vehicle is first created to perform any firmware specific setup.
bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const override
bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override
void setGuidedMode(Vehicle *vehicle, bool guidedMode) const override
Set guided flight mode.
QString gotoFlightMode(void) const override
Returns the flight mode which the vehicle will be in if it is performing a goto location.
QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass) const override
List of supported mission commands. Empty list for all commands supported.
bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const override
QString flightMode(uint8_t base_mode, uint32_t custom_mode) const override
QString takeOffFlightMode(void) const override
Returns the flight mode for TakeOff.
QString pauseFlightMode(void) const override
Returns The flight mode which indicates the vehicle is paused.
bool sendHomePositionToVehicle(void) const override
bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const override
void startMission(Vehicle *vehicle) const override
Command the vehicle to start the mission.
void updateAvailableFlightModes(FlightModeList &modeList) override
Update Available flight modes recieved from vehicle.
MAV_AUTOPILOT _autopilotType() const override
QString _internalParameterMetaDataFile(const Vehicle *vehicle) const override
ParameterMetaData * _createParameterMetaData() final
QString takeControlFlightMode(void) const override
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
bool fixedWingAirSpeedLimitsAvailable(Vehicle *vehicle) const override
QString missionFlightMode(void) const override
Returns the flight mode for running missions.
void pauseVehicle(Vehicle *vehicle) const override
QString autoDisarmParameter(Vehicle *vehicle) const override
QString landFlightMode(void) const override
Returns the flight mode for Land.
QString rtlFlightMode(void) const override
Returns the flight mode for RTL.
void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const override
Command vehicle to return to launch.
void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const override
Command vehicle to rotate towards specified location.
uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const override
Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
void startTakeoff(Vehicle *vehicle) const override
Command the vehicle to start a takeoff.
double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *vehicle) const override
QStringList flightModes(Vehicle *vehicle) const override
QString getHobbsMeter(Vehicle *vehicle) const override
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
bool isGuidedMode(const Vehicle *vehicle) const override
Returns whether the vehicle is in guided mode or not.
QString offlineEditingParamFile(Vehicle *vehicle) const override
Return the resource file which contains the set of params loaded for offline editing.
void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const override
Command vehicle to takeoff from current location to the specified height.
QVariant expandedToolbarIndicatorSource(const Vehicle *vehicle, const QString &indicatorName) const override
double minimumEquivalentAirspeed(Vehicle *vehicle) const override
QString followFlightMode(void) const override
Returns the flight mode which the vehicle will be for follow me.
void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const override
bool supportsNegativeThrust(Vehicle *vehicle) const override
bool mulirotorSpeedLimitsAvailable(Vehicle *vehicle) const override
QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const override
double maximumEquivalentAirspeed(Vehicle *vehicle) const override
void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeRel, bool pauseVehicle) override
QString stabilizedFlightMode(void) const override
Returns the flight mode for Stabilized.
void _changeAltAfterPause(void *resultHandlerData, bool pauseSucceeded)
AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const override
bool hasGripper(const Vehicle *vehicle) const override
void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const override
void guidedModeLand(Vehicle *vehicle) const override
Command vehicle to land at current location.