Commit 4b4ece63 authored by Don Gagne's avatar Don Gagne Committed by GitHub
Browse files

Merge pull request #4036 from DonLakeFlyer/OfflineVehicle

Offline vehicle support
parents cbd6c750 a42225cc
......@@ -273,6 +273,8 @@
<file alias="APMParameterFactMetaData.Sub.3.4.xml">src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml</file>
<file alias="CopterGeoFenceEditor.qml">src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml</file>
<file alias="PlaneGeoFenceEditor.qml">src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml</file>
<file alias="Copter.OfflineEditing.params">src/FirmwarePlugin/APM/Copter3.4.OfflineEditing.params</file>
<file alias="Plane.OfflineEditing.params">src/FirmwarePlugin/APM/Plane3.7.OfflineEditing.params</file>
</qresource>
<qresource prefix="/FirmwarePlugin">
<file alias="GeoFenceEditor.qml">src/FirmwarePlugin/GeoFenceEditor.qml</file>
......
......@@ -52,7 +52,7 @@ bool APMAirframeComponent::requiresSetup(void) const
bool APMAirframeComponent::setupComplete(void) const
{
if (_requiresFrameSetup) {
return _autopilot->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0;
return _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0;
} else {
return true;
}
......
......@@ -609,16 +609,15 @@ void APMCompassCal::startCalibration(void)
connect(_calWorkerThread, &CalWorkerThread::vehicleTextMessage, this, &APMCompassCal::vehicleTextMessage);
// Clear the offset parameters so we get raw data
AutoPilotPlugin* plugin = _vehicle->autopilotPlugin();
for (int i=0; i<3; i++) {
_calWorkerThread->rgCompassAvailable[i] = true;
const char* deviceIdParam = CalWorkerThread::rgCompassParams[i][3];
if (plugin->parameterExists(-1, deviceIdParam)) {
_calWorkerThread->rgCompassAvailable[i] = plugin->getParameterFact(-1, deviceIdParam)->rawValue().toInt() > 0;
if (_vehicle->parameterExists(-1, deviceIdParam)) {
_calWorkerThread->rgCompassAvailable[i] = _vehicle->getParameterFact(-1, deviceIdParam)->rawValue().toInt() > 0;
for (int j=0; j<3; j++) {
const char* offsetParam = CalWorkerThread::rgCompassParams[i][j];
Fact* paramFact = plugin->getParameterFact(-1, offsetParam);
Fact* paramFact = _vehicle->getParameterFact(-1, offsetParam);
_rgSavedCompassOffsets[i][j] = paramFact->rawValue().toFloat();
paramFact->setRawValue(0.0);
......@@ -637,12 +636,11 @@ void APMCompassCal::cancelCalibration(void)
_stopCalibration();
// Put the original offsets back
AutoPilotPlugin* plugin = _vehicle->autopilotPlugin();
for (int i=0; i<3; i++) {
for (int j=0; j<3; j++) {
const char* offsetParam = CalWorkerThread::rgCompassParams[i][j];
if (plugin->parameterExists(-1, offsetParam)) {
plugin->getParameterFact(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]);
if (_vehicle->parameterExists(-1, offsetParam)) {
_vehicle->getParameterFact(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]);
}
}
}
......
......@@ -40,7 +40,7 @@ bool APMPowerComponent::requiresSetup(void) const
bool APMPowerComponent::setupComplete(void) const
{
return _autopilot->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("BATT_CAPACITY"))->rawValue().toInt() != 0;
return _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("BATT_CAPACITY"))->rawValue().toInt() != 0;
}
QStringList APMPowerComponent::setupCompleteChangedTriggerList(void) const
......
......@@ -19,7 +19,7 @@ APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilo
_mapParams << QStringLiteral("RCMAP_ROLL") << QStringLiteral("RCMAP_PITCH") << QStringLiteral("RCMAP_YAW") << QStringLiteral("RCMAP_THROTTLE");
foreach (const QString& mapParam, _mapParams) {
Fact* fact = _autopilot->getParameterFact(-1, mapParam);
Fact* fact = _vehicle->getParameterFact(-1, mapParam);
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
}
......@@ -56,7 +56,7 @@ bool APMRadioComponent::setupComplete(void) const
// First check for all attitude controls mapped
for (int i=0; i<_mapParams.count(); i++) {
mapValues << _autopilot->getParameterFact(FactSystem::defaultComponentId, _mapParams[i])->rawValue().toInt();
mapValues << _vehicle->getParameterFact(FactSystem::defaultComponentId, _mapParams[i])->rawValue().toInt();
if (mapValues[i] <= 0) {
return false;
}
......@@ -64,14 +64,14 @@ bool APMRadioComponent::setupComplete(void) const
// Next check RC#_MIN/MAX/TRIM all at defaults
foreach (const QString& mapParam, _mapParams) {
int channel = _autopilot->getParameterFact(-1, mapParam)->rawValue().toInt();
if (_autopilot->getParameterFact(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) {
int channel = _vehicle->getParameterFact(-1, mapParam)->rawValue().toInt();
if (_vehicle->getParameterFact(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) {
return true;
}
if (_autopilot->getParameterFact(-1, QString("RC%1_MAX").arg(channel))->rawValue().toInt() != 1900) {
if (_vehicle->getParameterFact(-1, QString("RC%1_MAX").arg(channel))->rawValue().toInt() != 1900) {
return true;
}
if (_autopilot->getParameterFact(-1, QString("RC%1_TRIM").arg(channel))->rawValue().toInt() != 1500) {
if (_vehicle->getParameterFact(-1, QString("RC%1_TRIM").arg(channel))->rawValue().toInt() != 1500) {
return true;
}
}
......@@ -116,17 +116,17 @@ void APMRadioComponent::_connectSetupTriggers(void)
// Get the channels for attitude controls and connect to those values for triggers
foreach (const QString& mapParam, _mapParams) {
int channel = _autopilot->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt();
int channel = _vehicle->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt();
Fact* fact = _autopilot->getParameterFact(-1, QString("RC%1_MIN").arg(channel));
Fact* fact = _vehicle->getParameterFact(-1, QString("RC%1_MIN").arg(channel));
_triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
fact = _autopilot->getParameterFact(-1, QString("RC%1_MAX").arg(channel));
fact = _vehicle->getParameterFact(-1, QString("RC%1_MAX").arg(channel));
_triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
fact = _autopilot->getParameterFact(-1, QString("RC%1_TRIM").arg(channel));
fact = _vehicle->getParameterFact(-1, QString("RC%1_TRIM").arg(channel));
_triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
}
......
......@@ -62,7 +62,7 @@ QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const
// Accelerometer triggers
triggers << "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z";
if (_autopilot->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) {
if (_vehicle->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) {
triggers << QStringLiteral("INS_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3");
triggers << QStringLiteral("INS_ACC2OFFS_X") << QStringLiteral("INS_ACC2OFFS_Y") << QStringLiteral("INS_ACC2OFFS_Z");
triggers << QStringLiteral("INS_ACC3OFFS_X") << QStringLiteral("INS_ACC3OFFS_Y") << QStringLiteral("INS_ACC3OFFS_Z");
......@@ -108,10 +108,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const
rgOffsets[2] << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_Y") << QStringLiteral("COMPASS_OFS3_Z");
for (size_t i=0; i<cCompass; i++) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 &&
_autopilot->getParameterFact(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 &&
_vehicle->getParameterFact(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) {
for (size_t j=0; j<cOffset; j++) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, rgOffsets[i][j])->rawValue().toFloat() == 0.0f) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, rgOffsets[i][j])->rawValue().toFloat() == 0.0f) {
return true;
}
}
......@@ -133,7 +133,7 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
rgOffsets.clear();
// This parameter is not available in all firmware version. Specifically missing from older Solo firmware.
if (_autopilot->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) {
if (_vehicle->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) {
rgUse << QStringLiteral("INS_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3");
// We have usage information for the remaining accels, so we can test them sa well
......@@ -147,9 +147,9 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
}
for (int i=0; i<rgAccels.count(); i++) {
if (rgUse.count() == 0 || _autopilot->getParameterFact(FactSystem::defaultComponentId, rgUse[i])->rawValue().toInt() != 0) {
if (rgUse.count() == 0 || _vehicle->getParameterFact(FactSystem::defaultComponentId, rgUse[i])->rawValue().toInt() != 0) {
for (int j=0; j<rgAccels[0].count(); j++) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, rgAccels[i][j])->rawValue().toFloat() == 0.0f) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, rgAccels[i][j])->rawValue().toFloat() == 0.0f) {
return true;
}
}
......
......@@ -60,7 +60,7 @@ QUrl APMTuningComponent::setupSource(void) const
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
// Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares
if (_autopilot->parameterExists(-1, QStringLiteral("CH9_OPT"))) {
if (_vehicle->parameterExists(-1, QStringLiteral("CH9_OPT"))) {
qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
}
break;
......
......@@ -117,16 +117,6 @@ void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& na
_vehicle->getParameterLoader()->refreshParametersPrefix(componentId, namePrefix);
}
bool AutoPilotPlugin::parameterExists(int componentId, const QString& name) const
{
return _vehicle->getParameterLoader()->parameterExists(componentId, name);
}
Fact* AutoPilotPlugin::getParameterFact(int componentId, const QString& name)
{
return _vehicle->getParameterLoader()->getFact(componentId, name);
}
bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name)
{
switch (provider) {
......
......@@ -7,131 +7,119 @@
*
****************************************************************************/
#ifndef AUTOPILOTPLUGIN_H
#define AUTOPILOTPLUGIN_H
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include <QObject>
#include <QList>
#include <QString>
#include <QQmlContext>
#ifndef AUTOPILOTPLUGIN_H
#define AUTOPILOTPLUGIN_H
#include "VehicleComponent.h"
#include "FactSystem.h"
#include "Vehicle.h"
#include <QObject>
#include <QList>
#include <QString>
#include <QQmlContext>
class ParameterLoader;
class Vehicle;
class FirmwarePlugin;
#include "VehicleComponent.h"
#include "FactSystem.h"
#include "Vehicle.h"
/// This is the base class for AutoPilot plugins
///
/// The AutoPilotPlugin class is an abstract base class which represent the methods and objects
/// which are specific to a certain AutoPilot. This is the only place where AutoPilot specific
/// code should reside in QGroundControl. The remainder of the QGroundControl source is
/// generic to a common mavlink implementation.
class ParameterLoader;
class Vehicle;
class FirmwarePlugin;
class AutoPilotPlugin : public QObject
{
Q_OBJECT
/// This is the base class for AutoPilot plugins
///
/// The AutoPilotPlugin class is an abstract base class which represent the methods and objects
/// which are specific to a certain AutoPilot. This is the only place where AutoPilot specific
/// code should reside in QGroundControl. The remainder of the QGroundControl source is
/// generic to a common mavlink implementation.
public:
AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~AutoPilotPlugin();
class AutoPilotPlugin : public QObject
{
Q_OBJECT
/// true: parameters are ready for use
Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged)
public:
AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~AutoPilotPlugin();
/// true: parameters are missing from firmware response, false: all parameters received from firmware
Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged)
/// true: parameters are ready for use
Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged)
/// List of VehicleComponent objects
Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT)
/// true: parameters are missing from firmware response, false: all parameters received from firmware
Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged)
/// false: One or more vehicle components require setup
Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged)
/// List of VehicleComponent objects
Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT)
/// Reset all parameters to their default values
Q_INVOKABLE void resetAllParametersToDefaults(void);
/// false: One or more vehicle components require setup
Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged)
/// Re-request the full set of parameters from the autopilot
Q_INVOKABLE void refreshAllParameters(unsigned char componentID = MAV_COMP_ID_ALL);
/// Reset all parameters to their default values
Q_INVOKABLE void resetAllParametersToDefaults(void);
/// Request a refresh on the specific parameter
Q_INVOKABLE void refreshParameter(int componentId, const QString& name);
/// Re-request the full set of parameters from the autopilot
Q_INVOKABLE void refreshAllParameters(unsigned char componentID = MAV_COMP_ID_ALL);
/// Request a refresh on all parameters that begin with the specified prefix
Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix);
/// Request a refresh on the specific parameter
Q_INVOKABLE void refreshParameter(int componentId, const QString& name);
/// Returns all parameter names
QStringList parameterNames(int componentId);
/// Request a refresh on all parameters that begin with the specified prefix
Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix);
/// Writes the parameter facts to the specified stream
void writeParametersToStream(QTextStream &stream);
/// Returns true if the specifed parameter exists from the default component
Q_INVOKABLE bool parameterExists(int componentId, const QString& name) const;
/// Reads the parameters from the stream and updates values
/// @return Errors during load. Empty string for no errors
QString readParametersFromStream(QTextStream &stream);
/// Returns all parameter names
QStringList parameterNames(int componentId);
/// Returns true if the specifed fact exists
Q_INVOKABLE bool factExists(FactSystem::Provider_t provider, ///< fact provider
int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name
/// Returns the specified parameter Fact from the default component
/// WARNING: Returns a default Fact if parameter does not exists. If that possibility exists, check for existence first with
/// parameterExists.
Fact* getParameterFact(int componentId, const QString& name);
/// Returns the specified Fact.
/// WARNING: Will assert if fact does not exists. If that possibility exists, check for existence first with
/// factExists.
Fact* getFact(FactSystem::Provider_t provider, ///< fact provider
int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name
/// Writes the parameter facts to the specified stream
void writeParametersToStream(QTextStream &stream);
const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
/// Reads the parameters from the stream and updates values
/// @return Errors during load. Empty string for no errors
QString readParametersFromStream(QTextStream &stream);
// Must be implemented by derived class
virtual const QVariantList& vehicleComponents(void) = 0;
/// Returns true if the specifed fact exists
Q_INVOKABLE bool factExists(FactSystem::Provider_t provider, ///< fact provider
int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name
// Property accessors
bool parametersReady(void) { return _parametersReady; }
bool missingParameters(void) { return _missingParameters; }
bool setupComplete(void);
/// Returns the specified Fact.
/// WARNING: Will assert if fact does not exists. If that possibility exists, check for existence first with
/// factExists.
Fact* getFact(FactSystem::Provider_t provider, ///< fact provider
int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name
Vehicle* vehicle(void) { return _vehicle; }
virtual void _parametersReadyPreChecks(bool parametersReady) = 0;
const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
signals:
void parametersReadyChanged(bool parametersReady);
void missingParametersChanged(bool missingParameters);
void setupCompleteChanged(bool setupComplete);
void parameterListProgress(float value);
// Must be implemented by derived class
virtual const QVariantList& vehicleComponents(void) = 0;
protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { }
// Property accessors
bool parametersReady(void) { return _parametersReady; }
bool missingParameters(void) { return _missingParameters; }
bool setupComplete(void);
Vehicle* _vehicle;
FirmwarePlugin* _firmwarePlugin;
bool _parametersReady;
bool _missingParameters;
bool _setupComplete;
Vehicle* vehicle(void) { return _vehicle; }
virtual void _parametersReadyPreChecks(bool parametersReady) = 0;
signals:
void parametersReadyChanged(bool parametersReady);
void missingParametersChanged(bool missingParameters);
void setupCompleteChanged(bool setupComplete);
void parameterListProgress(float value);
private slots:
void _uasDisconnected(void);
void _parametersReadyChanged(bool parametersReady);
protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { }
private:
void _recalcSetupComplete(void);
};
Vehicle* _vehicle;
FirmwarePlugin* _firmwarePlugin;
bool _parametersReady;
bool _missingParameters;
bool _setupComplete;
private slots:
void _uasDisconnected(void);
void _parametersReadyChanged(bool parametersReady);
private:
void _recalcSetupComplete(void);
};
#endif
#endif
......@@ -129,7 +129,7 @@ bool AirframeComponent::requiresSetup(void) const
bool AirframeComponent::setupComplete(void) const
{
return _autopilot->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt() != 0;
return _vehicle->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt() != 0;
}
QStringList AirframeComponent::setupCompleteChangedTriggerList(void) const
......
......@@ -43,17 +43,17 @@ QString FlightModesComponent::iconResource(void) const
bool FlightModesComponent::requiresSetup(void) const
{
return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true;
return _vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true;
}
bool FlightModesComponent::setupComplete(void) const
{
if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) {
if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) {
return true;
}
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0 ||
(_autopilot->parameterExists(FactSystem::defaultComponentId, "RC_MAP_FLTMODE") && _autopilot->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_FLTMODE")->rawValue().toInt() != 0)) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0 ||
(_vehicle->parameterExists(FactSystem::defaultComponentId, "RC_MAP_FLTMODE") && _vehicle->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_FLTMODE")->rawValue().toInt() != 0)) {
return true;
}
......@@ -81,7 +81,7 @@ QUrl FlightModesComponent::summaryQmlSource(void) const
QString FlightModesComponent::prerequisiteSetup(void) const
{
if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) {
if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) {
// No RC input
return QString();
} else {
......
......@@ -117,8 +117,8 @@ void PX4AutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters)
// Check for older parameter version set
// FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp
// should be used instead.
if (parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF") ||
parameterExists(FactSystem::defaultComponentId, "COM_DL_LOSS_EN")) {
if (_vehicle->parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF") ||
_vehicle->parameterExists(FactSystem::defaultComponentId, "COM_DL_LOSS_EN")) {
_incorrectParameterVersion = true;
qgcApp()->showMessage("This version of GroundControl can only perform vehicle setup on a newer version of firmware. "
"Please perform a Firmware Upgrade if you wish to use Vehicle Setup.");
......
......@@ -35,18 +35,18 @@ QString PX4RadioComponent::iconResource(void) const
bool PX4RadioComponent::requiresSetup(void) const
{
return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true;
return _vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true;
}
bool PX4RadioComponent::setupComplete(void) const
{
if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) {
if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) {
// The best we can do to detect the need for a radio calibration is look for attitude
// controls to be mapped.
QStringList attitudeMappings;
attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE";
foreach(const QString &mapParam, attitudeMappings) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) {
return false;
}
}
......@@ -76,7 +76,7 @@ QUrl PX4RadioComponent::summaryQmlSource(void) const
QString PX4RadioComponent::prerequisiteSetup(void) const
{
if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) {
if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) {
PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
if (!plugin->airframeComponent()->setupComplete()) {
......
......@@ -44,9 +44,9 @@ bool PowerComponent::requiresSetup(void) const
bool PowerComponent::setupComplete(void) const
{
QVariant cvalue, evalue, nvalue;
return _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f &&
_autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f &&
_autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0;
return _vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f &&
_vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f &&
_vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0;
}
QStringList PowerComponent::setupCompleteChangedTriggerList(void) const
......
......@@ -49,14 +49,14 @@ bool SensorsComponent::requiresSetup(void) const
bool SensorsComponent::setupComplete(void) const
{
foreach (const QString &triggerParam, _deviceIds) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) {
return false;
}
}
if (_vehicle->fixedWing() || _vehicle->vtol()) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, _airspeedCal)->rawValue().toFloat() == 0.0f) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, _airspeedCal)->rawValue().toFloat() == 0.0f) {
return false;
}
}
......
......@@ -306,9 +306,9 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
// Work out what the autopilot is configured to
int sides = 0;
if (_autopilot->parameterExists(FactSystem::defaultComponentId, "CAL_MAG_SIDES")) {
if (_vehicle->parameterExists(FactSystem::defaultComponentId, "CAL_MAG_SIDES")) {
// Read the requested calibration directions off the system
sides = _autopilot->getParameterFact(FactSystem::defaultComponentId, "CAL_MAG_SIDES")->rawValue().toFloat();
sides = _vehicle->getParameterFact(FactSystem::defaultComponentId, "CAL_MAG_SIDES")->rawValue().toFloat();
} else {
// There is no valid setting, default to all six sides
sides = (1 << 5) | (1 << 4) | (1 << 3) | (1 << 2) | (1 << 1) | (1 << 0);
......
......@@ -31,6 +31,8 @@ FactPanelController::FactPanelController(bool standaloneUnitTesting)
if (_vehicle) {
_uas = _vehicle->uas();
_autopilot = _vehicle->autopilotPlugin();
} else {
_vehicle = qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle();
}
if (!standaloneUnitTesting) {
......@@ -102,7 +104,7 @@ bool FactPanelController::_allParametersExists(int componentId, QStringList name
bool noMissingFacts = true;
foreach (const QString &name, names) {
if (_autopilot && !_autopilot->parameterExists(componentId, name)) {
if (_vehicle && !_vehicle->parameterExists(componentId, name)) {
_reportMissingParameter(componentId, name);
noMissingFacts = false;
}
......@@ -120,8 +122,8 @@ void FactPanelController::_checkForMissingFactPanel(void)
Fact* FactPanelController::getParameterFact(int componentId, const QString& name, bool reportMissing)
{
if (_autopilot && _autopilot->parameterExists(componentId, name)) {
Fact* fact = _autopilot->getParameterFact(componentId, name);
if (_vehicle && _vehicle->parameterExists(componentId, name)) {
Fact* fact = _vehicle->getParameterFact(componentId, name);
QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership);
return fact;
} else {
......@@ -133,7 +135,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name
bool FactPanelController::parameterExists(int componentId, const QString& name)
{
return _autopilot ? _autopilot->parameterExists(componentId, name) : false;
return _vehicle ? _vehicle->parameterExists(componentId, name) : false;
}
void FactPanelController::_showInternalError(const QString& errorMsg)
......
......@@ -96,7 +96,7 @@ void FactSystemTestBase::_qmlUpdate_test(void)
// Change the value
QVariant paramValue = 12;
_plugin->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_THROTTLE")->setRawValue(paramValue);
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_THROTTLE")->setRawValue(paramValue);
QTest::qWait(500); // Let the signals flow through
......
......@@ -39,7 +39,7 @@ const char* ParameterLoader::_cachedMetaDataFilePrefix = "ParameterFactMetaData"
ParameterLoader::ParameterLoader(Vehicle* vehicle)
: QObject(vehicle)
, _vehicle(vehicle)
, _mavlink(qgcApp()->toolbox()->mavlinkProtocol())
, _mavlink(NULL)
, _parametersReady(false)
, _initialLoadComplete(false)
, _waitingForDefaultComponent(false)
......@@ -53,8 +53,12 @@ ParameterLoader::ParameterLoader(Vehicle* vehicle)
, _initialRequestRetryCount(0)
, _totalParamCount(0)
{
Q_ASSERT(_vehicle);
Q_ASSERT(_mavlink);
if (_vehicle->isOfflineEditingVehicle()) {
_loadOfflineEditingParams();
return;
}
_mavlink = qgcApp()->toolbox()->mavlinkProtocol();
// We signal this to ouselves in order to start timer on our thread
connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer);
......@@ -1212,3 +1216,71 @@ QString ParameterLoader::_remapParamNameToVersion(const QString& paramName)
return mappedParamName;
}
/// The offline editing vehicle can have custom loaded params bolted into it.
void ParameterLoader::_loadOfflineEditingParams(void)
{
QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
if (paramFilename.isEmpty()) {
return;
}
QFile paramFile(paramFilename);
if (!paramFile.open(QFile::ReadOnly)) {
qCWarning(ParameterLoaderLog) << "Unable to open offline editing params file" << paramFilename;
}
QTextStream paramStream(&paramFile);
while (!paramStream.atEnd()) {
QString line = paramStream.readLine();
if (line.startsWith("#")) {
continue;
}
QStringList paramData = line.split("\t");
Q_ASSERT(paramData.count() == 5);
_defaultComponentId = paramData.at(1).toInt();
QString paramName = paramData.at(2);
QString valStr = paramData.at(3);
MAV_PARAM_TYPE paramType = static_cast<MAV_PARAM_TYPE>(paramData.at(4).toUInt());
QVariant paramValue;
switch (paramType) {
case MAV_PARAM_TYPE_REAL32:
paramValue = QVariant(valStr.toFloat());
break;
case MAV_PARAM_TYPE_UINT32:
paramValue = QVariant(valStr.toUInt());
break;
case MAV_PARAM_TYPE_INT32:
paramValue = QVariant(valStr.toInt());
break;
case MAV_PARAM_TYPE_UINT16:
paramValue = QVariant((quint16)valStr.toUInt());
break;
case MAV_PARAM_TYPE_INT16:
paramValue = QVariant((qint16)valStr.toInt());
break;
case MAV_PARAM_TYPE_UINT8:
paramValue = QVariant((quint8)valStr.toUInt());
break;
case MAV_PARAM_TYPE_INT8:
paramValue = QVariant((qint8)valStr.toUInt());
break;
default:
qCritical() << "Unknown type" << paramType;
paramValue = QVariant(valStr.toInt());
break;
}
Fact* fact = new Fact(_defaultComponentId, paramName, _mavTypeToFactType(paramType), this);
_mapParameterName2Variant[_defaultComponentId][paramName] = QVariant::fromValue(fact);
}
_addMetaDataToDefaultComponent();
_parametersReady = true;
_initialLoadComplete = true;
}
......@@ -125,6 +125,7 @@ private:
void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value);
void _addMetaDataToDefaultComponent(void);
QString _remapParamNameToVersion(const QString& paramName);
void _loadOfflineEditingParams(void);
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
......
Supports Markdown
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