Commit f606cdda authored by Don Gagne's avatar Don Gagne

clear setting clears cached files

parent 34ee1349
......@@ -46,10 +46,17 @@ PX4AirframeLoader::PX4AirframeLoader(AutoPilotPlugin* autopilot, UASInterface* u
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
///
/// The meta data comes from firmware airframes.xml file.
void PX4AirframeLoader::loadAirframeFactMetaData(void)
void PX4AirframeLoader::loadAirframeMetaData(void)
{
if (_airframeMetaDataLoaded) {
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
if (!qgcApp()->runningUnitTests()) {
// First look for meta data that comes from a firmware download. Fall back to resource if not there.
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
airframeFilename = parameterDir.filePath("PX4AirframeFactMetaData.xml");
airframeFilename = aiframeMetaDataFile();
}
if (airframeFilename.isEmpty() || !QFile(airframeFilename).exists()) {
airframeFilename = ":/AutoPilotPlugins/PX4/AirframeFactMetaData.xml";
......
......@@ -49,7 +49,10 @@ public:
/// @param uas Uas which this set of facts is associated with
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:
enum {
......
......@@ -81,7 +81,7 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
_airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this);
Q_CHECK_PTR(_airframeFacts);
PX4AirframeLoader::loadAirframeFactMetaData();
PX4AirframeLoader::loadAirframeMetaData();
}
PX4AutoPilotPlugin::~PX4AutoPilotPlugin()
......
......@@ -620,13 +620,18 @@ void ParameterLoader::_writeLocalParamCache()
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)
{
uint32_t crc32_value = 0;
/* The datastructure of the cache table */
QMap<int, MapID2NamedParam> cache_map;
const QDir settingsDir(QFileInfo(QSettings().fileName()).dir());
QFile cache_file(settingsDir.filePath("param_cache"));
QFile cache_file(parameterCacheFile());
if (!cache_file.exists()) {
/* no local cache, immediately refresh all params */
refreshAllParameters();
......
......@@ -52,6 +52,9 @@ public:
ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
~ParameterLoader();
/// @return Location of parameter cache file
static QString parameterCacheFile(void);
/// Returns true if the full set of facts are ready
bool parametersAreReady(void) { return _parametersReady; }
......
......@@ -78,6 +78,13 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
return var;
}
QString PX4ParameterMetaData::parameterMetaDataFile(void)
{
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
return parameterDir.filePath("PX4ParameterFactMetaData.xml");
}
/// Load Parameter Fact meta data
///
/// 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
if (!qgcApp()->runningUnitTests()) {
// First look for meta data that comes from a firmware download. Fall back to resource if not there.
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
parameterFilename = parameterDir.filePath("PX4ParameterFactMetaData.xml");
parameterFilename = parameterMetaDataFile();
}
if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) {
parameterFilename = ":/AutoPilotPlugins/PX4/ParameterFactMetaData.xml";
......
......@@ -49,6 +49,9 @@ public:
void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
/// @return Location of PX4 parameter meta data file
static QString parameterMetaDataFile(void);
private:
enum {
XmlStateNone,
......
......@@ -97,6 +97,7 @@
#include "VideoSurface.h"
#include "VideoReceiver.h"
#include "LogDownloadController.h"
#include "PX4AirframeLoader.h"
#ifndef __ios__
#include "SerialLink.h"
......@@ -365,8 +366,13 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
if (fClearSettingsOptions) {
// User requested settings to be cleared on command line
settings.clear();
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());
......
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