From 0f72ca05e935dc06c577e150df061b0af0021e3e Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sun, 25 May 2014 20:14:26 +0200 Subject: [PATCH] OP-1351 cleaned up instruction handling code (less hacky) --- .../calibration/gyrobiascalibrationmodel.cpp | 2 +- .../calibration/gyrobiascalibrationmodel.h | 2 +- .../calibration/levelcalibrationmodel.cpp | 9 ++++---- .../calibration/levelcalibrationmodel.h | 2 +- .../calibration/sixpointcalibrationmodel.cpp | 11 +++++---- .../calibration/sixpointcalibrationmodel.h | 2 +- .../plugins/config/calibration/wizardmodel.h | 2 +- .../src/plugins/config/configrevowidget.cpp | 23 +++++++++++-------- .../src/plugins/config/configrevowidget.h | 3 ++- 9 files changed, 30 insertions(+), 26 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp index b636de288..2f00fc711 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp @@ -71,7 +71,7 @@ void GyroBiasCalibrationModel::start() attitudeSettings->updated(); displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_NED); - displayInstructions(tr("Calibrating the gyroscopes. Keep the copter/plane steady..."), WizardModel::Notice, true); + displayInstructions(tr("Calibrating the gyroscopes. Keep the copter/plane steady..."), WizardModel::Notice); gyro_accum_x.clear(); gyro_accum_y.clear(); diff --git a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h index 5b1a61a79..88901137f 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h @@ -47,7 +47,7 @@ public: signals: void displayVisualHelp(QString elementID); - void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false); + void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info); void started(); void stopped(); void storeAndClearBoardRotation(); diff --git a/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.cpp index 866703c07..f18f7e869 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.cpp @@ -40,7 +40,6 @@ LevelCalibrationModel::LevelCalibrationModel(QObject *parent) : {} -/******* Level calibration *******/ /** * Starts an accelerometer bias calibration. */ @@ -64,7 +63,7 @@ void LevelCalibrationModel::start() attitudeState->setMetadata(mdata); /* Show instructions and enable controls */ - displayInstructions(tr("Place horizontally and click Save Position button..."), WizardModel::Info, true); + displayInstructions(tr("Place horizontally and click Save Position button..."), WizardModel::Info); displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_NED); savePositionEnabledChanged(true); position = 0; @@ -134,8 +133,6 @@ void LevelCalibrationModel::getSample(UAVObject *obj) displayInstructions(tr("Leave horizontally, rotate 180° along yaw axis and click Save Position button...")); displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_SWD); - started(); - savePositionEnabledChanged(true); break; case 2: @@ -145,13 +142,13 @@ void LevelCalibrationModel::getSample(UAVObject *obj) rot_data_roll /= 2; attitudeState->setMetadata(initialAttitudeStateMdata); compute(); - stopped(); displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY); displayInstructions(tr("Board leveling completed successfully.")); break; } } } + void LevelCalibrationModel::compute() { stopped(); @@ -168,6 +165,7 @@ void LevelCalibrationModel::compute() attitudeSettings->setData(attitudeSettingsData); attitudeSettings->updated(); } + UAVObjectManager *LevelCalibrationModel::getObjectManager() { ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); @@ -176,4 +174,5 @@ UAVObjectManager *LevelCalibrationModel::getObjectManager() Q_ASSERT(objMngr); return objMngr; } + } diff --git a/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.h index 87c8c0c1b..802fee86f 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.h @@ -50,7 +50,7 @@ public: signals: void displayVisualHelp(QString elementID); - void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false); + void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info); void started(); void stopped(); void savePositionEnabledChanged(bool state); diff --git a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp index 96459eddc..239b1e4b0 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp @@ -198,11 +198,11 @@ void SixPointCalibrationModel::start(bool calibrateAccel, bool calibrateMag) mag->setMetadata(mdata); } - /* Show instructions and enable controls */ - displayInstructions((*currentSteps)[0].instructions, WizardModel::Info, true); - showHelp((*currentSteps)[0].visualHelp); - started(); + + // Show instructions and enable controls + displayInstructions((*currentSteps)[0].instructions, WizardModel::Info); + showHelp((*currentSteps)[0].visualHelp); savePositionEnabledChanged(true); position = 0; mag_fit_x.clear(); @@ -492,7 +492,8 @@ void SixPointCalibrationModel::compute(bool mag, bool accel) } else { displayInstructions(tr("Bad calibration. Please review the instructions and repeat."), WizardModel::Error); } - position = -1; // set to run again + // set to run again + position = -1; } UAVObjectManager *SixPointCalibrationModel::getObjectManager() { diff --git a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h index d9cbd3532..79ab8a444 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h @@ -66,7 +66,7 @@ public: signals: void displayVisualHelp(QString elementID); - void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false); + void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info); void started(); void stopped(); void storeAndClearBoardRotation(); diff --git a/ground/openpilotgcs/src/plugins/config/calibration/wizardmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/wizardmodel.h index 4fbc47a91..6cc431318 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/wizardmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/wizardmodel.h @@ -66,7 +66,7 @@ private: QString m_instructions; signals: - void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false); + void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info); void currentStateChanged(WizardState *status); }; diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 2e7fa84f6..3593ced97 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -125,8 +125,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_sixPointCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations())); connect(m_sixPointCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation())); connect(m_sixPointCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation())); - connect(m_sixPointCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType, bool)), - this, SLOT(displayInstructions(QString, WizardModel::MessageType, bool))); + connect(m_sixPointCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)), + this, SLOT(displayInstructions(QString, WizardModel::MessageType))); connect(m_sixPointCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString))); connect(m_sixPointCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->sixPointsSave, SLOT(setEnabled(bool))); @@ -137,8 +137,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_levelCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations())); connect(m_levelCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations())); - connect(m_levelCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType, bool)), - this, SLOT(displayInstructions(QString, WizardModel::MessageType, bool))); + connect(m_levelCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)), + this, SLOT(displayInstructions(QString, WizardModel::MessageType))); connect(m_levelCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString))); connect(m_levelCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->boardLevelSavePos, SLOT(setEnabled(bool))); connect(m_levelCalibrationModel, SIGNAL(progressChanged(int)), this->m_ui->boardLevelProgress, SLOT(setValue(int))); @@ -153,8 +153,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_gyroBiasCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations())); connect(m_gyroBiasCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation())); connect(m_gyroBiasCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation())); - connect(m_gyroBiasCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType, bool)), - this, SLOT(displayInstructions(QString, WizardModel::MessageType, bool))); + connect(m_gyroBiasCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)), + this, SLOT(displayInstructions(QString, WizardModel::MessageType))); connect(m_gyroBiasCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString))); connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation())); @@ -242,11 +242,13 @@ void ConfigRevoWidget::displayVisualHelp(QString elementID) updateVisualHelp(); } -void ConfigRevoWidget::displayInstructions(QString text, WizardModel::MessageType type, bool clear) +void ConfigRevoWidget::clearInstructions() +{ + m_ui->calibrationInstructions->clear(); +} + +void ConfigRevoWidget::displayInstructions(QString text, WizardModel::MessageType type) { - if (clear || text.isNull()) { - m_ui->calibrationInstructions->clear(); - } if (!text.isNull()) { switch(type) { case WizardModel::Error: @@ -314,6 +316,7 @@ void ConfigRevoWidget::clearHomeLocation() void ConfigRevoWidget::disableAllCalibrations() { + clearInstructions(); m_ui->sixPointsStartAccel->setEnabled(false); m_ui->sixPointsStartMag->setEnabled(false); m_ui->boardLevelStart->setEnabled(false); diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index 545310e13..6d93539d8 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -68,7 +68,8 @@ private slots: void storeAndClearBoardRotation(); void recallBoardRotation(); void displayVisualHelp(QString elementID); - void displayInstructions(QString instructions, WizardModel::MessageType type = WizardModel::Info, bool clear = false); + void clearInstructions(); + void displayInstructions(QString instructions, WizardModel::MessageType type = WizardModel::Info); void displayTemperature(float temp); void displayTemperatureGradient(float tempGradient);