QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ArduSubFirmwarePlugin.cc
Go to the documentation of this file.
3#include "Vehicle.h"
4
5QGC_LOGGING_CATEGORY(APMSubmarineFactGroupLog, "FirmwarePlugin.ArduSubFirmwarePlugin")
6
8 : FactGroup(300, QStringLiteral(":/json/Vehicle/SubmarineFact.json"), parent)
9{
10 // qCDebug(APMSubmarineFactGroupLog) << Q_FUNC_INFO << this;
11
12 _addFact(&_camTiltFact);
13 _addFact(&_tetherTurnsFact);
14 _addFact(&_lightsLevel1Fact);
15 _addFact(&_lightsLevel2Fact);
16 _addFact(&_pilotGainFact);
17 _addFact(&_inputHoldFact);
18 _addFact(&_rollPitchToggleFact);
19 _addFact(&_rangefinderDistanceFact);
20 _addFact(&_rangefinderTargetFact);
21
22 _camTiltFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
23 _tetherTurnsFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
24 _lightsLevel1Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
25 _lightsLevel2Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
26 _pilotGainFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
27 _inputHoldFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
28 _rollPitchToggleFact.setRawValue(2); // 2 shows "Unavailable" in older firmwares
29 _rangefinderDistanceFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
30 _rangefinderTargetFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
31}
32
34{
35 // qCDebug(APMSubmarineFactGroupLog) << Q_FUNC_INFO << this;
36}
37
39{
40 return vehicleImageOpaque(vehicle);
41}
42
43void ArduSubFirmwarePlugin::adjustMetaData(MAV_TYPE vehicleType, FactMetaData *metaData)
44{
45 Q_UNUSED(vehicleType);
46
47 if (!metaData) {
48 return;
49 }
50
51 if (_factRenameMap.contains(metaData->name())) {
52 metaData->setShortDescription(QString(_factRenameMap[metaData->name()]));
53 }
54}
55
60
65
67{
68 for (FirmwareFlightMode &mode: modeList) {
69 mode.fixedWing = false;
70 mode.multiRotor = true;
71 }
72
73 _updateFlightModeList(modeList);
74}
75
77{
78 switch (val) {
80 return APMSubMode::AUTO;
82 return APMSubMode::GUIDED;
83 default:
84 return UINT32_MAX;
85 }
86}
87
88/*===========================================================================*/
89
90bool ArduSubFirmwarePlugin::_remapParamNameIntialized = false;
91FirmwarePlugin::remapParamNameMajorVersionMap_t ArduSubFirmwarePlugin::_remapParamName;
92
94 : APMFirmwarePlugin(parent)
95 , _infoFactGroup(this)
96{
109 });
110
111 static FlightModeList availableFlightModes = {
112 // Mode Name , Custom Mode CanBeSet adv
113 { _manualFlightMode , APMSubMode::MANUAL , true , true },
115 { _acroFlightMode , APMSubMode::ACRO , true , true },
116 { _altHoldFlightMode , APMSubMode::ALT_HOLD , true , true },
117 { _autoFlightMode , APMSubMode::AUTO , true , true },
118 { _guidedFlightMode , APMSubMode::GUIDED , true , true },
119 { _circleFlightMode , APMSubMode::CIRCLE , true , true },
120 { _surfaceFlightMode , APMSubMode::SURFACE , true , true },
121 { _posHoldFlightMode , APMSubMode::POSHOLD , true , true },
123 { _surftrakFlightMode , APMSubMode::SURFTRAK , true , true },
124 };
125 updateAvailableFlightModes(availableFlightModes);
126
127 if (!_remapParamNameIntialized) {
128 // ArduPilot 4.7: parameter renames and SI unit conversion
129 FirmwarePlugin::remapParamNameMap_t &remapV4_7 = _remapParamName[4][7];
130
131 // Position controller: PSC_VELXY_* -> PSC_NE_VEL_*
132 remapV4_7["PSC_NE_VEL_P"] = QStringLiteral("PSC_VELXY_P");
133 remapV4_7["PSC_NE_VEL_I"] = QStringLiteral("PSC_VELXY_I");
134 remapV4_7["PSC_NE_VEL_D"] = QStringLiteral("PSC_VELXY_D");
135 remapV4_7["PSC_NE_VEL_IMAX"] = QStringLiteral("PSC_VELXY_IMAX");
136 remapV4_7["PSC_NE_VEL_FLTE"] = QStringLiteral("PSC_VELXY_FLTE");
137 remapV4_7["PSC_NE_VEL_FLTD"] = QStringLiteral("PSC_VELXY_FLTD");
138 remapV4_7["PSC_NE_VEL_FF"] = QStringLiteral("PSC_VELXY_FF");
139
140 // Position controller: PSC_VELZ_* -> PSC_D_VEL_*
141 remapV4_7["PSC_D_VEL_P"] = QStringLiteral("PSC_VELZ_P");
142 remapV4_7["PSC_D_VEL_I"] = QStringLiteral("PSC_VELZ_I");
143 remapV4_7["PSC_D_VEL_D"] = QStringLiteral("PSC_VELZ_D");
144 remapV4_7["PSC_D_VEL_IMAX"] = QStringLiteral("PSC_VELZ_IMAX");
145 remapV4_7["PSC_D_VEL_FLTE"] = QStringLiteral("PSC_VELZ_FLTE");
146 remapV4_7["PSC_D_VEL_FF"] = QStringLiteral("PSC_VELZ_FF");
147
148 // Position controller: PSC_ACCZ_* -> PSC_D_ACC_*
149 remapV4_7["PSC_D_ACC_P"] = QStringLiteral("PSC_ACCZ_P");
150 remapV4_7["PSC_D_ACC_I"] = QStringLiteral("PSC_ACCZ_I");
151 remapV4_7["PSC_D_ACC_D"] = QStringLiteral("PSC_ACCZ_D");
152 remapV4_7["PSC_D_ACC_IMAX"] = QStringLiteral("PSC_ACCZ_IMAX");
153 remapV4_7["PSC_D_ACC_FLTD"] = QStringLiteral("PSC_ACCZ_FLTD");
154 remapV4_7["PSC_D_ACC_FLTE"] = QStringLiteral("PSC_ACCZ_FLTE");
155 remapV4_7["PSC_D_ACC_FLTT"] = QStringLiteral("PSC_ACCZ_FLTT");
156 remapV4_7["PSC_D_ACC_FF"] = QStringLiteral("PSC_ACCZ_FF");
157 remapV4_7["PSC_D_ACC_SMAX"] = QStringLiteral("PSC_ACCZ_SMAX");
158
159 // Position controller: PSC_POSXY_P -> PSC_NE_POS_P
160 remapV4_7["PSC_NE_POS_P"] = QStringLiteral("PSC_POSXY_P");
161
162 // Position controller: PSC_POSZ_P -> PSC_D_POS_P
163 remapV4_7["PSC_D_POS_P"] = QStringLiteral("PSC_POSZ_P");
164
165 // Waypoint navigation: WPNAV_* -> WP_*
166 remapV4_7["WP_ACC"] = QStringLiteral("WPNAV_ACCEL");
167 remapV4_7["WP_ACC_CNR"] = QStringLiteral("WPNAV_ACCEL_C");
168 remapV4_7["WP_ACC_Z"] = QStringLiteral("WPNAV_ACCEL_Z");
169 remapV4_7["WP_RADIUS_M"] = QStringLiteral("WPNAV_RADIUS");
170 remapV4_7["WP_SPD"] = QStringLiteral("WPNAV_SPEED");
171 remapV4_7["WP_SPD_DN"] = QStringLiteral("WPNAV_SPEED_DN");
172 remapV4_7["WP_SPD_UP"] = QStringLiteral("WPNAV_SPEED_UP");
173
174 // Attitude controller
175 remapV4_7["ATC_ACC_R_MAX"] = QStringLiteral("ATC_ACCEL_R_MAX");
176 remapV4_7["ATC_ACC_P_MAX"] = QStringLiteral("ATC_ACCEL_P_MAX");
177 remapV4_7["ATC_ACC_Y_MAX"] = QStringLiteral("ATC_ACCEL_Y_MAX");
178 remapV4_7["ATC_RATE_WPY_MAX"]= QStringLiteral("ATC_SLEW_YAW");
179
180 // Circle
181 remapV4_7["CIRCLE_RADIUS_M"] = QStringLiteral("CIRCLE_RADIUS");
182
183 // EKF
184 remapV4_7["EK3_FLOW_MAX"] = QStringLiteral("EK3_MAX_FLOW");
185
186 // Common
187 remapV4_7["ARMING_SKIPCHK"] = QStringLiteral("ARMING_CHECK");
188
189 _remapParamNameIntialized = true;
190 }
191
192 _nameToFactGroupMap.insert("apmSubInfo", &_infoFactGroup);
193
194 _factRenameMap[QStringLiteral("altitudeRelative")] = QStringLiteral("Depth");
195 _factRenameMap[QStringLiteral("flightTime")] = QStringLiteral("Dive Time");
196 _factRenameMap[QStringLiteral("altitudeAMSL")] = QStringLiteral("");
197 _factRenameMap[QStringLiteral("hobbs")] = QStringLiteral("");
198 _factRenameMap[QStringLiteral("airSpeed")] = QStringLiteral("");
199}
200
205
207{
208 return ((majorVersionNumber == 4) ? 7 : Vehicle::versionNotSetValue);
209}
210
212{
213 vehicle->requestDataStream(MAV_DATA_STREAM_RAW_SENSORS, 2);
214 vehicle->requestDataStream(MAV_DATA_STREAM_EXTENDED_STATUS, 2);
215 vehicle->requestDataStream(MAV_DATA_STREAM_RC_CHANNELS, 2);
216 vehicle->requestDataStream(MAV_DATA_STREAM_POSITION, 3);
217 vehicle->requestDataStream(MAV_DATA_STREAM_EXTRA1, 20);
218 vehicle->requestDataStream(MAV_DATA_STREAM_EXTRA2, 10);
219 vehicle->requestDataStream(MAV_DATA_STREAM_EXTRA3, 3);
220}
221
222bool ArduSubFirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const
223{
224 Q_UNUSED(vehicle);
226 return ((capabilities & available) == capabilities);
227}
228
229void ArduSubFirmwarePlugin::_handleNamedValueFloat(mavlink_message_t *message)
230{
231 mavlink_named_value_float_t value{};
232 mavlink_msg_named_value_float_decode(message, &value);
233
234 const QString name = QString(value.name);
235
236 if (name == "CamTilt") {
237 _infoFactGroup.getFact("cameraTilt")->setRawValue(value.value * 100);
238 } else if (name == "TetherTrn") {
239 _infoFactGroup.getFact("tetherTurns")->setRawValue(value.value);
240 } else if (name == "Lights1") {
241 _infoFactGroup.getFact("lights1")->setRawValue(value.value * 100);
242 } else if (name == "Lights2") {
243 _infoFactGroup.getFact("lights2")->setRawValue(value.value * 100);
244 } else if (name == "PilotGain") {
245 _infoFactGroup.getFact("pilotGain")->setRawValue(value.value * 100);
246 } else if (name == "InputHold") {
247 _infoFactGroup.getFact("inputHold")->setRawValue(value.value);
248 } else if (name == "RollPitch") {
249 _infoFactGroup.getFact("rollPitchToggle")->setRawValue(value.value);
250 } else if (name == "RFTarget") {
251 _infoFactGroup.getFact("rangefinderTarget")->setRawValue(value.value);
252 }
253}
254
255void ArduSubFirmwarePlugin::_handleMavlinkMessage(mavlink_message_t *message)
256{
257 switch (message->msgid) {
258 case (MAVLINK_MSG_ID_NAMED_VALUE_FLOAT):
259 _handleNamedValueFloat(message);
260 break;
261 case (MAVLINK_MSG_ID_RANGEFINDER):
262 {
263 mavlink_rangefinder_t msg{};
264 mavlink_msg_rangefinder_decode(message, &msg);
265 _infoFactGroup.getFact("rangefinderDistance")->setRawValue(msg.distance);
266 break;
267 }
268 default:
269 break;
270 }
271}
272
274{
275 _handleMavlinkMessage(message);
277}
278
279QMap<QString, FactGroup*>* ArduSubFirmwarePlugin::factGroups()
280{
281 return &_nameToFactGroupMap;
282}
QList< FirmwareFlightMode > FlightModeList
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
This is the base class for all stack specific APM firmware plugins.
bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override
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
void adjustMetaData(MAV_TYPE vehicleType, FactMetaData *metaData) override
QString stabilizedFlightMode() const override
Returns the flight mode for Stabilized.
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override
ArduSubFirmwarePlugin(QObject *parent=nullptr)
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...
const QString _motorDetectionFlightMode
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
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
Q_INVOKABLE Fact * getFact(const QString &name) const
Definition FactGroup.cc:72
Holds the meta data associated with a Fact.
void setShortDescription(const QString &shortDescription)
QString name() const
void setRawValue(const QVariant &value)
Definition Fact.cc:128
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
FirmwareCapabilities
Set of optional capabilites which firmware may support.
@ GuidedModeCapability
Vehicle supports guided mode commands.
@ SetFlightModeCapability
FirmwarePlugin::setFlightMode method is supported.
@ PauseVehicleCapability
Vehicle supports pausing at current location.
void _updateFlightModeList(FlightModeList &flightModeList)
QMap< QString, QString > remapParamNameMap_t
FlightModeCustomModeMap _modeEnumToString
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple=true)
Definition Vehicle.cc:1529
static const int versionNotSetValue