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 <QtCore/QLoggingCategory>
4
5#include "FactGroup.h"
6#include "APMFirmwarePlugin.h"
7
8Q_DECLARE_LOGGING_CATEGORY(APMSubmarineFactGroupLog)
9
11{
12 Q_OBJECT
13 Q_PROPERTY(Fact *camTilt READ camTilt CONSTANT)
14 Q_PROPERTY(Fact *tetherTurns READ tetherTurns CONSTANT)
15 Q_PROPERTY(Fact *lightsLevel1 READ lightsLevel1 CONSTANT)
16 Q_PROPERTY(Fact *lightsLevel2 READ lightsLevel2 CONSTANT)
17 Q_PROPERTY(Fact *pilotGain READ pilotGain CONSTANT)
18 Q_PROPERTY(Fact *inputHold READ inputHold CONSTANT)
19 Q_PROPERTY(Fact *rangefinderDistance READ rangefinderDistance CONSTANT)
20 Q_PROPERTY(Fact *rangefinderTarget READ rangefinderTarget CONSTANT)
21
22public:
23 explicit APMSubmarineFactGroup(QObject *parent = nullptr);
25
26 Fact *camTilt() { return &_camTiltFact; }
27 Fact *tetherTurns() { return &_tetherTurnsFact; }
28 Fact *lightsLevel1() { return &_lightsLevel1Fact; }
29 Fact *lightsLevel2() { return &_lightsLevel2Fact; }
30 Fact *pilotGain() { return &_pilotGainFact; }
31 Fact *inputHold() { return &_inputHoldFact; }
32 Fact *rangefinderDistance() { return &_rangefinderDistanceFact; }
33 Fact *rangefinderTarget() { return &_rangefinderTargetFact; }
34
35private:
36 Fact _camTiltFact = Fact(0, QStringLiteral("cameraTilt"), FactMetaData::valueTypeDouble);
37 Fact _tetherTurnsFact = Fact(0, QStringLiteral("tetherTurns"), FactMetaData::valueTypeDouble);
38 Fact _lightsLevel1Fact = Fact(0, QStringLiteral("lights1"), FactMetaData::valueTypeDouble);
39 Fact _lightsLevel2Fact = Fact(0, QStringLiteral("lights2"), FactMetaData::valueTypeDouble);
40 Fact _pilotGainFact = Fact(0, QStringLiteral("pilotGain"), FactMetaData::valueTypeDouble);
41 Fact _inputHoldFact = Fact(0, QStringLiteral("inputHold"), FactMetaData::valueTypeDouble);
42 Fact _rollPitchToggleFact = Fact(0, QStringLiteral("rollPitchToggle"), FactMetaData::valueTypeDouble);
43 Fact _rangefinderDistanceFact = Fact(0, QStringLiteral("rangefinderDistance"), FactMetaData::valueTypeDouble);
44 Fact _rangefinderTargetFact = Fact(0, QStringLiteral("rangefinderTarget"), FactMetaData::valueTypeDouble);
45};
46
47/*===========================================================================*/
48
50{
51 enum Mode : uint32_t {
52 STABILIZE = 0, // Hold level position
53 ACRO = 1, // Manual angular rate, throttle
54 ALT_HOLD = 2, // Depth hold
55 AUTO = 3, // Full auto to waypoint
56 GUIDED = 4, // Full auto to coordinate/direction
59 CIRCLE = 7, // Auto circling
61 SURFACE = 9, // Auto return to surface
68 POSHOLD = 16, // Hold position
71 MANUAL = 19,
73 SURFTRAK = 21, // Surface (seafloor) tracking, aka hold range
74 };
75};
76
78{
79 Q_OBJECT
80
81public:
82 explicit ArduSubFirmwarePlugin(QObject *parent = nullptr);
84
85 int defaultJoystickTXMode() const override { return 3; }
86 void initializeStreamRates(Vehicle *vehicle) override;
87 bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const override;
88 bool supportsThrottleModeCenterZero() const override { return false; }
89 bool supportsRadio() const override { return false; }
90 bool supportsJSButton() const override { return true; }
91 bool supportsMotorInterference() const override { return false; }
92
94 QString vehicleImageOpaque(const Vehicle* /*vehicle*/) const override { return QStringLiteral("/qmlimages/subVehicleArrowOpaque.png"); }
95
97 QString vehicleImageOutline(const Vehicle* vehicle) const override;
98
99 QString brandImageIndoor(const Vehicle *vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImageSub"); }
100 QString brandImageOutdoor(const Vehicle *vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImageSub"); }
101 const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap() const override { return _remapParamName; }
102 int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override;
103 bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override;
104 QMap<QString, FactGroup*> *factGroups() override;
105 void adjustMetaData(MAV_TYPE vehicleType, FactMetaData *metaData) override;
106
107 QString stabilizedFlightMode() const override;
108 QString motorDetectionFlightMode() const override;
109 void updateAvailableFlightModes(FlightModeList &modeList) override;
110
111 QString offlineEditingParamFile(Vehicle *vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Sub.OfflineEditing.params"); }
112
113protected:
114 uint32_t _convertToCustomFlightModeEnum(uint32_t val) const override;
115
116 const QString _manualFlightMode = tr("Manual");
117 const QString _stabilizeFlightMode = tr("Stabilize");
118 const QString _acroFlightMode = tr("Acro");
119 const QString _altHoldFlightMode = tr("Depth Hold");
120 const QString _autoFlightMode = tr("Auto");
121 const QString _guidedFlightMode = tr("Guided");
122 const QString _circleFlightMode = tr("Circle");
123 const QString _surfaceFlightMode = tr("Surface");
124 const QString _posHoldFlightMode =tr("Position Hold");
125 const QString _motorDetectionFlightMode = tr("Motor Detection");
126 const QString _surftrakFlightMode = tr("Surftrak");
127
128private:
129 QVariantList _toolIndicators;
130 static bool _remapParamNameIntialized;
131 QMap<QString, QString> _factRenameMap;
133 void _handleNamedValueFloat(mavlink_message_t *message);
134 void _handleMavlinkMessage(mavlink_message_t *message);
135
136 QMap<QString, FactGroup*> _nameToFactGroupMap;
137 APMSubmarineFactGroup _infoFactGroup;
138};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
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
Returns the mapping structure which is used to map from one parameter name to another based on firmwa...
void adjustMetaData(MAV_TYPE vehicleType, FactMetaData *metaData) override
QString stabilizedFlightMode() const override
Returns the flight mode for Stabilized.
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override
Returns the highest major version number that is known to the remap for this specified major version.
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
QString brandImageIndoor(const Vehicle *vehicle) const override
Return the resource file which contains the brand image for the vehicle for Indoor theme.
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
QString brandImageOutdoor(const Vehicle *vehicle) const override
Return the resource file which contains the brand image for the vehicle for Outdoor theme.
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:19
A Fact is used to hold a single value within the system.
Definition Fact.h:19
FirmwareCapabilities
Set of optional capabilites which firmware may support.
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t