From fcddb6f2528c510646c1ac656a9ea0ebb74f08fe Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Fri, 16 Feb 2018 10:34:05 -0800 Subject: [PATCH] Remove usage of PREFLIGHT_STORAGE Buggy and no longer needed --- src/FactSystem/ParameterManager.cc | 22 ---------------------- src/FactSystem/ParameterManager.h | 1 - src/FirmwarePlugin/FirmwarePlugin.h | 9 ++++----- src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc | 2 +- 4 files changed, 5 insertions(+), 29 deletions(-) diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 03b994d..775c4e9 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -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; diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index d0f45b1..a4f06d7 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -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 diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 4016383..5242eb6 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -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 diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 3a5c797..d8b68b2 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -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; }