Browse Source

Merge pull request #2747 from DonLakeFlyer/ClearSettings

clear setting clears cached files
QGC4.4
Don Gagne 9 years ago
parent
commit
a7a49bf718
  1. 13
      src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc
  2. 5
      src/AutoPilotPlugins/PX4/PX4AirframeLoader.h
  3. 2
      src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc
  4. 9
      src/FactSystem/ParameterLoader.cc
  5. 3
      src/FactSystem/ParameterLoader.h
  6. 11
      src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
  7. 3
      src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
  8. 6
      src/QGCApplication.cc

13
src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc

@ -46,10 +46,17 @@ PX4AirframeLoader::PX4AirframeLoader(AutoPilotPlugin* autopilot, UASInterface* u
Q_ASSERT(uas); Q_ASSERT(uas);
} }
QString PX4AirframeLoader::aiframeMetaDataFile(void)
{
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
return parameterDir.filePath("PX4AirframeFactMetaData.xml");
}
/// Load Airframe Fact meta data /// Load Airframe Fact meta data
/// ///
/// The meta data comes from firmware airframes.xml file. /// The meta data comes from firmware airframes.xml file.
void PX4AirframeLoader::loadAirframeFactMetaData(void) void PX4AirframeLoader::loadAirframeMetaData(void)
{ {
if (_airframeMetaDataLoaded) { if (_airframeMetaDataLoaded) {
return; return;
@ -64,9 +71,7 @@ void PX4AirframeLoader::loadAirframeFactMetaData(void)
// We want unit test builds to always use the resource based meta data to provide repeatable results // We want unit test builds to always use the resource based meta data to provide repeatable results
if (!qgcApp()->runningUnitTests()) { if (!qgcApp()->runningUnitTests()) {
// First look for meta data that comes from a firmware download. Fall back to resource if not there. // First look for meta data that comes from a firmware download. Fall back to resource if not there.
QSettings settings; airframeFilename = aiframeMetaDataFile();
QDir parameterDir = QFileInfo(settings.fileName()).dir();
airframeFilename = parameterDir.filePath("PX4AirframeFactMetaData.xml");
} }
if (airframeFilename.isEmpty() || !QFile(airframeFilename).exists()) { if (airframeFilename.isEmpty() || !QFile(airframeFilename).exists()) {
airframeFilename = ":/AutoPilotPlugins/PX4/AirframeFactMetaData.xml"; airframeFilename = ":/AutoPilotPlugins/PX4/AirframeFactMetaData.xml";

5
src/AutoPilotPlugins/PX4/PX4AirframeLoader.h

@ -49,7 +49,10 @@ public:
/// @param uas Uas which this set of facts is associated with /// @param uas Uas which this set of facts is associated with
PX4AirframeLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = NULL); PX4AirframeLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = NULL);
static void loadAirframeFactMetaData(void); static void loadAirframeMetaData(void);
/// @return Location of PX4 airframe fact meta data file
static QString aiframeMetaDataFile(void);
private: private:
enum { enum {

2
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc

@ -81,7 +81,7 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
_airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this); _airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this);
Q_CHECK_PTR(_airframeFacts); Q_CHECK_PTR(_airframeFacts);
PX4AirframeLoader::loadAirframeFactMetaData(); PX4AirframeLoader::loadAirframeMetaData();
} }
PX4AutoPilotPlugin::~PX4AutoPilotPlugin() PX4AutoPilotPlugin::~PX4AutoPilotPlugin()

9
src/FactSystem/ParameterLoader.cc

@ -620,13 +620,18 @@ void ParameterLoader::_writeLocalParamCache()
ds << cache_map; ds << cache_map;
} }
QString ParameterLoader::parameterCacheFile(void)
{
const QDir settingsDir(QFileInfo(QSettings().fileName()).dir());
return settingsDir.filePath("param_cache");
}
void ParameterLoader::_tryCacheHashLoad(int uasId, QVariant hash_value) void ParameterLoader::_tryCacheHashLoad(int uasId, QVariant hash_value)
{ {
uint32_t crc32_value = 0; uint32_t crc32_value = 0;
/* The datastructure of the cache table */ /* The datastructure of the cache table */
QMap<int, MapID2NamedParam> cache_map; QMap<int, MapID2NamedParam> cache_map;
const QDir settingsDir(QFileInfo(QSettings().fileName()).dir()); QFile cache_file(parameterCacheFile());
QFile cache_file(settingsDir.filePath("param_cache"));
if (!cache_file.exists()) { if (!cache_file.exists()) {
/* no local cache, immediately refresh all params */ /* no local cache, immediately refresh all params */
refreshAllParameters(); refreshAllParameters();

3
src/FactSystem/ParameterLoader.h

@ -53,6 +53,9 @@ public:
~ParameterLoader(); ~ParameterLoader();
/// @return Location of parameter cache file
static QString parameterCacheFile(void);
/// Returns true if the full set of facts are ready /// Returns true if the full set of facts are ready
bool parametersAreReady(void) { return _parametersReady; } bool parametersAreReady(void) { return _parametersReady; }

11
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc

@ -78,6 +78,13 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
return var; return var;
} }
QString PX4ParameterMetaData::parameterMetaDataFile(void)
{
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
return parameterDir.filePath("PX4ParameterFactMetaData.xml");
}
/// Load Parameter Fact meta data /// Load Parameter Fact meta data
/// ///
/// The meta data comes from firmware parameters.xml file. /// The meta data comes from firmware parameters.xml file.
@ -97,9 +104,7 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
// We want unit test builds to always use the resource based meta data to provide repeatable results // We want unit test builds to always use the resource based meta data to provide repeatable results
if (!qgcApp()->runningUnitTests()) { if (!qgcApp()->runningUnitTests()) {
// First look for meta data that comes from a firmware download. Fall back to resource if not there. // First look for meta data that comes from a firmware download. Fall back to resource if not there.
QSettings settings; parameterFilename = parameterMetaDataFile();
QDir parameterDir = QFileInfo(settings.fileName()).dir();
parameterFilename = parameterDir.filePath("PX4ParameterFactMetaData.xml");
} }
if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) { if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) {
parameterFilename = ":/AutoPilotPlugins/PX4/ParameterFactMetaData.xml"; parameterFilename = ":/AutoPilotPlugins/PX4/ParameterFactMetaData.xml";

3
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h

@ -49,6 +49,9 @@ public:
void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
/// @return Location of PX4 parameter meta data file
static QString parameterMetaDataFile(void);
private: private:
enum { enum {
XmlStateNone, XmlStateNone,

6
src/QGCApplication.cc

@ -97,6 +97,7 @@
#include "VideoSurface.h" #include "VideoSurface.h"
#include "VideoReceiver.h" #include "VideoReceiver.h"
#include "LogDownloadController.h" #include "LogDownloadController.h"
#include "PX4AirframeLoader.h"
#ifndef __ios__ #ifndef __ios__
#include "SerialLink.h" #include "SerialLink.h"
@ -365,8 +366,13 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
if (fClearSettingsOptions) { if (fClearSettingsOptions) {
// User requested settings to be cleared on command line // User requested settings to be cleared on command line
settings.clear(); settings.clear();
settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION); settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION);
QFile::remove(PX4AirframeLoader::aiframeMetaDataFile());
QFile::remove(PX4ParameterMetaData::parameterMetaDataFile());
QFile::remove(ParameterLoader::parameterCacheFile());
} }
_defaultMapPosition.setLatitude(settings.value(_defaultMapPositionLatKey, 37.803784).toDouble()); _defaultMapPosition.setLatitude(settings.value(_defaultMapPositionLatKey, 37.803784).toDouble());

Loading…
Cancel
Save