Unverified Commit 21dfcf4f authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6144 from DonLakeFlyer/PreflightStorage

Remove usage of PREFLIGHT_STORAGE
parents 44ffe7f6 fcddb6f2
......@@ -324,11 +324,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_setupCategoryMap();
}
if (_prevWaitingWriteParamNameCount != 0 && waitingWriteParamNameCount == 0) {
// If all the writes just finished the vehicle is up to date, so persist.
_saveToEEPROM();
}
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
// which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
// which in turn causes a perf problem with all the param cache updates.
......@@ -862,23 +857,6 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
}
}
void ParameterManager::_saveToEEPROM(void)
{
if (_saveRequired) {
_saveRequired = false;
if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) {
_vehicle->sendMavCommand(MAV_COMP_ID_ALL,
MAV_CMD_PREFLIGHT_STORAGE,
true, // showError
1, // Write parameters to EEPROM
-1); // Don't do anything with mission storage
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM";
} else {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
}
}
}
QString ParameterManager::readParametersFromStream(QTextStream& stream)
{
QString errors;
......
......@@ -153,7 +153,6 @@ private:
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
void _saveToEEPROM(void);
void _checkInitialLoadComplete(void);
/// First mapping is by component id
......
......@@ -43,11 +43,10 @@ public:
/// Set of optional capabilites which firmware may support
typedef enum {
SetFlightModeCapability = 1 << 0, ///< FirmwarePlugin::setFlightMode method is supported
MavCmdPreflightStorageCapability = 1 << 1, ///< MAV_CMD_PREFLIGHT_STORAGE is supported
PauseVehicleCapability = 1 << 2, ///< Vehicle supports pausing at current location
GuidedModeCapability = 1 << 3, ///< Vehicle supports guided mode commands
OrbitModeCapability = 1 << 4, ///< Vehicle supports orbit mode
TakeoffVehicleCapability = 1 << 5, ///< Vehicle supports guided takeoff
PauseVehicleCapability = 1 << 1, ///< Vehicle supports pausing at current location
GuidedModeCapability = 1 << 2, ///< Vehicle supports guided mode commands
OrbitModeCapability = 1 << 3, ///< Vehicle supports orbit mode
TakeoffVehicleCapability = 1 << 4, ///< Vehicle supports guided takeoff
} FirmwareCapabilities;
/// Maps from on parameter name to another
......
......@@ -227,7 +227,7 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void)
bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
{
int available = MavCmdPreflightStorageCapability | SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
if (vehicle->multiRotor() || vehicle->vtol()) {
available |= TakeoffVehicleCapability;
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment