7#include <QtCore/QMutex>
8#include <QtNetwork/QAbstractSocket>
37 QString
flightMode(uint8_t base_mode, uint32_t custom_mode)
const override;
57 MAV_AUTOPILOT
_autopilotType()
const override {
return MAV_AUTOPILOT_ARDUPILOTMEGA; }
76 static qreal
calcAltOffsetPT(uint32_t atmospheric1, qreal temperature1, uint32_t atmospheric2, qreal temperature2);
77 static qreal
calcAltOffsetP(uint32_t atmospheric1, uint32_t atmospheric2);
84 void setSupportedModes(QList<APMCustomMode> supportedModes) { _supportedModes = supportedModes; }
94 void _artooSocketError(QAbstractSocket::SocketError socketError);
103 void _soloVideoHandshake();
104 bool _guidedModeTakeoff(
Vehicle *vehicle,
double altitudeRel)
const;
107 QString _getLatestVersionFileUrl(
Vehicle *vehicle)
const final;
108 QString _versionRegex() const final {
return QStringLiteral(
" V([0-9,\\.]*)$"); }
111 static void _setBaroGndTemp(
Vehicle *vehicle, qreal temperature);
112 static void _setBaroAltOffset(
Vehicle *vehicle, qreal offset);
117 QVariantList _toolIndicatorList;
118 QList<APMCustomMode> _supportedModes;
119 QMap<
int , QMap<
int ,
bool >> _ardupilotComponentMap;
121 QMutex _adjustOutgoingMavlinkMutex;
123 static constexpr const char *_artooIP =
"10.1.1.1";
124 static constexpr int _artooVideoHandshakePort = 5502;
126 static uint8_t _reencodeMavlinkChannel();
127 static QMutex &_reencodeMavlinkChannelMutex();
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;
136 static FirmwareParameterHeader _parseParamsHeader(
const QString &filePath);
145 using FirmwarePluginInstanceData::FirmwarePluginInstanceData;
157 case MAV_CMD_DO_SET_MISSION_CURRENT:
struct __mavlink_message mavlink_message_t
bool MAV_CMD_DO_REPOSITION_unsupported
QTime lastHomePositionTime
CommandSupportedResult anyVersionSupportsCommand(MAV_CMD cmd) const final
bool MAV_CMD_DO_REPOSITION_supported
QTime lastBatteryStatusTime
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.
virtual ~APMFirmwarePlugin()
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...