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);
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);
29 _rangefinderDistanceFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
30 _rangefinderTargetFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
45 Q_UNUSED(vehicleType);
51 if (_factRenameMap.contains(metaData->
name())) {
69 mode.fixedWing =
false;
70 mode.multiRotor =
true;
90bool ArduSubFirmwarePlugin::_remapParamNameIntialized =
false;
95 , _infoFactGroup(this)
127 if (!_remapParamNameIntialized) {
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");
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");
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");
160 remapV4_7[
"PSC_NE_POS_P"] = QStringLiteral(
"PSC_POSXY_P");
163 remapV4_7[
"PSC_D_POS_P"] = QStringLiteral(
"PSC_POSZ_P");
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");
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");
181 remapV4_7[
"CIRCLE_RADIUS_M"] = QStringLiteral(
"CIRCLE_RADIUS");
184 remapV4_7[
"EK3_FLOW_MAX"] = QStringLiteral(
"EK3_MAX_FLOW");
187 remapV4_7[
"ARMING_SKIPCHK"] = QStringLiteral(
"ARMING_CHECK");
189 _remapParamNameIntialized =
true;
192 _nameToFactGroupMap.insert(
"apmSubInfo", &_infoFactGroup);
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(
"");
226 return ((capabilities & available) == capabilities);
231 mavlink_named_value_float_t value{};
232 mavlink_msg_named_value_float_decode(message, &value);
234 const QString name = QString(value.name);
236 if (name ==
"CamTilt") {
238 }
else if (name ==
"TetherTrn") {
240 }
else if (name ==
"Lights1") {
242 }
else if (name ==
"Lights2") {
244 }
else if (name ==
"PilotGain") {
246 }
else if (name ==
"InputHold") {
248 }
else if (name ==
"RollPitch") {
250 }
else if (name ==
"RFTarget") {
257 switch (message->msgid) {
258 case (MAVLINK_MSG_ID_NAMED_VALUE_FLOAT):
259 _handleNamedValueFloat(message);
261 case (MAVLINK_MSG_ID_RANGEFINDER):
263 mavlink_rangefinder_t msg{};
264 mavlink_msg_rangefinder_decode(message, &msg);
275 _handleMavlinkMessage(message);
281 return &_nameToFactGroupMap;
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
const QString _surfaceFlightMode
void initializeStreamRates(Vehicle *vehicle) override
QMap< QString, FactGroup * > * factGroups() override
Returns a pointer to a dictionary of firmware-specific FactGroups.
const QString _manualFlightMode
const QString _autoFlightMode
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
const QString _acroFlightMode
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 _circleFlightMode
const QString _motorDetectionFlightMode
const QString _stabilizeFlightMode
const QString _guidedFlightMode
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
const QString _surftrakFlightMode
QString motorDetectionFlightMode() const override
Returns the flight mode for Motor Detection.
const QString _posHoldFlightMode
void updateAvailableFlightModes(FlightModeList &modeList) override
Update Available flight modes recieved from vehicle.
const QString _altHoldFlightMode
Used to group Facts together into an object hierarachy.
Q_INVOKABLE Fact * getFact(const QString &name) const
void setRawValue(const QVariant &value)
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)
static const int versionNotSetValue