QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ArduSubFirmwarePlugin.h
Go to the documentation of this file.
1#pragma once
2
3#include "FactGroup.h"
4#include "APMFirmwarePlugin.h"
5
7{
8 Q_OBJECT
9 Q_PROPERTY(Fact *camTilt READ camTilt CONSTANT)
10 Q_PROPERTY(Fact *tetherTurns READ tetherTurns CONSTANT)
11 Q_PROPERTY(Fact *lightsLevel1 READ lightsLevel1 CONSTANT)
12 Q_PROPERTY(Fact *lightsLevel2 READ lightsLevel2 CONSTANT)
13 Q_PROPERTY(Fact *pilotGain READ pilotGain CONSTANT)
14 Q_PROPERTY(Fact *inputHold READ inputHold CONSTANT)
15 Q_PROPERTY(Fact *rangefinderDistance READ rangefinderDistance CONSTANT)
16 Q_PROPERTY(Fact *rangefinderTarget READ rangefinderTarget CONSTANT)
17
18public:
19 explicit APMSubmarineFactGroup(QObject *parent = nullptr);
21
22 Fact *camTilt() { return &_camTiltFact; }
23 Fact *tetherTurns() { return &_tetherTurnsFact; }
24 Fact *lightsLevel1() { return &_lightsLevel1Fact; }
25 Fact *lightsLevel2() { return &_lightsLevel2Fact; }
26 Fact *pilotGain() { return &_pilotGainFact; }
27 Fact *inputHold() { return &_inputHoldFact; }
28 Fact *rangefinderDistance() { return &_rangefinderDistanceFact; }
29 Fact *rangefinderTarget() { return &_rangefinderTargetFact; }
30
31private:
32 Fact _camTiltFact = Fact(0, QStringLiteral("cameraTilt"), FactMetaData::valueTypeDouble);
33 Fact _tetherTurnsFact = Fact(0, QStringLiteral("tetherTurns"), FactMetaData::valueTypeDouble);
34 Fact _lightsLevel1Fact = Fact(0, QStringLiteral("lights1"), FactMetaData::valueTypeDouble);
35 Fact _lightsLevel2Fact = Fact(0, QStringLiteral("lights2"), FactMetaData::valueTypeDouble);
36 Fact _pilotGainFact = Fact(0, QStringLiteral("pilotGain"), FactMetaData::valueTypeDouble);
37 Fact _inputHoldFact = Fact(0, QStringLiteral("inputHold"), FactMetaData::valueTypeDouble);
38 Fact _rollPitchToggleFact = Fact(0, QStringLiteral("rollPitchToggle"), FactMetaData::valueTypeDouble);
39 Fact _rangefinderDistanceFact = Fact(0, QStringLiteral("rangefinderDistance"), FactMetaData::valueTypeDouble);
40 Fact _rangefinderTargetFact = Fact(0, QStringLiteral("rangefinderTarget"), FactMetaData::valueTypeDouble);
41};
42
43/*===========================================================================*/
44
46{
47 enum Mode : uint32_t {
48 STABILIZE = 0, // Hold level position
49 ACRO = 1, // Manual angular rate, throttle
50 ALT_HOLD = 2, // Depth hold
51 AUTO = 3, // Full auto to waypoint
52 GUIDED = 4, // Full auto to coordinate/direction
55 CIRCLE = 7, // Auto circling
57 SURFACE = 9, // Auto return to surface
64 POSHOLD = 16, // Hold position
67 MANUAL = 19,
69 SURFTRAK = 21, // Surface (seafloor) tracking, aka hold range
70 };
71};
72
74{
75 Q_OBJECT
76
77public:
78 explicit ArduSubFirmwarePlugin(QObject *parent = nullptr);
80
81 int defaultJoystickTXMode() const override { return 3; }
82 void initializeStreamRates(Vehicle *vehicle) override;
83 bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const override;
84 bool supportsThrottleModeCenterZero() const override { return true; }
85 bool supportsNegativeThrust(Vehicle *vehicle) const override { Q_UNUSED(vehicle); return true; }
86 bool supportsRadio() const override { return false; }
87 bool supportsJSButton() const override { return true; }
88 bool supportsMotorInterference() const override { return false; }
89
91 QString vehicleImageOpaque(const Vehicle* /*vehicle*/) const override { return QStringLiteral("/qmlimages/subVehicleArrowOpaque.png"); }
92
94 QString vehicleImageOutline(const Vehicle* vehicle) const override;
95
96 const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap() const override { return _remapParamName; }
97 int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override;
98 bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override;
99 QMap<QString, FactGroup*> *factGroups() override;
100 void adjustMetaData(MAV_TYPE vehicleType, FactMetaData *metaData) override;
101
102 QString stabilizedFlightMode() const override;
103 QString motorDetectionFlightMode() const override;
104 void updateAvailableFlightModes(FlightModeList &modeList) override;
105
106 QString offlineEditingParamFile(Vehicle *vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Sub.OfflineEditing.params"); }
107
108protected:
109 uint32_t _convertToCustomFlightModeEnum(uint32_t val) const override;
110
111 const QString _manualFlightMode = tr("Manual");
112 const QString _stabilizeFlightMode = tr("Stabilize");
113 const QString _acroFlightMode = tr("Acro");
114 const QString _altHoldFlightMode = tr("Depth Hold");
115 const QString _autoFlightMode = tr("Auto");
116 const QString _guidedFlightMode = tr("Guided");
117 const QString _circleFlightMode = tr("Circle");
118 const QString _surfaceFlightMode = tr("Surface");
119 const QString _posHoldFlightMode =tr("Position Hold");
120 const QString _motorDetectionFlightMode = tr("Motor Detection");
121 const QString _surftrakFlightMode = tr("Surftrak");
122
123private:
124 QVariantList _toolIndicators;
125 static bool _remapParamNameIntialized;
126 QMap<QString, QString> _factRenameMap;
128 void _handleNamedValueFloat(mavlink_message_t *message);
129 void _handleMavlinkMessage(mavlink_message_t *message);
130
131 QMap<QString, FactGroup*> _nameToFactGroupMap;
132 APMSubmarineFactGroup _infoFactGroup;
133};
QList< FirmwareFlightMode > FlightModeList
struct __mavlink_message mavlink_message_t
This is the base class for all stack specific APM firmware plugins.
void initializeStreamRates(Vehicle *vehicle) override
QMap< QString, FactGroup * > * factGroups() override
Returns a pointer to a dictionary of firmware-specific FactGroups.
uint32_t _convertToCustomFlightModeEnum(uint32_t val) const override
const FirmwarePlugin::remapParamNameMajorVersionMap_t & paramNameRemapMajorVersionMap() const override
void adjustMetaData(MAV_TYPE vehicleType, FactMetaData *metaData) override
QString stabilizedFlightMode() const override
Returns the flight mode for Stabilized.
bool supportsNegativeThrust(Vehicle *vehicle) const override
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override
bool supportsRadio() const override
QString vehicleImageOpaque(const Vehicle *) const override
Return the resource file which contains the vehicle icon used in the flight view when the view is dar...
bool supportsMotorInterference() const override
const QString _motorDetectionFlightMode
QString offlineEditingParamFile(Vehicle *vehicle) const override
Return the resource file which contains the set of params loaded for offline editing.
QString vehicleImageOutline(const Vehicle *vehicle) const override
Return the resource file which contains the vehicle icon used in the flight view when the view is lig...
bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override
bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const override
int defaultJoystickTXMode() const override
bool supportsJSButton() const override
bool supportsThrottleModeCenterZero() const override
QString motorDetectionFlightMode() const override
Returns the flight mode for Motor Detection.
void updateAvailableFlightModes(FlightModeList &modeList) override
Update Available flight modes recieved from vehicle.
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
Holds the meta data associated with a Fact.
A Fact is used to hold a single value within the system.
Definition Fact.h:17
FirmwareCapabilities
Set of optional capabilites which firmware may support.
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t