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

Merge pull request #1509 from DonLakeFlyer/ParamRework

Re-write of parameter system to move all control to FactSystem
parents 439d6cf8 834aa526
......@@ -151,11 +151,9 @@ INCLUDEPATH += \
src/uas \
src/ui \
src/ui/configuration \
src/ui/designer \
src/ui/flightdisplay \
src/ui/linechart \
src/ui/map \
src/ui/map3D \
src/ui/mapdisplay \
src/ui/mavlink \
src/ui/mission \
......@@ -170,13 +168,6 @@ FORMS += \
src/ui/configuration/SerialSettingsDialog.ui \
src/ui/configuration/terminalconsole.ui \
src/ui/DebugConsole.ui \
src/ui/designer/QGCActionButton.ui \
src/ui/designer/QGCCommandButton.ui \
src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCTextLabel.ui \
src/ui/designer/QGCToolWidget.ui \
src/ui/designer/QGCToolWidgetComboBox.ui \
src/ui/designer/QGCXYPlot.ui \
src/ui/HDDisplay.ui \
src/ui/Linechart.ui \
src/ui/MainWindow.ui \
......@@ -215,7 +206,6 @@ FORMS += \
src/ui/QGCUASFileViewMulti.ui \
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/QMap3D.ui \
src/ui/SerialSettings.ui \
src/ui/SettingsDialog.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
......@@ -279,30 +269,17 @@ HEADERS += \
src/QmlControls/ScreenTools.h \
src/uas/QGCMAVLinkUASFactory.h \
src/uas/QGCUASFileManager.h \
src/uas/QGCUASParamManager.h \
src/uas/QGCUASParamManagerInterface.h \
src/uas/UAS.h \
src/uas/UASInterface.h \
src/uas/UASManager.h \
src/uas/UASManagerInterface.h \
src/uas/UASMessageHandler.h \
src/uas/UASParameterCommsMgr.h \
src/uas/UASParameterDataModel.h \
src/uas/UASWaypointManager.h \
src/ui/configuration/ApmHighlighter.h \
src/ui/configuration/console.h \
src/ui/configuration/SerialSettingsDialog.h \
src/ui/configuration/terminalconsole.h \
src/ui/DebugConsole.h \
src/ui/designer/QGCCommandButton.h \
src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCRadioChannelDisplay.h \
src/ui/designer/QGCTextLabel.h \
src/ui/designer/QGCToolWidget.h \
src/ui/designer/QGCToolWidgetComboBox.h \
src/ui/designer/QGCToolWidgetItem.h \
src/ui/designer/QGCXYPlot.h \
src/ui/designer/RCChannelWidget.h \
src/ui/flightdisplay/QGCFlightDisplay.h \
src/ui/HDDisplay.h \
src/ui/HSIDisplay.h \
......@@ -423,27 +400,15 @@ SOURCES += \
src/QmlControls/ScreenTools.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/uas/QGCUASFileManager.cc \
src/uas/QGCUASParamManager.cc \
src/uas/UAS.cc \
src/uas/UASManager.cc \
src/uas/UASMessageHandler.cc \
src/uas/UASParameterCommsMgr.cc \
src/uas/UASParameterDataModel.cc \
src/uas/UASWaypointManager.cc \
src/ui/configuration/ApmHighlighter.cc \
src/ui/configuration/console.cpp \
src/ui/configuration/SerialSettingsDialog.cc \
src/ui/configuration/terminalconsole.cpp \
src/ui/DebugConsole.cc \
src/ui/designer/QGCCommandButton.cc \
src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCRadioChannelDisplay.cpp \
src/ui/designer/QGCTextLabel.cc \
src/ui/designer/QGCToolWidget.cc \
src/ui/designer/QGCToolWidgetComboBox.cc \
src/ui/designer/QGCToolWidgetItem.cc \
src/ui/designer/QGCXYPlot.cc \
src/ui/designer/RCChannelWidget.cc \
src/ui/flightdisplay/QGCFlightDisplay.cc \
src/ui/HDDisplay.cc \
src/ui/HSIDisplay.cc \
......@@ -553,11 +518,7 @@ HEADERS += \
src/qgcunittest/FlightGearTest.h \
src/qgcunittest/MockMavlinkFileServer.h \
src/qgcunittest/MockMavlinkInterface.h \
src/qgcunittest/MockQGCUASParamManager.h \
src/qgcunittest/MockUAS.h \
src/qgcunittest/MockUASManager.h \
src/qgcunittest/MultiSignalSpy.h \
src/qgcunittest/QGCUASFileManagerTest.h \
src/qgcunittest/TCPLinkTest.h \
src/qgcunittest/TCPLoopBackServer.h \
src/FactSystem/FactSystemTestBase.h \
......@@ -577,11 +538,7 @@ HEADERS += \
SOURCES += \
src/qgcunittest/FlightGearTest.cc \
src/qgcunittest/MockMavlinkFileServer.cc \
src/qgcunittest/MockQGCUASParamManager.cc \
src/qgcunittest/MockUAS.cc \
src/qgcunittest/MockUASManager.cc \
src/qgcunittest/MultiSignalSpy.cc \
src/qgcunittest/QGCUASFileManagerTest.cc \
src/qgcunittest/TCPLinkTest.cc \
src/qgcunittest/TCPLoopBackServer.cc \
src/FactSystem/FactSystemTestBase.cc \
......
......@@ -55,113 +55,6 @@ exists($$MAVLINKPATH/common) {
error($$sprintf("MAVLink folder does not exist at '%1'! Run 'git submodule init && git submodule update' on the command line.",$$MAVLINKPATH_REL))
}
#
# [OPTIONAL] OpenSceneGraph
# Allow the user to override OpenSceneGraph compilation through a DISABLE_OPEN_SCENE_GRAPH
# define like: `qmake DEFINES=DISABLE_OPEN_SCENE_GRAPH`
contains(DEFINES, DISABLE_OPEN_SCENE_GRAPH) {
message("Skipping support for OpenSceneGraph (manual override from command line)")
DEFINES -= DISABLE_OPEN_SCENE_GRAPH
}
# Otherwise the user can still disable this feature in the user_config.pri file.
else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_OPEN_SCENE_GRAPH) {
message("Skipping support for OpenSceneGraph (manual override from user_config.pri)")
}
else:MacBuild {
# GLUT and OpenSceneGraph are part of standard install on Mac
message("Including support for OpenSceneGraph")
CONFIG += OSGDependency
INCLUDEPATH += \
$$BASEDIR/libs/lib/mac64/include
LIBS += \
-L$$BASEDIR/libs/lib/mac64/lib \
-losgWidget
} else:LinuxBuild {
exists(/usr/include/osg) | exists(/usr/local/include/osg) {
message("Including support for OpenSceneGraph")
CONFIG += OSGDependency
} else {
warning("Skipping support for OpenSceneGraph (missing libraries, see README)")
}
} else:WindowsBuild {
exists($$BASEDIR/libs/lib/osg123) {
message("Including support for OpenSceneGraph")
CONFIG += OSGDependency
INCLUDEPATH += \
$$BASEDIR/libs/lib/osgEarth/win32/include \
$$BASEDIR/libs/lib/osgEarth_3rdparty/win32/OpenSceneGraph-2.8.2/include
LIBS += -L$$BASEDIR/libs/lib/osgEarth_3rdparty/win32/OpenSceneGraph-2.8.2/lib
} else {
warning("Skipping support for OpenSceneGraph (missing libraries, see README)")
}
} else {
message("Skipping support for OpenSceneGraph (unsupported platform)")
}
OSGDependency {
DEFINES += QGC_OSG_ENABLED
LIBS += \
-losg \
-losgViewer \
-losgGA \
-losgDB \
-losgText \
-lOpenThreads
HEADERS += \
src/ui/map3D/gpl.h \
src/ui/map3D/CameraParams.h \
src/ui/map3D/ViewParamWidget.h \
src/ui/map3D/SystemContainer.h \
src/ui/map3D/SystemViewParams.h \
src/ui/map3D/GlobalViewParams.h \
src/ui/map3D/SystemGroupNode.h \
src/ui/map3D/Q3DWidget.h \
src/ui/map3D/GCManipulator.h \
src/ui/map3D/ImageWindowGeode.h \
src/ui/map3D/PixhawkCheetahNode.h \
src/ui/map3D/Pixhawk3DWidget.h \
src/ui/map3D/Q3DWidgetFactory.h \
src/ui/map3D/WebImageCache.h \
src/ui/map3D/WebImage.h \
src/ui/map3D/TextureCache.h \
src/ui/map3D/Texture.h \
src/ui/map3D/Imagery.h \
src/ui/map3D/HUDScaleGeode.h \
src/ui/map3D/WaypointGroupNode.h \
src/ui/map3D/TerrainParamDialog.h \
src/ui/map3D/ImageryParamDialog.h
SOURCES += \
src/ui/map3D/gpl.cc \
src/ui/map3D/CameraParams.cc \
src/ui/map3D/ViewParamWidget.cc \
src/ui/map3D/SystemContainer.cc \
src/ui/map3D/SystemViewParams.cc \
src/ui/map3D/GlobalViewParams.cc \
src/ui/map3D/SystemGroupNode.cc \
src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/ImageWindowGeode.cc \
src/ui/map3D/GCManipulator.cc \
src/ui/map3D/PixhawkCheetahNode.cc \
src/ui/map3D/Pixhawk3DWidget.cc \
src/ui/map3D/Q3DWidgetFactory.cc \
src/ui/map3D/WebImageCache.cc \
src/ui/map3D/WebImage.cc \
src/ui/map3D/TextureCache.cc \
src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc \
src/ui/map3D/TerrainParamDialog.cc \
src/ui/map3D/ImageryParamDialog.cc
}
#
# [REQUIRED] EIGEN matrix library
# NOMINMAX constant required to make internal min/max work.
......
......@@ -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