1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-17 02:52:12 +01:00

OP-975 Remove noise calibration

This commit is contained in:
Alessio Morale 2014-04-09 01:12:31 +02:00
parent 694cb01ace
commit 45915e3387
3 changed files with 37 additions and 454 deletions

View File

@ -57,7 +57,7 @@
// Uncomment this to enable 6 point calibration on the accels
#define SIX_POINT_CAL_ACCEL
#define SAMPLE_SIZE 40
const double ConfigRevoWidget::maxVarValue = 0.1;
// *****************
@ -91,126 +91,6 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
m_ui->sixPointsHelp->scene()->addItem(paperplane);
m_ui->sixPointsHelp->setSceneRect(paperplane->boundingRect());
// Initialization of the Revo sensor noise bargraph graph
m_ui->sensorsBargraph->setScene(new QGraphicsScene(this));
QSvgRenderer *renderer = new QSvgRenderer();
sensorsBargraph = new QGraphicsSvgItem();
renderer->load(QString(":/configgadget/images/ahrs-calib.svg"));
sensorsBargraph->setSharedRenderer(renderer);
sensorsBargraph->setElementId("background");
sensorsBargraph->setObjectName("background");
m_ui->sensorsBargraph->scene()->addItem(sensorsBargraph);
m_ui->sensorsBargraph->setSceneRect(sensorsBargraph->boundingRect());
// Initialize the 9 bargraph values:
QMatrix lineMatrix = renderer->matrixForElement("accel_x");
QRectF rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_x"));
qreal startX = rect.x();
qreal startY = rect.y() + rect.height();
// maxBarHeight will be used for scaling it later.
maxBarHeight = rect.height();
// Then once we have the initial location, we can put it
// into a QGraphicsSvgItem which we will display at the same
// place: we do this so that the heading scale can be clipped to
// the compass dial region.
accel_x = new QGraphicsSvgItem();
accel_x->setSharedRenderer(renderer);
accel_x->setElementId("accel_x");
m_ui->sensorsBargraph->scene()->addItem(accel_x);
accel_x->setPos(startX, startY);
accel_x->setTransform(QTransform::fromScale(1, 0), true);
lineMatrix = renderer->matrixForElement("accel_y");
rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_y"));
startX = rect.x();
startY = rect.y() + rect.height();
accel_y = new QGraphicsSvgItem();
accel_y->setSharedRenderer(renderer);
accel_y->setElementId("accel_y");
m_ui->sensorsBargraph->scene()->addItem(accel_y);
accel_y->setPos(startX, startY);
accel_y->setTransform(QTransform::fromScale(1, 0), true);
lineMatrix = renderer->matrixForElement("accel_z");
rect = lineMatrix.mapRect(renderer->boundsOnElement("accel_z"));
startX = rect.x();
startY = rect.y() + rect.height();
accel_z = new QGraphicsSvgItem();
accel_z->setSharedRenderer(renderer);
accel_z->setElementId("accel_z");
m_ui->sensorsBargraph->scene()->addItem(accel_z);
accel_z->setPos(startX, startY);
accel_z->setTransform(QTransform::fromScale(1, 0), true);
lineMatrix = renderer->matrixForElement("gyro_x");
rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_x"));
startX = rect.x();
startY = rect.y() + rect.height();
gyro_x = new QGraphicsSvgItem();
gyro_x->setSharedRenderer(renderer);
gyro_x->setElementId("gyro_x");
m_ui->sensorsBargraph->scene()->addItem(gyro_x);
gyro_x->setPos(startX, startY);
gyro_x->setTransform(QTransform::fromScale(1, 0), true);
lineMatrix = renderer->matrixForElement("gyro_y");
rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_y"));
startX = rect.x();
startY = rect.y() + rect.height();
gyro_y = new QGraphicsSvgItem();
gyro_y->setSharedRenderer(renderer);
gyro_y->setElementId("gyro_y");
m_ui->sensorsBargraph->scene()->addItem(gyro_y);
gyro_y->setPos(startX, startY);
gyro_y->setTransform(QTransform::fromScale(1, 0), true);
lineMatrix = renderer->matrixForElement("gyro_z");
rect = lineMatrix.mapRect(renderer->boundsOnElement("gyro_z"));
startX = rect.x();
startY = rect.y() + rect.height();
gyro_z = new QGraphicsSvgItem();
gyro_z->setSharedRenderer(renderer);
gyro_z->setElementId("gyro_z");
m_ui->sensorsBargraph->scene()->addItem(gyro_z);
gyro_z->setPos(startX, startY);
gyro_z->setTransform(QTransform::fromScale(1, 0), true);
lineMatrix = renderer->matrixForElement("mag_x");
rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_x"));
startX = rect.x();
startY = rect.y() + rect.height();
mag_x = new QGraphicsSvgItem();
mag_x->setSharedRenderer(renderer);
mag_x->setElementId("mag_x");
m_ui->sensorsBargraph->scene()->addItem(mag_x);
mag_x->setPos(startX, startY);
mag_x->setTransform(QTransform::fromScale(1, 0), true);
lineMatrix = renderer->matrixForElement("mag_y");
rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_y"));
startX = rect.x();
startY = rect.y() + rect.height();
mag_y = new QGraphicsSvgItem();
mag_y->setSharedRenderer(renderer);
mag_y->setElementId("mag_y");
m_ui->sensorsBargraph->scene()->addItem(mag_y);
mag_y->setPos(startX, startY);
mag_y->setTransform(QTransform::fromScale(1, 0), true);
lineMatrix = renderer->matrixForElement("mag_z");
rect = lineMatrix.mapRect(renderer->boundsOnElement("mag_z"));
startX = rect.x();
startY = rect.y() + rect.height();
mag_z = new QGraphicsSvgItem();
mag_z->setSharedRenderer(renderer);
mag_z->setElementId("mag_z");
m_ui->sensorsBargraph->scene()->addItem(mag_z);
mag_z->setPos(startX, startY);
mag_z->setTransform(QTransform::fromScale(1, 0), true);
// Must set up the UI (above) before setting up the UAVO mappings or refreshWidgetValues
// will be dealing with some null pointers
addUAVObject("RevoCalibration");
@ -242,7 +122,6 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(doStartAccelGyroBiasCalibration()));
connect(m_ui->sixPointsStart, SIGNAL(clicked()), this, SLOT(doStartSixPointCalibration()));
connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData()));
connect(m_ui->noiseMeasurementStart, SIGNAL(clicked()), this, SLOT(doStartNoiseMeasurement()));
connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation()));
@ -270,16 +149,13 @@ void ConfigRevoWidget::showEvent(QShowEvent *event)
// Thit fitInView method should only be called now, once the
// widget is shown, otherwise it cannot compute its values and
// the result is usually a sensorsBargraph that is way too small.
m_ui->sensorsBargraph->fitInView(sensorsBargraph, Qt::KeepAspectRatio);
m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio);
m_thermalCalibrationModel->init();
}
void ConfigRevoWidget::resizeEvent(QResizeEvent *event)
{
Q_UNUSED(event)
m_ui->sensorsBargraph->fitInView(sensorsBargraph, Qt::KeepAspectRatio);
m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio);
}
@ -704,9 +580,9 @@ void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject *obj)
}
#ifdef SIX_POINT_CAL_ACCEL
if (accel_accum_x.size() >= 20 && mag_accum_x.size() >= 20 && collectingData == true) {
if (accel_accum_x.size() >= SAMPLE_SIZE && mag_accum_x.size() >= SAMPLE_SIZE && collectingData == true) {
#else
if (mag_accum_x.size() >= 20 && collectingData == true) {
if (mag_accum_x.size() >= SAMPLE_SIZE && collectingData == true) {
#endif
collectingData = false;
@ -925,223 +801,8 @@ void ConfigRevoWidget::displayPlane(QString elementID)
m_ui->sixPointsHelp->fitInView(paperplane, Qt::KeepAspectRatio);
}
/*********** Noise measurement functions **************/
/**
* Connect sensor updates and timeout for measuring the noise
*/
void ConfigRevoWidget::doStartNoiseMeasurement()
{
QMutexLocker lock(&sensorsUpdateLock);
// Store and reset board rotation before calibration starts
isBoardRotationStored = false;
storeAndClearBoardRotation();
Q_UNUSED(lock);
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
Q_ASSERT(homeLocation);
HomeLocation::DataFields homeLocationData = homeLocation->getData();
// check if Homelocation is set
if (!homeLocationData.Set) {
QMessageBox msgBox;
msgBox.setInformativeText(tr("<p>HomeLocation not SET.</p><p>Please set your HomeLocation and try again. Aborting calibration!</p>"));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.setIcon(QMessageBox::Information);
msgBox.exec();
return;
}
accel_accum_x.clear();
accel_accum_y.clear();
accel_accum_z.clear();
gyro_accum_x.clear();
gyro_accum_y.clear();
gyro_accum_z.clear();
mag_accum_x.clear();
mag_accum_y.clear();
mag_accum_z.clear();
/* Need to get as many accel, mag and gyro updates as possible */
AccelState *accelState = AccelState::GetInstance(getObjectManager());
Q_ASSERT(accelState);
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
Q_ASSERT(gyroState);
MagState *mag = MagState::GetInstance(getObjectManager());
Q_ASSERT(mag);
UAVObject::Metadata mdata;
initialAccelStateMdata = accelState->getMetadata();
mdata = initialAccelStateMdata;
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = 100;
accelState->setMetadata(mdata);
initialGyroStateMdata = gyroState->getMetadata();
mdata = initialGyroStateMdata;
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = 100;
gyroState->setMetadata(mdata);
initialMagStateMdata = mag->getMetadata();
mdata = initialMagStateMdata;
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = 100;
mag->setMetadata(mdata);
/* Connect for updates */
connect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *)));
connect(gyroState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *)));
connect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *)));
}
/**
* Called when any of the sensors are updated. Stores the sample for measuring the
* variance at the end
*/
void ConfigRevoWidget::doGetNoiseSample(UAVObject *obj)
{
QMutexLocker lock(&sensorsUpdateLock);
Q_UNUSED(lock);
Q_ASSERT(obj);
switch (obj->getObjID()) {
case GyroState::OBJID:
{
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
Q_ASSERT(gyroState);
GyroState::DataFields gyroData = gyroState->getData();
gyro_accum_x.append(gyroData.x);
gyro_accum_y.append(gyroData.y);
gyro_accum_z.append(gyroData.z);
break;
}
case AccelState::OBJID:
{
AccelState *accelState = AccelState::GetInstance(getObjectManager());
Q_ASSERT(accelState);
AccelState::DataFields accelStateData = accelState->getData();
accel_accum_x.append(accelStateData.x);
accel_accum_y.append(accelStateData.y);
accel_accum_z.append(accelStateData.z);
break;
}
case MagState::OBJID:
{
MagState *mags = MagState::GetInstance(getObjectManager());
Q_ASSERT(mags);
MagState::DataFields magData = mags->getData();
mag_accum_x.append(magData.x);
mag_accum_y.append(magData.y);
mag_accum_z.append(magData.z);
break;
}
default:
Q_ASSERT(0);
}
float p1 = (float)mag_accum_x.length() / (float)NOISE_SAMPLES;
float p2 = (float)gyro_accum_x.length() / (float)NOISE_SAMPLES;
float p3 = (float)accel_accum_x.length() / (float)NOISE_SAMPLES;
float prog = (p1 < p2) ? p1 : p2;
prog = (prog < p3) ? prog : p3;
m_ui->noiseMeasurementProgress->setValue(prog * 100);
if (mag_accum_x.length() >= NOISE_SAMPLES &&
gyro_accum_x.length() >= NOISE_SAMPLES &&
accel_accum_x.length() >= NOISE_SAMPLES) {
// No need to for more updates
MagState *mags = MagState::GetInstance(getObjectManager());
AccelState *accelState = AccelState::GetInstance(getObjectManager());
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
disconnect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *)));
disconnect(gyroState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *)));
disconnect(mags, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetNoiseSample(UAVObject *)));
EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager());
Q_ASSERT(ekfConfiguration);
if (ekfConfiguration) {
EKFConfiguration::DataFields revoCalData = ekfConfiguration->getData();
revoCalData.Q[EKFConfiguration::Q_ACCELX] = listVar(accel_accum_x);
revoCalData.Q[EKFConfiguration::Q_ACCELY] = listVar(accel_accum_y);
revoCalData.Q[EKFConfiguration::Q_ACCELZ] = listVar(accel_accum_z);
revoCalData.Q[EKFConfiguration::Q_GYROX] = listVar(gyro_accum_x);
revoCalData.Q[EKFConfiguration::Q_GYROY] = listVar(gyro_accum_y);
revoCalData.Q[EKFConfiguration::Q_GYROZ] = listVar(gyro_accum_z);
revoCalData.R[EKFConfiguration::R_MAGX] = listVar(mag_accum_x);
revoCalData.R[EKFConfiguration::R_MAGY] = listVar(mag_accum_y);
revoCalData.R[EKFConfiguration::R_MAGZ] = listVar(mag_accum_z);
ekfConfiguration->setData(revoCalData);
}
// Recall saved board rotation
recallBoardRotation();
}
}
/********** UI Functions *************/
/**
Draws the sensor variances bargraph
*/
void ConfigRevoWidget::drawVariancesGraph()
{
EKFConfiguration *ekfConfiguration = EKFConfiguration::GetInstance(getObjectManager());
Q_ASSERT(ekfConfiguration);
if (!ekfConfiguration) {
return;
}
EKFConfiguration::DataFields ekfConfigurationData = ekfConfiguration->getData();
// The expected range is from 1E-6 to 1E-1
double steps = 6; // 6 bars on the graph
float accel_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELX]));
if (accel_x) {
accel_x->setTransform(QTransform::fromScale(1, accel_x_var), false);
}
float accel_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELY]));
if (accel_y) {
accel_y->setTransform(QTransform::fromScale(1, accel_y_var), false);
}
float accel_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_ACCELZ]));
if (accel_z) {
accel_z->setTransform(QTransform::fromScale(1, accel_z_var), false);
}
float gyro_x_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROX]));
if (gyro_x) {
gyro_x->setTransform(QTransform::fromScale(1, gyro_x_var), false);
}
float gyro_y_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROY]));
if (gyro_y) {
gyro_y->setTransform(QTransform::fromScale(1, gyro_y_var), false);
}
float gyro_z_var = -1 / steps * (1 + steps + log10(ekfConfigurationData.Q[EKFConfiguration::Q_GYROZ]));
if (gyro_z) {
gyro_z->setTransform(QTransform::fromScale(1, gyro_z_var), false);
}
// Scale by 1e-3 because mag vars are much higher.
float mag_x_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGX]));
if (mag_x) {
mag_x->setTransform(QTransform::fromScale(1, mag_x_var), false);
}
float mag_y_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGY]));
if (mag_y) {
mag_y->setTransform(QTransform::fromScale(1, mag_y_var), false);
}
float mag_z_var = -1 / steps * (1 + steps + log10(1e-3 * ekfConfigurationData.R[EKFConfiguration::R_MAGZ]));
if (mag_z) {
mag_z->setTransform(QTransform::fromScale(1, mag_z_var), false);
}
}
/**
* Called by the ConfigTaskWidget parent when RevoCalibration is updated
@ -1151,9 +812,6 @@ void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object)
{
ConfigTaskWidget::refreshWidgetsValues(object);
drawVariancesGraph();
m_ui->noiseMeasurementStart->setEnabled(true);
m_ui->sixPointsStart->setEnabled(true);
m_ui->accelBiasStart->setEnabled(true);
m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate."));

View File

@ -51,7 +51,6 @@ public:
~ConfigRevoWidget();
private:
void drawVariancesGraph();
void displayPlane(QString elementID);
// ! Computes the scale and bias of the mag based on collected data
@ -60,16 +59,6 @@ private:
OpenPilot::ThermalCalibrationModel *m_thermalCalibrationModel;
Ui_RevoSensorsWidget *m_ui;
QGraphicsSvgItem *paperplane;
QGraphicsSvgItem *sensorsBargraph;
QGraphicsSvgItem *accel_x;
QGraphicsSvgItem *accel_y;
QGraphicsSvgItem *accel_z;
QGraphicsSvgItem *gyro_x;
QGraphicsSvgItem *gyro_y;
QGraphicsSvgItem *gyro_z;
QGraphicsSvgItem *mag_x;
QGraphicsSvgItem *mag_y;
QGraphicsSvgItem *mag_z;
QMutex sensorsUpdateLock;
double maxBarHeight;
int phaseCounter;
@ -121,10 +110,6 @@ private slots:
void doStartAccelGyroBiasCalibration();
void doGetAccelGyroBiasData(UAVObject *);
// Slots for measuring the sensor noise
void doStartNoiseMeasurement();
void doGetNoiseSample(UAVObject *);
// Slot for clearing home location
void clearHomeLocation();

View File

@ -62,64 +62,6 @@
<property name="verticalSpacing">
<number>6</number>
</property>
<item row="1" column="1">
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>#3: Sensor noise calibration</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<widget class="QGraphicsView" name="sensorsBargraph">
<property name="toolTip">
<string>These are the sensor variance values computed by the AHRS.
Tip: lower is better!</string>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QPushButton" name="noiseMeasurementStart">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Press to start a calibration procedure, about 15 seconds.
Hint: run this with engines at cruising speed.</string>
</property>
<property name="text">
<string>Start</string>
</property>
</widget>
</item>
<item>
<widget class="QProgressBar" name="noiseMeasurementProgress">
<property name="enabled">
<bool>true</bool>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="textVisible">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="1" column="0">
<widget class="QGroupBox" name="groupBox_5">
<property name="title">
@ -317,9 +259,42 @@
</widget>
</item>
<item row="2" column="0" colspan="2">
<widget class="QTextEdit" name="sixPointCalibInstructions">
<property name="toolTip">
<string>Six Point Calibration instructions</string>
</property>
<property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</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:'Sans Serif'; font-size:9pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&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:11pt; font-weight:600;&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:11pt;&quot;&gt;Step #1 and #2 and 3 are really necessary. Step #4 will help you achieve the best possible results.&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; 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;#1: 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:11pt;&quot;&gt;The calibration will compute the variation of all sensors bias at different temperatures while the board warm 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;To perform this calibration leave the board to cool down at room temperature in the coldest places available. after 15-20 minutes attach the usb connector to the board and Click the Calibrate button leaving the board steady. Wait until completed&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 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;#2: Multi-Point 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 calibration will compute the scale for all sensors on the INS. Press &amp;quot;Start&amp;quot; to begin calibration, and follow the instructions which will be displayed here. Note that your HomeLocation must be set first, 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-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;&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;#3: 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: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;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>#4: Accelerometer Bias calibration</string>
<string>#3: Board level calibration</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
@ -349,41 +324,6 @@
</layout>
</widget>
</item>
<item row="3" column="0" colspan="2">
<widget class="QTextEdit" name="sixPointCalibInstructions">
<property name="toolTip">
<string>Six Point Calibration instructions</string>
</property>
<property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</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:'Sans Serif'; font-size:9pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&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:11pt; font-weight:600;&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:11pt;&quot;&gt;Step #1 and #2 and 3 are really necessary. Step #4 will help you achieve the best possible results.&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; 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;#1: 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:11pt;&quot;&gt;The calibration will compute the variation of all sensors bias at different temperatures while the board warm 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;To perform this calibration leave the board to cool down at room temperature in the coldest places available. after 15-20 minutes attach the usb connector to the board and Click the Calibrate button leaving the board steady. Wait until completed&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 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;#1: Multi-Point 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 calibration will compute the scale for all sensors on the INS. Press &amp;quot;Start&amp;quot; to begin calibration, and follow the instructions which will be displayed here. Note that your HomeLocation must be set first, 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-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:11pt;&quot;&gt;#2: Sensor noise 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 calibration will compute sensor variance under standard conditions. You can leave your engines running at low to mid throttle to take their vibration into account before pressing &amp;quot;Start&amp;quot;.&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; 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;#3: Accelerometer bias 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 accelerometer bias 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;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>