Commit 313ab9e5 authored by Don Gagne's avatar Don Gagne

parent 1bf29d32
......@@ -236,11 +236,13 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
// Parse command line options
bool fClearSettingsOptions = false; // Clear stored settings
bool fClearCache = false; // Clear parameter/airframe caches
bool logging = false; // Turn on logging
QString loggingOptions;
CmdLineOpt_t rgCmdLineOptions[] = {
{ "--clear-settings", &fClearSettingsOptions, nullptr },
{ "--clear-cache", &fClearCache, nullptr },
{ "--logging", &logging, &loggingOptions },
{ "--fake-mobile", &_fakeMobile, nullptr },
{ "--log-output", &_logOutput, nullptr },
......@@ -309,6 +311,15 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
}
settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION);
if (fClearCache) {
QDir dir(ParameterManager::parameterCacheDir());
dir.removeRecursively();
QFile airframe(FirmwareImage::cachedAirframeMetaDataFile());
airframe.remove();
QFile parameter(FirmwareImage::cachedParameterMetaDataFile());
parameter.remove();
}
// Set up our logging filters
QGCLoggingCategoryRegister::instance()->setFilterRulesFromSettings(loggingOptions);
......
......@@ -215,6 +215,21 @@ bool FirmwareImage::isCompatible(uint32_t boardId, uint32_t firmwareId) {
return result;
}
QString FirmwareImage::cachedParameterMetaDataFile(void)
{
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
return parameterDir.filePath(QStringLiteral("ParameterFactMetaData.xml"));
}
QString FirmwareImage::cachedAirframeMetaDataFile(void)
{
QSettings settings;
QDir airframeDir = QFileInfo(settings.fileName()).dir();
return airframeDir.filePath(QStringLiteral("PX4AirframeFactMetaData.xml"));
}
bool FirmwareImage::_px4Load(const QString& imageFilename)
{
_imageSize = 0;
......@@ -275,12 +290,8 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
_jsonParamXmlKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes
if (success) {
// Use settings location as our work directory, this way is something goes wrong the file is still there
// sitting next to the cache files.
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
QString parameterFilename = parameterDir.filePath("ParameterFactMetaData.xml");
QFile parameterFile(parameterFilename);
QString parameterFilename = cachedParameterMetaDataFile();
QFile parameterFile(cachedParameterMetaDataFile());
if (parameterFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
qint64 bytesWritten = parameterFile.write(decompressedBytes);
......@@ -306,12 +317,9 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
_jsonAirframeXmlKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes
if (success) {
// We cache the airframe xml in the same location as settings and parameters
QSettings settings;
QDir airframeDir = QFileInfo(settings.fileName()).dir();
QString airframeFilename = airframeDir.filePath("PX4AirframeFactMetaData.xml");
QString airframeFilename = cachedAirframeMetaDataFile();
//qDebug() << airframeFilename;
QFile airframeFile(airframeFilename);
QFile airframeFile(cachedAirframeMetaDataFile());
if (airframeFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
qint64 bytesWritten = airframeFile.write(decompressedBytes);
......
......@@ -59,6 +59,9 @@ public:
/// @return true: actual boardId is compatible with firmware boardId
bool isCompatible(uint32_t boardId, uint32_t firmwareId);
static QString cachedParameterMetaDataFile(void);
static QString cachedAirframeMetaDataFile(void);
signals:
void errorMessage(const QString& errorString);
void statusMessage(const QString& warningtring);
......
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