Commit 1abafb59 authored by Don Gagne's avatar Don Gagne

Merge pull request #1918 from DonLakeFlyer/ParametersReady

Allow param edit with missing parameters
parents 3e850d32 bac74f16
......@@ -30,17 +30,18 @@
#include "MainWindow.h"
#include "ParameterLoader.h"
AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
QObject(parent),
_vehicle(vehicle),
_pluginReady(false),
_setupComplete(false)
AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent)
: QObject(parent)
, _vehicle(vehicle)
, _parametersReady(false)
, _missingParameters(false)
, _setupComplete(false)
{
Q_ASSERT(vehicle);
connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected);
connect(this, &AutoPilotPlugin::pluginReadyChanged, this, &AutoPilotPlugin::_pluginReadyChanged);
connect(this, &AutoPilotPlugin::parametersReadyChanged, this, &AutoPilotPlugin::_parametersReadyChanged);
}
AutoPilotPlugin::~AutoPilotPlugin()
......@@ -50,13 +51,13 @@ AutoPilotPlugin::~AutoPilotPlugin()
void AutoPilotPlugin::_uasDisconnected(void)
{
_pluginReady = false;
emit pluginReadyChanged(_pluginReady);
_parametersReady = false;
emit parametersReadyChanged(_parametersReady);
}
void AutoPilotPlugin::_pluginReadyChanged(bool pluginReady)
void AutoPilotPlugin::_parametersReadyChanged(bool parametersReady)
{
if (pluginReady) {
if (parametersReady) {
_recalcSetupComplete();
if (!_setupComplete) {
QGCMessageBox::warning("Setup", "One or more vehicle components require setup prior to flight.");
......@@ -92,7 +93,7 @@ void AutoPilotPlugin::_recalcSetupComplete(void)
bool AutoPilotPlugin::setupComplete(void)
{
Q_ASSERT(_pluginReady);
Q_ASSERT(_parametersReady);
return _setupComplete;
}
......
......@@ -54,8 +54,11 @@ public:
AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~AutoPilotPlugin();
/// true: plugin is ready for use, plugin should no longer be used
Q_PROPERTY(bool pluginReady READ pluginReady NOTIFY pluginReadyChanged)
/// true: parameters are ready for use
Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged)
/// true: parameters are missing from firmware response, false: all parameters received from firmware
Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged)
/// List of VehicleComponent objects
Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT)
......@@ -113,13 +116,15 @@ public:
static void clearStaticData(void);
// Property accessors
bool pluginReady(void) { return _pluginReady; }
bool parametersReady(void) { return _parametersReady; }
bool missingParameters(void) { return _missingParameters; }
bool setupComplete(void);
Vehicle* vehicle(void) { return _vehicle; }
signals:
void pluginReadyChanged(bool pluginReady);
void parametersReadyChanged(bool parametersReady);
void missingParametersChanged(bool missingParameters);
void setupCompleteChanged(bool setupComplete);
void parameterListProgress(float value);
......@@ -131,12 +136,13 @@ protected:
virtual ParameterLoader* _getParameterLoader(void) = 0;
Vehicle* _vehicle;
bool _pluginReady;
bool _parametersReady;
bool _missingParameters;
bool _setupComplete;
private slots:
void _uasDisconnected(void);
void _pluginReadyChanged(bool pluginReady);
void _parametersReadyChanged(bool parametersReady);
private:
void _recalcSetupComplete(void);
......
......@@ -34,7 +34,7 @@ GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent
_parameterFacts = new GenericParameterFacts(this, vehicle, this);
Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &GenericParameterFacts::parametersReady, this, &GenericAutoPilotPlugin::_parametersReady);
connect(_parameterFacts, &GenericParameterFacts::parametersReady, this, &GenericAutoPilotPlugin::_parametersReadySlot);
connect(_parameterFacts, &GenericParameterFacts::parameterListProgress, this, &GenericAutoPilotPlugin::parameterListProgress);
}
......@@ -50,8 +50,10 @@ const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void)
return emptyList;
}
void GenericAutoPilotPlugin::_parametersReady(void)
void GenericAutoPilotPlugin::_parametersReadySlot(bool missingParameters)
{
_pluginReady = true;
emit pluginReadyChanged(_pluginReady);
_parametersReady = true;
_missingParameters = missingParameters;
emit missingParametersChanged(_missingParameters);
emit parametersReadyChanged(_parametersReady);
}
......@@ -45,7 +45,7 @@ public:
static void clearStaticData(void);
private slots:
void _parametersReady(void);
void _parametersReadySlot(bool missingParameters);
private:
// Overrides from AutoPilotPlugin
......
......@@ -79,7 +79,7 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
_parameterFacts = new PX4ParameterLoader(this, vehicle, this);
Q_CHECK_PTR(_parameterFacts);
connect(_parameterFacts, &PX4ParameterLoader::parametersReady, this, &PX4AutoPilotPlugin::_pluginReadyPreChecks);
connect(_parameterFacts, &PX4ParameterLoader::parametersReady, this, &PX4AutoPilotPlugin::_parametersReadyPreChecks);
connect(_parameterFacts, &PX4ParameterLoader::parameterListProgress, this, &PX4AutoPilotPlugin::parameterListProgress);
_airframeFacts = new PX4AirframeLoader(this, _vehicle->uas(), this);
......@@ -106,7 +106,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
if (_components.count() == 0 && !_incorrectParameterVersion) {
Q_ASSERT(_vehicle);
if (pluginReady()) {
if (parametersReady()) {
_airframeComponent = new AirframeComponent(_vehicle->uas(), this);
Q_CHECK_PTR(_airframeComponent);
_airframeComponent->setupTriggerSignals();
......@@ -137,7 +137,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
_safetyComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent));
} else {
qWarning() << "Call to vehicleCompenents prior to pluginReady";
qWarning() << "Call to vehicleCompenents prior to parametersReady";
}
}
......@@ -145,7 +145,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
}
/// This will perform various checks prior to signalling that the plug in ready
void PX4AutoPilotPlugin::_pluginReadyPreChecks(void)
void PX4AutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters)
{
// Check for older parameter version set
// FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp
......@@ -156,6 +156,8 @@ void PX4AutoPilotPlugin::_pluginReadyPreChecks(void)
"Please perform a Firmware Upgrade if you wish to use Vehicle Setup.");
}
_pluginReady = true;
emit pluginReadyChanged(_pluginReady);
_parametersReady = true;
_missingParameters = missingParameters;
emit missingParametersChanged(_missingParameters);
emit parametersReadyChanged(_parametersReady);
}
......@@ -63,7 +63,7 @@ public:
PowerComponent* powerComponent(void) { return _powerComponent; }
private slots:
void _pluginReadyPreChecks(void);
void _parametersReadyPreChecks(bool missingParameters);
private:
// Overrides from AutoPilotPlugin
......
......@@ -43,7 +43,8 @@ FactPanelController::FactPanelController(void) :
_autopilot = _vehicle->autopilotPlugin();
Q_ASSERT(_autopilot);
Q_ASSERT(_autopilot->pluginReady());
Q_ASSERT(_autopilot->parametersReady());
Q_ASSERT(!_autopilot->missingParameters());
// Do a delayed check for the _factPanel finally being set correctly from Qml
QTimer::singleShot(1000, this, &FactPanelController::_checkForMissingFactPanel);
......
......@@ -771,12 +771,12 @@ void ParameterLoader::_checkInitialLoadComplete(void)
"If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
"If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.");
qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
emit parametersReady(true);
} else {
// No failed parameters, ok to signal ready
_parametersReady = true;
_determineDefaultComponentId();
_setupGroupMap();
emit parametersReady();
emit parametersReady(false);
}
}
......@@ -91,7 +91,7 @@ public:
signals:
/// Signalled when the full set of facts are ready
void parametersReady(void);
void parametersReady(bool missingParameters);
/// Signalled to update progress of full parameter list request
void parameterListProgress(float value);
......
......@@ -132,7 +132,7 @@ bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
_ackTimeoutTimer->stop();
if (_retryAck != expectedAck) {
qCDebug(MissionManagerLog) << "Invalid ack sequence _retryAck:expectedAck" << _retryAck << expectedAck;
qCWarning(MissionManagerLog) << "Invalid ack sequence _retryAck:expectedAck" << _retryAck << expectedAck;
success = false;
} else {
success = true;
......
......@@ -72,7 +72,7 @@ bool MultiVehicleManager::notifyHeartbeatInfo(LinkInterface* link, int vehicleId
}
connect(vehicle, &Vehicle::allLinksDisconnected, this, &MultiVehicleManager::_deleteVehiclePhase1);
connect(vehicle->autopilotPlugin(), &AutoPilotPlugin::pluginReadyChanged, this, &MultiVehicleManager::_autopilotPluginReadyChanged);
connect(vehicle->autopilotPlugin(), &AutoPilotPlugin::parametersReadyChanged, this, &MultiVehicleManager::_autopilotParametersReadyChanged);
_vehicles.append(vehicle);
......@@ -138,7 +138,7 @@ void MultiVehicleManager::_deleteVehiclePhase2 (void)
if (_activeVehicle) {
_activeVehicle->setActive(true);
emit activeVehicleAvailableChanged(true);
if (_activeVehicle->autopilotPlugin()->pluginReady()) {
if (_activeVehicle->autopilotPlugin()->parametersReady()) {
emit parameterReadyVehicleAvailableChanged(true);
}
}
......@@ -181,14 +181,14 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void)
_activeVehicleAvailable = true;
emit activeVehicleAvailableChanged(true);
if (_activeVehicle->autopilotPlugin()->pluginReady()) {
if (_activeVehicle->autopilotPlugin()->parametersReady()) {
_parameterReadyVehicleAvailable = true;
emit parameterReadyVehicleAvailableChanged(true);
}
}
}
void MultiVehicleManager::_autopilotPluginReadyChanged(bool pluginReady)
void MultiVehicleManager::_autopilotParametersReadyChanged(bool parametersReady)
{
AutoPilotPlugin* autopilot = dynamic_cast<AutoPilotPlugin*>(sender());
......@@ -198,8 +198,8 @@ void MultiVehicleManager::_autopilotPluginReadyChanged(bool pluginReady)
}
if (autopilot->vehicle() == _activeVehicle) {
_parameterReadyVehicleAvailable = pluginReady;
emit parameterReadyVehicleAvailableChanged(pluginReady);
_parameterReadyVehicleAvailable = parametersReady;
emit parameterReadyVehicleAvailableChanged(parametersReady);
}
}
......
......@@ -92,7 +92,7 @@ private slots:
void _deleteVehiclePhase1(Vehicle* vehicle);
void _deleteVehiclePhase2(void);
void _setActiveVehiclePhase2(void);
void _autopilotPluginReadyChanged(bool pluginReady);
void _autopilotParametersReadyChanged(bool parametersReady);
private:
/// All access to singleton is through MultiVehicleManager::instance
......
......@@ -107,6 +107,8 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
_firmwarePlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(firmwareType);
_autopilotPlugin = AutoPilotPluginManager::instance()->newAutopilotPluginForVehicle(this);
connect(_autopilotPlugin, &AutoPilotPlugin::missingParametersChanged, this, &Vehicle::missingParametersChanged);
// Refresh timer
connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate()));
_refreshTimer->setInterval(UPDATE_TIMER);
......@@ -1058,3 +1060,8 @@ void Vehicle::setHilMode(bool hilMode)
mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, _custom_mode);
sendMessage(msg);
}
bool Vehicle::missingParameters(void)
{
return _autopilotPlugin->missingParameters();
}
......@@ -71,6 +71,8 @@ public:
Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged)
Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged)
Q_INVOKABLE QString getMavIconColor();
//-- System Messages
......@@ -178,6 +180,8 @@ public:
bool hilMode(void);
void setHilMode(bool hilMode);
bool missingParameters(void);
typedef enum {
MessageNone,
MessageNormal,
......@@ -248,6 +252,7 @@ signals:
void armedChanged(bool armed);
void flightModeChanged(const QString& flightMode);
void hilModeChanged(bool hilMode);
void missingParametersChanged(bool missingParameters);
/// Used internally to move sendMessage call to main thread
void _sendMessageOnThread(mavlink_message_t message);
......
......@@ -51,10 +51,14 @@ Rectangle {
property string messagePanelText: "missing message panel text"
readonly property string armedVehicleText: "This operation cannot be performed while vehicle is armed."
property bool fullParameterVehicleAvailable: multiVehicleManager.parameterReadyVehicleAvailable && !multiVehicleManager.activeVehicle.missingParameters
function showSummaryPanel()
{
if (multiVehicleManager.parameterReadyVehicleAvailable) {
if (fullParameterVehicleAvailable) {
panelLoader.source = "VehicleSummary.qml";
} else if (multiVehicleManager.parameterReadyVehicleAvailable) {
panelLoader.sourceComponent = missingParametersVehicleSummaryComponent
} else {
panelLoader.sourceComponent = disconnectedVehicleSummaryComponent
}
......@@ -137,6 +141,27 @@ Rectangle {
}
}
Component {
id: missingParametersVehicleSummaryComponent
Rectangle {
color: palette.windowShade
QGCLabel {
anchors.margins: defaultTextWidth * 2
anchors.fill: parent
verticalAlignment: Text.AlignVCenter
horizontalAlignment: Text.AlignHCenter
wrapMode: Text.WordWrap
font.pixelSize: ScreenTools.mediumFontPixelSize
text: "You are currently connected to a vehicle, but that vehicle did not return back the full parameter list. " +
"Because of this the full set of vehicle setup options are not available."
onLinkActivated: Qt.openUrlExternally(link)
}
}
}
Component {
id: messagePanelComponent
......@@ -194,14 +219,14 @@ Rectangle {
setupIndicator: true
setupComplete: joystickManager.activeJoystick ? joystickManager.activeJoystick.calibrated : false
exclusiveGroup: setupButtonGroup
visible: multiVehicleManager.parameterReadyVehicleAvailable && joystickManager.joysticks.length != 0
visible: fullParameterVehicleAvailable && joystickManager.joysticks.length != 0
text: "JOYSTICK"
onClicked: showJoystickPanel()
}
Repeater {
model: multiVehicleManager.parameterReadyVehicleAvailable ? multiVehicleManager.activeVehicle.autopilot.vehicleComponents : 0
model: fullParameterVehicleAvailable ? multiVehicleManager.activeVehicle.autopilot.vehicleComponents : 0
SubMenuButton {
width: buttonWidth
......
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