1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-25 14:54:16 +01:00

OP-1351 thermal calibration step now uses instruction panel like all other steps (WIP).

Display of temp and temp variation currently broken.
This commit is contained in:
Philippe Renon 2014-05-15 22:10:16 +02:00
parent e8b7a025ba
commit 4feaa72998
12 changed files with 146 additions and 160 deletions

View File

@ -37,8 +37,9 @@
#include "calibration/calibrationuiutils.h" #include "calibration/calibrationuiutils.h"
static const int LEVEL_SAMPLES = 100; static const int LEVEL_SAMPLES = 100;
#include "gyrobiascalibrationmodel.h"
namespace OpenPilot { namespace OpenPilot {
GyroBiasCalibrationModel::GyroBiasCalibrationModel(QObject *parent) : GyroBiasCalibrationModel::GyroBiasCalibrationModel(QObject *parent) :
QObject(parent), QObject(parent),
collectingData(false) collectingData(false)
@ -70,7 +71,7 @@ void GyroBiasCalibrationModel::start()
attitudeSettings->updated(); attitudeSettings->updated();
displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_NED); 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_x.clear();
gyro_accum_y.clear(); gyro_accum_y.clear();
@ -196,7 +197,7 @@ void GyroBiasCalibrationModel::getSample(UAVObject *obj)
gyroState->setMetadata(initialGyroStateMdata); gyroState->setMetadata(initialGyroStateMdata);
gyroSensor->setMetadata(initialGyroSensorMdata); gyroSensor->setMetadata(initialGyroSensorMdata);
displayInstructions(tr("Gyroscope calibration computed succesfully."), false); displayInstructions(tr("Gyroscope calibration completed succesfully."));
displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY); displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY);
// Recall saved board rotation // Recall saved board rotation

View File

@ -29,27 +29,35 @@
#ifndef GYROBIASCALIBRATIONMODEL_H #ifndef GYROBIASCALIBRATIONMODEL_H
#define GYROBIASCALIBRATIONMODEL_H #define GYROBIASCALIBRATIONMODEL_H
#include <QObject> #include "wizardmodel.h"
#include "extensionsystem/pluginmanager.h" #include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h" #include "uavobjectmanager.h"
#include "uavobject.h" #include "uavobject.h"
#include <QObject>
namespace OpenPilot { namespace OpenPilot {
class GyroBiasCalibrationModel : public QObject { class GyroBiasCalibrationModel : public QObject {
Q_OBJECT Q_OBJECT
public: public:
explicit GyroBiasCalibrationModel(QObject *parent = 0); explicit GyroBiasCalibrationModel(QObject *parent = 0);
signals: signals:
void displayVisualHelp(QString elementID); 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 disableAllCalibrations();
void enableAllCalibrations(); void enableAllCalibrations();
void storeAndClearBoardRotation(); void storeAndClearBoardRotation();
void recallBoardRotation(); void recallBoardRotation();
void progressChanged(int value); void progressChanged(int value);
public slots: public slots:
// Slots for gyro bias zero // Slots for gyro bias zero
void start(); void start();
private slots: private slots:
void getSample(UAVObject *obj); void getSample(UAVObject *obj);
@ -69,4 +77,5 @@ private:
UAVObjectManager *getObjectManager(); UAVObjectManager *getObjectManager();
}; };
} }
#endif // GYROBIASCALIBRATIONMODEL_H #endif // GYROBIASCALIBRATIONMODEL_H

View File

@ -32,7 +32,9 @@
#include "calibration/calibrationuiutils.h" #include "calibration/calibrationuiutils.h"
static const int LEVEL_SAMPLES = 100; static const int LEVEL_SAMPLES = 100;
namespace OpenPilot { namespace OpenPilot {
LevelCalibrationModel::LevelCalibrationModel(QObject *parent) : LevelCalibrationModel::LevelCalibrationModel(QObject *parent) :
QObject(parent) QObject(parent)
{} {}
@ -62,7 +64,7 @@ void LevelCalibrationModel::start()
attitudeState->setMetadata(mdata); attitudeState->setMetadata(mdata);
/* Show instructions and enable controls */ /* 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); displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_NED);
disableAllCalibrations(); disableAllCalibrations();
savePositionEnabledChanged(true); savePositionEnabledChanged(true);
@ -86,7 +88,7 @@ void LevelCalibrationModel::savePosition()
Q_ASSERT(attitudeState); Q_ASSERT(attitudeState);
connect(attitudeState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(getSample(UAVObject *))); 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_pitch = OpenPilot::CalibrationUtils::listMean(rot_accum_pitch);
rot_data_roll = OpenPilot::CalibrationUtils::listMean(rot_accum_roll); 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); displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_SWD);
disableAllCalibrations(); disableAllCalibrations();
@ -146,7 +148,7 @@ void LevelCalibrationModel::getSample(UAVObject *obj)
compute(); compute();
enableAllCalibrations(); enableAllCalibrations();
displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY); displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY);
displayInstructions(tr("Board leveling computed successfully."), false); displayInstructions(tr("Board leveling completed successfully."));
break; break;
} }
} }

View File

@ -28,36 +28,43 @@
#ifndef LEVELCALIBRATIONMODEL_H #ifndef LEVELCALIBRATIONMODEL_H
#define LEVELCALIBRATIONMODEL_H #define LEVELCALIBRATIONMODEL_H
#include <QObject> #include "wizardmodel.h"
#include <QMutex>
#include <QList>
#include "calibration/calibrationutils.h" #include "calibration/calibrationutils.h"
#include <revocalibration.h> #include <revocalibration.h>
#include <accelgyrosettings.h> #include <accelgyrosettings.h>
#include <homelocation.h> #include <homelocation.h>
#include <accelstate.h> #include <accelstate.h>
#include <magstate.h> #include <magstate.h>
#include <QObject>
#include <QMutex>
#include <QList>
namespace OpenPilot { namespace OpenPilot {
class LevelCalibrationModel : public QObject { class LevelCalibrationModel : public QObject {
Q_OBJECT Q_OBJECT
public: public:
explicit LevelCalibrationModel(QObject *parent = 0); explicit LevelCalibrationModel(QObject *parent = 0);
signals: signals:
void displayVisualHelp(QString elementID); 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 disableAllCalibrations();
void enableAllCalibrations(); void enableAllCalibrations();
void savePositionEnabledChanged(bool state); void savePositionEnabledChanged(bool state);
void progressChanged(int value); void progressChanged(int value);
public slots: public slots:
// Slots for calibrating the mags // Slots for calibrating the mags
void start(); void start();
void savePosition(); void savePosition();
private slots: private slots:
void getSample(UAVObject *obj); void getSample(UAVObject *obj);
void compute(); void compute();
private: private:
QMutex sensorsUpdateLock; QMutex sensorsUpdateLock;
int position; int position;
@ -71,4 +78,5 @@ private:
UAVObjectManager *getObjectManager(); UAVObjectManager *getObjectManager();
}; };
} }
#endif // LEVELCALIBRATIONMODEL_H #endif // LEVELCALIBRATIONMODEL_H

View File

@ -26,18 +26,22 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/ */
#include "sixpointcalibrationmodel.h" #include "sixpointcalibrationmodel.h"
#include <QThread>
#include "extensionsystem/pluginmanager.h" #include "extensionsystem/pluginmanager.h"
#include <QMessageBox>
#include "math.h"
#include "calibration/calibrationuiutils.h" #include "calibration/calibrationuiutils.h"
#include "math.h"
#include <QMessageBox>
#include <QThread>
#include "QDebug" #include "QDebug"
#define POINT_SAMPLE_SIZE 50 #define POINT_SAMPLE_SIZE 50
#define GRAVITY 9.81f #define GRAVITY 9.81f
#define sign(x) ((x < 0) ? -1 : 1) #define sign(x) ((x < 0) ? -1 : 1)
#define FITTING_USING_CONTINOUS_ACQUISITION #define FITTING_USING_CONTINOUS_ACQUISITION
namespace OpenPilot { namespace OpenPilot {
SixPointCalibrationModel::SixPointCalibrationModel(QObject *parent) : SixPointCalibrationModel::SixPointCalibrationModel(QObject *parent) :
QObject(parent), QObject(parent),
calibrationStepsMag(), calibrationStepsMag(),
@ -195,7 +199,7 @@ void SixPointCalibrationModel::start(bool calibrateAccel, bool calibrateMag)
} }
/* Show instructions and enable controls */ /* Show instructions and enable controls */
displayInstructions((*currentSteps)[0].instructions, true); displayInstructions((*currentSteps)[0].instructions, WizardModel::Info, true);
showHelp((*currentSteps)[0].visualHelp); showHelp((*currentSteps)[0].visualHelp);
disableAllCalibrations(); disableAllCalibrations();
@ -244,7 +248,7 @@ void SixPointCalibrationModel::savePositionData()
connect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(getSample(UAVObject *))); 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; position = (position + 1) % 6;
if (position != 0) { if (position != 0) {
displayInstructions((*currentSteps)[position].instructions, false); displayInstructions((*currentSteps)[position].instructions);
showHelp((*currentSteps)[position].visualHelp); showHelp((*currentSteps)[position].visualHelp);
} else { } else {
#ifdef FITTING_USING_CONTINOUS_ACQUISITION #ifdef FITTING_USING_CONTINOUS_ACQUISITION
@ -484,9 +488,9 @@ void SixPointCalibrationModel::compute(bool mag, bool accel)
} else { } else {
accelGyroSettings->setData(savedSettings.accelGyroSettings); accelGyroSettings->setData(savedSettings.accelGyroSettings);
} }
displayInstructions(tr("Sensor scale and bias computed succesfully."), true); displayInstructions(tr("Sensor scale and bias computed succesfully."));
} else { } 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 position = -1; // set to run again
} }

View File

@ -27,17 +27,22 @@
*/ */
#ifndef SIXPOINTCALIBRATIONMODEL_H #ifndef SIXPOINTCALIBRATIONMODEL_H
#define SIXPOINTCALIBRATIONMODEL_H #define SIXPOINTCALIBRATIONMODEL_H
#include <QMutex>
#include <QObject> #include "wizardmodel.h"
#include <QList>
#include "calibration/calibrationutils.h" #include "calibration/calibrationutils.h"
#include <QString>
#include <revocalibration.h> #include <revocalibration.h>
#include <accelgyrosettings.h> #include <accelgyrosettings.h>
#include <homelocation.h> #include <homelocation.h>
#include <accelstate.h> #include <accelstate.h>
#include <magstate.h> #include <magstate.h>
#include <QMutex>
#include <QObject>
#include <QList>
#include <QString>
namespace OpenPilot { namespace OpenPilot {
class SixPointCalibrationModel : public QObject { class SixPointCalibrationModel : public QObject {
Q_OBJECT Q_OBJECT
@ -61,7 +66,7 @@ public:
signals: signals:
void displayVisualHelp(QString elementID); 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 disableAllCalibrations();
void enableAllCalibrations(); void enableAllCalibrations();
void storeAndClearBoardRotation(); void storeAndClearBoardRotation();

View File

@ -33,6 +33,7 @@
#include "compensationcalculationtransition.h" #include "compensationcalculationtransition.h"
namespace OpenPilot { namespace OpenPilot {
ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) : ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) :
WizardModel(parent), WizardModel(parent),
m_startEnabled(false), m_startEnabled(false),
@ -41,7 +42,7 @@ ThermalCalibrationModel::ThermalCalibrationModel(QObject *parent) :
m_initDone(false) m_initDone(false)
{ {
m_helper.reset(new ThermalCalibrationHelper()); m_helper.reset(new ThermalCalibrationHelper());
m_readyState = new WizardState(tr("Start"), this), m_readyState = new WizardState("", this),
m_workingState = new WizardState(NULL, this); m_workingState = new WizardState(NULL, this);
m_saveSettingState = new WizardState(tr("Saving initial settings"), m_workingState); 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_readyState, SIGNAL(exited()), this, SLOT(wizardStarted()));
connect(m_completedState, SIGNAL(entered()), this, SLOT(wizardReady())); connect(m_completedState, SIGNAL(entered()), this, SLOT(wizardReady()));
connect(m_completedState, SIGNAL(exited()), this, SLOT(wizardStarted())); 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; m_steps << m_readyState << m_saveSettingState << m_setupState << m_acquisitionState << m_restoreState << m_calculateState;
} }
void ThermalCalibrationModel::init() void ThermalCalibrationModel::init()
{ {
if (!m_initDone) { if (!m_initDone) {
@ -80,7 +83,6 @@ void ThermalCalibrationModel::init()
start(); start();
setTemperature(0); setTemperature(0);
setTemperatureGradient(0); setTemperatureGradient(0);
emit instructionsChanged(instructions());
} }
} }
@ -115,4 +117,5 @@ void ThermalCalibrationModel::setTransitions()
m_workingState->addTransition(this, SIGNAL(abort()), m_abortState); m_workingState->addTransition(this, SIGNAL(abort()), m_abortState);
// Ready // Ready
} }
} }

View File

@ -37,7 +37,9 @@
#include <QStateMachine> #include <QStateMachine>
#include "../wizardstate.h" #include "../wizardstate.h"
#include "../wizardmodel.h" #include "../wizardmodel.h"
namespace OpenPilot { namespace OpenPilot {
class ThermalCalibrationModel : public WizardModel { class ThermalCalibrationModel : public WizardModel {
Q_PROPERTY(bool startEnable READ startEnabled NOTIFY startEnabledChanged) Q_PROPERTY(bool startEnable READ startEnabled NOTIFY startEnabledChanged)
Q_PROPERTY(bool endEnable READ endEnabled NOTIFY endEnabledChanged) 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(QString temperatureGradient READ temperatureGradient NOTIFY temperatureGradientChanged)
Q_PROPERTY(int progress READ progress WRITE setProgress NOTIFY progressChanged) Q_PROPERTY(int progress READ progress WRITE setProgress NOTIFY progressChanged)
Q_OBJECT Q_OBJECT
public: public:
explicit ThermalCalibrationModel(QObject *parent = 0); explicit ThermalCalibrationModel(QObject *parent = 0);
@ -181,19 +184,19 @@ signals:
void next(); void next();
void previous(); void previous();
void abort(); void abort();
public slots: public slots:
void stepChanged(WizardState *state); void stepChanged(WizardState *state);
void init(); void init();
void btnStart() void btnStart()
{ {
setInstructions("");
emit next(); emit next();
} }
void btnEnd() void btnEnd()
{ {
m_helper->stopAcquisition(); m_helper->stopAcquisition();
} }
void btnAbort() void btnAbort()
{ {
emit abort(); emit abort();

View File

@ -35,9 +35,11 @@
class WizardModel : public QStateMachine { class WizardModel : public QStateMachine {
Q_OBJECT Q_PROPERTY(QQmlListProperty<QObject> steps READ steps CONSTANT) Q_OBJECT Q_PROPERTY(QQmlListProperty<QObject> 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) Q_PROPERTY(WizardState * currentState READ currentState NOTIFY currentStateChanged)
public: public:
enum MessageType { Info, Notice, Warning, Error };
explicit WizardModel(QObject *parent = 0); explicit WizardModel(QObject *parent = 0);
QQmlListProperty<QObject> steps() QQmlListProperty<QObject> steps()
@ -45,25 +47,28 @@ public:
return QQmlListProperty<QObject>(this, m_steps); return QQmlListProperty<QObject>(this, m_steps);
} }
QString instructions() QString &instructions()
{ {
return m_instructions; return m_instructions;
} }
void setInstructions(QString instructions) void setInstructions(QString text, MessageType type = WizardModel::Info)
{ {
m_instructions = instructions; m_instructions = text;
emit instructionsChanged(instructions); emit displayInstructions(text, type);
} }
WizardState *currentState(); WizardState *currentState();
protected: protected:
QList<QObject *> m_steps; QList<QObject *> m_steps;
private: private:
QString m_instructions; QString m_instructions;
signals: signals:
void instructionsChanged(QString status); void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false);
void currentStateChanged(WizardState *status); void currentStateChanged(WizardState *status);
public slots:
}; };
#endif // WIZARDMODEL_H #endif // WIZARDMODEL_H

View File

@ -94,6 +94,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
// connect the thermalCalibration model to UI // connect the thermalCalibration model to UI
m_thermalCalibrationModel = new OpenPilot::ThermalCalibrationModel(this); m_thermalCalibrationModel = new OpenPilot::ThermalCalibrationModel(this);
m_thermalCalibrationModel->init();
connect(m_ui->ThermalBiasStart, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnStart())); connect(m_ui->ThermalBiasStart, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnStart()));
connect(m_ui->ThermalBiasEnd, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnEnd())); 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(endEnabledChanged(bool)), m_ui->ThermalBiasEnd, SLOT(setEnabled(bool)));
connect(m_thermalCalibrationModel, SIGNAL(cancelEnabledChanged(bool)), m_ui->ThermalBiasCancel, 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(displayInstructions(QString, WizardModel::MessageType)),
connect(m_thermalCalibrationModel, SIGNAL(temperatureChanged(QString)), m_ui->textTemperature, SLOT(setText(QString))); this, SLOT(displayInstructions(QString, WizardModel::MessageType)));
connect(m_thermalCalibrationModel, SIGNAL(temperatureGradientChanged(QString)), m_ui->textThermalGradient, 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(progressChanged(int)), m_ui->thermalBiasProgress, SLOT(setValue(int))); 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. // 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(enableAllCalibrations()), this, SLOT(enableAllCalibrations()));
connect(m_sixPointCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation())); connect(m_sixPointCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation()));
connect(m_sixPointCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation())); 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(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_sixPointCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->sixPointsSave, SLOT(setEnabled(bool))); 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(disableAllCalibrations()), this, SLOT(disableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(enableAllCalibrations()), this, SLOT(enableAllCalibrations())); 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(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_levelCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->boardLevelSavePos, SLOT(setEnabled(bool))); 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))); 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(enableAllCalibrations()), this, SLOT(enableAllCalibrations()));
connect(m_gyroBiasCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation())); connect(m_gyroBiasCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation()));
connect(m_gyroBiasCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation())); 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))); connect(m_gyroBiasCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
@ -170,12 +175,10 @@ ConfigRevoWidget::~ConfigRevoWidget()
// Do nothing // Do nothing
} }
void ConfigRevoWidget::showEvent(QShowEvent *event) void ConfigRevoWidget::showEvent(QShowEvent *event)
{ {
Q_UNUSED(event); Q_UNUSED(event);
updateVisualHelp(); updateVisualHelp();
m_thermalCalibrationModel->init();
} }
void ConfigRevoWidget::resizeEvent(QResizeEvent *event) void ConfigRevoWidget::resizeEvent(QResizeEvent *event)
@ -237,13 +240,24 @@ void ConfigRevoWidget::displayVisualHelp(QString elementID)
updateVisualHelp(); 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(); m_ui->calibrationInstructions->clear();
} }
if (!instructions.isNull()) { if (!text.isNull()) {
m_ui->calibrationInstructions->append(instructions); switch(type) {
case WizardModel::Error:
text = QString("<font color='red'>%1</font>").arg(text);
break;
case WizardModel::Notice:
text = QString("<font color='blue'>%1</font>").arg(text);
break;
case WizardModel::Info:
default:
break;
}
m_ui->calibrationInstructions->append(text);
} }
} }

View File

@ -29,7 +29,6 @@
#include "ui_revosensors.h" #include "ui_revosensors.h"
#include "configtaskwidget.h" #include "configtaskwidget.h"
#include "../uavobjectwidgetutils/configtaskwidget.h"
#include "extensionsystem/pluginmanager.h" #include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h" #include "uavobjectmanager.h"
#include "uavobject.h" #include "uavobject.h"
@ -69,7 +68,7 @@ private slots:
void displayVisualHelp(QString elementID); void displayVisualHelp(QString elementID);
void storeAndClearBoardRotation(); void storeAndClearBoardRotation();
void recallBoardRotation(); 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 // ! Overriden method from the configTaskWidget to update UI
virtual void refreshWidgetsValues(UAVObject *object = NULL); virtual void refreshWidgetsValues(UAVObject *object = NULL);

View File

@ -6,8 +6,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>789</width> <width>1014</width>
<height>674</height> <height>725</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -215,106 +215,9 @@
<item row="3" column="0"> <item row="3" column="0">
<widget class="QGroupBox" name="step4GroupBox"> <widget class="QGroupBox" name="step4GroupBox">
<property name="title"> <property name="title">
<string>Step 4: Thermal calibration*</string> <string>Step 4: Thermal calibration</string>
</property> </property>
<layout class="QVBoxLayout"> <layout class="QVBoxLayout">
<item>
<layout class="QHBoxLayout">
<item>
<widget class="QLabel" name="label_temperature">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>Temperature</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="textTemperature">
<property name="font">
<font>
<weight>50</weight>
<italic>true</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>0.00</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_thermalcal1">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>°C - Temperature rise</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="textThermalGradient">
<property name="font">
<font>
<weight>50</weight>
<italic>true</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>0.5</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_thermalcal2">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>°C/min</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_thermalbias">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="label_thermalDescription">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>&lt;this contains the current status of the thermal calibration wizard&gt;</string>
</property>
</widget>
</item>
<item> <item>
<layout class="QHBoxLayout" name="horizontalLayout_thermalbias2"> <layout class="QHBoxLayout" name="horizontalLayout_thermalbias2">
<item> <item>
@ -371,6 +274,19 @@
</item> </item>
</layout> </layout>
</item> </item>
<item>
<widget class="QLabel" name="temperatureLabel">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>&lt;temperature information&gt;</string>
</property>
</widget>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>
@ -428,12 +344,22 @@
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::StyledPanel</enum> <enum>QFrame::StyledPanel</enum>
</property> </property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOn</enum>
</property>
<property name="horizontalScrollBarPolicy"> <property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum> <enum>Qt::ScrollBarAlwaysOff</enum>
</property> </property>
<property name="sizeAdjustPolicy"> <property name="sizeAdjustPolicy">
<enum>QAbstractScrollArea::AdjustToContents</enum> <enum>QAbstractScrollArea::AdjustToContents</enum>
</property> </property>
<property name="html">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:600; font-style:normal;&quot;&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="textInteractionFlags"> <property name="textInteractionFlags">
<set>Qt::LinksAccessibleByKeyboard|Qt::LinksAccessibleByMouse|Qt::TextBrowserInteraction|Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse</set> <set>Qt::LinksAccessibleByKeyboard|Qt::LinksAccessibleByMouse|Qt::TextBrowserInteraction|Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse</set>
</property> </property>
@ -460,24 +386,31 @@ p, li { white-space: pre-wrap; }
&lt;tr&gt; &lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt; &lt;td style=&quot;border: none;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;&quot;&gt;Help&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;&quot;&gt;Help&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Steps 1, 2 and 3 are necessary. Step 4 is optional but may help achieve the best possible results.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Steps 1, 2 and 3 are necessary. Step 4 is optional but may help achieve the best possible results.&lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt; &lt;p align=&quot;center&quot; style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;&quot;&gt;Step 1: Accelerometer / magnetometer calibration&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;&quot;&gt;Step 1: Accelerometer / magnetometer calibration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This calibration will compute the scale for Magnetometer or Accelerometer sensors. &lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This calibration will compute the scale for Magnetometer or Accelerometer sensors. &lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Press &amp;quot;Calibrate Mag&amp;quot; or &amp;quot;Calibrate Accel&amp;quot; to begin calibration, and follow the instructions which will be displayed here. &lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Press &amp;quot;Calibrate Mag&amp;quot; or &amp;quot;Calibrate Accel&amp;quot; to begin calibration, and follow the instructions which will be displayed here. &lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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. &lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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. &lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Magnetometer calibration need to be performed inside your plane/copter to account for metal/magnetic stuffs on board.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Magnetometer calibration need to be performed inside your plane/copter to account for metal/magnetic stuffs on board.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600; font-style:italic;&quot;&gt;Note 1:&lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt; Your &lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;HomeLocation must be set first&lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600; font-style:italic;&quot;&gt;Note 2:&lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt; 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. &lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Note 1&lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;:&lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt; &lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; text-decoration: underline;&quot;&gt;Your HomeLocation must be set first&lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;, including the local magnetic field vector (Be) and acceleration due to gravity (g_e).&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Note 2&lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:600;&quot;&gt;:&lt;/span&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt; 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. &lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;You can simply assume that North is in front of you, right is East etc. and perform the calibration this way.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;You can simply assume that North is in front of you, right is East etc. and perform the calibration this way.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt; &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;&quot;&gt;Step 2: Board level calibration&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;&quot;&gt;Step 2: Board level calibration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt; &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;&quot;&gt;Step 3: Gyro Bias calculation&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;&quot;&gt;Step 3: Gyro bias calculation&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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. &lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;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. &lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt; &lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; font-style:italic;&quot;&gt;Step 4: Thermal Calibration&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;&quot;&gt;Step 4: Thermal calibration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-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;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;The calibration will compute sensors bias variations at different temperatures while the board warms up.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;The calibration will compute sensors bias variations at different temperatures while the board warms up.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This allow a certain amount of correction of those bias variations against temperature changes. It does improve both altitude hold and yaw performances.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This allow a certain amount of correction of those bias variations against temperature changes. It does improve both altitude hold and yaw performances.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;To perform this calibration leave the board to cool down at room temperature in the coldest places available.&lt;/span&gt;&lt;/p&gt; &lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;To perform this calibration leave the board to cool down at room temperature in the coldest places available.&lt;/span&gt;&lt;/p&gt;