From 4feaa72998a67c5a376b1015b43c56ab8010df23 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Thu, 15 May 2014 22:10:16 +0200 Subject: [PATCH] OP-1351 thermal calibration step now uses instruction panel like all other steps (WIP). Display of temp and temp variation currently broken. --- .../calibration/gyrobiascalibrationmodel.cpp | 7 +- .../calibration/gyrobiascalibrationmodel.h | 13 +- .../calibration/levelcalibrationmodel.cpp | 10 +- .../calibration/levelcalibrationmodel.h | 18 ++- .../calibration/sixpointcalibrationmodel.cpp | 20 ++- .../calibration/sixpointcalibrationmodel.h | 15 +- .../thermal/thermalcalibrationmodel.cpp | 9 +- .../thermal/thermalcalibrationmodel.h | 9 +- .../plugins/config/calibration/wizardmodel.h | 19 ++- .../src/plugins/config/configrevowidget.cpp | 38 +++-- .../src/plugins/config/configrevowidget.h | 3 +- .../src/plugins/config/revosensors.ui | 145 +++++------------- 12 files changed, 146 insertions(+), 160 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp index 1d35f0eef..bd8d46628 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.cpp @@ -37,8 +37,9 @@ #include "calibration/calibrationuiutils.h" static const int LEVEL_SAMPLES = 100; -#include "gyrobiascalibrationmodel.h" + namespace OpenPilot { + GyroBiasCalibrationModel::GyroBiasCalibrationModel(QObject *parent) : QObject(parent), collectingData(false) @@ -70,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..."), true); + displayInstructions(tr("Calibrating the gyroscopes. Keep the copter/plane steady..."), WizardModel::Notice, true); gyro_accum_x.clear(); gyro_accum_y.clear(); @@ -196,7 +197,7 @@ void GyroBiasCalibrationModel::getSample(UAVObject *obj) gyroState->setMetadata(initialGyroStateMdata); gyroSensor->setMetadata(initialGyroSensorMdata); - displayInstructions(tr("Gyroscope calibration computed succesfully."), false); + displayInstructions(tr("Gyroscope calibration completed succesfully.")); displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY); // Recall saved board rotation diff --git a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h index 14fa6c0eb..95d1cbcc2 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/gyrobiascalibrationmodel.h @@ -29,27 +29,35 @@ #ifndef GYROBIASCALIBRATIONMODEL_H #define GYROBIASCALIBRATIONMODEL_H -#include +#include "wizardmodel.h" #include "extensionsystem/pluginmanager.h" #include "uavobjectmanager.h" #include "uavobject.h" + +#include + namespace OpenPilot { + class GyroBiasCalibrationModel : public QObject { Q_OBJECT + public: explicit GyroBiasCalibrationModel(QObject *parent = 0); + signals: void displayVisualHelp(QString elementID); - void displayInstructions(QString instructions, bool replace); + void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false); void disableAllCalibrations(); void enableAllCalibrations(); void storeAndClearBoardRotation(); void recallBoardRotation(); void progressChanged(int value); + public slots: // Slots for gyro bias zero void start(); + private slots: void getSample(UAVObject *obj); @@ -69,4 +77,5 @@ private: UAVObjectManager *getObjectManager(); }; } + #endif // GYROBIASCALIBRATIONMODEL_H diff --git a/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.cpp index fd46259de..2bc2632f8 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.cpp @@ -32,7 +32,9 @@ #include "calibration/calibrationuiutils.h" static const int LEVEL_SAMPLES = 100; + namespace OpenPilot { + LevelCalibrationModel::LevelCalibrationModel(QObject *parent) : QObject(parent) {} @@ -62,7 +64,7 @@ void LevelCalibrationModel::start() attitudeState->setMetadata(mdata); /* Show instructions and enable controls */ - displayInstructions(tr("Place horizontally and click Save Position button..."), true); + displayInstructions(tr("Place horizontally and click Save Position button..."), WizardModel::Info, true); displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_NED); disableAllCalibrations(); savePositionEnabledChanged(true); @@ -86,7 +88,7 @@ void LevelCalibrationModel::savePosition() Q_ASSERT(attitudeState); connect(attitudeState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(getSample(UAVObject *))); - displayInstructions(tr("Hold..."), false); + displayInstructions(tr("Hold...")); } /** @@ -130,7 +132,7 @@ void LevelCalibrationModel::getSample(UAVObject *obj) rot_data_pitch = OpenPilot::CalibrationUtils::listMean(rot_accum_pitch); rot_data_roll = OpenPilot::CalibrationUtils::listMean(rot_accum_roll); - displayInstructions(tr("Leave horizontally, rotate 180° along yaw axis and click Save Position button..."), false); + displayInstructions(tr("Leave horizontally, rotate 180° along yaw axis and click Save Position button...")); displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_SWD); disableAllCalibrations(); @@ -146,7 +148,7 @@ void LevelCalibrationModel::getSample(UAVObject *obj) compute(); enableAllCalibrations(); displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY); - displayInstructions(tr("Board leveling computed successfully."), false); + displayInstructions(tr("Board leveling completed successfully.")); break; } } diff --git a/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.h index 07ce6ccc0..13c8535f6 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/levelcalibrationmodel.h @@ -28,36 +28,43 @@ #ifndef LEVELCALIBRATIONMODEL_H #define LEVELCALIBRATIONMODEL_H -#include -#include -#include +#include "wizardmodel.h" #include "calibration/calibrationutils.h" - #include #include #include #include #include + +#include +#include +#include + namespace OpenPilot { + class LevelCalibrationModel : public QObject { Q_OBJECT + public: explicit LevelCalibrationModel(QObject *parent = 0); signals: void displayVisualHelp(QString elementID); - void displayInstructions(QString instructions, bool replace); + void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false); void disableAllCalibrations(); void enableAllCalibrations(); void savePositionEnabledChanged(bool state); void progressChanged(int value); + public slots: // Slots for calibrating the mags void start(); void savePosition(); + private slots: void getSample(UAVObject *obj); void compute(); + private: QMutex sensorsUpdateLock; int position; @@ -71,4 +78,5 @@ private: UAVObjectManager *getObjectManager(); }; } + #endif // LEVELCALIBRATIONMODEL_H diff --git a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp index bc866b00d..0510f25af 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp @@ -26,18 +26,22 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "sixpointcalibrationmodel.h" -#include #include "extensionsystem/pluginmanager.h" -#include -#include "math.h" #include "calibration/calibrationuiutils.h" + +#include "math.h" +#include +#include #include "QDebug" + #define POINT_SAMPLE_SIZE 50 #define GRAVITY 9.81f #define sign(x) ((x < 0) ? -1 : 1) #define FITTING_USING_CONTINOUS_ACQUISITION + namespace OpenPilot { + SixPointCalibrationModel::SixPointCalibrationModel(QObject *parent) : QObject(parent), calibrationStepsMag(), @@ -195,7 +199,7 @@ void SixPointCalibrationModel::start(bool calibrateAccel, bool calibrateMag) } /* Show instructions and enable controls */ - displayInstructions((*currentSteps)[0].instructions, true); + displayInstructions((*currentSteps)[0].instructions, WizardModel::Info, true); showHelp((*currentSteps)[0].visualHelp); disableAllCalibrations(); @@ -244,7 +248,7 @@ void SixPointCalibrationModel::savePositionData() connect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(getSample(UAVObject *))); } - displayInstructions(tr("Hold..."), false); + displayInstructions(tr("Hold...")); } /** @@ -310,7 +314,7 @@ void SixPointCalibrationModel::getSample(UAVObject *obj) position = (position + 1) % 6; if (position != 0) { - displayInstructions((*currentSteps)[position].instructions, false); + displayInstructions((*currentSteps)[position].instructions); showHelp((*currentSteps)[position].visualHelp); } else { #ifdef FITTING_USING_CONTINOUS_ACQUISITION @@ -484,9 +488,9 @@ void SixPointCalibrationModel::compute(bool mag, bool accel) } else { accelGyroSettings->setData(savedSettings.accelGyroSettings); } - displayInstructions(tr("Sensor scale and bias computed succesfully."), true); + displayInstructions(tr("Sensor scale and bias computed succesfully.")); } else { - displayInstructions(tr("Bad calibration. Please review the instructions and repeat."), true); + displayInstructions(tr("Bad calibration. Please review the instructions and repeat."), WizardModel::Error); } position = -1; // set to run again } diff --git a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h index 128ff884a..a4a33428c 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h @@ -27,17 +27,22 @@ */ #ifndef SIXPOINTCALIBRATIONMODEL_H #define SIXPOINTCALIBRATIONMODEL_H -#include -#include -#include + +#include "wizardmodel.h" #include "calibration/calibrationutils.h" -#include #include #include #include #include #include + +#include +#include +#include +#include + namespace OpenPilot { + class SixPointCalibrationModel : public QObject { Q_OBJECT @@ -61,7 +66,7 @@ public: signals: void displayVisualHelp(QString elementID); - void displayInstructions(QString instructions, bool replace); + void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false); void disableAllCalibrations(); void enableAllCalibrations(); void storeAndClearBoardRotation(); diff --git a/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationmodel.cpp index 02921236e..2545f96a7 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationmodel.cpp @@ -33,6 +33,7 @@ #include "compensationcalculationtransition.h" namespace OpenPilot { + ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) : WizardModel(parent), m_startEnabled(false), @@ -41,7 +42,7 @@ ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) : m_initDone(false) { m_helper.reset(new ThermalCalibrationHelper()); - m_readyState = new WizardState(tr("Start"), this), + m_readyState = new WizardState("", this), m_workingState = new WizardState(NULL, this); m_saveSettingState = new WizardState(tr("Saving initial settings"), m_workingState); @@ -66,10 +67,12 @@ ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) : connect(m_readyState, SIGNAL(exited()), this, SLOT(wizardStarted())); connect(m_completedState, SIGNAL(entered()), this, SLOT(wizardReady())); connect(m_completedState, SIGNAL(exited()), this, SLOT(wizardStarted())); - this->setInitialState(m_readyState); + + setInitialState(m_readyState); m_steps << m_readyState << m_saveSettingState << m_setupState << m_acquisitionState << m_restoreState << m_calculateState; } + void ThermalCalibrationModel::init() { if (!m_initDone) { @@ -80,7 +83,6 @@ void ThermalCalibrationModel::init() start(); setTemperature(0); setTemperatureGradient(0); - emit instructionsChanged(instructions()); } } @@ -115,4 +117,5 @@ void ThermalCalibrationModel::setTransitions() m_workingState->addTransition(this, SIGNAL(abort()), m_abortState); // Ready } + } diff --git a/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationmodel.h index 310c5024a..7335baaf6 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/thermal/thermalcalibrationmodel.h @@ -37,7 +37,9 @@ #include #include "../wizardstate.h" #include "../wizardmodel.h" + namespace OpenPilot { + class ThermalCalibrationModel : public WizardModel { Q_PROPERTY(bool startEnable READ startEnabled NOTIFY startEnabledChanged) Q_PROPERTY(bool endEnable READ endEnabled NOTIFY endEnabledChanged) @@ -47,6 +49,7 @@ class ThermalCalibrationModel : public WizardModel { Q_PROPERTY(QString temperatureGradient READ temperatureGradient NOTIFY temperatureGradientChanged) Q_PROPERTY(int progress READ progress WRITE setProgress NOTIFY progressChanged) Q_OBJECT + public: explicit ThermalCalibrationModel(QObject *parent = 0); @@ -181,19 +184,19 @@ signals: void next(); void previous(); void abort(); -public slots: + + public slots: void stepChanged(WizardState *state); void init(); void btnStart() { + setInstructions(""); emit next(); } - void btnEnd() { m_helper->stopAcquisition(); } - void btnAbort() { emit abort(); diff --git a/ground/openpilotgcs/src/plugins/config/calibration/wizardmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/wizardmodel.h index d07fc6885..4fbc47a91 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/wizardmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/wizardmodel.h @@ -35,9 +35,11 @@ class WizardModel : public QStateMachine { Q_OBJECT Q_PROPERTY(QQmlListProperty steps READ steps CONSTANT) - Q_PROPERTY(QString instructions READ instructions NOTIFY instructionsChanged) + //Q_PROPERTY(QString instructions READ instructions NOTIFY instructionsChanged) Q_PROPERTY(WizardState * currentState READ currentState NOTIFY currentStateChanged) public: + enum MessageType { Info, Notice, Warning, Error }; + explicit WizardModel(QObject *parent = 0); QQmlListProperty steps() @@ -45,25 +47,28 @@ public: return QQmlListProperty(this, m_steps); } - QString instructions() + QString &instructions() { return m_instructions; } - void setInstructions(QString instructions) + void setInstructions(QString text, MessageType type = WizardModel::Info) { - m_instructions = instructions; - emit instructionsChanged(instructions); + m_instructions = text; + emit displayInstructions(text, type); } WizardState *currentState(); + protected: QList m_steps; + private: QString m_instructions; + signals: - void instructionsChanged(QString status); + void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false); void currentStateChanged(WizardState *status); -public slots: + }; #endif // WIZARDMODEL_H diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp index 092f7cb56..8eb61ff86 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.cpp @@ -94,6 +94,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : // connect the thermalCalibration model to UI m_thermalCalibrationModel = new OpenPilot::ThermalCalibrationModel(this); + m_thermalCalibrationModel->init(); connect(m_ui->ThermalBiasStart, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnStart())); connect(m_ui->ThermalBiasEnd, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnEnd())); @@ -103,9 +104,10 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_thermalCalibrationModel, SIGNAL(endEnabledChanged(bool)), m_ui->ThermalBiasEnd, SLOT(setEnabled(bool))); connect(m_thermalCalibrationModel, SIGNAL(cancelEnabledChanged(bool)), m_ui->ThermalBiasCancel, SLOT(setEnabled(bool))); - connect(m_thermalCalibrationModel, SIGNAL(instructionsChanged(QString)), m_ui->label_thermalDescription, SLOT(setText(QString))); - connect(m_thermalCalibrationModel, SIGNAL(temperatureChanged(QString)), m_ui->textTemperature, SLOT(setText(QString))); - connect(m_thermalCalibrationModel, SIGNAL(temperatureGradientChanged(QString)), m_ui->textThermalGradient, SLOT(setText(QString))); + connect(m_thermalCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)), + this, SLOT(displayInstructions(QString, WizardModel::MessageType))); +// connect(m_thermalCalibrationModel, SIGNAL(temperatureChanged(QString)), m_ui->textTemperature, SLOT(setText(QString))); +// connect(m_thermalCalibrationModel, SIGNAL(temperatureGradientChanged(QString)), m_ui->textThermalGradient, SLOT(setText(QString))); connect(m_thermalCalibrationModel, SIGNAL(progressChanged(int)), m_ui->thermalBiasProgress, SLOT(setValue(int))); // note: init for m_thermalCalibrationModel is done in showEvent to prevent cases wiht "Start" button not enabled due to some itming issue. @@ -119,7 +121,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_sixPointCalibrationModel, SIGNAL(enableAllCalibrations()), 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, bool)), this, SLOT(displayInstructions(QString, bool))); + connect(m_sixPointCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType, bool)), + this, SLOT(displayInstructions(QString, WizardModel::MessageType, bool))); connect(m_sixPointCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString))); connect(m_sixPointCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->sixPointsSave, SLOT(setEnabled(bool))); @@ -130,7 +133,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_levelCalibrationModel, SIGNAL(disableAllCalibrations()), this, SLOT(disableAllCalibrations())); connect(m_levelCalibrationModel, SIGNAL(enableAllCalibrations()), this, SLOT(enableAllCalibrations())); - connect(m_levelCalibrationModel, SIGNAL(displayInstructions(QString, bool)), this, SLOT(displayInstructions(QString, bool))); + connect(m_levelCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType, bool)), + this, SLOT(displayInstructions(QString, WizardModel::MessageType, bool))); 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))); @@ -146,7 +150,8 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) : connect(m_gyroBiasCalibrationModel, SIGNAL(enableAllCalibrations()), 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, bool)), this, SLOT(displayInstructions(QString, bool))); + connect(m_gyroBiasCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType, bool)), + this, SLOT(displayInstructions(QString, WizardModel::MessageType, bool))); connect(m_gyroBiasCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString))); @@ -170,12 +175,10 @@ ConfigRevoWidget::~ConfigRevoWidget() // Do nothing } - void ConfigRevoWidget::showEvent(QShowEvent *event) { Q_UNUSED(event); updateVisualHelp(); - m_thermalCalibrationModel->init(); } void ConfigRevoWidget::resizeEvent(QResizeEvent *event) @@ -237,13 +240,24 @@ void ConfigRevoWidget::displayVisualHelp(QString elementID) updateVisualHelp(); } -void ConfigRevoWidget::displayInstructions(QString instructions, bool replace) +void ConfigRevoWidget::displayInstructions(QString text, WizardModel::MessageType type, bool clear) { - if (replace || instructions.isNull()) { + if (clear || text.isEmpty()) { m_ui->calibrationInstructions->clear(); } - if (!instructions.isNull()) { - m_ui->calibrationInstructions->append(instructions); + if (!text.isNull()) { + switch(type) { + case WizardModel::Error: + text = QString("%1").arg(text); + break; + case WizardModel::Notice: + text = QString("%1").arg(text); + break; + case WizardModel::Info: + default: + break; + } + m_ui->calibrationInstructions->append(text); } } diff --git a/ground/openpilotgcs/src/plugins/config/configrevowidget.h b/ground/openpilotgcs/src/plugins/config/configrevowidget.h index 2b0caf2c0..8174561c1 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevowidget.h +++ b/ground/openpilotgcs/src/plugins/config/configrevowidget.h @@ -29,7 +29,6 @@ #include "ui_revosensors.h" #include "configtaskwidget.h" -#include "../uavobjectwidgetutils/configtaskwidget.h" #include "extensionsystem/pluginmanager.h" #include "uavobjectmanager.h" #include "uavobject.h" @@ -69,7 +68,7 @@ private slots: void displayVisualHelp(QString elementID); void storeAndClearBoardRotation(); void recallBoardRotation(); - void displayInstructions(QString instructions = QString(), bool replace = false); + void displayInstructions(QString instructions, WizardModel::MessageType type = WizardModel::Info, bool clear = false); // ! Overriden method from the configTaskWidget to update UI virtual void refreshWidgetsValues(UAVObject *object = NULL); diff --git a/ground/openpilotgcs/src/plugins/config/revosensors.ui b/ground/openpilotgcs/src/plugins/config/revosensors.ui index 7ba51f0e2..1bae3d945 100644 --- a/ground/openpilotgcs/src/plugins/config/revosensors.ui +++ b/ground/openpilotgcs/src/plugins/config/revosensors.ui @@ -6,8 +6,8 @@ 0 0 - 789 - 674 + 1014 + 725 @@ -215,106 +215,9 @@ - Step 4: Thermal calibration* + Step 4: Thermal calibration - - - - - - - 50 - false - - - - Temperature - - - - - - - - 50 - true - false - - - - 0.00 - - - - - - - - 50 - false - - - - °C - Temperature rise - - - - - - - - 50 - true - false - - - - 0.5 - - - - - - - - 50 - false - - - - °C/min - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - 50 - false - - - - <this contains the current status of the thermal calibration wizard> - - - @@ -371,6 +274,19 @@ + + + + + 50 + false + + + + <temperature information> + + + @@ -428,12 +344,22 @@ QFrame::StyledPanel + + Qt::ScrollBarAlwaysOn + Qt::ScrollBarAlwaysOff QAbstractScrollArea::AdjustToContents + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:600; font-style:normal;"> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p></body></html> + Qt::LinksAccessibleByKeyboard|Qt::LinksAccessibleByMouse|Qt::TextBrowserInteraction|Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse @@ -460,24 +386,31 @@ p, li { white-space: pre-wrap; } <tr> <td style="border: none;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Help</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Steps 1, 2 and 3 are necessary. Step 4 is optional but may help achieve the best possible results.</span></p> <p align="center" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Step 1: Accelerometer / magnetometer calibration</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 1: Accelerometer / magnetometer calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This calibration will compute the scale for Magnetometer or Accelerometer sensors. </span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Press &quot;Calibrate Mag&quot; or &quot;Calibrate Accel&quot; to begin calibration, and follow the instructions which will be displayed here. </span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">For optimal calibration perform the Accel calibration with the board not mounted to the craft. in this way you can accurately level the board on your desk/table during the process. </span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Magnetometer calibration need to be performed inside your plane/copter to account for metal/magnetic stuffs on board.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600; font-style:italic;">Note 1:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> Your </span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">HomeLocation must be set first</span><span style=" font-family:'Ubuntu'; font-size:11pt;">, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600; font-style:italic;">Note 2:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> There is no need to point exactly at South/North/West/East. They are just used to easily tells the user how to point the plane/craft. </span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 1</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> </span><span style=" font-family:'Ubuntu'; font-size:11pt; text-decoration: underline;">Your HomeLocation must be set first</span><span style=" font-family:'Ubuntu'; font-size:11pt;">, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">Note 2</span><span style=" font-family:'Ubuntu'; font-size:11pt; font-weight:600;">:</span><span style=" font-family:'Ubuntu'; font-size:11pt;"> There is no need to point exactly at South/North/West/East. These are just used to easily tells the user how to point the plane/craft. </span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">You can simply assume that North is in front of you, right is East etc. and perform the calibration this way.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Step 2: Board level calibration</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 2: Board level calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step will ensure that board leveling is accurate. Place your airframe as horizontally as possible (use a spirit level if necessary), then press Start below and do not move your airframe at all until the end of the calibration.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Step 3: Gyro Bias calculation</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 3: Gyro bias calculation</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This step allows to calibrate the gyro measured value when the board is steady. To perform the calibration leave the board/aircraft completely steady and click start. </span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;">Step 4: Thermal Calibration</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;">Step 4: Thermal calibration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">The calibration will compute sensors bias variations at different temperatures while the board warms up.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">This allow a certain amount of correction of those bias variations against temperature changes. It does improve both altitude hold and yaw performances.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">To perform this calibration leave the board to cool down at room temperature in the coldest places available.</span></p>