Commit 04f97369 authored by Don Gagne's avatar Don Gagne

Move parameter apis to Vehicle

parent 61202e9a
...@@ -52,7 +52,7 @@ bool APMAirframeComponent::requiresSetup(void) const ...@@ -52,7 +52,7 @@ bool APMAirframeComponent::requiresSetup(void) const
bool APMAirframeComponent::setupComplete(void) const bool APMAirframeComponent::setupComplete(void) const
{ {
if (_requiresFrameSetup) { if (_requiresFrameSetup) {
return _autopilot->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0; return _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0;
} else { } else {
return true; return true;
} }
......
...@@ -609,16 +609,15 @@ void APMCompassCal::startCalibration(void) ...@@ -609,16 +609,15 @@ void APMCompassCal::startCalibration(void)
connect(_calWorkerThread, &CalWorkerThread::vehicleTextMessage, this, &APMCompassCal::vehicleTextMessage); connect(_calWorkerThread, &CalWorkerThread::vehicleTextMessage, this, &APMCompassCal::vehicleTextMessage);
// Clear the offset parameters so we get raw data // Clear the offset parameters so we get raw data
AutoPilotPlugin* plugin = _vehicle->autopilotPlugin();
for (int i=0; i<3; i++) { for (int i=0; i<3; i++) {
_calWorkerThread->rgCompassAvailable[i] = true; _calWorkerThread->rgCompassAvailable[i] = true;
const char* deviceIdParam = CalWorkerThread::rgCompassParams[i][3]; const char* deviceIdParam = CalWorkerThread::rgCompassParams[i][3];
if (plugin->parameterExists(-1, deviceIdParam)) { if (_vehicle->parameterExists(-1, deviceIdParam)) {
_calWorkerThread->rgCompassAvailable[i] = plugin->getParameterFact(-1, deviceIdParam)->rawValue().toInt() > 0; _calWorkerThread->rgCompassAvailable[i] = _vehicle->getParameterFact(-1, deviceIdParam)->rawValue().toInt() > 0;
for (int j=0; j<3; j++) { for (int j=0; j<3; j++) {
const char* offsetParam = CalWorkerThread::rgCompassParams[i][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(); _rgSavedCompassOffsets[i][j] = paramFact->rawValue().toFloat();
paramFact->setRawValue(0.0); paramFact->setRawValue(0.0);
...@@ -637,12 +636,11 @@ void APMCompassCal::cancelCalibration(void) ...@@ -637,12 +636,11 @@ void APMCompassCal::cancelCalibration(void)
_stopCalibration(); _stopCalibration();
// Put the original offsets back // Put the original offsets back
AutoPilotPlugin* plugin = _vehicle->autopilotPlugin();
for (int i=0; i<3; i++) { for (int i=0; i<3; i++) {
for (int j=0; j<3; j++) { for (int j=0; j<3; j++) {
const char* offsetParam = CalWorkerThread::rgCompassParams[i][j]; const char* offsetParam = CalWorkerThread::rgCompassParams[i][j];
if (plugin->parameterExists(-1, offsetParam)) { if (_vehicle->parameterExists(-1, offsetParam)) {
plugin->getParameterFact(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]); _vehicle->getParameterFact(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]);
} }
} }
} }
......
...@@ -40,7 +40,7 @@ bool APMPowerComponent::requiresSetup(void) const ...@@ -40,7 +40,7 @@ bool APMPowerComponent::requiresSetup(void) const
bool APMPowerComponent::setupComplete(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 QStringList APMPowerComponent::setupCompleteChangedTriggerList(void) const
......
...@@ -19,7 +19,7 @@ APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilo ...@@ -19,7 +19,7 @@ APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilo
_mapParams << QStringLiteral("RCMAP_ROLL") << QStringLiteral("RCMAP_PITCH") << QStringLiteral("RCMAP_YAW") << QStringLiteral("RCMAP_THROTTLE"); _mapParams << QStringLiteral("RCMAP_ROLL") << QStringLiteral("RCMAP_PITCH") << QStringLiteral("RCMAP_YAW") << QStringLiteral("RCMAP_THROTTLE");
foreach (const QString& mapParam, _mapParams) { foreach (const QString& mapParam, _mapParams) {
Fact* fact = _autopilot->getParameterFact(-1, mapParam); Fact* fact = _vehicle->getParameterFact(-1, mapParam);
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
} }
...@@ -56,7 +56,7 @@ bool APMRadioComponent::setupComplete(void) const ...@@ -56,7 +56,7 @@ bool APMRadioComponent::setupComplete(void) const
// First check for all attitude controls mapped // First check for all attitude controls mapped
for (int i=0; i<_mapParams.count(); i++) { 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) { if (mapValues[i] <= 0) {
return false; return false;
} }
...@@ -64,14 +64,14 @@ bool APMRadioComponent::setupComplete(void) const ...@@ -64,14 +64,14 @@ bool APMRadioComponent::setupComplete(void) const
// Next check RC#_MIN/MAX/TRIM all at defaults // Next check RC#_MIN/MAX/TRIM all at defaults
foreach (const QString& mapParam, _mapParams) { foreach (const QString& mapParam, _mapParams) {
int channel = _autopilot->getParameterFact(-1, mapParam)->rawValue().toInt(); int channel = _vehicle->getParameterFact(-1, mapParam)->rawValue().toInt();
if (_autopilot->getParameterFact(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) { if (_vehicle->getParameterFact(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) {
return true; 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; 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; return true;
} }
} }
...@@ -116,17 +116,17 @@ void APMRadioComponent::_connectSetupTriggers(void) ...@@ -116,17 +116,17 @@ void APMRadioComponent::_connectSetupTriggers(void)
// Get the channels for attitude controls and connect to those values for triggers // Get the channels for attitude controls and connect to those values for triggers
foreach (const QString& mapParam, _mapParams) { 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; _triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); 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; _triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); 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; _triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
} }
......
...@@ -62,7 +62,7 @@ QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const ...@@ -62,7 +62,7 @@ QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const
// Accelerometer triggers // Accelerometer triggers
triggers << "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; 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_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3");
triggers << QStringLiteral("INS_ACC2OFFS_X") << QStringLiteral("INS_ACC2OFFS_Y") << QStringLiteral("INS_ACC2OFFS_Z"); 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"); triggers << QStringLiteral("INS_ACC3OFFS_X") << QStringLiteral("INS_ACC3OFFS_Y") << QStringLiteral("INS_ACC3OFFS_Z");
...@@ -108,10 +108,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const ...@@ -108,10 +108,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const
rgOffsets[2] << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_Y") << QStringLiteral("COMPASS_OFS3_Z"); rgOffsets[2] << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_Y") << QStringLiteral("COMPASS_OFS3_Z");
for (size_t i=0; i<cCompass; i++) { for (size_t i=0; i<cCompass; i++) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 && if (_vehicle->getParameterFact(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 &&
_autopilot->getParameterFact(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) { _vehicle->getParameterFact(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) {
for (size_t j=0; j<cOffset; j++) { 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; return true;
} }
} }
...@@ -133,7 +133,7 @@ bool APMSensorsComponent::accelSetupNeeded(void) const ...@@ -133,7 +133,7 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
rgOffsets.clear(); rgOffsets.clear();
// This parameter is not available in all firmware version. Specifically missing from older Solo firmware. // 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"); 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 // We have usage information for the remaining accels, so we can test them sa well
...@@ -147,9 +147,9 @@ bool APMSensorsComponent::accelSetupNeeded(void) const ...@@ -147,9 +147,9 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
} }
for (int i=0; i<rgAccels.count(); i++) { 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++) { 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; return true;
} }
} }
......
...@@ -60,7 +60,7 @@ QUrl APMTuningComponent::setupSource(void) const ...@@ -60,7 +60,7 @@ QUrl APMTuningComponent::setupSource(void) const
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
// Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares // 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"); qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
} }
break; break;
......
...@@ -117,16 +117,6 @@ void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& na ...@@ -117,16 +117,6 @@ void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& na
_vehicle->getParameterLoader()->refreshParametersPrefix(componentId, namePrefix); _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) bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name)
{ {
switch (provider) { switch (provider) {
......
...@@ -7,38 +7,34 @@ ...@@ -7,38 +7,34 @@
* *
****************************************************************************/ ****************************************************************************/
#ifndef AUTOPILOTPLUGIN_H
/// @file #define AUTOPILOTPLUGIN_H
/// @author Don Gagne <don@thegagnes.com>
#include <QObject>
#ifndef AUTOPILOTPLUGIN_H #include <QList>
#define AUTOPILOTPLUGIN_H #include <QString>
#include <QQmlContext>
#include <QObject>
#include <QList> #include "VehicleComponent.h"
#include <QString> #include "FactSystem.h"
#include <QQmlContext> #include "Vehicle.h"
#include "VehicleComponent.h" class ParameterLoader;
#include "FactSystem.h" class Vehicle;
#include "Vehicle.h" class FirmwarePlugin;
class ParameterLoader; /// This is the base class for AutoPilot plugins
class Vehicle; ///
class FirmwarePlugin; /// 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
/// This is the base class for AutoPilot plugins /// code should reside in QGroundControl. The remainder of the QGroundControl source is
/// /// generic to a common mavlink implementation.
/// 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 class AutoPilotPlugin : public QObject
/// code should reside in QGroundControl. The remainder of the QGroundControl source is {
/// generic to a common mavlink implementation.
class AutoPilotPlugin : public QObject
{
Q_OBJECT Q_OBJECT
public: public:
AutoPilotPlugin(Vehicle* vehicle, QObject* parent); AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~AutoPilotPlugin(); ~AutoPilotPlugin();
...@@ -66,17 +62,9 @@ ...@@ -66,17 +62,9 @@
/// Request a refresh on all parameters that begin with the specified prefix /// Request a refresh on all parameters that begin with the specified prefix
Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix); Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix);
/// Returns true if the specifed parameter exists from the default component
Q_INVOKABLE bool parameterExists(int componentId, const QString& name) const;
/// Returns all parameter names /// Returns all parameter names
QStringList parameterNames(int componentId); QStringList parameterNames(int componentId);
/// 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);
/// Writes the parameter facts to the specified stream /// Writes the parameter facts to the specified stream
void writeParametersToStream(QTextStream &stream); void writeParametersToStream(QTextStream &stream);
...@@ -109,13 +97,13 @@ ...@@ -109,13 +97,13 @@
Vehicle* vehicle(void) { return _vehicle; } Vehicle* vehicle(void) { return _vehicle; }
virtual void _parametersReadyPreChecks(bool parametersReady) = 0; virtual void _parametersReadyPreChecks(bool parametersReady) = 0;
signals: signals:
void parametersReadyChanged(bool parametersReady); void parametersReadyChanged(bool parametersReady);
void missingParametersChanged(bool missingParameters); void missingParametersChanged(bool missingParameters);
void setupCompleteChanged(bool setupComplete); void setupCompleteChanged(bool setupComplete);
void parameterListProgress(float value); void parameterListProgress(float value);
protected: protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin /// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { } AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { }
...@@ -126,12 +114,12 @@ ...@@ -126,12 +114,12 @@
bool _setupComplete; bool _setupComplete;
private slots: private slots:
void _uasDisconnected(void); void _uasDisconnected(void);
void _parametersReadyChanged(bool parametersReady); void _parametersReadyChanged(bool parametersReady);
private: private:
void _recalcSetupComplete(void); void _recalcSetupComplete(void);
}; };
#endif #endif
...@@ -129,7 +129,7 @@ bool AirframeComponent::requiresSetup(void) const ...@@ -129,7 +129,7 @@ bool AirframeComponent::requiresSetup(void) const
bool AirframeComponent::setupComplete(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 QStringList AirframeComponent::setupCompleteChangedTriggerList(void) const
......
...@@ -43,17 +43,17 @@ QString FlightModesComponent::iconResource(void) const ...@@ -43,17 +43,17 @@ QString FlightModesComponent::iconResource(void) const
bool FlightModesComponent::requiresSetup(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 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; return true;
} }
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0 || if (_vehicle->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)) { (_vehicle->parameterExists(FactSystem::defaultComponentId, "RC_MAP_FLTMODE") && _vehicle->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_FLTMODE")->rawValue().toInt() != 0)) {
return true; return true;
} }
...@@ -81,7 +81,7 @@ QUrl FlightModesComponent::summaryQmlSource(void) const ...@@ -81,7 +81,7 @@ QUrl FlightModesComponent::summaryQmlSource(void) const
QString FlightModesComponent::prerequisiteSetup(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 // No RC input
return QString(); return QString();
} else { } else {
......
...@@ -117,8 +117,8 @@ void PX4AutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters) ...@@ -117,8 +117,8 @@ void PX4AutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters)
// Check for older parameter version set // Check for older parameter version set
// FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp // FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp
// should be used instead. // should be used instead.
if (parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF") || if (_vehicle->parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF") ||
parameterExists(FactSystem::defaultComponentId, "COM_DL_LOSS_EN")) { _vehicle->parameterExists(FactSystem::defaultComponentId, "COM_DL_LOSS_EN")) {
_incorrectParameterVersion = true; _incorrectParameterVersion = true;
qgcApp()->showMessage("This version of GroundControl can only perform vehicle setup on a newer version of firmware. " 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."); "Please perform a Firmware Upgrade if you wish to use Vehicle Setup.");
......
...@@ -35,18 +35,18 @@ QString PX4RadioComponent::iconResource(void) const ...@@ -35,18 +35,18 @@ QString PX4RadioComponent::iconResource(void) const
bool PX4RadioComponent::requiresSetup(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 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 // The best we can do to detect the need for a radio calibration is look for attitude
// controls to be mapped. // controls to be mapped.
QStringList attitudeMappings; QStringList attitudeMappings;
attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE"; attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE";
foreach(const QString &mapParam, attitudeMappings) { 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; return false;
} }
} }
...@@ -76,7 +76,7 @@ QUrl PX4RadioComponent::summaryQmlSource(void) const ...@@ -76,7 +76,7 @@ QUrl PX4RadioComponent::summaryQmlSource(void) const
QString PX4RadioComponent::prerequisiteSetup(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); PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
if (!plugin->airframeComponent()->setupComplete()) { if (!plugin->airframeComponent()->setupComplete()) {
......
...@@ -44,9 +44,9 @@ bool PowerComponent::requiresSetup(void) const ...@@ -44,9 +44,9 @@ bool PowerComponent::requiresSetup(void) const
bool PowerComponent::setupComplete(void) const bool PowerComponent::setupComplete(void) const
{ {
QVariant cvalue, evalue, nvalue; QVariant cvalue, evalue, nvalue;
return _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f && return _vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f &&
_autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f && _vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f &&
_autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0; _vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0;
} }
QStringList PowerComponent::setupCompleteChangedTriggerList(void) const QStringList PowerComponent::setupCompleteChangedTriggerList(void) const
......
...@@ -49,14 +49,14 @@ bool SensorsComponent::requiresSetup(void) const ...@@ -49,14 +49,14 @@ bool SensorsComponent::requiresSetup(void) const
bool SensorsComponent::setupComplete(void) const bool SensorsComponent::setupComplete(void) const
{ {
foreach (const QString &triggerParam, _deviceIds) { 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; return false;
} }
} }
if (_vehicle->fixedWing() || _vehicle->vtol()) { if (_vehicle->fixedWing() || _vehicle->vtol()) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) { if (_vehicle->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, _airspeedCal)->rawValue().toFloat() == 0.0f) { if (_vehicle->getParameterFact(FactSystem::defaultComponentId, _airspeedCal)->rawValue().toFloat() == 0.0f) {
return false; return false;
} }
} }
......
...@@ -306,9 +306,9 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in ...@@ -306,9 +306,9 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
// Work out what the autopilot is configured to // Work out what the autopilot is configured to
int sides = 0; 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 // 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 { } else {
// There is no valid setting, default to all six sides // There is no valid setting, default to all six sides
sides = (1 << 5) | (1 << 4) | (1 << 3) | (1 << 2) | (1 << 1) | (1 << 0); sides = (1 << 5) | (1 << 4) | (1 << 3) | (1 << 2) | (1 << 1) | (1 << 0);
......
...@@ -31,6 +31,8 @@ FactPanelController::FactPanelController(bool standaloneUnitTesting) ...@@ -31,6 +31,8 @@ FactPanelController::FactPanelController(bool standaloneUnitTesting)
if (_vehicle) { if (_vehicle) {
_uas = _vehicle->uas(); _uas = _vehicle->uas();
_autopilot = _vehicle->autopilotPlugin(); _autopilot = _vehicle->autopilotPlugin();
} else {
_vehicle = qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle();
} }
if (!standaloneUnitTesting) { if (!standaloneUnitTesting) {
...@@ -102,7 +104,7 @@ bool FactPanelController::_allParametersExists(int componentId, QStringList name ...@@ -102,7 +104,7 @@ bool FactPanelController::_allParametersExists(int componentId, QStringList name
bool noMissingFacts = true; bool noMissingFacts = true;
foreach (const QString &name, names) { foreach (const QString &name, names) {
if (_autopilot && !_autopilot->parameterExists(componentId, name)) { if (_vehicle && !_vehicle->parameterExists(componentId, name)) {
_reportMissingParameter(componentId, name); _reportMissingParameter(componentId, name);
noMissingFacts = false; noMissingFacts = false;
} }
...@@ -120,8 +122,8 @@ void FactPanelController::_checkForMissingFactPanel(void) ...@@ -120,8 +122,8 @@ void FactPanelController::_checkForMissingFactPanel(void)
Fact* FactPanelController::getParameterFact(int componentId, const QString& name, bool reportMissing) Fact* FactPanelController::getParameterFact(int componentId, const QString& name, bool reportMissing)
{ {
if (_autopilot && _autopilot->parameterExists(componentId, name)) { if (_vehicle && _vehicle->parameterExists(componentId, name)) {
Fact* fact = _autopilot->getParameterFact(componentId, name); Fact* fact = _vehicle->getParameterFact(componentId, name);
QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership);
return fact; return fact;
} else { } else {
...@@ -133,7 +135,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name ...@@ -133,7 +135,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name
bool FactPanelController::parameterExists(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) void FactPanelController::_showInternalError(const QString& errorMsg)
......
...@@ -96,7 +96,7 @@ void FactSystemTestBase::_qmlUpdate_test(void) ...@@ -96,7 +96,7 @@ void FactSystemTestBase::_qmlUpdate_test(void)
// Change the value // Change the value
QVariant paramValue = 12; 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 QTest::qWait(500); // Let the signals flow through
......
...@@ -210,7 +210,7 @@ bool ArduCopterFirmwarePlugin::multiRotorCoaxialMotors(Vehicle* vehicle) ...@@ -210,7 +210,7 @@ bool ArduCopterFirmwarePlugin::multiRotorCoaxialMotors(Vehicle* vehicle)
bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle) bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle)
{ {
return vehicle->autopilotPlugin()->getParameterFact(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0; return vehicle->getParameterFact(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0;
} }
QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle) QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle)
......
...@@ -30,7 +30,7 @@ QGCFlickable { ...@@ -30,7 +30,7 @@ QGCFlickable {
property color textColor property color textColor
property var maxHeight property var maxHeight
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.disconnectedVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property real _margins: ScreenTools.defaultFontPixelWidth / 2 property real _margins: ScreenTools.defaultFontPixelWidth / 2
QGCPalette { id:qgcPal; colorGroupEnabled: true } QGCPalette { id:qgcPal; colorGroupEnabled: true }
......
...@@ -29,7 +29,7 @@ QGCFlickable { ...@@ -29,7 +29,7 @@ QGCFlickable {
property color backgroundColor property color backgroundColor
property var maxHeight property var maxHeight
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.disconnectedVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property real _margins: ScreenTools.defaultFontPixelWidth / 2 property real _margins: ScreenTools.defaultFontPixelWidth / 2
property real _barWidth: Math.round(ScreenTools.defaultFontPixelWidth * 3) property real _barWidth: Math.round(ScreenTools.defaultFontPixelWidth * 3)
......
...@@ -68,7 +68,7 @@ QStringList ParameterEditorController::searchParametersForComponent(int componen ...@@ -68,7 +68,7 @@ QStringList ParameterEditorController::searchParametersForComponent(int componen
if (searchText.isEmpty()) { if (searchText.isEmpty()) {
list += paramName; list += paramName;
} else { } else {
Fact* fact = _autopilot->getParameterFact(componentId, paramName); Fact* fact = _vehicle->getParameterFact(componentId, paramName);
if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) { if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) {
list += paramName; list += paramName;
...@@ -189,11 +189,11 @@ void ParameterEditorController::_updateParameters(void) ...@@ -189,11 +189,11 @@ void ParameterEditorController::_updateParameters(void)
if (_searchText.isEmpty()) { if (_searchText.isEmpty()) {
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) { foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) {
newParameterList.append(_autopilot->getParameterFact(_currentComponentId, parameter)); newParameterList.append(_vehicle->getParameterFact(_currentComponentId, parameter));
} }
} else { } else {
foreach(const QString &parameter, _autopilot->parameterNames(_vehicle->defaultComponentId())) { foreach(const QString &parameter, _autopilot->parameterNames(_vehicle->defaultComponentId())) {
Fact* fact = _autopilot->getParameterFact(_vehicle->defaultComponentId(), parameter); Fact* fact = _vehicle->getParameterFact(_vehicle->defaultComponentId(), parameter);
if (fact->name().contains(_searchText, Qt::CaseInsensitive) || if (fact->name().contains(_searchText, Qt::CaseInsensitive) ||
fact->shortDescription().contains(_searchText, Qt::CaseInsensitive) || fact->shortDescription().contains(_searchText, Qt::CaseInsensitive) ||
fact->longDescription().contains(_searchText, Qt::CaseInsensitive)) { fact->longDescription().contains(_searchText, Qt::CaseInsensitive)) {
......
...@@ -49,8 +49,8 @@ void VehicleComponent::setupTriggerSignals(void) ...@@ -49,8 +49,8 @@ void VehicleComponent::setupTriggerSignals(void)
{ {
// Watch for changed on trigger list params // Watch for changed on trigger list params
foreach (const QString &paramName, setupCompleteChangedTriggerList()) { foreach (const QString &paramName, setupCompleteChangedTriggerList()) {
if (_autopilot->parameterExists(FactSystem::defaultComponentId, paramName)) { if (_vehicle->parameterExists(FactSystem::defaultComponentId, paramName)) {
Fact* fact = _autopilot->getParameterFact(FactSystem::defaultComponentId, paramName); Fact* fact = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName);
connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated); connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated);
} }
} }
......
...@@ -378,7 +378,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType) ...@@ -378,7 +378,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType)
switchList << "RC_MAP_MODE_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_ACRO_SW"; switchList << "RC_MAP_MODE_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_ACRO_SW";
foreach (const QString &switchParam, switchList) { foreach (const QString &switchParam, switchList) {
Q_ASSERT(_autopilot->getParameterFact(FactSystem::defaultComponentId, switchParam)->rawValue().toInt() != channel + 1); Q_ASSERT(_vehicle->getParameterFact(FactSystem::defaultComponentId, switchParam)->rawValue().toInt() != channel + 1);
} }
} }
...@@ -393,7 +393,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType) ...@@ -393,7 +393,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType)
if (!found) { if (!found) {
const char* paramName = _functionInfo()[function].parameterName; const char* paramName = _functionInfo()[function].parameterName;
if (paramName) { if (paramName) {
_rgFunctionChannelMap[function] = _autopilot->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(); _rgFunctionChannelMap[function] = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt();
qCDebug(RadioConfigTestLog) << "Assigning switch" << function << _rgFunctionChannelMap[function]; qCDebug(RadioConfigTestLog) << "Assigning switch" << function << _rgFunctionChannelMap[function];
if (_rgFunctionChannelMap[function] == 0) { if (_rgFunctionChannelMap[function] == 0) {
_rgFunctionChannelMap[function] = -1; // -1 signals no mapping _rgFunctionChannelMap[function] = -1; // -1 signals no mapping
...@@ -469,8 +469,8 @@ void RadioConfigTest::_validateParameters(void) ...@@ -469,8 +469,8 @@ void RadioConfigTest::_validateParameters(void)
const char* paramName = _functionInfo()[chanFunction].parameterName; const char* paramName = _functionInfo()[chanFunction].parameterName;
if (paramName) { if (paramName) {
qCDebug(RadioConfigTestLog) << "Validate" << chanFunction << _autopilot->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(); qCDebug(RadioConfigTestLog) << "Validate" << chanFunction << _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt();
QCOMPARE(_autopilot->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedParameterValue); QCOMPARE(_vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedParameterValue);
} }
} }
...@@ -485,13 +485,13 @@ void RadioConfigTest::_validateParameters(void) ...@@ -485,13 +485,13 @@ void RadioConfigTest::_validateParameters(void)
int rcTrimExpected = _channelSettingsValidate()[chan].rcTrim; int rcTrimExpected = _channelSettingsValidate()[chan].rcTrim;
bool rcReversedExpected = _channelSettingsValidate()[chan].reversed; bool rcReversedExpected = _channelSettingsValidate()[chan].reversed;
int rcMinActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); int rcMinActual = _vehicle->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk);
QCOMPARE(convertOk, true); QCOMPARE(convertOk, true);
int rcMaxActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); int rcMaxActual = _vehicle->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk);
QCOMPARE(convertOk, true); QCOMPARE(convertOk, true);
int rcTrimActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); int rcTrimActual = _vehicle->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk);
QCOMPARE(convertOk, true); QCOMPARE(convertOk, true);
float rcReversedFloat = _autopilot->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->rawValue().toFloat(&convertOk); float rcReversedFloat = _vehicle->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->rawValue().toFloat(&convertOk);
QCOMPARE(convertOk, true); QCOMPARE(convertOk, true);
bool rcReversedActual = (rcReversedFloat == -1.0f); bool rcReversedActual = (rcReversedFloat == -1.0f);
...@@ -515,7 +515,7 @@ void RadioConfigTest::_validateParameters(void) ...@@ -515,7 +515,7 @@ void RadioConfigTest::_validateParameters(void)
const char* paramName = _functionInfo()[chanFunction].parameterName; const char* paramName = _functionInfo()[chanFunction].parameterName;
if (paramName) { if (paramName) {
// qCDebug(RadioConfigTestLog) << chanFunction << expectedValue << mapParamsSet[paramName].toInt(); // qCDebug(RadioConfigTestLog) << chanFunction << expectedValue << mapParamsSet[paramName].toInt();
QCOMPARE(_autopilot->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedValue); QCOMPARE(_vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedValue);
} }
} }
} }
......
...@@ -30,9 +30,8 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav ...@@ -30,9 +30,8 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav
ui->setupUi(this); ui->setupUi(this);
// refresh the parameter from onboard to make sure the current value is used // refresh the parameter from onboard to make sure the current value is used
AutoPilotPlugin* autopilot = _multiVehicleManager->getVehicleById(mav->getUASID())->autopilotPlugin(); Vehicle* vehicle = _multiVehicleManager->getVehicleById(mav->getUASID());
Q_ASSERT(autopilot); Fact* paramFact = vehicle->getParameterFact(FactSystem::defaultComponentId, param_id);
Fact* paramFact = autopilot->getParameterFact(FactSystem::defaultComponentId, param_id);
ui->minValueDoubleSpinBox->setValue(paramFact->rawMin().toDouble()); ui->minValueDoubleSpinBox->setValue(paramFact->rawMin().toDouble());
ui->maxValueDoubleSpinBox->setValue(paramFact->rawMax().toDouble()); ui->maxValueDoubleSpinBox->setValue(paramFact->rawMax().toDouble());
...@@ -44,7 +43,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav ...@@ -44,7 +43,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav
ui->paramIdLabel->setText(param_id); ui->paramIdLabel->setText(param_id);
connect(paramFact, &Fact::valueChanged, this, &QGCMapRCToParamDialog::_parameterUpdated); connect(paramFact, &Fact::valueChanged, this, &QGCMapRCToParamDialog::_parameterUpdated);
autopilot->refreshParameter(FactSystem::defaultComponentId, param_id); vehicle->autopilotPlugin()->refreshParameter(FactSystem::defaultComponentId, param_id);
} }
QGCMapRCToParamDialog::~QGCMapRCToParamDialog() QGCMapRCToParamDialog::~QGCMapRCToParamDialog()
......
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