QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APMFirmwarePlugin.h
Go to the documentation of this file.
1#pragma once
2
3#include "FirmwarePlugin.h"
4#include "FollowMe.h"
5#include "QGCMAVLink.h"
6
7#include <QtCore/QMutex>
8#include <QtNetwork/QAbstractSocket>
9
11{
12 enum Mode : uint32_t {
13 AUTO = 3,
14 GUIDED = 4,
15 RTL = 6,
16 SMART_RTL = 21
17 };
18};
19
23{
24 Q_OBJECT
25
26public:
27 QList<MAV_CMD> supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass) const override;
28 AutoPilotPlugin *autopilotPlugin(Vehicle* vehicle) const override;
29 bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const override;
30 void setGuidedMode(Vehicle *vehicle, bool guidedMode) const override;
31 void guidedModeTakeoff(Vehicle *vehicle, double altitudeRel) const override;
32 bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate& gotoCoord, double forwardFlightLoiterRadius) const override;
33 double minimumTakeoffAltitudeMeters(Vehicle *vehicle) const override;
34 void startTakeoff(Vehicle *vehicle) const override;
35 void startMission(Vehicle *vehicle) const override;
36 QStringList flightModes(Vehicle *vehicle) const override;
37 QString flightMode(uint8_t base_mode, uint32_t custom_mode) const override;
38 bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const override;
39 bool MAV_CMD_DO_SET_MODE_is_supported() const override { return true; }
40 bool isGuidedMode(const Vehicle *vehicle) const override;
41 QString gotoFlightMode() const override { return guidedFlightMode(); }
42 QString rtlFlightMode() const override;
43 QString smartRTLFlightMode() const override;
44 QString missionFlightMode() const override;
45 virtual QString guidedFlightMode() const;
46 void pauseVehicle(Vehicle *vehicle) const override;
47 void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const override;
48 void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle) override;
49 void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const override;
50 bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override;
51 void adjustOutgoingMavlinkMessageThreadSafe(Vehicle *vehicle, LinkInterface *outgoingLink, mavlink_message_t *message) override;
52 virtual void initializeStreamRates(Vehicle *vehicle);
53 void initializeVehicle(Vehicle *vehicle) override;
54 bool sendHomePositionToVehicle() const override { return true; }
55 QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const override;
56 QString _internalParameterMetaDataFile(const Vehicle* vehicle) const override;
57 MAV_AUTOPILOT _autopilotType() const override { return MAV_AUTOPILOT_ARDUPILOTMEGA; }
59 QString getHobbsMeter(Vehicle *vehicle) const override;
60 bool hasGripper(const Vehicle *vehicle) const override;
61 const QVariantList &toolIndicators(const Vehicle *vehicle) override;
62 double maximumEquivalentAirspeed(Vehicle *vehicle) const override;
63 double minimumEquivalentAirspeed(Vehicle *vehicle) const override;
64 bool fixedWingAirSpeedLimitsAvailable(Vehicle *vehicle) const override;
65 void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv) const override;
66 void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) const override;
67 QVariant expandedToolbarIndicatorSource (const Vehicle* vehicle, const QString& indicatorName) const override;
68
69 // support for changing speed in Copter guide mode:
70 bool mulirotorSpeedLimitsAvailable(Vehicle *vehicle) const override;
71 double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *vehicle) const override;
72 void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double speed) const override;
73
74 static QPair<QMetaObject::Connection,QMetaObject::Connection> startCompensatingBaro(Vehicle *vehicle);
75 static bool stopCompensatingBaro(const Vehicle *vehicle, QPair<QMetaObject::Connection,QMetaObject::Connection> updaters);
76 static qreal calcAltOffsetPT(uint32_t atmospheric1, qreal temperature1, uint32_t atmospheric2, qreal temperature2);
77 static qreal calcAltOffsetP(uint32_t atmospheric1, uint32_t atmospheric2);
78
79protected:
81 explicit APMFirmwarePlugin(QObject *parent = nullptr);
82 virtual ~APMFirmwarePlugin();
83
84 void setSupportedModes(QList<APMCustomMode> supportedModes) { _supportedModes = supportedModes; }
85
86 bool _coaxialMotors = false;
87
88 const QString _guidedFlightMode = tr("Guided");
89 const QString _rtlFlightMode = tr("RTL");
90 const QString _smartRtlFlightMode = tr("Smart RTL");
91 const QString _autoFlightMode = tr("Auto");
92
93private slots:
94 void _artooSocketError(QAbstractSocket::SocketError socketError);
95
96private:
97 void _adjustCalibrationMessageSeverity(mavlink_message_t *message) const;
98 void _setInfoSeverity(mavlink_message_t *message) const;
99 void _handleIncomingParamValue(Vehicle *vehicle, mavlink_message_t *message);
100 bool _handleIncomingStatusText(Vehicle *vehicle, mavlink_message_t *message);
101 void _handleIncomingHeartbeat(Vehicle *vehicle, mavlink_message_t *message);
102 void _handleOutgoingParamSetThreadSafe(Vehicle *vehicle, LinkInterface *outgoingLink, mavlink_message_t *message);
103 void _soloVideoHandshake();
104 bool _guidedModeTakeoff(Vehicle *vehicle, double altitudeRel) const;
105 void _handleRCChannels(Vehicle *vehicle, mavlink_message_t* message);
106 void _handleRCChannelsRaw(Vehicle *vehicle, mavlink_message_t* message);
107 QString _getLatestVersionFileUrl(Vehicle *vehicle) const final;
108 QString _versionRegex() const final { return QStringLiteral(" V([0-9,\\.]*)$"); }
109 QString _vehicleClassToString(QGCMAVLink::VehicleClass_t vehicleClass) const;
110
111 static void _setBaroGndTemp(Vehicle *vehicle, qreal temperature);
112 static void _setBaroAltOffset(Vehicle *vehicle, qreal offset);
113
114 // Any instance data here must be global to all vehicles
115 // Vehicle specific data should go into APMFirmwarePluginInstanceData
116
117 QVariantList _toolIndicatorList;
118 QList<APMCustomMode> _supportedModes;
119 QMap<int /* vehicle id */, QMap<int /* componentId */, bool /* true: component is part of ArduPilot stack */>> _ardupilotComponentMap;
120
121 QMutex _adjustOutgoingMavlinkMutex;
122
123 static constexpr const char *_artooIP = "10.1.1.1";
124 static constexpr int _artooVideoHandshakePort = 5502;
125
126 static uint8_t _reencodeMavlinkChannel();
127 static QMutex &_reencodeMavlinkChannelMutex();
128
129 struct FirmwareParameterHeader {
130 MAV_AUTOPILOT firmwareType = MAV_AUTOPILOT_GENERIC;
131 MAV_TYPE vehicleType = MAV_TYPE_GENERIC;
132 QVersionNumber versionNumber;
133 FIRMWARE_VERSION_TYPE versionType;
134 QString gitRevision;
135 };
136 static FirmwareParameterHeader _parseParamsHeader(const QString &filePath);
137};
138
139/*===========================================================================*/
140
142{
143 Q_OBJECT
144
145 using FirmwarePluginInstanceData::FirmwarePluginInstanceData;
146
147public:
148
149 // anyVersionSupportsCommand returns
150 // CommandSupportedResult::SUPPORTED if any version of the
151 // firmware has supported cmd. It return UNSUPPORTED if no
152 // version ever has. It returns UNKNOWN if that information is
153 // not known.
155 {
156 switch (cmd) {
157 case MAV_CMD_DO_SET_MISSION_CURRENT:
159 default:
161 }
162 }
163
166
169};
struct __mavlink_message mavlink_message_t
CommandSupportedResult anyVersionSupportsCommand(MAV_CMD cmd) const final
This is the base class for all stack specific APM firmware plugins.
bool isGuidedMode(const Vehicle *vehicle) const override
Returns whether the vehicle is in guided mode or not.
QVariant expandedToolbarIndicatorSource(const Vehicle *vehicle, const QString &indicatorName) const override
void setGuidedMode(Vehicle *vehicle, bool guidedMode) const override
Set guided flight mode.
bool sendHomePositionToVehicle() const override
QString flightMode(uint8_t base_mode, uint32_t custom_mode) const override
QString rtlFlightMode() const override
Returns the flight mode for RTL.
bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const override
static qreal calcAltOffsetPT(uint32_t atmospheric1, qreal temperature1, uint32_t atmospheric2, qreal temperature2)
QString getHobbsMeter(Vehicle *vehicle) const override
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimatationCapabilities) const override
Sends the appropriate mavlink message for follow me support.
bool fixedWingAirSpeedLimitsAvailable(Vehicle *vehicle) const override
bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const override
static QPair< QMetaObject::Connection, QMetaObject::Connection > startCompensatingBaro(Vehicle *vehicle)
void setSupportedModes(QList< APMCustomMode > supportedModes)
void startMission(Vehicle *vehicle) const override
Command the vehicle to start the mission.
virtual void initializeStreamRates(Vehicle *vehicle)
const QString _guidedFlightMode
QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const override
void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double speed) const override
void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const override
Command vehicle to rotate towards specified location.
bool hasGripper(const Vehicle *vehicle) const override
double minimumTakeoffAltitudeMeters(Vehicle *vehicle) const override
QStringList flightModes(Vehicle *vehicle) const override
MAV_AUTOPILOT _autopilotType() const override
void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const override
Command vehicle to return to launch.
bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override
static bool stopCompensatingBaro(const Vehicle *vehicle, QPair< QMetaObject::Connection, QMetaObject::Connection > updaters)
void guidedModeTakeoff(Vehicle *vehicle, double altitudeRel) const override
Command vehicle to takeoff from current location to the specified height.
double minimumEquivalentAirspeed(Vehicle *vehicle) const override
void startTakeoff(Vehicle *vehicle) const override
Command the vehicle to start a takeoff.
void adjustOutgoingMavlinkMessageThreadSafe(Vehicle *vehicle, LinkInterface *outgoingLink, mavlink_message_t *message) override
ParameterMetaData * _createParameterMetaData() override
QString smartRTLFlightMode() const override
Returns the flight mode for Smart RTL.
const QString _autoFlightMode
double maximumEquivalentAirspeed(Vehicle *vehicle) const override
QString missionFlightMode() const override
Returns the flight mode for running missions.
void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle) override
bool mulirotorSpeedLimitsAvailable(Vehicle *vehicle) const override
QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass) const override
List of supported mission commands. Empty list for all commands supported.
const QString _smartRtlFlightMode
double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *vehicle) const override
bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const override
void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const override
static qreal calcAltOffsetP(uint32_t atmospheric1, uint32_t atmospheric2)
AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const override
virtual QString guidedFlightMode() const
const QVariantList & toolIndicators(const Vehicle *vehicle) override
bool MAV_CMD_DO_SET_MODE_is_supported() const override
returns true if this flight stack supports MAV_CMD_DO_SET_MODE
QString _internalParameterMetaDataFile(const Vehicle *vehicle) const override
void pauseVehicle(Vehicle *vehicle) const override
void initializeVehicle(Vehicle *vehicle) override
Called when Vehicle is first created to perform any firmware specific setup.
QString gotoFlightMode() const override
Returns the flight mode which the vehicle will be in if it is performing a goto location.
const QString _rtlFlightMode
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.
The link interface defines the interface for all links used to communicate with the ground station ap...