Commit 5a039092 authored by Don Gagne's avatar Don Gagne

Fix APM parameter versioning

parent 4776d22d
...@@ -241,7 +241,11 @@ ...@@ -241,7 +241,11 @@
<file alias="APMAirframeFactMetaData.xml">src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml</file> <file alias="APMAirframeFactMetaData.xml">src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml</file>
</qresource> </qresource>
<qresource prefix="/FirmwarePlugin/APM"> <qresource prefix="/FirmwarePlugin/APM">
<file alias="APMParameterFactMetaData.xml">src/FirmwarePlugin/APM/APMParameterFactMetaData.xml</file> <file alias="APMParameterFactMetaData.Plane.3.3.xml">src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml</file>
<file alias="APMParameterFactMetaData.Plane.3.5.xml">src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.3.xml">src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.4.xml">src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.0.xml">src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml</file>
</qresource> </qresource>
<qresource prefix="/FirmwarePlugin/PX4"> <qresource prefix="/FirmwarePlugin/PX4">
<file alias="PX4ParameterFactMetaData.xml">src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml</file> <file alias="PX4ParameterFactMetaData.xml">src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml</file>
......
...@@ -30,6 +30,7 @@ ...@@ -30,6 +30,7 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "UASMessageHandler.h" #include "UASMessageHandler.h"
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "APMFirmwarePlugin.h"
#include "UAS.h" #include "UAS.h"
#include <QEasingCurve> #include <QEasingCurve>
...@@ -904,11 +905,20 @@ void ParameterLoader::_addMetaDataToDefaultComponent(void) ...@@ -904,11 +905,20 @@ void ParameterLoader::_addMetaDataToDefaultComponent(void)
return; return;
} }
// Load best parameter meta data set QString metaDataFile;
int majorVersion, minorVersion; int majorVersion, minorVersion;
QString metaDataFile = parameterMetaDataFile(_vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion); if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
// Parameter versioning is still not really figured out correctly. We need to handle ArduPilot specially based on vehicle version.
// The current three version are hardcoded in.
metaDataFile = ((APMFirmwarePlugin*)_vehicle->firmwarePlugin())->getParameterMetaDataFile(_vehicle);
qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile;
} else {
// Load best parameter meta data set
metaDataFile = parameterMetaDataFile(_vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
}
_parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile); _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);
qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
// Loop over all parameters in default component adding meta data // Loop over all parameters in default component adding meta data
QVariantMap& factMap = _mapParameterName2Variant[_defaultComponentId]; QVariantMap& factMap = _mapParameterName2Variant[_defaultComponentId];
......
...@@ -313,44 +313,44 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m ...@@ -313,44 +313,44 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
mavlink_statustext_t statusText; mavlink_statustext_t statusText;
mavlink_msg_statustext_decode(message, &statusText); mavlink_msg_statustext_decode(message, &statusText);
if (!_firmwareVersion.isValid() || statusText.severity < MAV_SEVERITY_NOTICE) { if (vehicle->firmwareMajorVersion() == -1 || statusText.severity < MAV_SEVERITY_NOTICE) {
messageText = _getMessageText(message); messageText = _getMessageText(message);
qCDebug(APMFirmwarePluginLog) << messageText; qCDebug(APMFirmwarePluginLog) << messageText;
if (!_firmwareVersion.isValid() && !messageText.contains(APM_SOLO_REXP)) { if (!messageText.contains(APM_SOLO_REXP)) {
// if don't know firmwareVersion yet, try and see if this message contains it // if don't know firmwareVersion yet, try and see if this message contains it
if (messageText.contains(APM_COPTER_REXP) || messageText.contains(APM_PLANE_REXP) || messageText.contains(APM_ROVER_REXP)) { if (messageText.contains(APM_COPTER_REXP) || messageText.contains(APM_PLANE_REXP) || messageText.contains(APM_ROVER_REXP)) {
// found version string // found version string
_firmwareVersion = APMFirmwareVersion(messageText); APMFirmwareVersion firmwareVersion(messageText);
_textSeverityAdjustmentNeeded = _isTextSeverityAdjustmentNeeded(_firmwareVersion); _textSeverityAdjustmentNeeded = _isTextSeverityAdjustmentNeeded(firmwareVersion);
if (!_firmwareVersion.isBeta() && !_firmwareVersion.isDev()) { vehicle->setFirmwareVersion(firmwareVersion.majorNumber(), firmwareVersion.minorNumber(), firmwareVersion.patchNumber());
int supportedMajorNumber = -1;
int supportedMinorNumber = -1; int supportedMajorNumber = -1;
int supportedMinorNumber = -1;
switch (vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING: switch (vehicle->vehicleType()) {
supportedMajorNumber = 3; case MAV_TYPE_FIXED_WING:
supportedMinorNumber = 2; supportedMajorNumber = 3;
break; supportedMinorNumber = 2;
case MAV_TYPE_QUADROTOR: break;
case MAV_TYPE_COAXIAL: case MAV_TYPE_QUADROTOR:
case MAV_TYPE_HELICOPTER: case MAV_TYPE_COAXIAL:
case MAV_TYPE_SUBMARINE: case MAV_TYPE_HELICOPTER:
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_SUBMARINE:
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_TRICOPTER: case MAV_TYPE_OCTOROTOR:
supportedMajorNumber = 3; case MAV_TYPE_TRICOPTER:
supportedMinorNumber = 2; supportedMajorNumber = 3;
break; supportedMinorNumber = 2;
default: break;
break; default:
} break;
}
if (supportedMajorNumber != -1) { if (supportedMajorNumber != -1) {
if (_firmwareVersion.majorNumber() < supportedMajorNumber || _firmwareVersion.minorNumber() < supportedMinorNumber) { if (firmwareVersion.majorNumber() < supportedMajorNumber || firmwareVersion.minorNumber() < supportedMinorNumber) {
qgcApp()->showMessage(QString("QGroundControl fully supports Version %1.%2 and above. You are using a version prior to that. This combination is untested, you may run into unpredictable results.").arg(supportedMajorNumber).arg(supportedMinorNumber)); qgcApp()->showMessage(QString("QGroundControl fully supports Version %1.%2 and above. You are using a version prior to that. This combination is untested, you may run into unpredictable results.").arg(supportedMajorNumber).arg(supportedMinorNumber));
}
} }
} }
} }
...@@ -601,7 +601,8 @@ QObject* APMFirmwarePlugin::loadParameterMetaData(const QString& metaDataFile) ...@@ -601,7 +601,8 @@ QObject* APMFirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
{ {
Q_UNUSED(metaDataFile); Q_UNUSED(metaDataFile);
APMParameterMetaData* metaData = new APMParameterMetaData; APMParameterMetaData* metaData = new APMParameterMetaData();
metaData->loadParameterFactMetaDataFile(metaDataFile);
return metaData; return metaData;
} }
...@@ -630,3 +631,32 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr ...@@ -630,3 +631,32 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr
{ {
qgcApp()->showMessage(tr("Error during Solo video link setup: %1").arg(socketError)); qgcApp()->showMessage(tr("Error during Solo video link setup: %1").arg(socketError));
} }
QString APMFirmwarePlugin::getParameterMetaDataFile(Vehicle* vehicle)
{
switch (vehicle->vehicleType()) {
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER:
if (vehicle->firmwareMajorVersion() < 3 || (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() <= 3)) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml");
} else {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml");
}
case MAV_TYPE_FIXED_WING:
if (vehicle->firmwareMajorVersion() < 3 || (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() <= 3)) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml");
} else {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml");
}
case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_SURFACE_BOAT:
case MAV_TYPE_SUBMARINE:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml");
default:
return QString();
}
}
...@@ -105,6 +105,8 @@ public: ...@@ -105,6 +105,8 @@ public:
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); } void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile); QObject* loadParameterMetaData (const QString& metaDataFile);
QString getParameterMetaDataFile(Vehicle* vehicle);
protected: protected:
/// All access to singleton is through stack specific implementation /// All access to singleton is through stack specific implementation
APMFirmwarePlugin(void); APMFirmwarePlugin(void);
...@@ -125,7 +127,6 @@ private: ...@@ -125,7 +127,6 @@ private:
void _handleHeartbeat(Vehicle* vehicle, mavlink_message_t* message); void _handleHeartbeat(Vehicle* vehicle, mavlink_message_t* message);
void _soloVideoHandshake(Vehicle* vehicle); void _soloVideoHandshake(Vehicle* vehicle);
APMFirmwareVersion _firmwareVersion;
bool _textSeverityAdjustmentNeeded; bool _textSeverityAdjustmentNeeded;
QList<APMCustomMode> _supportedModes; QList<APMCustomMode> _supportedModes;
QMap<QString, QTime> _noisyPrearmMap; QMap<QString, QTime> _noisyPrearmMap;
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
...@@ -37,8 +37,7 @@ QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVer ...@@ -37,8 +37,7 @@ QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVer
APMParameterMetaData::APMParameterMetaData(void) APMParameterMetaData::APMParameterMetaData(void)
: _parameterMetaDataLoaded(false) : _parameterMetaDataLoaded(false)
{ {
// APM meta data is not yet versioned
_loadParameterFactMetaData();
} }
/// Converts a string to a typed QVariant /// Converts a string to a typed QVariant
...@@ -123,10 +122,7 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum) ...@@ -123,10 +122,7 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum)
return vehicleName; return vehicleName;
} }
/// Load Parameter Fact meta data void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaDataFile)
///
/// The meta data comes from firmware parameters.xml file.
void APMParameterMetaData::_loadParameterFactMetaData()
{ {
if (_parameterMetaDataLoaded) { if (_parameterMetaDataLoaded) {
return; return;
...@@ -136,17 +132,9 @@ void APMParameterMetaData::_loadParameterFactMetaData() ...@@ -136,17 +132,9 @@ void APMParameterMetaData::_loadParameterFactMetaData()
QRegExp parameterCategories = QRegExp("ArduCopter|ArduPlane|APMrover2|AntennaTracker"); QRegExp parameterCategories = QRegExp("ArduCopter|ArduPlane|APMrover2|AntennaTracker");
QString currentCategory; QString currentCategory;
QString parameterFilename; qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << metaDataFile;
// Fixme:: always picking up the bundled xml, we would like to update it from web
// just not sure right now as the xml is in bad shape.
if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) {
parameterFilename = ":/FirmwarePlugin/APM/APMParameterFactMetaData.xml";
}
qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << parameterFilename;
QFile xmlFile(parameterFilename); QFile xmlFile(metaDataFile);
Q_ASSERT(xmlFile.exists()); Q_ASSERT(xmlFile.exists());
bool success = xmlFile.open(QIODevice::ReadOnly); bool success = xmlFile.open(QIODevice::ReadOnly);
...@@ -591,15 +579,18 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) ...@@ -591,15 +579,18 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
} }
} }
// FixMe:: not handling increment size as their is no place for it in FactMetaData and no ui
fact->setMetaData(metaData); fact->setMetaData(metaData);
} }
void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
{ {
Q_UNUSED(metaDataFile);
// Versioning not yet supported
majorVersion = -1; majorVersion = -1;
minorVersion = -1; minorVersion = -1;
// Meta data version is hacked in for now based on file name
QRegExp regExp(".*\\.(\\d)\\.(\\d)\\.xml$");
if (regExp.exactMatch(metaDataFile) && regExp.captureCount() == 2) {
majorVersion = regExp.cap(2).toInt();
minorVersion = 0;
}
} }
...@@ -70,6 +70,7 @@ public: ...@@ -70,6 +70,7 @@ public:
APMParameterMetaData(void); APMParameterMetaData(void);
void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
void loadParameterFactMetaDataFile(const QString& metaDataFile);
static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion); static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
...@@ -86,7 +87,6 @@ private: ...@@ -86,7 +87,6 @@ private:
XmlStateDone XmlStateDone
}; };
void _loadParameterFactMetaData();
QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk); QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
bool skipXMLBlock(QXmlStreamReader& xml, const QString& blockName); bool skipXMLBlock(QXmlStreamReader& xml, const QString& blockName);
bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData); bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData);
......
...@@ -121,6 +121,9 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -121,6 +121,9 @@ Vehicle::Vehicle(LinkInterface* link,
, _messageSeq(0) , _messageSeq(0)
, _compID(0) , _compID(0)
, _heardFrom(false) , _heardFrom(false)
, _firmwareMajorVersion(-1)
, _firmwareMinorVersion(-1)
, _firmwarePatchVersion(-1)
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble) , _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble) , _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble) , _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
...@@ -288,6 +291,9 @@ Vehicle::Vehicle(QObject* parent) ...@@ -288,6 +291,9 @@ Vehicle::Vehicle(QObject* parent)
, _messageSeq(0) , _messageSeq(0)
, _compID(0) , _compID(0)
, _heardFrom(false) , _heardFrom(false)
, _firmwareMajorVersion(-1)
, _firmwareMinorVersion(-1)
, _firmwarePatchVersion(-1)
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble) , _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble) , _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble) , _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
...@@ -1587,6 +1593,13 @@ void Vehicle::_prearmErrorTimeout(void) ...@@ -1587,6 +1593,13 @@ void Vehicle::_prearmErrorTimeout(void)
setPrearmError(QString()); setPrearmError(QString());
} }
void Vehicle::setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion)
{
_firmwareMajorVersion = majorVersion;
_firmwareMinorVersion = minorVersion;
_firmwarePatchVersion = patchVersion;
}
const char* VehicleGPSFactGroup::_hdopFactName = "hdop"; const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop"; const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGround"; const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGround";
......
...@@ -520,6 +520,11 @@ public: ...@@ -520,6 +520,11 @@ public:
bool containsLink(LinkInterface* link) { return _links.contains(link); } bool containsLink(LinkInterface* link) { return _links.contains(link); }
void doCommandLong(int component, MAV_CMD command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f); void doCommandLong(int component, MAV_CMD command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion);
public slots: public slots:
void setLatitude(double latitude); void setLatitude(double latitude);
void setLongitude(double longitude); void setLongitude(double longitude);
...@@ -731,6 +736,10 @@ private: ...@@ -731,6 +736,10 @@ private:
uint8_t _compID; uint8_t _compID;
bool _heardFrom; bool _heardFrom;
int _firmwareMajorVersion;
int _firmwareMinorVersion;
int _firmwarePatchVersion;
static const int _lowBatteryAnnounceRepeatMSecs; // Amount of time in between each low battery announcement static const int _lowBatteryAnnounceRepeatMSecs; // Amount of time in between each low battery announcement
QElapsedTimer _lowBatteryAnnounceTimer; QElapsedTimer _lowBatteryAnnounceTimer;
......
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