Commit 97c8b6dc authored by Don Gagne's avatar Don Gagne

FactSystem now only source for parameters

QGCUASParamManager and friends are replaced by FactSystem
parent 2d2ed7a7
......@@ -25,11 +25,11 @@
/// @author Don Gagne <don@thegagnes.com>
#include "AutoPilotPlugin.h"
#include "QGCUASParamManagerInterface.h"
#include "SetupView.h"
#include "QGCApplication.h"
#include "QGCMessageBox.h"
#include "MainWindow.h"
#include "ParameterLoader.h"
AutoPilotPlugin::AutoPilotPlugin(UASInterface* uas, QObject* parent) :
QObject(parent),
......@@ -160,27 +160,10 @@ const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{
Q_ASSERT(_uas);
_uas->getParamManager()->writeOnboardParamsToStream(stream, _uas->getUASName());
_getParameterLoader()->writeParametersToStream(stream, _uas->getUASName());
}
void AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{
Q_ASSERT(_uas);
Fact* autoSaveFact = NULL;
int previousAutoSave = 0;
if (parameterExists("COM_AUTOS_PAR")) {
autoSaveFact = getParameterFact("COM_AUTOS_PAR");
previousAutoSave = autoSaveFact->value().toInt();
autoSaveFact->setValue(1);
}
_uas->getParamManager()->readPendingParamsFromStream(stream);
if (autoSaveFact) {
autoSaveFact->setValue(previousAutoSave);
}
_getParameterLoader()->readParametersFromStream(stream);
}
......@@ -35,7 +35,8 @@
#include "UASInterface.h"
#include "VehicleComponent.h"
#include "FactSystem.h"
#include "ParameterLoader.h"
class ParameterLoader;
/// This is the base class for AutoPilot plugins
///
......@@ -115,6 +116,7 @@ public:
signals:
void pluginReadyChanged(bool pluginReady);
void setupCompleteChanged(bool setupComplete);
void parameterListProgress(float value);
protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
......
......@@ -31,10 +31,11 @@ GenericAutoPilotPlugin::GenericAutoPilotPlugin(UASInterface* uas, QObject* paren
{
Q_ASSERT(uas);
_parameterFacts = new GenericParameterFacts(uas, this);
_parameterFacts = new GenericParameterFacts(this, uas, this);
Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &GenericParameterFacts::parametersReady, this, &GenericAutoPilotPlugin::_parametersReady);
connect(_parameterFacts, &GenericParameterFacts::parameterListProgress, this, &GenericAutoPilotPlugin::parameterListProgress);
}
QList<AutoPilotPluginManager::FullMode_t> GenericAutoPilotPlugin::getModes(void)
......
......@@ -28,8 +28,8 @@
#include <QDebug>
GenericParameterFacts::GenericParameterFacts(UASInterface* uas, QObject* parent) :
ParameterLoader(uas, parent)
GenericParameterFacts::GenericParameterFacts(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent) :
ParameterLoader(autopilot, uas, parent)
{
Q_ASSERT(uas);
}
......@@ -28,6 +28,7 @@
#include "ParameterLoader.h"
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
......@@ -40,7 +41,7 @@ class GenericParameterFacts : public ParameterLoader
public:
/// @param uas Uas which this set of facts is associated with
GenericParameterFacts(UASInterface* uas, QObject* parent = NULL);
GenericParameterFacts(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent = NULL);
/// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
......
......@@ -81,7 +81,7 @@ AirframeComponentController::AirframeComponentController(QObject* parent) :
_airframeTypes.append(QVariant::fromValue(airframeType));
}
if (_autostartId != 0) {
// FIXME: Should be a user error
Q_UNUSED(autostartFound);
......@@ -104,33 +104,14 @@ void AirframeComponentController::changeAutostart(void)
_autoPilotPlugin->getParameterFact("SYS_AUTOSTART")->setValue(_autostartId);
_autoPilotPlugin->getParameterFact("SYS_AUTOCONFIG")->setValue(1);
// Wait for the parameters to come back to us
qgcApp()->setOverrideCursor(Qt::WaitCursor);
int waitSeconds = 10;
bool success = false;
QGCUASParamManagerInterface* paramMgr = _uas->getParamManager();
while (true) {
if (paramMgr->countPendingParams() == 0) {
success = true;
break;
}
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
QGC::SLEEP::sleep(1);
if (--waitSeconds == 0) {
break;
}
}
// Wait for the parameters to flow through system
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
QGC::SLEEP::sleep(1);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
if (!success) {
qgcApp()->restoreOverrideCursor();
QGCMessageBox::critical("Airframe Config", "Airframe Config parameters not received back from vehicle. Config has not been set.");
return;
}
// Reboot board and reconnect
_uas->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
......@@ -173,4 +154,3 @@ Airframe::~Airframe()
{
}
......@@ -24,7 +24,6 @@
#include "PX4AutoPilotPlugin.h"
#include "AutoPilotPluginManager.h"
#include "UASManager.h"
#include "QGCUASParamManagerInterface.h"
#include "PX4ParameterLoader.h"
#include "FlightModesComponentController.h"
#include "AirframeComponentController.h"
......@@ -79,10 +78,11 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) :
qmlRegisterType<FlightModesComponentController>("QGroundControl.Controllers", 1, 0, "FlightModesComponentController");
qmlRegisterType<AirframeComponentController>("QGroundControl.Controllers", 1, 0, "AirframeComponentController");
_parameterFacts = new PX4ParameterLoader(uas, this);
_parameterFacts = new PX4ParameterLoader(this, uas, this);
Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &PX4ParameterLoader::parametersReady, this, &PX4AutoPilotPlugin::_pluginReadyPreChecks);
connect(_parameterFacts, &PX4ParameterLoader::parameterListProgress, this, &PX4AutoPilotPlugin::parameterListProgress);
PX4ParameterLoader::loadParameterFactMetaData();
}
......@@ -197,26 +197,32 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
_airframeComponent = new AirframeComponent(_uas, this);
Q_CHECK_PTR(_airframeComponent);
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
_radioComponent = new RadioComponent(_uas, this);
Q_CHECK_PTR(_radioComponent);
_radioComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_radioComponent));
_flightModesComponent = new FlightModesComponent(_uas, this);
Q_CHECK_PTR(_flightModesComponent);
_flightModesComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent));
_sensorsComponent = new SensorsComponent(_uas, this);
Q_CHECK_PTR(_sensorsComponent);
_sensorsComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent));
_powerComponent = new PowerComponent(_uas, this);
Q_CHECK_PTR(_powerComponent);
_powerComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_powerComponent));
_safetyComponent = new SafetyComponent(_uas, this);
Q_CHECK_PTR(_safetyComponent);
_safetyComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent));
}
......
......@@ -25,32 +25,29 @@
/// @author Don Gagne <don@thegagnes.com>
#include "PX4Component.h"
#include "Fact.h"
#include "AutoPilotPlugin.h"
PX4Component::PX4Component(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) :
VehicleComponent(uas, autopilot, parent)
{
Q_ASSERT(uas);
Q_ASSERT(autopilot);
_paramMgr = _uas->getParamManager();
Q_ASSERT(_paramMgr);
}
bool fSuccess = connect(_paramMgr, SIGNAL(parameterUpdated(int, QString, QVariant)), this, SLOT(_parameterUpdated(int, QString, QVariant)));
Q_ASSERT(fSuccess);
Q_UNUSED(fSuccess);
void PX4Component::setupTriggerSignals(void)
{
// Watch for changed on trigger list params
foreach (QString paramName, setupCompleteChangedTriggerList()) {
Fact* fact = _autopilot->getParameterFact(paramName);
connect(fact, &Fact::valueChanged, this, &PX4Component::_triggerUpdated);
}
}
void PX4Component::_parameterUpdated(int compId, QString paramName, QVariant value)
void PX4Component::_triggerUpdated(QVariant value)
{
Q_UNUSED(value);
if (compId == _paramMgr->getDefaultComponentId()) {
QStringList triggerList = setupCompleteChangedTriggerList();
foreach(QString triggerParam, triggerList) {
if (paramName == triggerParam) {
emit setupCompleteChanged(setupComplete());
return;
}
}
}
emit setupCompleteChanged(setupComplete());
}
......@@ -43,13 +43,12 @@ public:
/// signal to be emitted. Last element is signalled by NULL.
virtual QStringList setupCompleteChangedTriggerList(void) const = 0;
private slots:
/// @brief Connected to QGCUASParamManagerInterface::parameterUpdated signal in order to signal
/// setupCompleteChanged at appropriate times.
void _parameterUpdated(int compId, QString paramName, QVariant value);
/// Should be called after the component is created (but not in constructor) to setup the
/// signals which are used to track parameter changes which affect setupComplete state.
void setupTriggerSignals(void);
private:
QGCUASParamManagerInterface* _paramMgr;
private slots:
void _triggerUpdated(QVariant value);
};
#endif
......@@ -38,8 +38,8 @@ QGC_LOGGING_CATEGORY(PX4ParameterLoaderLog, "PX4ParameterLoaderLog")
bool PX4ParameterLoader::_parameterMetaDataLoaded = false;
QMap<QString, FactMetaData*> PX4ParameterLoader::_mapParameterName2FactMetaData;
PX4ParameterLoader::PX4ParameterLoader(UASInterface* uas, QObject* parent) :
ParameterLoader(uas, parent)
PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent) :
ParameterLoader(autopilot, uas, parent)
{
Q_ASSERT(uas);
}
......@@ -221,7 +221,7 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
Q_CHECK_PTR(metaData);
if (_mapParameterName2FactMetaData.contains(name)) {
// We can't trust the meta dafa since we have dups
qDebug() << "Duplicate parameter found:" << name;
qCDebug(PX4ParameterLoaderLog) << "Duplicate parameter found:" << name;
badMetaData = true;
// Reset to default meta data
_mapParameterName2FactMetaData[name] = metaData;
......@@ -236,7 +236,7 @@ void PX4ParameterLoader::loadParameterFactMetaData(void)
metaData->setDefaultValue(varDefault);
} else {
// Non-fatal
qDebug() << "Parameter meta data with bad default value, name:" << name << " type:" << type << " default:" << strDefault;
qCDebug(PX4ParameterLoaderLog) << "Parameter meta data with bad default value, name:" << name << " type:" << type << " default:" << strDefault;
}
}
}
......
......@@ -32,6 +32,7 @@
#include "ParameterLoader.h"
#include "FactSystem.h"
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
......@@ -46,7 +47,7 @@ class PX4ParameterLoader : public ParameterLoader
public:
/// @param uas Uas which this set of facts is associated with
PX4ParameterLoader(UASInterface* uas, QObject* parent = NULL);
PX4ParameterLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = NULL);
/// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
......
......@@ -228,7 +228,6 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
}
_appendStatusLog(text);
qDebug() << text;
if (_unknownFirmwareVersion) {
// We don't know how to do visual cal with the version of firwmare
......@@ -401,8 +400,8 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
void SensorsComponentController::_refreshParams(void)
{
// Pull full set in order to get all cal values back
_autopilot->refreshAllParameters();
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "CAL_");
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "SENS_");
}
bool SensorsComponentController::fixedWing(void)
......
......@@ -40,29 +40,35 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec
void Fact::setValue(const QVariant& value)
{
QVariant newValue;
switch (type()) {
case FactMetaData::valueTypeInt8:
case FactMetaData::valueTypeInt16:
case FactMetaData::valueTypeInt32:
_value.setValue(QVariant(value.toInt()));
newValue = QVariant(value.toInt());
break;
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeUint16:
case FactMetaData::valueTypeUint32:
_value.setValue(value.toUInt());
newValue = QVariant(value.toUInt());
break;
case FactMetaData::valueTypeFloat:
_value.setValue(value.toFloat());
newValue = QVariant(value.toFloat());
break;
case FactMetaData::valueTypeDouble:
_value.setValue(value.toDouble());
newValue = QVariant(value.toDouble());
break;
}
emit valueChanged(_value);
emit _containerValueChanged(_value);
if (newValue != _value) {
_value.setValue(newValue);
emit valueChanged(_value);
emit _containerValueChanged(_value);
}
}
void Fact::_containerSetValue(const QVariant& value)
......
......@@ -59,9 +59,6 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot)
_uas = UASManager::instance()->getActiveUAS();
Q_ASSERT(_uas);
_paramMgr = _uas->getParamManager();
Q_ASSERT(_paramMgr);
// Get the plugin for the uas
AutoPilotPluginManager* pluginMgr = AutoPilotPluginManager::instance();
......@@ -74,7 +71,7 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot)
QSignalSpy spyPlugin(_plugin, SIGNAL(pluginReadyChanged(bool)));
if (!_plugin->pluginReady()) {
QCOMPARE(spyPlugin.wait(5000), true);
QCOMPARE(spyPlugin.wait(10000), true);
}
Q_ASSERT(_plugin->pluginReady());
}
......@@ -87,23 +84,17 @@ void FactSystemTestBase::_cleanup(void)
/// Basic test of parameter values in Fact System
void FactSystemTestBase::_parameter_default_component_id_test(void)
{
// Compare the value in the Parameter Manager with the value from the FactSystem.
QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, FactSystem::defaultComponentId, "RC_MAP_THROTTLE"));
Fact* fact = _plugin->getFact(FactSystem::ParameterProvider, FactSystem::defaultComponentId, "RC_MAP_THROTTLE");
QVERIFY(fact != NULL);
QVariant factValue = fact->value();
QCOMPARE(factValue.isValid(), true);
QVariant paramValue;
Q_ASSERT(_paramMgr->getParameterValue(_paramMgr->getDefaultComponentId(), "RC_MAP_THROTTLE", paramValue));
QCOMPARE(factValue.toInt(), paramValue.toInt());
QCOMPARE(factValue.toInt(), 3);
}
void FactSystemTestBase::_parameter_specific_component_id_test(void)
{
// Compare the value in the Parameter Manager with the value from the FactSystem.
QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, 50, "RC_MAP_THROTTLE"));
Fact* fact = _plugin->getFact(FactSystem::ParameterProvider, 50, "RC_MAP_THROTTLE");
QVERIFY(fact != NULL);
......@@ -111,10 +102,7 @@ void FactSystemTestBase::_parameter_specific_component_id_test(void)
QCOMPARE(factValue.isValid(), true);
QVariant paramValue;
Q_ASSERT(_paramMgr->getParameterValue(50, "RC_MAP_THROTTLE", paramValue));
QCOMPARE(factValue.toInt(), paramValue.toInt());
QCOMPARE(factValue.toInt(), 3);
// Test another component id
QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, 51, "COMPONENT_51"));
......@@ -123,9 +111,7 @@ void FactSystemTestBase::_parameter_specific_component_id_test(void)
factValue = fact->value();
QCOMPARE(factValue.isValid(), true);
Q_ASSERT(_paramMgr->getParameterValue(51, "COMPONENT_51", paramValue));
QCOMPARE(factValue.toInt(), paramValue.toInt());
QCOMPARE(factValue.toInt(), 51);
}
/// Test that QML can reference a Fact
......@@ -142,38 +128,7 @@ void FactSystemTestBase::_qml_test(void)
QVERIFY(control != NULL);
QVariant qmlValue = control->property("text").toInt();
QVariant paramMgrValue;
Q_ASSERT(_paramMgr->getParameterValue(_paramMgr->getDefaultComponentId(), "RC_MAP_THROTTLE", paramMgrValue));
QCOMPARE(qmlValue.toInt(), paramMgrValue.toInt());
}
// Test correct behavior when the Param Manager gets a parameter update
void FactSystemTestBase::_paramMgrSignal_test(void)
{
// Get the parameter Fact from the AutoPilot
Fact* fact = _plugin->getFact(FactSystem::ParameterProvider, -1, "RC_MAP_THROTTLE");
QVERIFY(fact != NULL);
// Setting a new value into the parameter should trigger a valueChanged signal on the Fact
QSignalSpy spyFact(fact, SIGNAL(valueChanged(QVariant)));
QVariant paramValue = 12;
_paramMgr->setParameter(_paramMgr->getDefaultComponentId(), "RC_MAP_THROTTLE", paramValue);
_paramMgr->sendPendingParameters(true, false);
// Wait for the Fact::valueChanged signal to come through
QCOMPARE(spyFact.wait(5000), true);
// Make sure the signal has the right value
QList<QVariant> arguments = spyFact.takeFirst();
qDebug() << arguments.at(0).type();
QCOMPARE(arguments.at(0).toInt(), 12);
// Make sure the Fact has the new value
QCOMPARE(fact->value().toInt(), 12);
QCOMPARE(qmlValue.toInt(), 3);
}
/// Test QML getting an updated Fact value
......@@ -185,11 +140,10 @@ void FactSystemTestBase::_qmlUpdate_test(void)
widget->setSource(QUrl::fromUserInput("qrc:unittest/FactSystemTest.qml"));
// Change the value using param manager
// Change the value
QVariant paramValue = 12;
_paramMgr->setParameter(_paramMgr->getDefaultComponentId(), "RC_MAP_THROTTLE", paramValue);
_paramMgr->sendPendingParameters(true, false);
_plugin->getParameterFact("RC_MAP_THROTTLE")->setValue(paramValue);
QTest::qWait(500); // Let the signals flow through
......
......@@ -46,11 +46,9 @@ protected:
void _parameter_default_component_id_test(void);
void _parameter_specific_component_id_test(void);
void _qml_test(void);
void _paramMgrSignal_test(void);
void _qmlUpdate_test(void);
UASInterface* _uas;
QGCUASParamManagerInterface* _paramMgr;
AutoPilotPlugin* _plugin;
LinkManager* _linkMgr;
};
......
......@@ -46,7 +46,6 @@ private slots:
void parameter_default_component_id_test(void) { _parameter_default_component_id_test(); }
void parameter_specific_component_id_test(void) { _parameter_specific_component_id_test(); }
void qml_test(void) { _qml_test(); }
void paramMgrSignal_test(void) { _paramMgrSignal_test(); }
void qmlUpdate_test(void) { _qmlUpdate_test(); }
};
......
......@@ -46,7 +46,6 @@ private slots:
void parameter_default_component_id_test(void) { _parameter_default_component_id_test(); }
void parameter_specific_component_id_test(void) { _parameter_specific_component_id_test(); }
void qml_test(void) { _qml_test(); }
void paramMgrSignal_test(void) { _paramMgrSignal_test(); }
void qmlUpdate_test(void) { _qmlUpdate_test(); }
};
......
This diff is collapsed.
......@@ -28,9 +28,13 @@
#include <QMap>
#include <QXmlStreamReader>
#include <QLoggingCategory>
#include <QMutex>
#include "FactSystem.h"
#include "UASInterface.h"
#include "MAVLinkProtocol.h"
#include "AutoPilotPlugin.h"
#include "QGCMavlink.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
......@@ -44,7 +48,7 @@ class ParameterLoader : public QObject
public:
/// @param uas Uas which this set of facts is associated with
ParameterLoader(UASInterface* uas, QObject* parent = NULL);
ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent = NULL);
~ParameterLoader();
......@@ -76,6 +80,9 @@ public:
const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
void readParametersFromStream(QTextStream& stream);
void writeParametersToStream(QTextStream &stream, const QString& name);
/// Return the parameter for which the default component id is derived from. Return an empty
/// string is this is not available.
virtual QString getDefaultComponentIdParam(void) const = 0;
......@@ -83,6 +90,12 @@ public:
signals:
/// Signalled when the full set of facts are ready
void parametersReady(void);
/// Signalled to update progress of full parameter list request
void parameterListProgress(float value);
/// Signalled to ourselves in order to get call on our own thread
void restartWaitingParamTimer(void);
protected:
/// Base implementation adds generic meta data based on variant type. Derived class can override to provide
......@@ -90,21 +103,27 @@ protected:
virtual void _addMetaDataToFact(Fact* fact);
private slots:
void _parameterUpdate(int uas, int componentId, QString parameterName, int mavType, QVariant value);
void _parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value);
void _valueUpdated(const QVariant& value);
void _paramMgrParameterListUpToDate(void);
void _restartWaitingParamTimer(void);
void _waitingParamTimeout(void);
private:
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
int _actualComponentId(int componentId);
void _determineDefaultComponentId(void);
void _setupGroupMap(void);
int _uasId; ///< Id for uas which this set of Facts are associated with
void _readParameterRaw(int componentId, const QString& paramName, int paramIndex);
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
void _saveToEEPROM(void);
QGCUASParamManagerInterface* _paramMgr;
AutoPilotPlugin* _autopilot;
UASInterface* _uas;
MAVLinkProtocol* _mavlink;
/// First mapping id\s by component id
/// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant
QMap<int, QVariantMap> _mapParameterName2Variant;
......@@ -115,6 +134,19 @@ private:
bool _parametersReady; ///< All params received from param mgr
int _defaultComponentId;
QString _defaultComponentIdParam;
QMap<int, int> _paramCountMap; ///< Map of total known parameter count, keyed by component id
QMap<int, QList<int> > _waitingReadParamIndexMap; ///< Map of param indices waiting for initial first time read, keyed by component id
QMap<int, QStringList> _waitingReadParamNameMap; ///< Map of param names we are waiting to hear a read response from, keyed by component id
QMap<int, QStringList> _waitingWriteParamNameMap; ///< Map of param names we are waiting to hear a write response from, keyed by component id
int _totalParamCount; ///< Number of parameters across all components
QTimer _waitingParamTimeoutTimer;
bool _fullRefresh;
QMutex _dataMutex;
};
#endif
\ No newline at end of file
......@@ -39,9 +39,6 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Make UAS aware that this link can be used to communicate with the actual robot
uasInterface->addLink(link);
// First thing we do with a new UAS is get the parameters
uasInterface->getParamManager()->requestParameterList();
// Now add UAS to "official" list, which makes the whole application aware of it
UASManager::instance()->addUAS(uasInterface);
......
#include "QGCUASParamManager.h"
#include <QApplication>
#include <QDir>
#include <QDebug>
#include "UASInterface.h"
#include "QGCMessageBox.h"
QGCUASParamManager::QGCUASParamManager(QObject *parent) :
QGCUASParamManagerInterface(parent),
mav(NULL),
paramDataModel(this),
_parametersReady(false)
{
}
QGCUASParamManager* QGCUASParamManager::initWithUAS(UASInterface* uas)
{
mav = uas;
paramDataModel.setUASID(mav->getUASID());
paramCommsMgr.initWithUAS(uas);
connectToModelAndComms();
return this;
}
void QGCUASParamManager::connectToModelAndComms()
{
// Pass along comms mgr status msgs
connect(&paramCommsMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)),
this, SIGNAL(parameterStatusMsgUpdated(QString,int)));
connect(&paramCommsMgr, SIGNAL(parameterListUpToDate()), this, SLOT(_parameterListUpToDate()));
connect(&paramCommsMgr, SIGNAL(parameterListProgress(float)), this, SIGNAL(parameterListProgress(float)));
// Pass along data model updates
connect(&paramDataModel, SIGNAL(parameterUpdated(int, QString , QVariant )),
this, SIGNAL(parameterUpdated(int, QString , QVariant )));
connect(&paramDataModel, SIGNAL(pendingParamUpdate(int , const QString& , QVariant , bool )),
this, SIGNAL(pendingParamUpdate(int , const QString& , QVariant , bool )));
}
void QGCUASParamManager::clearAllPendingParams()
{
paramDataModel.clearAllPendingParams();
emit parameterStatusMsgUpdated(tr("Cleared all pending params"), UASParameterCommsMgr::ParamCommsStatusLevel_OK);
}
int QGCUASParamManager::getDefaultComponentId()
{
return paramDataModel.getDefaultComponentId();
}
QList<int> QGCUASParamManager::getComponentForParam(const QString& parameter) const
{
return paramDataModel.getComponentForOnboardParam(parameter);
}
bool QGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const
{
return paramDataModel.getOnboardParamValue(component,parameter,value);
}
void QGCUASParamManager::requestParameterUpdate(int component, const QString& parameter)
{
if (mav) {
paramCommsMgr.requestParameterUpdate(component,parameter);
}
}
/**
* Send a request to deliver the list of onboard parameters
* to the MAV.
*/
void QGCUASParamManager::requestParameterList()
{
if (mav) {
emit parameterStatusMsgUpdated(tr("Requested param list.. waiting"), UASParameterCommsMgr::ParamCommsStatusLevel_OK);
paramCommsMgr.requestParameterList();
}
}
void QGCUASParamManager::requestParameterListIfEmpty()
{
if (mav) {
int totalOnboard = paramDataModel.countOnboardParams();
if (totalOnboard < 2) { //TODO arbitrary constant, maybe 0 is OK?
requestParameterList();
}
}
}
void QGCUASParamManager::setParamDescriptions(const QMap<QString,QString>& paramInfo) {
paramDataModel.setParamDescriptions(paramInfo);
}
void QGCUASParamManager::setParameter(int compId, QString paramName, QVariant value)
{
if ((0 == compId) || (-1 == compId)) {
//attempt to get an actual component ID
compId = paramDataModel.getDefaultComponentId();
}
paramDataModel.updatePendingParamWithValue(compId,paramName,value);
}
void QGCUASParamManager::sendPendingParameters(bool persistAfterSend, bool forceSend)
{
paramCommsMgr.sendPendingParameters(persistAfterSend, forceSend);
}
void QGCUASParamManager::setPendingParam(int compId, const QString& paramName, const QVariant& value, bool forceSend)
{
if ((0 == compId) || (-1 == compId)) {
//attempt to get an actual component ID
compId = paramDataModel.getDefaultComponentId();
}
paramDataModel.updatePendingParamWithValue(compId,paramName,value, forceSend);
}
UASInterface* QGCUASParamManager::getUAS()
{
return mav;
}
UASParameterDataModel* QGCUASParamManager::dataModel()
{
return &paramDataModel;
}
void QGCUASParamManager::writeOnboardParamsToStream(QTextStream &stream, const QString& uasName)
{
paramDataModel.writeOnboardParamsToStream(stream,uasName);
}
void QGCUASParamManager::readPendingParamsFromStream(QTextStream &stream)
{
paramDataModel.readUpdateParamsFromStream(stream);
}
void QGCUASParamManager::copyVolatileParamsToPersistent()
{
int changedParamCount = paramDataModel.countPendingParams();
if (changedParamCount > 0) {
QGCMessageBox::warning(tr("Warning"),
tr("There are locally changed parameters. Please transmit them first (<TRANSMIT>) or update them with the onboard values (<REFRESH>) before storing onboard from RAM to ROM."));
}
else {
paramCommsMgr.writeParamsToPersistentStorage();
}
}
void QGCUASParamManager::copyPersistentParamsToVolatile()
{
if (mav) {
mav->readParametersFromStorage(); //TODO use comms mgr instead?
}
}
void QGCUASParamManager::requestRcCalibrationParamsUpdate() {
paramCommsMgr.requestRcCalibrationParamsUpdate();
}
void QGCUASParamManager::_parameterListUpToDate(void)
{
//qDebug() << "Emitting parameters ready, count:" << paramDataModel.countOnboardParams();
_parametersReady = true;
emit parameterListUpToDate();
}
#ifndef QGCUASPARAMMANAGER_H
#define QGCUASPARAMMANAGER_H
#include <QWidget>
#include <QMap>
#include <QTimer>
#include <QVariant>
#include "UASParameterDataModel.h"
#include "QGCUASParamManagerInterface.h"
#include "UASParameterCommsMgr.h"
//forward declarations
class QTextStream;
class UASInterface;
class QGCUASParamManager : public QGCUASParamManagerInterface
{
Q_OBJECT
public:
QGCUASParamManager(QObject* parent = 0);
QGCUASParamManager* initWithUAS(UASInterface* uas);
/** @brief Get the known, confirmed value of a parameter */
virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const;
/** @brief determine which component is the root component for the UAS and return its ID or 0 if unknown */
virtual int getDefaultComponentId();
/**
* @brief Get a list of all component IDs using this parameter name
* @param parameter The string encoding the parameter name
* @return A list with all components using this parameter name. Can be empty.
*/
virtual QList<int> getComponentForParam(const QString& parameter) const;
/** @brief Provide tooltips / user-visible descriptions for parameters */
virtual void setParamDescriptions(const QMap<QString,QString>& paramDescs);
/**
* @brief Count the pending parameters in the current transmission
* @return The number of pending parameters
*/
virtual int countPendingParams() {
return paramDataModel.countPendingParams();
}
/**
* @brief Count the number of onboard parameters
* @return The number of onboard parameters
*/
virtual int countOnboardParams() {
return paramDataModel.countOnboardParams();
}
/** @brief Get the UAS of this widget
* @return The MAV of this mgr. Unless the MAV object has been destroyed, this is never null.
*/
UASInterface* getUAS();
/** @return The data model managed by this class */
virtual UASParameterDataModel* dataModel();
/// @return true: first full set of parameters received
virtual bool parametersReady(void) { return _parametersReady; }
protected:
void connectToModelAndComms();
signals:
/** @brief We updated the parameter status message */
void parameterStatusMsgUpdated(QString msg, int level);
/** @brief We have received a complete list of all parameters onboard the MAV */
void parameterListUpToDate();
void parameterListProgress(float percentComplete);
/** @brief We've received an update of a parameter's value */
void parameterUpdated(int compId, QString paramName, QVariant value);
/** @brief Notifies listeners that a param was added to or removed from the pending list */
void pendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending);
public slots:
/** @brief Send one parameter to the MAV: changes value in transient memory of MAV */
virtual void setParameter(int component, QString parameterName, QVariant value);
/** @brief Send all pending parameters to the MAV, for storage in transient (RAM) memory
* @param persistAfterSend If true, all parameters will be written to persistent storage as well
*/
virtual void sendPendingParameters(bool persistAfterSend = false, bool forceSend = false);
/** @brief Request list of parameters from MAV */
virtual void requestParameterList();
/** @brief Request a list of params onboard the MAV if the onboard param list we have is empty */
virtual void requestParameterListIfEmpty();
/** @brief queue a pending parameter for sending to the MAV */
virtual void setPendingParam(int componentId, const QString& key, const QVariant& value, bool forceSend = false);
/** @brief remove all params from the pending list */
virtual void clearAllPendingParams();
/** @brief Request a single parameter by name from the MAV */
virtual void requestParameterUpdate(int component, const QString& parameter);
virtual void writeOnboardParamsToStream(QTextStream &stream, const QString& uasName);
virtual void readPendingParamsFromStream(QTextStream &stream);
virtual void requestRcCalibrationParamsUpdate();
/** @brief Copy the current parameters in volatile RAM to persistent storage (EEPROM/HDD) */
virtual void copyVolatileParamsToPersistent();
/** @brief Copy the parameters from persistent storage to volatile RAM */
virtual void copyPersistentParamsToVolatile();
private slots:
void _parameterListUpToDate(void);
protected:
// Parameter data model
UASInterface* mav; ///< The MAV this manager is controlling
UASParameterDataModel paramDataModel;///< Shared data model of parameters
UASParameterCommsMgr paramCommsMgr; ///< Shared comms mgr for parameters
bool _parametersReady;
};
#endif // QGCUASPARAMMANAGER_H
#ifndef QGCUASPARAMMANAGERINTERFACE_H
#define QGCUASPARAMMANAGERINTERFACE_H
#include <QWidget>
#include <QMap>
#include <QTimer>
#include <QVariant>
#include <QTextStream>
#include "UASParameterDataModel.h"
/**
* @brief This is the abstract base class for QGCUASParamManager. Although there is
* normally only a single QGCUASParamManager we still use an abstract base interface
* since this allows us to create mock versions.
*
* See QGCUASParamManager.h for method documentation
**/
//forward declarations
class QTextStream;
class UASInterface;
class UASParameterCommsMgr;
class QGCUASParamManagerInterface : public QObject
{
public:
QGCUASParamManagerInterface(QObject* parent = NULL) : QObject(parent) { }
virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const = 0;
virtual int getDefaultComponentId() = 0;
virtual QList<int> getComponentForParam(const QString& parameter) const = 0;
virtual void setParamDescriptions(const QMap<QString,QString>& paramDescs) = 0;
virtual int countPendingParams() = 0;
virtual int countOnboardParams() = 0;
virtual UASParameterDataModel* dataModel() = 0;
virtual bool parametersReady(void) = 0;
public slots:
virtual void setParameter(int component, QString parameterName, QVariant value) = 0;
virtual void sendPendingParameters(bool persistAfterSend = false, bool forceSend = false) = 0;
virtual void requestParameterList() = 0;
virtual void requestParameterListIfEmpty() = 0;
virtual void setPendingParam(int componentId, const QString& key, const QVariant& value, bool forceSend = false) = 0;
virtual void clearAllPendingParams() = 0;
virtual void requestParameterUpdate(int component, const QString& parameter) = 0;
virtual void writeOnboardParamsToStream(QTextStream &stream, const QString& uasName) = 0;
virtual void readPendingParamsFromStream(QTextStream &stream) = 0;
virtual void requestRcCalibrationParamsUpdate() = 0;
virtual void copyVolatileParamsToPersistent() = 0;
virtual void copyPersistentParamsToVolatile() = 0;
signals:
void parameterStatusMsgUpdated(QString msg, int level);
void parameterListUpToDate();
void parameterListProgress(float percentComplete);
void parameterUpdated(int compId, QString paramName, QVariant value);
void pendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending);
};
#endif // QGCUASPARAMMANAGER_H
......@@ -27,7 +27,6 @@
#include "QGCMAVLink.h"
#include "LinkManager.h"
#include "SerialLink.h"
#include "UASParameterCommsMgr.h"
#include <Eigen/Geometry>
#include "AutoPilotPluginManager.h"
#include "QGCMessageBox.h"
......@@ -143,8 +142,6 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
receivedMode(false),
paramsOnceRequested(false),
paramMgr(this),
simulation(0),
// The protected members.
......@@ -230,8 +227,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
statusTimeout.start(500);
readSettings();
//need to init paramMgr after readSettings have been loaded, to properly set autopilot and so forth
paramMgr.initWithUAS(this);
// Initial signals
emit disarmed();
emit armingChanged(false);
......@@ -1645,26 +1641,6 @@ quint64 UAS::getUnixTime(quint64 time)
return ret;
}
/**
* @param component that will be searched for in the map of parameters.
*/
QList<QString> UAS::getParameterNames(int component)
{
if (parameters.contains(component))
{
return parameters.value(component)->keys();
}
else
{
return QList<QString>();
}
}
QList<int> UAS::getComponentIds()
{
return parameters.keys();
}
/**
* @param newBaseMode that UAS is to be set to.
* @param newCustomMode that UAS is to be set to.
......@@ -1914,21 +1890,6 @@ quint64 UAS::getUptime() const
}
}
void UAS::writeParametersToStorage()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
sendMessage(msg);
}
void UAS::readParametersFromStorage()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
sendMessage(msg);
}
bool UAS::isRotaryWing()
{
switch (type) {
......@@ -2205,116 +2166,11 @@ void UAS::enableExtra3Transmission(int rate)
sendMessage(msg);
}
/**
* Set a parameter value onboard
*
* @param component The component to set the parameter
* @param id Name of the parameter
*/
void UAS::setParameter(const int compId, const QString& paramId, const QVariant& value)
{
if (!paramId.isNull())
{
mavlink_message_t msg;
mavlink_param_set_t p;
mavlink_param_union_t union_value;
// Assign correct value based on QVariant
// TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
switch ((int)value.type())
{
case QVariant::Char:
union_value.param_float = (unsigned char)value.toChar().toLatin1();
p.param_type = MAV_PARAM_TYPE_INT8;
break;
case QVariant::Int:
union_value.param_float = value.toInt();
p.param_type = MAV_PARAM_TYPE_INT32;
break;
case QVariant::UInt:
union_value.param_float = value.toUInt();
p.param_type = MAV_PARAM_TYPE_UINT32;
break;
case QMetaType::Float:
union_value.param_float = value.toFloat();
p.param_type = MAV_PARAM_TYPE_REAL32;
break;
default:
qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
return;
}
}
else
{
switch ((int)value.type())
{
case QVariant::Char:
union_value.param_int8 = (unsigned char)value.toChar().toLatin1();
p.param_type = MAV_PARAM_TYPE_INT8;
break;
case QVariant::Int:
union_value.param_int32 = value.toInt();
p.param_type = MAV_PARAM_TYPE_INT32;
break;
case QVariant::UInt:
union_value.param_uint32 = value.toUInt();
p.param_type = MAV_PARAM_TYPE_UINT32;
break;
case QMetaType::Float:
union_value.param_float = value.toFloat();
p.param_type = MAV_PARAM_TYPE_REAL32;
break;
default:
qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
return;
}
}
p.param_value = union_value.param_float;
p.target_system = (uint8_t)uasId;
p.target_component = (uint8_t)compId;
//qDebug() << "SENT PARAM:" << value;
// Copy string into buffer, ensuring not to exceed the buffer size
for (unsigned int i = 0; i < sizeof(p.param_id); i++)
{
// String characters
if ((int)i < paramId.length())
{
p.param_id[i] = paramId.toLatin1()[i];
}
else
{
// Fill rest with zeros
p.param_id[i] = 0;
}
}
mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
sendMessage(msg);
}
}
//TODO update this to use the parameter manager / param data model instead
void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramUnion)
{
int compId = msg.compid;
// Insert component if necessary
if (!parameters.contains(compId)) {
parameters.insert(compId, new QMap<QString, QVariant>());
}
// Insert parameter into registry
if (parameters.value(compId)->contains(paramName)) {
parameters.value(compId)->remove(paramName);
}
QVariant paramValue;
// Insert with correct type
......@@ -2374,50 +2230,7 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
parameters.value(compId)->insert(paramName, paramValue);
emit parameterChanged(uasId, compId, paramName, paramValue);
emit parameterUpdate(uasId, compId, paramName, rawValue.param_type, paramValue);
emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, paramValue);
}
/**
* Request parameter, use parameter name to request it.
*/
void UAS::requestParameter(int component, int id)
{
// Request parameter, use parameter name to request it
mavlink_message_t msg;
mavlink_param_request_read_t read;
read.param_index = id;
read.param_id[0] = '\0'; // Enforce null termination
read.target_system = uasId;
read.target_component = component;
mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
sendMessage(msg);
//qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id;
}
/**
* Request a parameter, use parameter name to request it.
*/
void UAS::requestParameter(int component, const QString& parameter)
{
// Request parameter, use parameter name to request it
mavlink_message_t msg;
mavlink_param_request_read_t read;
read.param_index = -1;
// Copy full param name or maximum max field size
if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)
{
emit textMessageReceived(uasId, 0, MAV_SEVERITY_WARNING, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1));
}
strncpy(read.param_id, parameter.toStdString().c_str(), sizeof(read.param_id));
read.param_id[sizeof(read.param_id) - 1] = '\0'; // Enforce null termination
read.target_system = uasId;
read.target_component = component;
mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
sendMessage(msg);
//qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
}
/**
......
......@@ -40,7 +40,6 @@ This file is part of the QGROUNDCONTROL project
#include "QGCFlightGearLink.h"
#include "QGCJSBSimLink.h"
#include "QGCXPlaneLink.h"
#include "QGCUASParamManager.h"
#include "QGCUASFileManager.h"
Q_DECLARE_LOGGING_CATEGORY(UASLog)
......@@ -462,11 +461,6 @@ protected: //COMMENTS FOR TEST UNIT
bool blockHomePositionChanges; ///< Block changes to the home position
bool receivedMode; ///< True if mode was retrieved from current conenction to UAS
/// PARAMETERS
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once
QGCUASParamManager paramMgr; ///< Parameter manager for this UAS
/// SIMULATION
QGCHilLink* simulation; ///< Hardware in the loop simulation link
......@@ -493,11 +487,6 @@ public:
return &waypointManager;
}
/** @brief Get reference to the param manager **/
virtual QGCUASParamManagerInterface* getParamManager() {
return &paramMgr;
}
virtual QGCUASFileManager* getFileManager() {
return &fileManager;
}
......@@ -821,25 +810,6 @@ public slots:
/** @brief Set current mode of operation, e.g. auto or manual, does not check the arming status, for anything else than arming/disarming operations use setMode instead */
void setModeArm(uint8_t newBaseMode, uint32_t newCustomMode);
/** @brief Request a single parameter by name */
void requestParameter(int component, const QString& parameter);
/** @brief Request a single parameter by index */
void requestParameter(int component, int id);
/** @brief Set a system parameter */
void setParameter(const int compId, const QString& paramId, const QVariant& value);
/** @brief Write parameters to permanent storage */
void writeParametersToStorage();
/** @brief Read parameters from permanent storage */
void readParametersFromStorage();
/** @brief Get the names of all parameters */
QList<QString> getParameterNames(int component);
/** @brief Get the ids of all components */
QList<int> getComponentIds();
void enableAllDataTransmission(int rate);
void enableRawSensorDataTransmission(int rate);
void enableExtendedSystemStatusTransmission(int rate);
......
......@@ -40,9 +40,7 @@ This file is part of the QGROUNDCONTROL project
#include "LinkInterface.h"
#include "ProtocolInterface.h"
#include "UASParameterDataModel.h"
#include "UASWaypointManager.h"
#include "QGCUASParamManagerInterface.h"
class QGCUASFileManager;
......@@ -134,9 +132,6 @@ public:
/** @brief Get reference to the waypoint manager **/
virtual UASWaypointManager* getWaypointManager(void) = 0;
/** @brief Get reference to the param manager **/
virtual QGCUASParamManagerInterface* getParamManager() = 0;
virtual QGCUASFileManager* getFileManager() = 0;
/** @brief Send a message over this link (to this or to all UAS on this link) */
......@@ -314,19 +309,6 @@ public slots:
virtual void setLocalOriginAtCurrentGPSPosition() = 0;
/** @brief Set world frame origin / home position at this GPS position */
virtual void setHomePosition(double lat, double lon, double alt) = 0;
/** @brief Request one specific onboard parameter */
virtual void requestParameter(int component, const QString& parameter) = 0;
/** @brief Write parameter to permanent storage */
virtual void writeParametersToStorage() = 0;
/** @brief Read parameter from permanent storage */
virtual void readParametersFromStorage() = 0;
/** @brief Set a system parameter
* @param component ID of the system component to write the parameter to
* @param id String identifying the parameter
* @warning The length of the ID string is limited by the MAVLink format! Take care to not exceed it
* @param value Value of the parameter, IEEE 754 single precision floating point
*/
virtual void setParameter(const int component, const QString& id, const QVariant& value) = 0;
/**
* @brief Add a link to the list of current links
......@@ -496,11 +478,7 @@ signals:
void waypointSelected(int uasId, int id);
void waypointReached(UASInterface* uas, int id);
void autoModeChanged(bool autoMode);
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void parameterChanged(int uas, int component, int parameterCount, int parameterId, QString parameterName, QVariant value);
void parameterUpdate(int uas, int component, QString parameterName, int type, QVariant value);
void patternDetected(int uasId, QString patternPath, float confidence, bool detected);
void letterDetected(int uasId, QString letter, float confidence, bool detected);
void parameterUpdate(int uas, int component, QString parameterName, int parameterCount, int parameterId, int type, QVariant value);
/**
* @brief The battery status has been updated
*
......
This diff is collapsed.
#ifndef UASPARAMETERCOMMSMGR_H
#define UASPARAMETERCOMMSMGR_H
#include <QObject>
#include <QMap>
#include <QTimer>
#include <QVariant>
#include <QVector>
#include <QLoggingCategory>
class UASInterface;
class UASParameterDataModel;
Q_DECLARE_LOGGING_CATEGORY(UASParameterCommsMgrLog)
class UASParameterCommsMgr : public QObject
{
Q_OBJECT
public:
explicit UASParameterCommsMgr(QObject *parent = 0);
UASParameterCommsMgr* initWithUAS(UASInterface* model);///< Two-stage constructor
~UASParameterCommsMgr();
typedef enum ParamCommsStatusLevel {
ParamCommsStatusLevel_OK = 0,
ParamCommsStatusLevel_Warning = 2,
ParamCommsStatusLevel_Error = 4,
ParamCommsStatusLevel_Count
} ParamCommsStatusLevel_t;
protected:
/** @brief activate the silence timer if there are unack'd reads or writes */
virtual void updateSilenceTimer();
virtual void setParameterStatusMsg(const QString& msg, ParamCommsStatusLevel_t level=ParamCommsStatusLevel_OK);
/** @brief Load settings that control eg retransmission timeouts */
void loadParamCommsSettings();
/** @brief clear transmissionMissingPackets and transmissionMissingWriteAckPackets */
void clearRetransmissionLists(int& missingReadCount, int& missingWriteCount );
/** @brief we are waiting for a response to this read param request */
virtual void markReadParamWaiting(int compId, int paramId);
/** @brief we are waiting for a response to this write param request */
void markWriteParamWaiting(int compId, QString paramName, QVariant value);
void resendReadWriteRequests();
void resetAfterListReceive();
void emitPendingParameterCommit(int compId, const QString& key, QVariant& value);
signals:
void commitPendingParameter(int component, QString parameter, QVariant value);
void parameterChanged(int component, int parameterIndex, QVariant value);
void parameterValueConfirmed(int uas, int component,int paramCount, int paramId, QString parameter, QVariant value);
/** @brief We have received a complete list of all parameters onboard the MAV */
void parameterListUpToDate();
void parameterListProgress(float percentComplete);
void parameterUpdateRequested(int component, const QString& parameter);
void parameterUpdateRequestedById(int componentId, int paramId);
/** @brief We updated the parameter status message */
void parameterStatusMsgUpdated(QString msg, int level);
/// @brief We signal this to ourselves in order to get timer started/stopped on our own thread.
void _startSilenceTimer(void);
void _stopSilenceTimer(void);
public slots:
/** @brief Iterate through all components, through all pending parameters and send them to UAS */
virtual void sendPendingParameters(bool copyToPersistent = false, bool forceSend = false);
/** @brief Write the current onboard parameters from transient RAM into persistent storage, e.g. EEPROM or harddisk */
virtual void writeParamsToPersistentStorage();
/** @brief Write one parameter to the MAV */
virtual void setParameter(int component, QString parameterName, QVariant value, bool forceSend = false);
/** @brief Request list of parameters from MAV */
virtual void requestParameterList();
/** @brief The max silence time expired */
virtual void silenceTimerExpired();
/** @brief Request a single parameter update by name */
virtual void requestParameterUpdate(int component, const QString& parameter);
/** @brief Request an update of RC parameters */
virtual void requestRcCalibrationParamsUpdate();
virtual void receivedParameterUpdate(int uas, int compId, int paramCount, int paramId, QString paramName, QVariant value);
protected:
QMap<int, int> knownParamListSize;///< The known param list size for each component, by component ID
quint64 lastReceiveTime; ///< The last time we received anything from our partner
quint64 lastSilenceTimerReset;
UASInterface* mav; ///< The MAV we're talking to
int maxSilenceTimeout; ///< If nothing received within this period of time, abandon resends
UASParameterDataModel* paramDataModel;
bool persistParamsAfterSend; ///< Copy all parameters to persistent storage after sending
QMap<int, QSet<int>*> readsWaiting; ///< All reads that have not yet been received, by component ID
int retransmitBurstLimit; ///< Number of packets requested for retransmission per burst
int silenceTimeout; ///< If nothing received within this period of time, start resends
QTimer silenceTimer; ///< Timer handling parameter retransmission
bool transmissionListMode; ///< Currently requesting list
QMap<int, QMap<QString, QVariant>* > writesWaiting; ///< All writes that have not yet been ack'd, by component ID
private slots:
/// @brief We signal this to ourselves in order to get timer started/stopped on our own thread.
void _startSilenceTimerOnThisThread(void);
void _stopSilenceTimerOnThisThread(void);
private:
void _sendParamRequestListMsg(void);
};
#endif // UASPARAMETERCOMMSMGR_H
This diff is collapsed.
#ifndef UASPARAMETERDATAMODEL_H
#define UASPARAMETERDATAMODEL_H
#include <QMap>
#include <QObject>
#include <QVariant>
class QTextStream;
class UASParameterDataModel : public QObject
{
Q_OBJECT
public:
explicit UASParameterDataModel(QObject *parent = 0);
//Parameter meta info
bool isParamMinKnown(const QString& param) { return paramMin.contains(param); }
virtual bool isValueLessThanParamMin(const QString& param, double dblVal);
bool isParamMaxKnown(const QString& param) { return paramMax.contains(param); }
virtual bool isValueGreaterThanParamMax(const QString& param, double dblVal);
bool isParamDefaultKnown(const QString& param) { return paramDefault.contains(param); }
double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); }
double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); }
double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); }
virtual QString getParamDescription(const QString& param) { return paramDescriptions.value(param, ""); }
virtual void setParamDescriptions(const QMap<QString,QString>& paramInfo);
/** @brief Get the default component ID for the UAS */
virtual int getDefaultComponentId();
//TODO make this method protected?
/** @brief Ensure that the data model is aware of this component
* @param compId Id of the component
*/
virtual void addComponent(int compId);
/**
* @brief Return a list of all components for this parameter name
* @param parameter The parameter string to search for
* @return A list with all components, can be potentially empty
*/
virtual QList<int> getComponentForOnboardParam(const QString& parameter) const;
/** @brief clears every parameter for every loaded component */
virtual void forgetAllOnboardParams();
/** @brief add this parameter to pending list iff it has changed from onboard value
* @return true if the parameter is now pending
*/
virtual bool updatePendingParamWithValue(int componentId, const QString &key, const QVariant &value, bool forceSend = false);
virtual void handleParamUpdate(int componentId, const QString& key, const QVariant& value);
virtual bool getOnboardParamValue(int componentId, const QString& key, QVariant& value) const;
virtual bool isParamChangePending(int componentId,const QString& key);
QMap<QString , QVariant>* getPendingParamsForComponent(int componentId) {
return pendingParameters.value(componentId);
}
QMap<QString , QVariant>* getOnboardParamsForComponent(int componentId) {
return onboardParameters.value(componentId);
}
QMap<int, QMap<QString, QVariant>* >* getAllPendingParams() {
return &pendingParameters;
}
QMap<int, QMap<QString, QVariant>* >* getAllOnboardParams() {
return &onboardParameters;
}
/** @brief return a count of all pending parameters */
virtual int countPendingParams();
/** @brief return a count of all onboard parameters we've received */
virtual int countOnboardParams();
virtual void writeOnboardParamsToStream(QTextStream &stream, const QString& uasName);
virtual void readUpdateParamsFromStream(QTextStream &stream);
virtual void loadParamMetaInfoFromStream(QTextStream& stream);
void setUASID(int anId) { this->uasId = anId; }
protected:
/** @brief set the confirmed value of a parameter in the onboard params list */
virtual void setOnboardParam(int componentId, const QString& key, const QVariant& value);
/** @brief Save the parameter with a the type specified in the QVariant as fixed */
void setParamWithTypeInMap(int compId, const QString& key, const QVariant &value, QMap<int, QMap<QString, QVariant>* >& map);
/** @brief Write a new pending parameter value that may be eventually sent to the UAS */
virtual void setPendingParam(int componentId, const QString &key, const QVariant& value);
/** @brief remove a parameter from the pending list */
virtual void removePendingParam(int compId, const QString &key);
signals:
/** @brief We've received an update of a parameter's value */
void parameterUpdated(int compId, QString paramName, QVariant value);
/** @brief Notifies listeners that a param was added to or removed from the pending list */
void pendingParamUpdate(int compId, const QString& paramName, QVariant value, bool isPending);
void allPendingParamsCommitted(); ///< All pending params have been committed to the MAV
public slots:
virtual void clearAllPendingParams();
protected:
int defaultComponentId; ///< Cached default component ID
int uasId; ///< The UAS / MAV to which this data model pertains
QMap<int, QMap<QString, QVariant>* > pendingParameters; ///< Changed values that have not yet been transmitted to the UAS, by component ID
QMap<int, QMap<QString, QVariant>* > onboardParameters; ///< All parameters confirmed to be stored onboard the UAS, by component ID
// Tooltip data structures
QMap<QString, QString> paramDescriptions; ///< Tooltip values
// Min / Default / Max data structures
QMap<QString, double> paramMin; ///< Minimum param values
QMap<QString, double> paramDefault; ///< Default param values
QMap<QString, double> paramMax; ///< Minimum param values
};
#endif // UASPARAMETERDATAMODEL_H
......@@ -26,6 +26,7 @@
#include "QGCMapRCToParamDialog.h"
#include "ui_QGCMapRCToParamDialog.h"
#include "AutoPilotPluginManager.h"
#include <QDebug>
#include <QTimer>
......@@ -41,6 +42,8 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id,
ui(new Ui::QGCMapRCToParamDialog)
{
ui->setupUi(this);
// only enable ok button when param was refreshed
QPushButton *okButton = ui->buttonBox->button(QDialogButtonBox::Ok);
......@@ -92,44 +95,27 @@ void QGCMapRCToParamDialog::paramLoaded(bool success, float value, QString messa
}
}
ParamLoader::ParamLoader(QString paramName, UASInterface* uas, QObject* parent) :
QObject(parent),
_uas(uas),
_paramName(paramName),
_paramReceived(false)
{
_autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas);
Q_ASSERT(_autopilot);
}
void ParamLoader::load()
{
// refresh the parameter from onboard to make sure the current value is used
paramMgr->requestParameterUpdate(paramMgr->getDefaultComponentId(), param_id);
// wait until parameter update is received
QEventLoop loop;
QTimer timer;
connect(&timer, &QTimer::timeout, &loop, &QEventLoop::quit);
timer.start(10 * 1e3);
// overloaded signal:
connect(mav, static_cast<void (UASInterface::*)(
int, int, QString, QVariant)>(&UASInterface::parameterChanged),
this, &ParamLoader::handleParameterChanged);
connect(this, &ParamLoader::correctParameterChanged,
&loop, &QEventLoop::quit);
loop.exec();
if (!param_received == true) {
// timeout
emit paramLoaded(false, 0.0f, "Timeout");
return;
}
QVariant current_param_value;
bool got_param = paramMgr->getParameterValue(paramMgr->getDefaultComponentId(),
param_id, current_param_value);
QString message = got_param ? "" : "param manager Error";
emit paramLoaded(got_param, current_param_value.toFloat(), message);
connect(_autopilot->getParameterFact(_paramName), &Fact::valueChanged, this, &ParamLoader::_parameterUpdated);
// refresh the parameter from onboard to make sure the current value is used
_autopilot->refreshParameter(FactSystem::defaultComponentId, _paramName);
}
void ParamLoader::handleParameterChanged(int uas, int component, QString parameterName, QVariant value)
void ParamLoader::_parameterUpdated(QVariant value)
{
Q_UNUSED(component);
Q_UNUSED(value);
if (uas == mav->getUASID() && parameterName == param_id) {
param_received = true;
emit correctParameterChanged();
}
emit paramLoaded(true, _autopilot->getParameterFact(_paramName)->value().toFloat(), "");
}
......@@ -30,7 +30,9 @@
#include <QDialog>
#include <QThread>
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
namespace Ui {
class QGCMapRCToParamDialog;
......@@ -42,27 +44,23 @@ class ParamLoader : public QObject
Q_OBJECT
public:
ParamLoader(QString param_id, UASInterface *mav, QObject * parent = 0):
QObject(parent),
mav(mav),
paramMgr(mav->getParamManager()),
param_id(param_id),
param_received(false)
{}
ParamLoader(QString paramName, UASInterface* uas, QObject* parent = NULL);
public slots:
void load();
void handleParameterChanged(int uas, int component, QString parameterName, QVariant value);
signals:
void paramLoaded(bool success, float value, QString message = "");
void correctParameterChanged();
private slots:
void _parameterUpdated(QVariant value);
protected:
UASInterface *mav;
QGCUASParamManagerInterface* paramMgr;
QString param_id;
bool param_received;
private:
UASInterface* _uas;
AutoPilotPlugin* _autopilot;
QString _paramName;
bool _paramReceived;
};
class QGCMapRCToParamDialog : public QDialog
......
......@@ -30,6 +30,7 @@
#include "PX4RCCalibration.h"
#include "UASManager.h"
#include "QGCMessageBox.h"
#include "AutoPilotPluginManager.h"
QGC_LOGGING_CATEGORY(PX4RCCalibrationLog, "PX4RCCalibrationLog")
......@@ -86,8 +87,7 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) :
_transmitterMode(2),
_chanCount(0),
_rcCalState(rcCalStateChannelWait),
_mav(NULL),
_paramMgr(NULL),
_uas(NULL),
_ui(new Ui::PX4RCCalibration),
_unitTestMode(false)
{
......@@ -122,19 +122,19 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) :
_rgAttitudeControl[4].valueWidget = _ui->flapsValue;
// This code assume we already have an active UAS with ready parameters
_mav = UASManager::instance()->getActiveUAS();
Q_ASSERT(_mav);
_uas = UASManager::instance()->getActiveUAS();
Q_ASSERT(_uas);
// Connect new signals
bool fSucceeded;
Q_UNUSED(fSucceeded);
fSucceeded = connect(_mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(_remoteControlChannelRawChanged(int,float)));
fSucceeded = connect(_uas, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(_remoteControlChannelRawChanged(int,float)));
Q_ASSERT(fSucceeded);
_paramMgr = _mav->getParamManager();
Q_ASSERT(_paramMgr);
Q_ASSERT(_paramMgr->parametersReady());
_autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas);
Q_ASSERT(_autopilot);
Q_ASSERT(_autopilot->pluginReady());
connect(_ui->spektrumBind, &QPushButton::clicked, this, &PX4RCCalibration::_spektrumBind);
......@@ -701,19 +701,13 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void)
rcCalFunctionReturnSwitch };
static const size_t crgFlightModeFunctions = sizeof(rgFlightModeFunctions) / sizeof(rgFlightModeFunctions[0]);
int componentId = _paramMgr->getDefaultComponentId();
for (size_t i=0; i < crgFlightModeFunctions; i++) {
QVariant value;
enum rcCalFunctions curFunction = rgFlightModeFunctions[i];
bool paramFound = _paramMgr->getParameterValue(componentId, _rgFunctionInfo[curFunction].parameterName, value);
Q_ASSERT(paramFound);
Q_UNUSED(paramFound);
bool ok;
int switchChannel = value.toInt(&ok);
int switchChannel = _autopilot->getParameterFact(_rgFunctionInfo[curFunction].parameterName)->value().toInt(&ok);
Q_ASSERT(ok);
Q_UNUSED(ok);
// Parameter: 1-based channel, 0=not mapped
// _rgFunctionChannelMapping: 0-based channel, _chanMax=not mapped
......@@ -729,8 +723,6 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void)
/// @brief Sets internal calibration values from the stored parameters
void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void)
{
Q_ASSERT(_paramMgr);
// Initialize all function mappings to not set
for (size_t i=0; i<_chanMax; i++) {
......@@ -750,58 +742,36 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void)
QString maxTpl("RC%1_MAX");
QString trimTpl("RC%1_TRIM");
QString revTpl("RC%1_REV");
QVariant value;
bool paramFound;
bool convertOk;
int componentId = _paramMgr->getDefaultComponentId();
for (int i = 0; i < _chanMax; ++i) {
struct ChannelInfo* info = &_rgChannelInfo[i];
paramFound = _paramMgr->getParameterValue(componentId, trimTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
info->rcTrim = value.toInt(&convertOk);
Q_ASSERT(convertOk);
}
info->rcTrim = _autopilot->getParameterFact(trimTpl.arg(i+1))->value().toInt(&convertOk);
Q_ASSERT(convertOk);
paramFound = _paramMgr->getParameterValue(componentId, minTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
info->rcMin = value.toInt(&convertOk);
Q_ASSERT(convertOk);
}
info->rcMin = _autopilot->getParameterFact(minTpl.arg(i+1))->value().toInt(&convertOk);
Q_ASSERT(convertOk);
paramFound = _paramMgr->getParameterValue(componentId, maxTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
info->rcMax = value.toInt(&convertOk);
Q_ASSERT(convertOk);
}
info->rcMax = _autopilot->getParameterFact(maxTpl.arg(i+1))->value().toInt(&convertOk);
Q_ASSERT(convertOk);
paramFound = _paramMgr->getParameterValue(componentId, revTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
float floatReversed = value.toFloat(&convertOk);
Q_ASSERT(convertOk);
Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f);
info->reversed = floatReversed == -1.0f;
}
float floatReversed = _autopilot->getParameterFact(revTpl.arg(i+1))->value().toFloat(&convertOk);
Q_ASSERT(convertOk);
Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f);
info->reversed = floatReversed == -1.0f;
}
for (int i=0; i<rcCalFunctionMax; i++) {
int32_t paramChannel;
paramFound = _paramMgr->getParameterValue(componentId, _rgFunctionInfo[i].parameterName, value);
Q_ASSERT(paramFound);
if (paramFound) {
paramChannel = value.toInt(&convertOk);
Q_ASSERT(convertOk);
if (paramChannel != 0) {
_rgFunctionChannelMapping[i] = paramChannel - 1;
_rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i;
}
paramChannel = _autopilot->getParameterFact(_rgFunctionInfo[i].parameterName)->value().toInt(&convertOk);
Q_ASSERT(convertOk);
if (paramChannel != 0) {
_rgFunctionChannelMapping[i] = paramChannel - 1;
_rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i;
}
}
......@@ -813,7 +783,7 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void)
void PX4RCCalibration::_spektrumBind(void)
{
Q_ASSERT(_mav);
Q_ASSERT(_uas);
QMessageBox bindTypeMsg(this);
......@@ -837,7 +807,7 @@ void PX4RCCalibration::_spektrumBind(void)
} else {
Q_ASSERT(false);
}
_mav->pairRX(0, bindType);
_uas->pairRX(0, bindType);
}
}
......@@ -890,15 +860,12 @@ void PX4RCCalibration::_validateCalibration(void)
/// @brief Saves the rc calibration values to the board parameters.
void PX4RCCalibration::_writeCalibration(void)
{
if (!_mav) return;
if (!_uas) return;
_mav->stopCalibration();
_uas->stopCalibration();
_validateCalibration();
QGCUASParamManagerInterface* paramMgr = _mav->getParamManager();
Q_ASSERT(paramMgr);
QString minTpl("RC%1_MIN");
QString maxTpl("RC%1_MAX");
QString trimTpl("RC%1_TRIM");
......@@ -907,11 +874,12 @@ void PX4RCCalibration::_writeCalibration(void)
// Note that the rc parameters are all float, so you must cast to float in order to get the right QVariant
for (int chan = 0; chan<_chanMax; chan++) {
struct ChannelInfo* info = &_rgChannelInfo[chan];
int oneBasedChannel = chan + 1;
paramMgr->setPendingParam(0, trimTpl.arg(oneBasedChannel), (float)info->rcTrim);
paramMgr->setPendingParam(0, minTpl.arg(oneBasedChannel), (float)info->rcMin);
paramMgr->setPendingParam(0, maxTpl.arg(oneBasedChannel), (float)info->rcMax);
paramMgr->setPendingParam(0, revTpl.arg(oneBasedChannel), info->reversed ? -1.0f : 1.0f);
int oneBasedChannel = chan + 1;
_autopilot->getParameterFact(trimTpl.arg(oneBasedChannel))->setValue((float)info->rcTrim);
_autopilot->getParameterFact(minTpl.arg(oneBasedChannel))->setValue((float)info->rcMin);
_autopilot->getParameterFact(maxTpl.arg(oneBasedChannel))->setValue((float)info->rcMax);
_autopilot->getParameterFact(revTpl.arg(oneBasedChannel))->setValue(info->reversed ? -1.0f : 1.0f);
}
// Write function mapping parameters
......@@ -924,16 +892,13 @@ void PX4RCCalibration::_writeCalibration(void)
// Note that the channel value is 1-based
paramChannel = _rgFunctionChannelMapping[i] + 1;
}
paramMgr->setPendingParam(0, _rgFunctionInfo[i].parameterName, paramChannel);
_autopilot->getParameterFact(_rgFunctionInfo[i].parameterName)->setValue(paramChannel);
}
// If the RC_CHAN_COUNT parameter is available write the channel count
if (paramMgr->getComponentForParam("RC_CHAN_CNT").count() != 0) {
paramMgr->setPendingParam(0, "RC_CHAN_CNT", _chanCount);
if (_autopilot->parameterExists("RC_CHAN_CNT")) {
_autopilot->getParameterFact("RC_CHAN_CNT")->setValue(_chanCount);
}
//let the param mgr manage sending all the pending RC_foo updates and persisting after
paramMgr->sendPendingParameters(true, true);
_stopCalibration();
_setInternalCalibrationValuesFromParameters();
......@@ -986,7 +951,7 @@ void PX4RCCalibration::_startCalibration(void)
_resetInternalCalibrationValues();
// Let the mav known we are starting calibration. This should turn off motors and so forth.
_mav->startCalibration(UASInterface::StartCalibrationRadio);
_uas->startCalibration(UASInterface::StartCalibrationRadio);
_ui->rcCalNext->setText(tr("Next"));
_ui->rcCalCancel->setEnabled(true);
......@@ -1000,8 +965,8 @@ void PX4RCCalibration::_stopCalibration(void)
{
_currentStep = -1;
if (_mav) {
_mav->stopCalibration();
if (_uas) {
_uas->stopCalibration();
_setInternalCalibrationValuesFromParameters();
} else {
_resetInternalCalibrationValues();
......
......@@ -35,6 +35,7 @@
#include "UASInterface.h"
#include "RCValueWidget.h"
#include "QGCLoggingCategory.h"
#include "AutoPilotPlugin.h"
#include "ui_PX4RCCalibration.h"
......@@ -254,8 +255,8 @@ private:
RCValueWidget* _rgRCValueMonitorWidget[_chanMax]; ///< Array of radio channel value widgets
QLabel* _rgRCValueMonitorLabel[_chanMax]; ///< Array of radio channel value labels
UASInterface* _mav; ///< The current MAV
QGCUASParamManagerInterface* _paramMgr;
UASInterface* _uas;
AutoPilotPlugin* _autopilot;
Ui::PX4RCCalibration* _ui;
......
......@@ -305,18 +305,18 @@ void MainToolBar::_setActiveUAS(UASInterface* active)
disconnect(_mav, &UASInterface::remoteControlRSSIChanged, this, &MainToolBar::_remoteControlRSSIChanged);
disconnect(_mav, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*,QString,QString)));
disconnect(_mav, SIGNAL(armingChanged(bool)), this, SLOT(_updateArmingState(bool)));
if (_mav->getWaypointManager())
{
if (_mav->getWaypointManager()) {
disconnect(_mav->getWaypointManager(), &UASWaypointManager::currentWaypointChanged, this, &MainToolBar::_updateCurrentWaypoint);
disconnect(_mav->getWaypointManager(), &UASWaypointManager::waypointDistanceChanged, this, &MainToolBar::_updateWaypointDistance);
}
UAS* pUas = dynamic_cast<UAS*>(_mav);
if(pUas) {
disconnect(pUas, &UAS::satelliteCountChanged, this, &MainToolBar::_setSatelliteCount);
}
QGCUASParamManagerInterface* paramMgr = _mav->getParamManager();
Q_ASSERT(paramMgr);
disconnect(paramMgr, SIGNAL(parameterListProgress(float)), this, SLOT(_setProgressBarValue(float)));
disconnect(AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_mav), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue);
}
// Connect new system
_mav = active;
......@@ -334,19 +334,20 @@ void MainToolBar::_setActiveUAS(UASInterface* active)
connect(_mav, &UASInterface::remoteControlRSSIChanged, this, &MainToolBar::_remoteControlRSSIChanged);
connect(_mav, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*, QString,QString)));
connect(_mav, SIGNAL(armingChanged(bool)), this, SLOT(_updateArmingState(bool)));
if (_mav->getWaypointManager())
{
if (_mav->getWaypointManager()) {
connect(_mav->getWaypointManager(), &UASWaypointManager::currentWaypointChanged, this, &MainToolBar::_updateCurrentWaypoint);
connect(_mav->getWaypointManager(), &UASWaypointManager::waypointDistanceChanged, this, &MainToolBar::_updateWaypointDistance);
}
UAS* pUas = dynamic_cast<UAS*>(_mav);
if(pUas) {
_setSatelliteCount(pUas->getSatelliteCount(), QString(""));
connect(pUas, &UAS::satelliteCountChanged, this, &MainToolBar::_setSatelliteCount);
}
QGCUASParamManagerInterface* paramMgr = _mav->getParamManager();
Q_ASSERT(paramMgr);
connect(paramMgr, SIGNAL(parameterListProgress(float)), this, SLOT(_setProgressBarValue(float)));
connect(AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_mav), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue);
// Reset connection lost (if any)
_currentHeartbeatTimeout = 0;
emit heartbeatTimeoutChanged(_currentHeartbeatTimeout);
......
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