From d4d26f03c4376740860239b29154d130c46f4c62 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 24 Nov 2015 20:20:21 -0800 Subject: [PATCH] Explicit raw/cooked values --- .../APM/APMAirframeComponent.cc | 2 +- src/AutoPilotPlugins/PX4/AirframeComponent.cc | 2 +- .../PX4/AirframeComponentController.cc | 7 +- .../PX4/FlightModesComponent.cc | 8 +- .../PX4/FlightModesComponentController.cc | 162 +++++++++--------- src/AutoPilotPlugins/PX4/PowerComponent.cc | 6 +- src/AutoPilotPlugins/PX4/RadioComponent.cc | 8 +- .../PX4/RadioComponentController.cc | 24 +-- src/AutoPilotPlugins/PX4/SensorsComponent.cc | 2 +- src/FactSystem/Fact.cc | 32 ++-- src/FactSystem/Fact.h | 12 +- src/FactSystem/FactSystemTestBase.cc | 8 +- src/FactSystem/ParameterLoader.cc | 10 +- src/MissionManager/MissionItem.cc | 34 ++-- src/MissionManager/MissionItem.h | 6 +- src/qgcunittest/PX4RCCalibrationTest.cc | 18 +- 16 files changed, 170 insertions(+), 171 deletions(-) diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.cc b/src/AutoPilotPlugins/APM/APMAirframeComponent.cc index 468baf03c..906be71ee 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.cc @@ -59,7 +59,7 @@ bool APMAirframeComponent::setupComplete(void) const { // You'll need to figure out which parameters trigger setup complete #if 0 - return _autopilot->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->value().toInt() != 0; + return _autopilot->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt() != 0; #else return true; #endif diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.cc b/src/AutoPilotPlugins/PX4/AirframeComponent.cc index e99236ee2..26ad00137 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.cc @@ -142,7 +142,7 @@ bool AirframeComponent::requiresSetup(void) const bool AirframeComponent::setupComplete(void) const { - return _autopilot->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->value().toInt() != 0; + return _autopilot->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt() != 0; } QString AirframeComponent::setupStateDescription(void) const diff --git a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc index 8cc0f058a..8fc232cc2 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc @@ -57,8 +57,7 @@ AirframeComponentController::AirframeComponentController(void) : // Load up member variables bool autostartFound = false; - _autostartId = getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->value().toInt(); - + _autostartId = getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt(); for (int tindex = 0; tindex < AirframeComponentAirframes::get().count(); tindex++) { @@ -114,8 +113,8 @@ void AirframeComponentController::changeAutostart(void) connect(sysAutoConfigFact, &Fact::vehicleUpdated, this, &AirframeComponentController::_waitParamWriteSignal); // We use forceSetValue to params are sent even if the previous value is that same as the new value - sysAutoStartFact->forceSetValue(_autostartId); - sysAutoConfigFact->forceSetValue(1); + sysAutoStartFact->forceSetRawValue(_autostartId); + sysAutoConfigFact->forceSetRawValue(1); } void AirframeComponentController::_waitParamWriteSignal(QVariant value) diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponent.cc b/src/AutoPilotPlugins/PX4/FlightModesComponent.cc index cef48ab81..a36a1e50a 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponent.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponent.cc @@ -68,13 +68,13 @@ QString FlightModesComponent::iconResource(void) const bool FlightModesComponent::requiresSetup(void) const { - return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->value().toInt() == 1 ? false : true; + return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true; } bool FlightModesComponent::setupComplete(void) const { - return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->value().toInt() == 1 || - _autopilot->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->value().toInt() != 0; + return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 || + _autopilot->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0; } QString FlightModesComponent::setupStateDescription(void) const @@ -117,7 +117,7 @@ QUrl FlightModesComponent::summaryQmlSource(void) const QString FlightModesComponent::prerequisiteSetup(void) const { - if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->value().toInt() == 1) { + if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) { // No RC input return QString(); } else { diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc index 1c55ff127..f6c241ae5 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc @@ -78,10 +78,10 @@ void FlightModesComponentController::_init(void) QVariant value; - _rgRCMin[channel] = getParameterFact(FactSystem::defaultComponentId, rcMinParam)->value().toInt(); - _rgRCMax[channel] = getParameterFact(FactSystem::defaultComponentId, rcMaxParam)->value().toInt(); + _rgRCMin[channel] = getParameterFact(FactSystem::defaultComponentId, rcMinParam)->rawValue().toInt(); + _rgRCMax[channel] = getParameterFact(FactSystem::defaultComponentId, rcMaxParam)->rawValue().toInt(); - float floatReversed = getParameterFact(-1, rcRevParam)->value().toFloat(); + float floatReversed = getParameterFact(-1, rcRevParam)->rawValue().toFloat(); _rgRCReversed[channel] = floatReversed == -1.0f; _rcValues[channel] = 0.0; @@ -89,7 +89,7 @@ void FlightModesComponentController::_init(void) // RC_CHAN_CNT parameter is set by Radio Cal to specify the number of radio channels. if (parameterExists(FactSystem::defaultComponentId, "RC_CHAN_CNT")) { - _channelCount = getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->value().toInt(); + _channelCount = getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->rawValue().toInt(); } else { _channelCount =_chanMax; } @@ -98,9 +98,9 @@ void FlightModesComponentController::_init(void) _channelCount = _chanMax; } - int modeChannel = getParameterFact(-1, "RC_MAP_MODE_SW")->value().toInt(); - int posCtlChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->value().toInt(); - int loiterChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->value().toInt(); + int modeChannel = getParameterFact(-1, "RC_MAP_MODE_SW")->rawValue().toInt(); + int posCtlChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->rawValue().toInt(); + int loiterChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->rawValue().toInt(); if (posCtlChannel == 0) { // PosCtl disabled so AltCtl must move back to main Mode switch @@ -125,7 +125,7 @@ void FlightModesComponentController::_init(void) attitudeParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2"; foreach(QString attitudeParam, attitudeParams) { - int channel = getParameterFact(-1, attitudeParam)->value().toInt(); + int channel = getParameterFact(-1, attitudeParam)->rawValue().toInt(); if (channel != 0) { usedChannels << channel; } @@ -168,7 +168,7 @@ void FlightModesComponentController::_validateConfiguration(void) switchParams << "RC_MAP_MODE_SW" << "RC_MAP_ACRO_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_OFFB_SW"; for(int i=0; ivalue().toInt(); + int map = getParameterFact(FactSystem::defaultComponentId, switchParams[i])->rawValue().toInt(); switchMappings << map; if (map < 0 || map > _channelCount) { @@ -184,7 +184,7 @@ void FlightModesComponentController::_validateConfiguration(void) attitudeParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2"; for (int i=0; ivalue().toInt(); + int map = getParameterFact(FactSystem::defaultComponentId, attitudeParams[i])->rawValue().toInt(); for (int j=0; jvalue().toFloat(); + float threshold = getParameterFact(-1, thresholdParam)->rawValue().toFloat(); if (threshold < 0.0f || threshold > 1.0f) { _validConfiguration = false; _configurationErrors += QString("%1 is set to %2. Threshold must between 0.0 and 1.0 (inclusive).\n").arg(thresholdParam).arg(threshold); @@ -239,7 +239,7 @@ double FlightModesComponentController::_switchLiveRange(const QString& param) { QVariant value; - int channel = getParameterFact(-1, param)->value().toInt(); + int channel = getParameterFact(-1, param)->rawValue().toInt(); if (channel == 0) { return 0.0; } else { @@ -269,7 +269,7 @@ double FlightModesComponentController::acroModeRcValue(void) double FlightModesComponentController::altCtlModeRcValue(void) { - int posCtlSwitchChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->value().toInt(); + int posCtlSwitchChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->rawValue().toInt(); if (posCtlSwitchChannel == 0) { return _switchLiveRange("RC_MAP_MODE_SW"); @@ -285,8 +285,8 @@ double FlightModesComponentController::posCtlModeRcValue(void) double FlightModesComponentController::missionModeRcValue(void) { - int returnSwitchChannel = getParameterFact(-1, "RC_MAP_RETURN_SW")->value().toInt(); - int loiterSwitchChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->value().toInt(); + int returnSwitchChannel = getParameterFact(-1, "RC_MAP_RETURN_SW")->rawValue().toInt(); + int loiterSwitchChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->rawValue().toInt(); const char* switchChannelParam = "RC_MAP_MODE_SW"; @@ -334,20 +334,20 @@ void FlightModesComponentController::_recalcModeSelections(void) _offboardModeSelected = false; // Convert channels to 0-based, -1 signals not mapped - int modeSwitchChannel = getParameterFact(-1, "RC_MAP_MODE_SW")->value().toInt() - 1; - int acroSwitchChannel = getParameterFact(-1, "RC_MAP_ACRO_SW")->value().toInt() - 1; - int posCtlSwitchChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->value().toInt() - 1; - int loiterSwitchChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->value().toInt() - 1; - int returnSwitchChannel = getParameterFact(-1, "RC_MAP_RETURN_SW")->value().toInt() - 1; - int offboardSwitchChannel = getParameterFact(-1, "RC_MAP_OFFB_SW")->value().toInt() - 1; - - double autoThreshold = getParameterFact(-1, "RC_AUTO_TH")->value().toDouble(); - double assistThreshold = getParameterFact(-1, "RC_ASSIST_TH")->value().toDouble(); - double acroThreshold = getParameterFact(-1, "RC_ACRO_TH")->value().toDouble(); - double posCtlThreshold = getParameterFact(-1, "RC_POSCTL_TH")->value().toDouble(); - double loiterThreshold = getParameterFact(-1, "RC_LOITER_TH")->value().toDouble(); - double returnThreshold = getParameterFact(-1, "RC_RETURN_TH")->value().toDouble(); - double offboardThreshold = getParameterFact(-1, "RC_OFFB_TH")->value().toDouble(); + int modeSwitchChannel = getParameterFact(-1, "RC_MAP_MODE_SW")->rawValue().toInt() - 1; + int acroSwitchChannel = getParameterFact(-1, "RC_MAP_ACRO_SW")->rawValue().toInt() - 1; + int posCtlSwitchChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->rawValue().toInt() - 1; + int loiterSwitchChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->rawValue().toInt() - 1; + int returnSwitchChannel = getParameterFact(-1, "RC_MAP_RETURN_SW")->rawValue().toInt() - 1; + int offboardSwitchChannel = getParameterFact(-1, "RC_MAP_OFFB_SW")->rawValue().toInt() - 1; + + double autoThreshold = getParameterFact(-1, "RC_AUTO_TH")->rawValue().toDouble(); + double assistThreshold = getParameterFact(-1, "RC_ASSIST_TH")->rawValue().toDouble(); + double acroThreshold = getParameterFact(-1, "RC_ACRO_TH")->rawValue().toDouble(); + double posCtlThreshold = getParameterFact(-1, "RC_POSCTL_TH")->rawValue().toDouble(); + double loiterThreshold = getParameterFact(-1, "RC_LOITER_TH")->rawValue().toDouble(); + double returnThreshold = getParameterFact(-1, "RC_RETURN_TH")->rawValue().toDouble(); + double offboardThreshold = getParameterFact(-1, "RC_OFFB_TH")->rawValue().toDouble(); if (modeSwitchChannel >= 0) { if (offboardSwitchChannel >= 0 && _rcValues[offboardSwitchChannel] >= offboardThreshold) { @@ -382,12 +382,12 @@ void FlightModesComponentController::_recalcModeSelections(void) void FlightModesComponentController::_recalcModeRows(void) { - int modeSwitchChannel = getParameterFact(-1, "RC_MAP_MODE_SW")->value().toInt(); - int acroSwitchChannel = getParameterFact(-1, "RC_MAP_ACRO_SW")->value().toInt(); - int posCtlSwitchChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->value().toInt(); - int loiterSwitchChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->value().toInt(); - int returnSwitchChannel = getParameterFact(-1, "RC_MAP_RETURN_SW")->value().toInt(); - int offboardSwitchChannel = getParameterFact(-1, "RC_MAP_OFFB_SW")->value().toInt(); + int modeSwitchChannel = getParameterFact(-1, "RC_MAP_MODE_SW")->rawValue().toInt(); + int acroSwitchChannel = getParameterFact(-1, "RC_MAP_ACRO_SW")->rawValue().toInt(); + int posCtlSwitchChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->rawValue().toInt(); + int loiterSwitchChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->rawValue().toInt(); + int returnSwitchChannel = getParameterFact(-1, "RC_MAP_RETURN_SW")->rawValue().toInt(); + int offboardSwitchChannel = getParameterFact(-1, "RC_MAP_OFFB_SW")->rawValue().toInt(); if (modeSwitchChannel == 0) { _acroModeRow = 0; @@ -477,65 +477,65 @@ double FlightModesComponentController::manualModeThreshold(void) double FlightModesComponentController::assistModeThreshold(void) { - return getParameterFact(-1, "RC_ASSIST_TH")->value().toDouble(); + return getParameterFact(-1, "RC_ASSIST_TH")->rawValue().toDouble(); } double FlightModesComponentController::autoModeThreshold(void) { - return getParameterFact(-1, "RC_AUTO_TH")->value().toDouble(); + return getParameterFact(-1, "RC_AUTO_TH")->rawValue().toDouble(); } double FlightModesComponentController::acroModeThreshold(void) { - return getParameterFact(-1, "RC_ACRO_TH")->value().toDouble(); + return getParameterFact(-1, "RC_ACRO_TH")->rawValue().toDouble(); } double FlightModesComponentController::altCtlModeThreshold(void) { - return _assistModeVisible ? 0.0 : getParameterFact(-1, "RC_ASSIST_TH")->value().toDouble(); + return _assistModeVisible ? 0.0 : getParameterFact(-1, "RC_ASSIST_TH")->rawValue().toDouble(); } double FlightModesComponentController::posCtlModeThreshold(void) { - return getParameterFact(-1, "RC_POSCTL_TH")->value().toDouble(); + return getParameterFact(-1, "RC_POSCTL_TH")->rawValue().toDouble(); } double FlightModesComponentController::missionModeThreshold(void) { - return _autoModeVisible ? 0.0 : getParameterFact(-1, "RC_AUTO_TH")->value().toDouble(); + return _autoModeVisible ? 0.0 : getParameterFact(-1, "RC_AUTO_TH")->rawValue().toDouble(); } double FlightModesComponentController::loiterModeThreshold(void) { - return getParameterFact(-1, "RC_LOITER_TH")->value().toDouble(); + return getParameterFact(-1, "RC_LOITER_TH")->rawValue().toDouble(); } double FlightModesComponentController::returnModeThreshold(void) { - return getParameterFact(-1, "RC_RETURN_TH")->value().toDouble(); + return getParameterFact(-1, "RC_RETURN_TH")->rawValue().toDouble(); } double FlightModesComponentController::offboardModeThreshold(void) { - return getParameterFact(-1, "RC_OFFB_TH")->value().toDouble(); + return getParameterFact(-1, "RC_OFFB_TH")->rawValue().toDouble(); } void FlightModesComponentController::setAssistModeThreshold(double threshold) { - getParameterFact(-1, "RC_ASSIST_TH")->setValue(threshold); + getParameterFact(-1, "RC_ASSIST_TH")->setRawValue(threshold); _recalcModeSelections(); } void FlightModesComponentController::setAutoModeThreshold(double threshold) { - getParameterFact(-1, "RC_AUTO_TH")->setValue(threshold); + getParameterFact(-1, "RC_AUTO_TH")->setRawValue(threshold); _recalcModeSelections(); } void FlightModesComponentController::setAcroModeThreshold(double threshold) { - getParameterFact(-1, "RC_ACRO_TH")->setValue(threshold); + getParameterFact(-1, "RC_ACRO_TH")->setRawValue(threshold); _recalcModeSelections(); } @@ -546,7 +546,7 @@ void FlightModesComponentController::setAltCtlModeThreshold(double threshold) void FlightModesComponentController::setPosCtlModeThreshold(double threshold) { - getParameterFact(-1, "RC_POSCTL_TH")->setValue(threshold); + getParameterFact(-1, "RC_POSCTL_TH")->setRawValue(threshold); _recalcModeSelections(); } @@ -557,19 +557,19 @@ void FlightModesComponentController::setMissionModeThreshold(double threshold) void FlightModesComponentController::setLoiterModeThreshold(double threshold) { - getParameterFact(-1, "RC_LOITER_TH")->setValue(threshold); + getParameterFact(-1, "RC_LOITER_TH")->setRawValue(threshold); _recalcModeSelections(); } void FlightModesComponentController::setReturnModeThreshold(double threshold) { - getParameterFact(-1, "RC_RETURN_TH")->setValue(threshold); + getParameterFact(-1, "RC_RETURN_TH")->setRawValue(threshold); _recalcModeSelections(); } void FlightModesComponentController::setOffboardModeThreshold(double threshold) { - getParameterFact(-1, "RC_OFFB_TH")->setValue(threshold); + getParameterFact(-1, "RC_OFFB_TH")->setRawValue(threshold); _recalcModeSelections(); } @@ -580,7 +580,7 @@ int FlightModesComponentController::_channelToChannelIndex(int channel) int FlightModesComponentController::_channelToChannelIndex(const QString& channelParam) { - return _channelToChannelIndex(getParameterFact(-1, channelParam)->value().toInt()); + return _channelToChannelIndex(getParameterFact(-1, channelParam)->rawValue().toInt()); } int FlightModesComponentController::manualModeChannelIndex(void) @@ -605,7 +605,7 @@ int FlightModesComponentController::acroModeChannelIndex(void) int FlightModesComponentController::altCtlModeChannelIndex(void) { - int posCtlSwitchChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->value().toInt(); + int posCtlSwitchChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->rawValue().toInt(); if (posCtlSwitchChannel == 0) { return _channelToChannelIndex("RC_MAP_MODE_SW"); @@ -626,7 +626,7 @@ int FlightModesComponentController::loiterModeChannelIndex(void) int FlightModesComponentController::missionModeChannelIndex(void) { - int loiterSwitchChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->value().toInt(); + int loiterSwitchChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->rawValue().toInt(); if (loiterSwitchChannel == 0) { return _channelToChannelIndex("RC_MAP_MODE_SW"); @@ -652,7 +652,7 @@ int FlightModesComponentController::_channelIndexToChannel(int index) void FlightModesComponentController::setManualModeChannelIndex(int index) { - getParameterFact(-1, "RC_MAP_MODE_SW")->setValue(_channelIndexToChannel(index)); + getParameterFact(-1, "RC_MAP_MODE_SW")->setRawValue(_channelIndexToChannel(index)); _recalcModeSelections(); _recalcModeRows(); @@ -662,7 +662,7 @@ void FlightModesComponentController::setManualModeChannelIndex(int index) void FlightModesComponentController::setAcroModeChannelIndex(int index) { - getParameterFact(-1, "RC_MAP_ACRO_SW")->setValue(_channelIndexToChannel(index)); + getParameterFact(-1, "RC_MAP_ACRO_SW")->setRawValue(_channelIndexToChannel(index)); _recalcModeSelections(); _recalcModeRows(); @@ -672,14 +672,14 @@ void FlightModesComponentController::setPosCtlModeChannelIndex(int index) { int channel = _channelIndexToChannel(index); - getParameterFact(-1, "RC_MAP_POSCTL_SW")->setValue(channel); + getParameterFact(-1, "RC_MAP_POSCTL_SW")->setRawValue(channel); if (channel == 0) { // PosCtl disabled so AltCtl must move back to main Mode switch _assistModeVisible = false; } else { // Assist mode is visible if AltCtl/PosCtl are on seperate channel from main Mode switch - _assistModeVisible = channel != getParameterFact(-1, "RC_MAP_MODE_SW")->value().toInt(); + _assistModeVisible = channel != getParameterFact(-1, "RC_MAP_MODE_SW")->rawValue().toInt(); } emit modesVisibleChanged(); @@ -694,14 +694,14 @@ void FlightModesComponentController::setLoiterModeChannelIndex(int index) { int channel = _channelIndexToChannel(index); - getParameterFact(-1, "RC_MAP_LOITER_SW")->setValue(channel); + getParameterFact(-1, "RC_MAP_LOITER_SW")->setRawValue(channel); if (channel == 0) { // Loiter disabled so Mission must move back to main Mode switch _autoModeVisible = false; } else { // Auto mode is visible if Mission/Loiter are on seperate channel from main Mode switch - _autoModeVisible = channel != getParameterFact(-1, "RC_MAP_MODE_SW")->value().toInt(); + _autoModeVisible = channel != getParameterFact(-1, "RC_MAP_MODE_SW")->rawValue().toInt(); } emit modesVisibleChanged(); @@ -714,7 +714,7 @@ void FlightModesComponentController::setLoiterModeChannelIndex(int index) void FlightModesComponentController::setReturnModeChannelIndex(int index) { - getParameterFact(-1, "RC_MAP_RETURN_SW")->setValue(_channelIndexToChannel(index)); + getParameterFact(-1, "RC_MAP_RETURN_SW")->setRawValue(_channelIndexToChannel(index)); _recalcModeSelections(); _recalcModeRows(); emit channelIndicesChanged(); @@ -723,7 +723,7 @@ void FlightModesComponentController::setReturnModeChannelIndex(int index) void FlightModesComponentController::setOffboardModeChannelIndex(int index) { - getParameterFact(-1, "RC_MAP_OFFB_SW")->setValue(_channelIndexToChannel(index)); + getParameterFact(-1, "RC_MAP_OFFB_SW")->setRawValue(_channelIndexToChannel(index)); _recalcModeSelections(); _recalcModeRows(); emit channelIndicesChanged(); @@ -739,17 +739,17 @@ void FlightModesComponentController::generateThresholds(void) thresholdParams << "RC_ASSIST_TH" << "RC_AUTO_TH" << "RC_ACRO_TH" << "RC_POSCTL_TH" << "RC_LOITER_TH" << "RC_RETURN_TH" << "RC_OFFB_TH"; foreach(QString thresholdParam, thresholdParams) { - getParameterFact(-1, thresholdParam)->setValue(0.0f); + getParameterFact(-1, thresholdParam)->setRawValue(0.0f); } // Redistribute - int modeChannel = getParameterFact(-1, "RC_MAP_MODE_SW")->value().toInt(); - int acroChannel = getParameterFact(-1, "RC_MAP_ACRO_SW")->value().toInt(); - int posCtlChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->value().toInt(); - int loiterChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->value().toInt(); - int returnChannel = getParameterFact(-1, "RC_MAP_RETURN_SW")->value().toInt(); - int offboardChannel = getParameterFact(-1, "RC_MAP_OFFB_SW")->value().toInt(); + int modeChannel = getParameterFact(-1, "RC_MAP_MODE_SW")->rawValue().toInt(); + int acroChannel = getParameterFact(-1, "RC_MAP_ACRO_SW")->rawValue().toInt(); + int posCtlChannel = getParameterFact(-1, "RC_MAP_POSCTL_SW")->rawValue().toInt(); + int loiterChannel = getParameterFact(-1, "RC_MAP_LOITER_SW")->rawValue().toInt(); + int returnChannel = getParameterFact(-1, "RC_MAP_RETURN_SW")->rawValue().toInt(); + int offboardChannel = getParameterFact(-1, "RC_MAP_OFFB_SW")->rawValue().toInt(); if (modeChannel != 0) { int positions = 3; // Manual/Assist/Auto always exist @@ -771,35 +771,35 @@ void FlightModesComponentController::generateThresholds(void) if (acroOnModeSwitch) { currentThreshold += increment; - getParameterFact(-1, "RC_ACRO_TH")->setValue(currentThreshold); + getParameterFact(-1, "RC_ACRO_TH")->setRawValue(currentThreshold); acroChannel = 0; } currentThreshold += increment; - getParameterFact(-1, "RC_ASSIST_TH")->setValue(currentThreshold); + getParameterFact(-1, "RC_ASSIST_TH")->setRawValue(currentThreshold); if (posCtlOnModeSwitch) { currentThreshold += increment; - getParameterFact(-1, "RC_POSCTL_TH")->setValue(currentThreshold); + getParameterFact(-1, "RC_POSCTL_TH")->setRawValue(currentThreshold); posCtlChannel = 0; } currentThreshold += increment; - getParameterFact(-1, "RC_AUTO_TH")->setValue(currentThreshold); + getParameterFact(-1, "RC_AUTO_TH")->setRawValue(currentThreshold); if (loiterOnModeSwitch) { currentThreshold += increment; - getParameterFact(-1, "RC_LOITER_TH")->setValue(currentThreshold); + getParameterFact(-1, "RC_LOITER_TH")->setRawValue(currentThreshold); loiterChannel = 0; } if (returnOnModeSwitch) { currentThreshold += increment; - getParameterFact(-1, "RC_RETURN_TH")->setValue(currentThreshold); + getParameterFact(-1, "RC_RETURN_TH")->setRawValue(currentThreshold); returnChannel = 0; } if (offboardOnModeSwitch) { currentThreshold += increment; - getParameterFact(-1, "RC_OFFB_TH")->setValue(currentThreshold); + getParameterFact(-1, "RC_OFFB_TH")->setRawValue(currentThreshold); offboardChannel = 0; } } @@ -807,23 +807,23 @@ void FlightModesComponentController::generateThresholds(void) if (acroChannel != 0) { // If only two positions don't set threshold at midrange. Setting to 0.25 // allows for this channel to work with either a two or three position switch - getParameterFact(-1, "RC_ACRO_TH")->setValue(0.25f); + getParameterFact(-1, "RC_ACRO_TH")->setRawValue(0.25f); } if (posCtlChannel != 0) { - getParameterFact(-1, "RC_POSCTL_TH")->setValue(0.25f); + getParameterFact(-1, "RC_POSCTL_TH")->setRawValue(0.25f); } if (loiterChannel != 0) { - getParameterFact(-1, "RC_LOITER_TH")->setValue(0.25f); + getParameterFact(-1, "RC_LOITER_TH")->setRawValue(0.25f); } if (returnChannel != 0) { - getParameterFact(-1, "RC_RETURN_TH")->setValue(0.25f); + getParameterFact(-1, "RC_RETURN_TH")->setRawValue(0.25f); } if (offboardChannel != 0) { - getParameterFact(-1, "RC_OFFB_TH")->setValue(0.25f); + getParameterFact(-1, "RC_OFFB_TH")->setRawValue(0.25f); } emit thresholdsChanged(); diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.cc b/src/AutoPilotPlugins/PX4/PowerComponent.cc index 16be86cbf..5f2381225 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.cc +++ b/src/AutoPilotPlugins/PX4/PowerComponent.cc @@ -57,9 +57,9 @@ bool PowerComponent::requiresSetup(void) const bool PowerComponent::setupComplete(void) const { QVariant cvalue, evalue, nvalue; - return _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->value().toFloat() != 0.0f && - _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->value().toFloat() != 0.0f && - _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->value().toInt() != 0; + return _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f && + _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f && + _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0; } QString PowerComponent::setupStateDescription(void) const diff --git a/src/AutoPilotPlugins/PX4/RadioComponent.cc b/src/AutoPilotPlugins/PX4/RadioComponent.cc index 0f95fb1a4..fead1e094 100644 --- a/src/AutoPilotPlugins/PX4/RadioComponent.cc +++ b/src/AutoPilotPlugins/PX4/RadioComponent.cc @@ -53,18 +53,18 @@ QString RadioComponent::iconResource(void) const bool RadioComponent::requiresSetup(void) const { - return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->value().toInt() == 1 ? false : true; + return _autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true; } bool RadioComponent::setupComplete(void) const { - if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->value().toInt() != 1) { + if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) { // The best we can do to detect the need for a radio calibration is look for attitude // controls to be mapped. QStringList attitudeMappings; attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE"; foreach(QString mapParam, attitudeMappings) { - if (_autopilot->getParameterFact(FactSystem::defaultComponentId, mapParam)->value().toInt() == 0) { + if (_autopilot->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) { return false; } } @@ -115,7 +115,7 @@ QUrl RadioComponent::summaryQmlSource(void) const QString RadioComponent::prerequisiteSetup(void) const { - if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->value().toInt() != 1) { + if (_autopilot->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) { PX4AutoPilotPlugin* plugin = dynamic_cast(_autopilot); Q_ASSERT(plugin); diff --git a/src/AutoPilotPlugins/PX4/RadioComponentController.cc b/src/AutoPilotPlugins/PX4/RadioComponentController.cc index e251c2532..7fe94bbf2 100644 --- a/src/AutoPilotPlugins/PX4/RadioComponentController.cc +++ b/src/AutoPilotPlugins/PX4/RadioComponentController.cc @@ -652,7 +652,7 @@ void RadioComponentController::_resetInternalCalibrationValues(void) enum rcCalFunctions curFunction = rgFlightModeFunctions[i]; bool ok; - int switchChannel = getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[curFunction].parameterName)->value().toInt(&ok); + int switchChannel = getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[curFunction].parameterName)->rawValue().toInt(&ok); Q_ASSERT(ok); // Parameter: 1-based channel, 0=not mapped @@ -694,16 +694,16 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) for (int i = 0; i < _chanMax; ++i) { struct ChannelInfo* info = &_rgChannelInfo[i]; - info->rcTrim = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1))->value().toInt(&convertOk); + info->rcTrim = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1))->rawValue().toInt(&convertOk); Q_ASSERT(convertOk); - info->rcMin = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1))->value().toInt(&convertOk); + info->rcMin = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1))->rawValue().toInt(&convertOk); Q_ASSERT(convertOk); - info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->value().toInt(&convertOk); + info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt(&convertOk); Q_ASSERT(convertOk); - float floatReversed = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1))->value().toFloat(&convertOk); + float floatReversed = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1))->rawValue().toFloat(&convertOk); Q_ASSERT(convertOk); Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f); info->reversed = floatReversed == -1.0f; @@ -712,7 +712,7 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) for (int i=0; ivalue().toInt(&convertOk); + paramChannel = getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->rawValue().toInt(&convertOk); Q_ASSERT(convertOk); if (paramChannel != 0) { @@ -794,10 +794,10 @@ void RadioComponentController::_writeCalibration(void) struct ChannelInfo* info = &_rgChannelInfo[chan]; int oneBasedChannel = chan + 1; - getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->setValue((float)info->rcTrim); - getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->setValue((float)info->rcMin); - getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->setValue((float)info->rcMax); - getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->setValue(info->reversed ? -1.0f : 1.0f); + getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->setRawValue((float)info->rcTrim); + getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->setRawValue((float)info->rcMin); + getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->setRawValue((float)info->rcMax); + getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->setRawValue(info->reversed ? -1.0f : 1.0f); } // Write function mapping parameters @@ -810,12 +810,12 @@ void RadioComponentController::_writeCalibration(void) // Note that the channel value is 1-based paramChannel = _rgFunctionChannelMapping[i] + 1; } - getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->setValue(paramChannel); + getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->setRawValue(paramChannel); } // If the RC_CHAN_COUNT parameter is available write the channel count if (parameterExists(FactSystem::defaultComponentId, "RC_CHAN_CNT")) { - getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->setValue(_chanCount); + getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->setRawValue(_chanCount); } _stopCalibration(); diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.cc b/src/AutoPilotPlugins/PX4/SensorsComponent.cc index ba28439f3..d810c6a94 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.cc @@ -62,7 +62,7 @@ bool SensorsComponent::requiresSetup(void) const bool SensorsComponent::setupComplete(void) const { foreach(QString triggerParam, setupCompleteChangedTriggerList()) { - if (_autopilot->getParameterFact(FactSystem::defaultComponentId, triggerParam)->value().toFloat() == 0.0f) { + if (_autopilot->getParameterFact(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) { return false; } } diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index 81c920616..f3740f4aa 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -73,16 +73,16 @@ const Fact& Fact::operator=(const Fact& other) return *this; } -void Fact::forceSetValue(const QVariant& value) +void Fact::forceSetRawValue(const QVariant& value) { if (_metaData) { QVariant typedValue; QString errorString; if (_metaData->convertAndValidate(value, true /* convertOnly */, typedValue, errorString)) { - _rawValue.setValue(_metaData->cookedTranslator()(typedValue)); - emit valueChanged(typedValue); - emit _containerValueChanged(typedValue); + _rawValue.setValue(typedValue); + emit valueChanged(cookedValue()); + emit _containerRawValueChanged(rawValue()); } } else { qWarning() << "Meta data pointer missing"; @@ -98,8 +98,8 @@ void Fact::setRawValue(const QVariant& value) if (_metaData->convertAndValidate(value, true /* convertOnly */, typedValue, errorString)) { if (typedValue != _rawValue) { _rawValue.setValue(typedValue); - emit valueChanged(this->value()); - emit _containerValueChanged(this->value()); + emit valueChanged(cookedValue()); + emit _containerRawValueChanged(rawValue()); } } } else { @@ -107,7 +107,7 @@ void Fact::setRawValue(const QVariant& value) } } -void Fact::setValue(const QVariant& value) +void Fact::setCookedValue(const QVariant& value) { if (_metaData) { setRawValue(_metaData->cookedTranslator()(value)); @@ -121,7 +121,7 @@ void Fact::setEnumStringValue(const QString& value) if (_metaData) { int index = _metaData->enumStrings().indexOf(value); if (index != -1) { - setValue(_metaData->enumValues()[index]); + setCookedValue(_metaData->enumValues()[index]); } } else { qWarning() << "Meta data pointer missing"; @@ -131,16 +131,16 @@ void Fact::setEnumStringValue(const QString& value) void Fact::setEnumIndex(int index) { if (_metaData) { - setValue(_metaData->enumValues()[index]); + setCookedValue(_metaData->enumValues()[index]); } else { qWarning() << "Meta data pointer missing"; } } -void Fact::_containerSetValue(const QVariant& value) +void Fact::_containerSetRawValue(const QVariant& value) { _rawValue = value; - emit valueChanged(_rawValue); + emit valueChanged(cookedValue()); emit vehicleUpdated(_rawValue); } @@ -154,7 +154,7 @@ int Fact::componentId(void) const return _componentId; } -QVariant Fact::value(void) const +QVariant Fact::cookedValue(void) const { if (_metaData) { return _metaData->rawTranslator()(_rawValue); @@ -183,7 +183,7 @@ int Fact::enumIndex(void) const if (_metaData) { int index = 0; foreach (QVariant enumValue, _metaData->enumValues()) { - if (enumValue == value()) { + if (enumValue == rawValue()) { return index; } index ++; @@ -236,7 +236,7 @@ QString Fact::_variantToString(const QVariant& variant) const QString Fact::valueString(void) const { - return _variantToString(value()); + return _variantToString(cookedValue()); } QVariant Fact::defaultValue(void) const @@ -365,14 +365,14 @@ QString Fact::group(void) const void Fact::setMetaData(FactMetaData* metaData) { _metaData = metaData; - emit valueChanged(value()); + emit valueChanged(cookedValue()); } bool Fact::valueEqualsDefault(void) const { if (_metaData) { if (_metaData->defaultValueAvailable()) { - return _metaData->defaultValue() == value(); + return _metaData->defaultValue() == rawValue(); } else { return false; } diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index a1f2b6c5f..4acd5f70d 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -67,7 +67,7 @@ public: Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT) Q_PROPERTY(QString units READ units CONSTANT) - Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged) + Q_PROPERTY(QVariant value READ cookedValue WRITE setCookedValue NOTIFY valueChanged) Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged) Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) @@ -75,6 +75,7 @@ public: /// @param convertOnly true: validate type conversion only, false: validate against meta data as well Q_INVOKABLE QString validate(const QString& value, bool convertOnly); + QVariant cookedValue (void) const; /// Value after translation int componentId (void) const; int decimalPlaces (void) const; QVariant defaultValue (void) const; @@ -97,24 +98,23 @@ public: QString shortDescription (void) const; FactMetaData::ValueType_t type (void) const; QString units (void) const; - QVariant value (void) const; QString valueString (void) const; bool valueEqualsDefault (void) const; void setRawValue (const QVariant& value); - void setValue (const QVariant& value); + void setCookedValue (const QVariant& value); void setEnumIndex (int index); void setEnumStringValue (const QString& value); // C++ methods /// Sets and sends new value to vehicle even if value is the same - void forceSetValue(const QVariant& value); + void forceSetRawValue(const QVariant& value); /// Sets the meta data associated with the Fact. void setMetaData(FactMetaData* metaData); - void _containerSetValue(const QVariant& value); + void _containerSetRawValue(const QVariant& value); /// Generally you should not change the name of a fact. But if you know what you are doing, you can. void _setName(const QString& name) { _name = name; } @@ -131,7 +131,7 @@ signals: /// Signalled when property has been changed by a call to the property write accessor /// /// This signal is meant for use by Fact container implementations. - void _containerValueChanged(const QVariant& value); + void _containerRawValueChanged(const QVariant& value); private: QString _variantToString(const QVariant& variant) const; diff --git a/src/FactSystem/FactSystemTestBase.cc b/src/FactSystem/FactSystemTestBase.cc index 67c759e35..885628b96 100644 --- a/src/FactSystem/FactSystemTestBase.cc +++ b/src/FactSystem/FactSystemTestBase.cc @@ -61,7 +61,7 @@ void FactSystemTestBase::_parameter_default_component_id_test(void) 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(); + QVariant factValue = fact->rawValue(); QCOMPARE(factValue.isValid(), true); QCOMPARE(factValue.toInt(), 3); @@ -72,7 +72,7 @@ void FactSystemTestBase::_parameter_specific_component_id_test(void) QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, 50, "RC_MAP_THROTTLE")); Fact* fact = _plugin->getFact(FactSystem::ParameterProvider, 50, "RC_MAP_THROTTLE"); QVERIFY(fact != NULL); - QVariant factValue = fact->value(); + QVariant factValue = fact->rawValue(); QCOMPARE(factValue.isValid(), true); @@ -82,7 +82,7 @@ void FactSystemTestBase::_parameter_specific_component_id_test(void) QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, 51, "COMPONENT_51")); fact = _plugin->getFact(FactSystem::ParameterProvider, 51, "COMPONENT_51"); QVERIFY(fact != NULL); - factValue = fact->value(); + factValue = fact->rawValue(); QCOMPARE(factValue.isValid(), true); QCOMPARE(factValue.toInt(), 51); @@ -119,7 +119,7 @@ void FactSystemTestBase::_qmlUpdate_test(void) // Change the value QVariant paramValue = 12; - _plugin->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_THROTTLE")->setValue(paramValue); + _plugin->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_THROTTLE")->setRawValue(paramValue); QTest::qWait(500); // Let the signals flow through diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 553c0efff..db2d15f79 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -245,14 +245,14 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param _mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact); // We need to know when the fact changes from QML so that we can send the new value to the parameter manager - connect(fact, &Fact::_containerValueChanged, this, &ParameterLoader::_valueUpdated); + connect(fact, &Fact::_containerRawValueChanged, this, &ParameterLoader::_valueUpdated); } Q_ASSERT(_mapParameterName2Variant[componentId].contains(parameterName)); Fact* fact = _mapParameterName2Variant[componentId][parameterName].value(); Q_ASSERT(fact); - fact->_containerSetValue(value); + fact->_containerSetRawValue(value); if (setMetaData) { _vehicle->firmwarePlugin()->addMetaDataToFact(fact); @@ -465,7 +465,7 @@ void ParameterLoader::_waitingParamTimeout(void) foreach(QString paramName, _waitingWriteParamNameMap[componentId].keys()) { paramsRequested = true; _waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count - _writeParameterRaw(componentId, paramName, _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->value()); + _writeParameterRaw(componentId, paramName, _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue()); qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")"; if (++batchCount > maxBatchSize) { @@ -586,7 +586,7 @@ void ParameterLoader::_writeLocalParamCache() foreach(int id, _mapParameterId2Name[component].keys()) { const QString name(_mapParameterId2Name[component][id]); const Fact *fact = _mapParameterName2Variant[component][name].value(); - cache_map[component][id] = NamedParam(name, ParamTypeVal(fact->type(), fact->value())); + cache_map[component][id] = NamedParam(name, ParamTypeVal(fact->type(), fact->rawValue())); } } @@ -700,7 +700,7 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream) } qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr; - fact->setValue(valStr); + fact->setRawValue(valStr); } } } diff --git a/src/MissionManager/MissionItem.cc b/src/MissionManager/MissionItem.cc index 228f1a2c9..436e0c1c8 100644 --- a/src/MissionManager/MissionItem.cc +++ b/src/MissionManager/MissionItem.cc @@ -193,9 +193,9 @@ MissionItem::MissionItem(int sequenceNumber, _param2Fact.setRawValue(param2); _param3Fact.setRawValue(param3); _param4Fact.setRawValue(param4); - _param5Fact.setValue(param5); - _param6Fact.setValue(param6); - _param7Fact.setValue(param7); + _param5Fact.setRawValue(param5); + _param6Fact.setRawValue(param6); + _param7Fact.setRawValue(param7); } MissionItem::MissionItem(const MissionItem& other, QObject* parent) @@ -226,13 +226,13 @@ const MissionItem& MissionItem::operator=(const MissionItem& other) _syncFrameToAltitudeRelativeToHome(); _syncCommandToSupportedCommand(QVariant(this->command())); - _param1Fact.setValue(other._param1Fact.value()); - _param2Fact.setValue(other._param2Fact.value()); - _param3Fact.setValue(other._param3Fact.value()); - _param4Fact.setValue(other._param4Fact.value()); - _param5Fact.setValue(other._param5Fact.value()); - _param6Fact.setValue(other._param6Fact.value()); - _param7Fact.setValue(other._param7Fact.value()); + _param1Fact.setRawValue(other._param1Fact.rawValue()); + _param2Fact.setRawValue(other._param2Fact.rawValue()); + _param3Fact.setRawValue(other._param3Fact.rawValue()); + _param4Fact.setRawValue(other._param4Fact.rawValue()); + _param5Fact.setRawValue(other._param5Fact.rawValue()); + _param6Fact.setRawValue(other._param6Fact.rawValue()); + _param7Fact.setRawValue(other._param7Fact.rawValue()); return *this; } @@ -525,7 +525,7 @@ void MissionItem::setSequenceNumber(int sequenceNumber) void MissionItem::setCommand(MAV_CMD command) { if ((MAV_CMD)this->command() != command) { - _commandFact.setValue(command); + _commandFact.setRawValue(command); setDefaultsForCommand(); emit commandChanged(this->command()); } @@ -540,7 +540,7 @@ void MissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) void MissionItem::setFrame(MAV_FRAME frame) { if (this->frame() != frame) { - _frameFact.setValue(frame); + _frameFact.setRawValue(frame); frameChanged(frame); } } @@ -548,7 +548,7 @@ void MissionItem::setFrame(MAV_FRAME frame) void MissionItem::setAutoContinue(bool autoContinue) { if (this->autoContinue() != autoContinue) { - _autoContinueFact.setValue(autoContinue); + _autoContinueFact.setRawValue(autoContinue); } } @@ -748,7 +748,7 @@ QmlObjectListModel* MissionItem::comboboxFacts(void) QGeoCoordinate MissionItem::coordinate(void) const { - return QGeoCoordinate(_param5Fact.value().toDouble(), _param6Fact.value().toDouble(), _param7Fact.value().toDouble()); + return QGeoCoordinate(_param5Fact.rawValue().toDouble(), _param6Fact.rawValue().toDouble(), _param7Fact.rawValue().toDouble()); } void MissionItem::setCoordinate(const QGeoCoordinate& coordinate) @@ -835,7 +835,7 @@ void MissionItem::_syncFrameToAltitudeRelativeToHome(void) { if (!_syncingAltitudeRelativeToHomeAndFrame) { _syncingAltitudeRelativeToHomeAndFrame = true; - _altitudeRelativeToHomeFact.setValue(relativeAltitude()); + _altitudeRelativeToHomeFact.setRawValue(relativeAltitude()); _syncingAltitudeRelativeToHomeAndFrame = false; } } @@ -844,7 +844,7 @@ void MissionItem::_syncSupportedCommandToCommand(const QVariant& value) { if (!_syncingSupportedCommandAndCommand) { _syncingSupportedCommandAndCommand = true; - _commandFact.setValue(value.toInt()); + _commandFact.setRawValue(value.toInt()); _syncingSupportedCommandAndCommand = false; } } @@ -853,7 +853,7 @@ void MissionItem::_syncCommandToSupportedCommand(const QVariant& value) { if (!_syncingSupportedCommandAndCommand) { _syncingSupportedCommandAndCommand = true; - _supportedCommandFact.setValue(value.toInt()); + _supportedCommandFact.setRawValue(value.toInt()); _syncingSupportedCommandAndCommand = false; } } diff --git a/src/MissionManager/MissionItem.h b/src/MissionManager/MissionItem.h index 37f6d0fa0..6459c49ef 100644 --- a/src/MissionManager/MissionItem.h +++ b/src/MissionManager/MissionItem.h @@ -95,7 +95,7 @@ public: // Property accesors - MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_commandFact.value().toInt(); }; + MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_commandFact.cookedValue().toInt(); }; QString commandDescription (void) const; QString commandName (void) const; QGeoCoordinate coordinate (void) const; @@ -135,8 +135,8 @@ public: // C++ only methods - MAV_FRAME frame (void) const { return (MAV_FRAME)_frameFact.value().toInt(); } - bool autoContinue(void) const { return _autoContinueFact.value().toBool(); } + MAV_FRAME frame (void) const { return (MAV_FRAME)_frameFact.rawValue().toInt(); } + bool autoContinue(void) const { return _autoContinueFact.rawValue().toBool(); } double param1 (void) const { return _param1Fact.rawValue().toDouble(); } double param2 (void) const { return _param2Fact.rawValue().toDouble(); } double param3 (void) const { return _param3Fact.rawValue().toDouble(); } diff --git a/src/qgcunittest/PX4RCCalibrationTest.cc b/src/qgcunittest/PX4RCCalibrationTest.cc index 04091421c..73dd2f671 100644 --- a/src/qgcunittest/PX4RCCalibrationTest.cc +++ b/src/qgcunittest/PX4RCCalibrationTest.cc @@ -389,7 +389,7 @@ void RadioConfigTest::_fullCalibration_test(void) switchList << "RC_MAP_MODE_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_ACRO_SW"; foreach (QString switchParam, switchList) { - Q_ASSERT(_autopilot->getParameterFact(FactSystem::defaultComponentId, switchParam)->value().toInt() != channel + 1); + Q_ASSERT(_autopilot->getParameterFact(FactSystem::defaultComponentId, switchParam)->rawValue().toInt() != channel + 1); } _rgFunctionChannelMap[function] = channel; @@ -401,7 +401,7 @@ void RadioConfigTest::_fullCalibration_test(void) // If we aren't mapping this function during calibration, set it to the previous setting if (!found) { - _rgFunctionChannelMap[function] = _autopilot->getParameterFact(FactSystem::defaultComponentId, RadioComponentController::_rgFunctionInfo[function].parameterName)->value().toInt(); + _rgFunctionChannelMap[function] = _autopilot->getParameterFact(FactSystem::defaultComponentId, RadioComponentController::_rgFunctionInfo[function].parameterName)->rawValue().toInt(); qCDebug(RadioConfigTestLog) << "Assigning switch" << function << _rgFunctionChannelMap[function]; if (_rgFunctionChannelMap[function] == 0) { _rgFunctionChannelMap[function] = -1; // -1 signals no mapping @@ -465,8 +465,8 @@ void RadioConfigTest::_validateParameters(void) expectedParameterValue = chanIndex + 1; // 1-based parameter value } - qCDebug(RadioConfigTestLog) << "Validate" << chanFunction << _autopilot->getParameterFact(FactSystem::defaultComponentId, RadioComponentController::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(); - QCOMPARE(_autopilot->getParameterFact(FactSystem::defaultComponentId, RadioComponentController::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(), expectedParameterValue); + qCDebug(RadioConfigTestLog) << "Validate" << chanFunction << _autopilot->getParameterFact(FactSystem::defaultComponentId, RadioComponentController::_rgFunctionInfo[chanFunction].parameterName)->rawValue().toInt(); + QCOMPARE(_autopilot->getParameterFact(FactSystem::defaultComponentId, RadioComponentController::_rgFunctionInfo[chanFunction].parameterName)->rawValue().toInt(), expectedParameterValue); } // Validate the channel settings. Note the channels are 1-based in parameter names. @@ -480,13 +480,13 @@ void RadioConfigTest::_validateParameters(void) int rcTrimExpected = _rgChannelSettingsValidate[chan].rcTrim; bool rcReversedExpected = _rgChannelSettingsValidate[chan].reversed; - int rcMinActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->value().toInt(&convertOk); + int rcMinActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); QCOMPARE(convertOk, true); - int rcMaxActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->value().toInt(&convertOk); + int rcMaxActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); QCOMPARE(convertOk, true); - int rcTrimActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->value().toInt(&convertOk); + int rcTrimActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); QCOMPARE(convertOk, true); - float rcReversedFloat = _autopilot->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->value().toFloat(&convertOk); + float rcReversedFloat = _autopilot->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->rawValue().toFloat(&convertOk); QCOMPARE(convertOk, true); bool rcReversedActual = (rcReversedFloat == -1.0f); @@ -508,6 +508,6 @@ void RadioConfigTest::_validateParameters(void) expectedValue = _rgFunctionChannelMap[chanFunction] + 1; // 1-based } // qCDebug(RadioConfigTestLog) << chanFunction << expectedValue << mapParamsSet[RadioComponentController::_rgFunctionInfo[chanFunction].parameterName].toInt(); - QCOMPARE(_autopilot->getParameterFact(FactSystem::defaultComponentId, RadioComponentController::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(), expectedValue); + QCOMPARE(_autopilot->getParameterFact(FactSystem::defaultComponentId, RadioComponentController::_rgFunctionInfo[chanFunction].parameterName)->rawValue().toInt(), expectedValue); } } -- 2.22.0