2011-12-24 20:57:10 +01:00
|
|
|
/**
|
|
|
|
******************************************************************************
|
|
|
|
*
|
|
|
|
* @file ConfigRevoWidget.h
|
|
|
|
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
|
|
* @addtogroup GCSPlugins GCS Plugins
|
|
|
|
* @{
|
|
|
|
* @addtogroup ConfigPlugin Config Plugin
|
|
|
|
* @{
|
|
|
|
* @brief The Configuration Gadget used to update settings in the firmware
|
|
|
|
*****************************************************************************/
|
|
|
|
/*
|
|
|
|
* This program is free software; you can redistribute it and/or modify
|
|
|
|
* it under the terms of the GNU General Public License as published by
|
|
|
|
* the Free Software Foundation; either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This program is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
|
|
|
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
|
|
|
* for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program; if not, write to the Free Software Foundation, Inc.,
|
|
|
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
|
|
|
*/
|
2012-01-29 03:00:15 +01:00
|
|
|
#include "configrevowidget.h"
|
2011-12-24 20:57:10 +01:00
|
|
|
|
|
|
|
#include "math.h"
|
|
|
|
#include <QDebug>
|
|
|
|
#include <QTimer>
|
|
|
|
#include <QStringList>
|
2013-09-15 23:06:25 +02:00
|
|
|
#include <QWidget>
|
|
|
|
#include <QTextEdit>
|
|
|
|
#include <QVBoxLayout>
|
|
|
|
#include <QPushButton>
|
2012-05-28 16:19:03 +02:00
|
|
|
#include <QMessageBox>
|
2011-12-24 20:57:10 +01:00
|
|
|
#include <QThread>
|
|
|
|
#include <QErrorMessage>
|
|
|
|
#include <iostream>
|
|
|
|
#include <QDesktopServices>
|
|
|
|
#include <QUrl>
|
2012-06-14 06:07:23 +02:00
|
|
|
#include <attitudesettings.h>
|
2013-05-03 02:17:44 +02:00
|
|
|
#include <ekfconfiguration.h>
|
2011-12-24 20:57:10 +01:00
|
|
|
#include <revocalibration.h>
|
2013-12-26 16:56:54 +01:00
|
|
|
#include <accelgyrosettings.h>
|
2012-05-27 21:15:31 +02:00
|
|
|
#include <homelocation.h>
|
2013-05-18 19:36:45 +02:00
|
|
|
#include <accelstate.h>
|
|
|
|
#include <gyrostate.h>
|
2013-05-20 10:33:02 +02:00
|
|
|
#include <magstate.h>
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2011-12-24 22:56:16 +01:00
|
|
|
#define GRAVITY 9.81f
|
2011-12-24 20:57:10 +01:00
|
|
|
#include "assertions.h"
|
|
|
|
#include "calibration.h"
|
|
|
|
|
|
|
|
#define sign(x) ((x < 0) ? -1 : 1)
|
|
|
|
|
2012-06-13 21:52:34 +02:00
|
|
|
// Uncomment this to enable 6 point calibration on the accels
|
2014-04-09 01:12:31 +02:00
|
|
|
#define SAMPLE_SIZE 40
|
2011-12-24 20:57:10 +01:00
|
|
|
const double ConfigRevoWidget::maxVarValue = 0.1;
|
|
|
|
|
|
|
|
// *****************
|
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
class Thread : public QThread {
|
2011-12-24 20:57:10 +01:00
|
|
|
public:
|
|
|
|
static void usleep(unsigned long usecs)
|
|
|
|
{
|
|
|
|
QThread::usleep(usecs);
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
|
|
|
// *****************
|
|
|
|
|
2011-12-24 22:56:16 +01:00
|
|
|
ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
|
|
|
|
ConfigTaskWidget(parent),
|
2012-08-18 14:18:10 +02:00
|
|
|
m_ui(new Ui_RevoSensorsWidget()),
|
2013-05-12 11:27:12 +02:00
|
|
|
collectingData(false),
|
|
|
|
position(-1),
|
|
|
|
isBoardRotationStored(false)
|
2011-12-24 20:57:10 +01:00
|
|
|
{
|
|
|
|
m_ui->setupUi(this);
|
|
|
|
|
|
|
|
// Initialization of the Paper plane widget
|
|
|
|
m_ui->sixPointsHelp->setScene(new QGraphicsScene(this));
|
2014-04-09 02:23:50 +02:00
|
|
|
displayPlane(m_ui->sixPointsHelp, "snow");
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2014-04-09 02:23:50 +02:00
|
|
|
m_ui->levelingHelp->setScene(new QGraphicsScene(this));
|
|
|
|
displayPlane(m_ui->levelingHelp, "snow");
|
2012-06-13 20:19:17 +02:00
|
|
|
// Must set up the UI (above) before setting up the UAVO mappings or refreshWidgetValues
|
|
|
|
// will be dealing with some null pointers
|
|
|
|
addUAVObject("RevoCalibration");
|
2013-05-03 02:17:44 +02:00
|
|
|
addUAVObject("EKFConfiguration");
|
2013-05-12 11:27:12 +02:00
|
|
|
addUAVObject("HomeLocation");
|
|
|
|
addUAVObject("AttitudeSettings");
|
2014-01-13 02:03:01 +01:00
|
|
|
addUAVObject("RevoSettings");
|
|
|
|
addUAVObject("AccelGyroSettings");
|
2012-06-13 20:19:17 +02:00
|
|
|
autoLoadWidgets();
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2014-01-13 02:03:01 +01:00
|
|
|
// connect the thermalCalibration model to UI
|
2014-01-17 18:58:35 +01:00
|
|
|
m_thermalCalibrationModel = new OpenPilot::ThermalCalibrationModel(this);
|
2014-01-13 02:03:01 +01:00
|
|
|
|
2014-01-13 02:35:41 +01:00
|
|
|
connect(m_ui->ThermalBiasStart, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnStart()));
|
|
|
|
connect(m_ui->ThermalBiasEnd, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnEnd()));
|
|
|
|
connect(m_ui->ThermalBiasCancel, SIGNAL(clicked()), m_thermalCalibrationModel, SLOT(btnAbort()));
|
2014-01-13 02:03:01 +01:00
|
|
|
|
2014-01-13 02:35:41 +01:00
|
|
|
connect(m_thermalCalibrationModel, SIGNAL(startEnabledChanged(bool)), m_ui->ThermalBiasStart, 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)));
|
2014-01-13 02:03:01 +01:00
|
|
|
|
2014-01-13 02:35:41 +01:00
|
|
|
connect(m_thermalCalibrationModel, SIGNAL(instructionsChanged(QString)), m_ui->label_thermalDescription, SLOT(setText(QString)));
|
2014-01-16 23:09:08 +01:00
|
|
|
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)));
|
2014-03-09 16:43:31 +01:00
|
|
|
// note: init for m_thermalCalibrationModel is done in showEvent to prevent cases wiht "Start" button not enabled due to some itming issue.
|
2014-01-13 02:03:01 +01:00
|
|
|
|
2011-12-24 20:57:10 +01:00
|
|
|
// Connect the signals
|
2012-06-14 06:07:23 +02:00
|
|
|
connect(m_ui->accelBiasStart, SIGNAL(clicked()), this, SLOT(doStartAccelGyroBiasCalibration()));
|
2014-04-09 02:22:48 +02:00
|
|
|
connect(m_ui->sixPointsStartAccel, SIGNAL(clicked()), this, SLOT(doStartSixPointCalibrationAccel()));
|
|
|
|
connect(m_ui->sixPointsStartMag, SIGNAL(clicked()), this, SLOT(doStartSixPointCalibrationMag()));
|
2011-12-24 20:57:10 +01:00
|
|
|
connect(m_ui->sixPointsSave, SIGNAL(clicked()), this, SLOT(savePositionData()));
|
2013-03-27 13:09:48 +01:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation()));
|
|
|
|
|
2014-01-01 22:49:04 +01:00
|
|
|
addWidgetBinding("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm);
|
2013-03-27 13:09:48 +01:00
|
|
|
|
2014-01-01 22:49:04 +01:00
|
|
|
addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->rollRotation, AttitudeSettings::BOARDROTATION_ROLL);
|
|
|
|
addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->pitchRotation, AttitudeSettings::BOARDROTATION_PITCH);
|
|
|
|
addWidgetBinding("AttitudeSettings", "BoardRotation", m_ui->yawRotation, AttitudeSettings::BOARDROTATION_YAW);
|
|
|
|
addWidgetBinding("AttitudeSettings", "AccelTau", m_ui->accelTau);
|
2013-05-12 11:27:12 +02:00
|
|
|
|
2013-03-27 13:09:48 +01:00
|
|
|
populateWidgets();
|
|
|
|
refreshWidgetsValues();
|
2013-05-12 11:27:12 +02:00
|
|
|
m_ui->tabWidget->setCurrentIndex(0);
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
|
|
|
ConfigRevoWidget::~ConfigRevoWidget()
|
|
|
|
{
|
|
|
|
// Do nothing
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
void ConfigRevoWidget::showEvent(QShowEvent *event)
|
|
|
|
{
|
|
|
|
Q_UNUSED(event)
|
|
|
|
// Thit fitInView method should only be called now, once the
|
|
|
|
// widget is shown, otherwise it cannot compute its values and
|
2012-06-13 19:37:17 +02:00
|
|
|
// the result is usually a sensorsBargraph that is way too small.
|
2014-04-09 01:15:08 +02:00
|
|
|
m_ui->sixPointsHelp->fitInView(m_ui->sixPointsHelp->scene()->sceneRect(), Qt::IgnoreAspectRatio);
|
2014-04-09 02:23:50 +02:00
|
|
|
m_ui->levelingHelp->fitInView(m_ui->levelingHelp->scene()->sceneRect(), Qt::IgnoreAspectRatio);
|
2014-02-06 01:40:22 +01:00
|
|
|
m_thermalCalibrationModel->init();
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
|
|
|
void ConfigRevoWidget::resizeEvent(QResizeEvent *event)
|
|
|
|
{
|
|
|
|
Q_UNUSED(event)
|
2014-04-09 01:15:08 +02:00
|
|
|
m_ui->sixPointsHelp->fitInView(m_ui->sixPointsHelp->scene()->sceneRect(), Qt::IgnoreAspectRatio);
|
2014-04-09 02:23:50 +02:00
|
|
|
m_ui->levelingHelp->fitInView(m_ui->levelingHelp->scene()->sceneRect(), Qt::IgnoreAspectRatio);
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
2013-05-12 11:27:12 +02:00
|
|
|
* Starts an accelerometer bias calibration.
|
|
|
|
*/
|
2012-06-14 06:07:23 +02:00
|
|
|
void ConfigRevoWidget::doStartAccelGyroBiasCalibration()
|
2011-12-24 20:57:10 +01:00
|
|
|
{
|
2013-05-12 11:27:12 +02:00
|
|
|
// Store and reset board rotation before calibration starts
|
|
|
|
isBoardRotationStored = false;
|
|
|
|
storeAndClearBoardRotation();
|
|
|
|
|
2011-12-24 20:57:10 +01:00
|
|
|
m_ui->accelBiasStart->setEnabled(false);
|
|
|
|
m_ui->accelBiasProgress->setValue(0);
|
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
|
2011-12-24 22:56:16 +01:00
|
|
|
Q_ASSERT(revoCalibration);
|
|
|
|
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
|
|
|
|
revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_FALSE;
|
|
|
|
revoCalibration->setData(revoCalibrationData);
|
|
|
|
revoCalibration->updated();
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2012-06-14 06:07:23 +02:00
|
|
|
// Disable gyro bias correction while calibrating
|
2013-05-12 11:27:12 +02:00
|
|
|
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
|
2012-06-14 06:07:23 +02:00
|
|
|
Q_ASSERT(attitudeSettings);
|
|
|
|
AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData();
|
|
|
|
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE;
|
|
|
|
attitudeSettings->setData(attitudeSettingsData);
|
|
|
|
attitudeSettings->updated();
|
|
|
|
|
2011-12-24 20:57:10 +01:00
|
|
|
accel_accum_x.clear();
|
|
|
|
accel_accum_y.clear();
|
|
|
|
accel_accum_z.clear();
|
2012-06-14 06:07:23 +02:00
|
|
|
gyro_accum_x.clear();
|
|
|
|
gyro_accum_y.clear();
|
|
|
|
gyro_accum_z.clear();
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2012-06-14 06:07:23 +02:00
|
|
|
UAVObject::Metadata mdata;
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2012-06-14 01:09:10 +02:00
|
|
|
/* Need to get as many accel updates as possible */
|
2013-05-18 19:36:45 +02:00
|
|
|
AccelState *accelState = AccelState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(accelState);
|
|
|
|
initialAccelStateMdata = accelState->getMetadata();
|
|
|
|
mdata = initialAccelStateMdata;
|
2012-05-04 04:09:25 +02:00
|
|
|
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
|
2011-12-24 20:57:10 +01:00
|
|
|
mdata.flightTelemetryUpdatePeriod = 100;
|
2013-05-18 19:36:45 +02:00
|
|
|
accelState->setMetadata(mdata);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(gyroState);
|
|
|
|
initialGyroStateMdata = gyroState->getMetadata();
|
|
|
|
mdata = initialGyroStateMdata;
|
2012-06-14 06:07:23 +02:00
|
|
|
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
|
|
|
|
mdata.flightTelemetryUpdatePeriod = 100;
|
2013-05-18 19:36:45 +02:00
|
|
|
gyroState->setMetadata(mdata);
|
2012-06-14 06:07:23 +02:00
|
|
|
|
2011-12-24 22:56:16 +01:00
|
|
|
// Now connect to the accels and mag updates, gather for 100 samples
|
2011-12-24 20:57:10 +01:00
|
|
|
collectingData = true;
|
2013-05-18 19:36:45 +02:00
|
|
|
connect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *)));
|
|
|
|
connect(gyroState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *)));
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
2013-05-12 11:27:12 +02:00
|
|
|
Updates the accel bias raw values
|
|
|
|
*/
|
2012-06-14 06:07:23 +02:00
|
|
|
void ConfigRevoWidget::doGetAccelGyroBiasData(UAVObject *obj)
|
2011-12-24 20:57:10 +01:00
|
|
|
{
|
2012-06-14 06:07:23 +02:00
|
|
|
QMutexLocker lock(&sensorsUpdateLock);
|
2013-05-12 11:27:12 +02:00
|
|
|
|
2012-06-14 06:07:23 +02:00
|
|
|
Q_UNUSED(lock);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
switch (obj->getObjID()) {
|
2013-05-18 19:36:45 +02:00
|
|
|
case AccelState::OBJID:
|
2012-06-14 06:07:23 +02:00
|
|
|
{
|
2013-05-18 19:36:45 +02:00
|
|
|
AccelState *accelState = AccelState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(accelState);
|
|
|
|
AccelState::DataFields accelStateData = accelState->getData();
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
accel_accum_x.append(accelStateData.x);
|
|
|
|
accel_accum_y.append(accelStateData.y);
|
|
|
|
accel_accum_z.append(accelStateData.z);
|
2012-06-14 06:07:23 +02:00
|
|
|
break;
|
|
|
|
}
|
2013-05-18 19:36:45 +02:00
|
|
|
case GyroState::OBJID:
|
2012-06-14 06:07:23 +02:00
|
|
|
{
|
2013-05-18 19:36:45 +02:00
|
|
|
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(gyroState);
|
|
|
|
GyroState::DataFields gyroStateData = gyroState->getData();
|
2012-06-14 06:07:23 +02:00
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
gyro_accum_x.append(gyroStateData.x);
|
|
|
|
gyro_accum_y.append(gyroStateData.y);
|
|
|
|
gyro_accum_z.append(gyroStateData.z);
|
2012-06-14 06:07:23 +02:00
|
|
|
break;
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
2012-06-14 06:07:23 +02:00
|
|
|
default:
|
|
|
|
Q_ASSERT(0);
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
2012-06-14 06:07:23 +02:00
|
|
|
// Work out the progress based on whichever has less
|
2013-05-12 11:27:12 +02:00
|
|
|
double p1 = (double)accel_accum_x.size() / (double)NOISE_SAMPLES;
|
|
|
|
double p2 = (double)accel_accum_y.size() / (double)NOISE_SAMPLES;
|
2012-06-14 06:07:23 +02:00
|
|
|
m_ui->accelBiasProgress->setValue(((p1 < p2) ? p1 : p2) * 100);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
if (accel_accum_x.size() >= NOISE_SAMPLES &&
|
|
|
|
gyro_accum_y.size() >= NOISE_SAMPLES &&
|
|
|
|
collectingData == true) {
|
2011-12-24 20:57:10 +01:00
|
|
|
collectingData = false;
|
2012-06-14 06:07:23 +02:00
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
AccelState *accelState = AccelState::GetInstance(getObjectManager());
|
|
|
|
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
|
2012-06-14 06:07:23 +02:00
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
disconnect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *)));
|
|
|
|
disconnect(gyroState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetAccelGyroBiasData(UAVObject *)));
|
2012-06-14 06:07:23 +02:00
|
|
|
|
2011-12-24 20:57:10 +01:00
|
|
|
m_ui->accelBiasStart->setEnabled(true);
|
|
|
|
|
2013-12-29 18:58:45 +01:00
|
|
|
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
|
2011-12-24 22:56:16 +01:00
|
|
|
Q_ASSERT(revoCalibration);
|
2013-12-26 16:56:54 +01:00
|
|
|
AccelGyroSettings *accelGyroSettings = AccelGyroSettings::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(accelGyroSettings);
|
|
|
|
|
|
|
|
|
2013-12-29 18:58:45 +01:00
|
|
|
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
|
2013-12-26 16:56:54 +01:00
|
|
|
AccelGyroSettings::DataFields accelGyroSettingsData = accelGyroSettings->getData();
|
|
|
|
|
2011-12-24 22:56:16 +01:00
|
|
|
revoCalibrationData.BiasCorrectedRaw = RevoCalibration::BIASCORRECTEDRAW_TRUE;
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2012-06-14 06:07:23 +02:00
|
|
|
// Update the biases based on collected data
|
2013-12-26 16:56:54 +01:00
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_X] += listMean(accel_accum_x);
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Y] += listMean(accel_accum_y);
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Z] += (listMean(accel_accum_z) + GRAVITY);
|
|
|
|
accelGyroSettingsData.gyro_bias[AccelGyroSettings::GYRO_BIAS_X] += listMean(gyro_accum_x);
|
|
|
|
accelGyroSettingsData.gyro_bias[AccelGyroSettings::GYRO_BIAS_Y] += listMean(gyro_accum_y);
|
|
|
|
accelGyroSettingsData.gyro_bias[AccelGyroSettings::GYRO_BIAS_Z] += listMean(gyro_accum_z);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2011-12-24 22:56:16 +01:00
|
|
|
revoCalibration->setData(revoCalibrationData);
|
|
|
|
revoCalibration->updated();
|
2013-12-26 16:56:54 +01:00
|
|
|
accelGyroSettings->setData(accelGyroSettingsData);
|
|
|
|
accelGyroSettings->updated();
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
|
2012-06-14 06:07:23 +02:00
|
|
|
Q_ASSERT(attitudeSettings);
|
|
|
|
AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData();
|
|
|
|
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE;
|
|
|
|
attitudeSettings->setData(attitudeSettingsData);
|
|
|
|
attitudeSettings->updated();
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
accelState->setMetadata(initialAccelStateMdata);
|
|
|
|
gyroState->setMetadata(initialGyroStateMdata);
|
2013-05-12 11:27:12 +02:00
|
|
|
|
|
|
|
// Recall saved board rotation
|
|
|
|
recallBoardRotation();
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
int LinearEquationsSolving(int nDim, double *pfMatr, double *pfVect, double *pfSolution)
|
2011-12-24 22:56:16 +01:00
|
|
|
{
|
2013-05-12 11:27:12 +02:00
|
|
|
double fMaxElem;
|
|
|
|
double fAcc;
|
|
|
|
|
|
|
|
int i, j, k, m;
|
|
|
|
|
|
|
|
for (k = 0; k < (nDim - 1); k++) { // base row of matrix
|
|
|
|
// search of line with max element
|
|
|
|
fMaxElem = fabs(pfMatr[k * nDim + k]);
|
|
|
|
m = k;
|
|
|
|
for (i = k + 1; i < nDim; i++) {
|
|
|
|
if (fMaxElem < fabs(pfMatr[i * nDim + k])) {
|
|
|
|
fMaxElem = pfMatr[i * nDim + k];
|
|
|
|
m = i;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// permutation of base line (index k) and max element line(index m)
|
|
|
|
if (m != k) {
|
|
|
|
for (i = k; i < nDim; i++) {
|
|
|
|
fAcc = pfMatr[k * nDim + i];
|
|
|
|
pfMatr[k * nDim + i] = pfMatr[m * nDim + i];
|
|
|
|
pfMatr[m * nDim + i] = fAcc;
|
|
|
|
}
|
|
|
|
fAcc = pfVect[k];
|
|
|
|
pfVect[k] = pfVect[m];
|
|
|
|
pfVect[m] = fAcc;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (pfMatr[k * nDim + k] == 0.) {
|
|
|
|
return 0; // needs improvement !!!
|
|
|
|
}
|
|
|
|
// triangulation of matrix with coefficients
|
|
|
|
for (j = (k + 1); j < nDim; j++) { // current row of matrix
|
|
|
|
fAcc = -pfMatr[j * nDim + k] / pfMatr[k * nDim + k];
|
|
|
|
for (i = k; i < nDim; i++) {
|
|
|
|
pfMatr[j * nDim + i] = pfMatr[j * nDim + i] + fAcc * pfMatr[k * nDim + i];
|
|
|
|
}
|
|
|
|
pfVect[j] = pfVect[j] + fAcc * pfVect[k]; // free member recalculation
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
for (k = (nDim - 1); k >= 0; k--) {
|
|
|
|
pfSolution[k] = pfVect[k];
|
|
|
|
for (i = (k + 1); i < nDim; i++) {
|
|
|
|
pfSolution[k] -= (pfMatr[k * nDim + i] * pfSolution[i]);
|
|
|
|
}
|
|
|
|
pfSolution[k] = pfSolution[k] / pfMatr[k * nDim + k];
|
|
|
|
}
|
|
|
|
|
|
|
|
return 1;
|
2011-12-24 22:56:16 +01:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
int SixPointInConstFieldCal(double ConstMag, double x[6], double y[6], double z[6], double S[3], double b[3])
|
2011-12-24 22:56:16 +01:00
|
|
|
{
|
2013-05-12 11:27:12 +02:00
|
|
|
int i;
|
|
|
|
double A[5][5];
|
|
|
|
double f[5], c[5];
|
|
|
|
double xp, yp, zp, Sx;
|
|
|
|
|
|
|
|
// Fill in matrix A -
|
|
|
|
// write six difference-in-magnitude equations of the form
|
|
|
|
// Sx^2(x2^2-x1^2) + 2*Sx*bx*(x2-x1) + Sy^2(y2^2-y1^2) + 2*Sy*by*(y2-y1) + Sz^2(z2^2-z1^2) + 2*Sz*bz*(z2-z1) = 0
|
|
|
|
// or in other words
|
|
|
|
// 2*Sx*bx*(x2-x1)/Sx^2 + Sy^2(y2^2-y1^2)/Sx^2 + 2*Sy*by*(y2-y1)/Sx^2 + Sz^2(z2^2-z1^2)/Sx^2 + 2*Sz*bz*(z2-z1)/Sx^2 = (x1^2-x2^2)
|
|
|
|
for (i = 0; i < 5; i++) {
|
|
|
|
A[i][0] = 2.0 * (x[i + 1] - x[i]);
|
|
|
|
A[i][1] = y[i + 1] * y[i + 1] - y[i] * y[i];
|
|
|
|
A[i][2] = 2.0 * (y[i + 1] - y[i]);
|
|
|
|
A[i][3] = z[i + 1] * z[i + 1] - z[i] * z[i];
|
|
|
|
A[i][4] = 2.0 * (z[i + 1] - z[i]);
|
|
|
|
f[i] = x[i] * x[i] - x[i + 1] * x[i + 1];
|
|
|
|
}
|
|
|
|
|
|
|
|
// solve for c0=bx/Sx, c1=Sy^2/Sx^2; c2=Sy*by/Sx^2, c3=Sz^2/Sx^2, c4=Sz*bz/Sx^2
|
|
|
|
if (!LinearEquationsSolving(5, (double *)A, f, c)) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// use one magnitude equation and c's to find Sx - doesn't matter which - all give the same answer
|
|
|
|
xp = x[0]; yp = y[0]; zp = z[0];
|
|
|
|
Sx = sqrt(ConstMag * ConstMag / (xp * xp + 2 * c[0] * xp + c[0] * c[0] + c[1] * yp * yp + 2 * c[2] * yp + c[2] * c[2] / c[1] + c[3] * zp * zp + 2 * c[4] * zp + c[4] * c[4] / c[3]));
|
|
|
|
|
|
|
|
S[0] = Sx;
|
|
|
|
b[0] = Sx * c[0];
|
|
|
|
S[1] = sqrt(c[1] * Sx * Sx);
|
|
|
|
b[1] = c[2] * Sx * Sx / S[1];
|
|
|
|
S[2] = sqrt(c[3] * Sx * Sx);
|
|
|
|
b[2] = c[4] * Sx * Sx / S[2];
|
|
|
|
|
|
|
|
return 1;
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
2012-06-14 17:01:05 +02:00
|
|
|
/********** Functions for six point calibration **************/
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2014-04-09 02:22:48 +02:00
|
|
|
void ConfigRevoWidget::doStartSixPointCalibrationMag(){
|
|
|
|
doStartSixPointCalibration(false, true);
|
|
|
|
}
|
|
|
|
void ConfigRevoWidget::doStartSixPointCalibrationAccel(){
|
|
|
|
doStartSixPointCalibration(true, false);
|
|
|
|
}
|
|
|
|
|
2011-12-24 20:57:10 +01:00
|
|
|
/**
|
2013-05-12 11:27:12 +02:00
|
|
|
* Called by the "Start" button. Sets up the meta data and enables the
|
|
|
|
* buttons to perform six point calibration of the magnetometer (optionally
|
|
|
|
* accel) to compute the scale and bias of this sensor based on the current
|
|
|
|
* home location magnetic strength.
|
|
|
|
*/
|
2014-04-09 17:35:30 +02:00
|
|
|
void ConfigRevoWidget::doStartSixPointCalibration(bool calibrateAccel, bool calibrateMag)
|
2011-12-24 22:56:16 +01:00
|
|
|
{
|
2014-04-09 17:35:30 +02:00
|
|
|
calibratingAccel = calibrateAccel;
|
|
|
|
calibratingMag = calibrateMag;
|
2013-05-12 11:27:12 +02:00
|
|
|
// Store and reset board rotation before calibration starts
|
|
|
|
isBoardRotationStored = false;
|
|
|
|
storeAndClearBoardRotation();
|
|
|
|
|
2013-12-29 18:58:45 +01:00
|
|
|
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
|
2013-05-12 11:27:12 +02:00
|
|
|
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
|
2013-12-26 16:56:54 +01:00
|
|
|
AccelGyroSettings *accelGyroSettings = AccelGyroSettings::GetInstance(getObjectManager());
|
2013-05-12 11:27:12 +02:00
|
|
|
|
2011-12-24 22:56:16 +01:00
|
|
|
Q_ASSERT(revoCalibration);
|
2012-05-28 16:19:03 +02:00
|
|
|
Q_ASSERT(homeLocation);
|
2013-12-29 18:58:45 +01:00
|
|
|
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
|
2012-05-28 16:19:03 +02:00
|
|
|
HomeLocation::DataFields homeLocationData = homeLocation->getData();
|
2013-12-26 16:56:54 +01:00
|
|
|
AccelGyroSettings::DataFields accelGyroSettingsData = accelGyroSettings->getData();
|
2012-05-28 16:19:03 +02:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
// check if Homelocation is set
|
|
|
|
if (!homeLocationData.Set) {
|
2012-05-28 16:19:03 +02:00
|
|
|
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;
|
|
|
|
}
|
2011-12-24 22:56:16 +01:00
|
|
|
|
|
|
|
// Calibration accel
|
2013-12-26 16:56:54 +01:00
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_X] = 1;
|
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_Y] = 1;
|
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_Z] = 1;
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_X] = 0;
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Y] = 0;
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Z] = 0;
|
2011-12-24 22:56:16 +01:00
|
|
|
|
2012-06-13 19:28:59 +02:00
|
|
|
accel_accum_x.clear();
|
|
|
|
accel_accum_y.clear();
|
|
|
|
accel_accum_z.clear();
|
|
|
|
|
2011-12-24 22:56:16 +01:00
|
|
|
// Calibration mag
|
2013-08-11 18:04:36 +02:00
|
|
|
// Reset the transformation matrix to identity
|
|
|
|
for(int i = 0; i < RevoCalibration::MAG_TRANSFORM_R2C2; i++){
|
|
|
|
revoCalibrationData.mag_transform[i] = 0;
|
|
|
|
}
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R0C0] = 1;
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R1C1] = 1;
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R2C2] = 1;
|
2013-05-12 11:27:12 +02:00
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = 0;
|
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = 0;
|
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = 0;
|
2011-12-24 22:56:16 +01:00
|
|
|
|
2012-07-25 18:26:37 +02:00
|
|
|
// Disable adaptive mag nulling
|
|
|
|
initialMagCorrectionRate = revoCalibrationData.MagBiasNullingRate;
|
|
|
|
revoCalibrationData.MagBiasNullingRate = 0;
|
|
|
|
|
2011-12-24 22:56:16 +01:00
|
|
|
revoCalibration->setData(revoCalibrationData);
|
2013-12-26 16:56:54 +01:00
|
|
|
accelGyroSettings->setData(accelGyroSettingsData);
|
2011-12-24 22:56:16 +01:00
|
|
|
|
2012-06-14 17:07:45 +02:00
|
|
|
Thread::usleep(100000);
|
2011-12-24 22:56:16 +01:00
|
|
|
|
2012-06-14 17:07:45 +02:00
|
|
|
gyro_accum_x.clear();
|
|
|
|
gyro_accum_y.clear();
|
|
|
|
gyro_accum_z.clear();
|
|
|
|
mag_accum_x.clear();
|
|
|
|
mag_accum_y.clear();
|
|
|
|
mag_accum_z.clear();
|
2011-12-24 22:56:16 +01:00
|
|
|
|
2012-06-15 20:15:21 +02:00
|
|
|
UAVObject::Metadata mdata;
|
|
|
|
|
2012-06-14 17:07:45 +02:00
|
|
|
/* Need to get as many accel updates as possible */
|
2013-05-18 19:36:45 +02:00
|
|
|
AccelState *accelState = AccelState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(accelState);
|
2012-06-14 17:07:45 +02:00
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
initialAccelStateMdata = accelState->getMetadata();
|
|
|
|
mdata = initialAccelStateMdata;
|
2012-06-14 17:07:45 +02:00
|
|
|
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
|
|
|
|
mdata.flightTelemetryUpdatePeriod = 100;
|
2013-05-18 19:36:45 +02:00
|
|
|
accelState->setMetadata(mdata);
|
2011-12-24 22:56:16 +01:00
|
|
|
|
2012-06-14 17:07:45 +02:00
|
|
|
/* Need to get as many mag updates as possible */
|
2013-05-20 10:33:02 +02:00
|
|
|
MagState *mag = MagState::GetInstance(getObjectManager());
|
2012-06-14 17:07:45 +02:00
|
|
|
Q_ASSERT(mag);
|
2013-05-20 10:33:02 +02:00
|
|
|
initialMagStateMdata = mag->getMetadata();
|
|
|
|
mdata = initialMagStateMdata;
|
2012-06-14 17:07:45 +02:00
|
|
|
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
|
|
|
|
mdata.flightTelemetryUpdatePeriod = 100;
|
|
|
|
mag->setMetadata(mdata);
|
|
|
|
|
|
|
|
/* Show instructions and enable controls */
|
|
|
|
m_ui->sixPointCalibInstructions->clear();
|
|
|
|
m_ui->sixPointCalibInstructions->append("Place horizontally and click save position...");
|
2014-04-09 02:23:50 +02:00
|
|
|
displayPlane(m_ui->sixPointsHelp, "plane-horizontal");
|
2014-04-09 02:22:48 +02:00
|
|
|
m_ui->sixPointsStartAccel->setEnabled(false);
|
|
|
|
m_ui->sixPointsStartMag->setEnabled(false);
|
2012-06-14 17:07:45 +02:00
|
|
|
m_ui->sixPointsSave->setEnabled(true);
|
|
|
|
position = 0;
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
2012-06-14 17:01:05 +02:00
|
|
|
/**
|
2013-05-12 11:27:12 +02:00
|
|
|
* Saves the data from the aircraft in one of six positions.
|
|
|
|
* This is called when they click "save position" and starts
|
|
|
|
* averaging data for this position.
|
|
|
|
*/
|
2012-06-14 17:01:05 +02:00
|
|
|
void ConfigRevoWidget::savePositionData()
|
|
|
|
{
|
|
|
|
QMutexLocker lock(&sensorsUpdateLock);
|
2013-05-12 11:27:12 +02:00
|
|
|
|
2012-06-14 17:01:05 +02:00
|
|
|
m_ui->sixPointsSave->setEnabled(false);
|
|
|
|
|
|
|
|
accel_accum_x.clear();
|
|
|
|
accel_accum_y.clear();
|
|
|
|
accel_accum_z.clear();
|
|
|
|
mag_accum_x.clear();
|
|
|
|
mag_accum_y.clear();
|
|
|
|
mag_accum_z.clear();
|
|
|
|
|
|
|
|
collectingData = true;
|
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
AccelState *accelState = AccelState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(accelState);
|
2013-05-20 10:33:02 +02:00
|
|
|
MagState *mag = MagState::GetInstance(getObjectManager());
|
2012-06-14 17:01:05 +02:00
|
|
|
Q_ASSERT(mag);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-18 19:36:45 +02:00
|
|
|
connect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *)));
|
2013-05-12 11:27:12 +02:00
|
|
|
connect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *)));
|
2012-06-14 17:01:05 +02:00
|
|
|
|
|
|
|
m_ui->sixPointCalibInstructions->append("Hold...");
|
|
|
|
}
|
2011-12-24 20:57:10 +01:00
|
|
|
|
|
|
|
/**
|
2013-05-12 11:27:12 +02:00
|
|
|
* Grab a sample of mag (optionally accel) data while in this position and
|
|
|
|
* store it for averaging. When sufficient points are collected advance
|
|
|
|
* to the next position (give message to user) or compute the scale and bias
|
|
|
|
*/
|
|
|
|
void ConfigRevoWidget::doGetSixPointCalibrationMeasurement(UAVObject *obj)
|
2011-12-24 20:57:10 +01:00
|
|
|
{
|
2012-06-14 17:01:05 +02:00
|
|
|
QMutexLocker lock(&sensorsUpdateLock);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2012-06-14 17:01:05 +02:00
|
|
|
// This is necessary to prevent a race condition on disconnect signal and another update
|
|
|
|
if (collectingData == true) {
|
2013-05-18 19:36:45 +02:00
|
|
|
if (obj->getObjID() == 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);
|
2014-04-09 17:35:30 +02:00
|
|
|
|
2013-05-20 10:33:02 +02:00
|
|
|
} else if (obj->getObjID() == MagState::OBJID) {
|
|
|
|
MagState *mag = MagState::GetInstance(getObjectManager());
|
2012-06-14 17:01:05 +02:00
|
|
|
Q_ASSERT(mag);
|
2013-05-20 10:33:02 +02:00
|
|
|
MagState::DataFields magData = mag->getData();
|
2012-06-14 17:01:05 +02:00
|
|
|
mag_accum_x.append(magData.x);
|
|
|
|
mag_accum_y.append(magData.y);
|
|
|
|
mag_accum_z.append(magData.z);
|
|
|
|
} else {
|
|
|
|
Q_ASSERT(0);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-04-09 01:12:31 +02:00
|
|
|
if (accel_accum_x.size() >= SAMPLE_SIZE && mag_accum_x.size() >= SAMPLE_SIZE && collectingData == true) {
|
2014-04-09 17:35:30 +02:00
|
|
|
|
2012-06-14 17:01:05 +02:00
|
|
|
collectingData = false;
|
|
|
|
|
|
|
|
m_ui->sixPointsSave->setEnabled(true);
|
|
|
|
|
|
|
|
// Store the mean for this position for the accel
|
2013-05-18 19:36:45 +02:00
|
|
|
AccelState *accelState = AccelState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(accelState);
|
|
|
|
disconnect(accelState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *)));
|
2012-06-14 17:01:05 +02:00
|
|
|
accel_data_x[position] = listMean(accel_accum_x);
|
|
|
|
accel_data_y[position] = listMean(accel_accum_y);
|
|
|
|
accel_data_z[position] = listMean(accel_accum_z);
|
|
|
|
|
|
|
|
// Store the mean for this position for the mag
|
2013-05-20 10:33:02 +02:00
|
|
|
MagState *mag = MagState::GetInstance(getObjectManager());
|
2012-06-14 17:01:05 +02:00
|
|
|
Q_ASSERT(mag);
|
2013-05-12 11:27:12 +02:00
|
|
|
disconnect(mag, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(doGetSixPointCalibrationMeasurement(UAVObject *)));
|
2012-06-14 17:01:05 +02:00
|
|
|
mag_data_x[position] = listMean(mag_accum_x);
|
|
|
|
mag_data_y[position] = listMean(mag_accum_y);
|
|
|
|
mag_data_z[position] = listMean(mag_accum_z);
|
|
|
|
|
|
|
|
position = (position + 1) % 6;
|
2013-05-12 11:27:12 +02:00
|
|
|
if (position == 1) {
|
2012-06-14 17:01:05 +02:00
|
|
|
m_ui->sixPointCalibInstructions->append("Place with left side down and click save position...");
|
2014-04-09 02:23:50 +02:00
|
|
|
displayPlane(m_ui->sixPointsHelp, "plane-left");
|
2012-06-14 17:01:05 +02:00
|
|
|
}
|
2013-05-12 11:27:12 +02:00
|
|
|
if (position == 2) {
|
2012-06-14 17:01:05 +02:00
|
|
|
m_ui->sixPointCalibInstructions->append("Place upside down and click save position...");
|
2014-04-09 02:23:50 +02:00
|
|
|
displayPlane(m_ui->sixPointsHelp, "plane-flip");
|
2012-06-14 17:01:05 +02:00
|
|
|
}
|
2013-05-12 11:27:12 +02:00
|
|
|
if (position == 3) {
|
2012-06-14 17:01:05 +02:00
|
|
|
m_ui->sixPointCalibInstructions->append("Place with right side down and click save position...");
|
2014-04-09 02:23:50 +02:00
|
|
|
displayPlane(m_ui->sixPointsHelp, "plane-right");
|
2012-06-14 17:01:05 +02:00
|
|
|
}
|
2013-05-12 11:27:12 +02:00
|
|
|
if (position == 4) {
|
2012-06-14 17:01:05 +02:00
|
|
|
m_ui->sixPointCalibInstructions->append("Place with nose up and click save position...");
|
2014-04-09 02:23:50 +02:00
|
|
|
displayPlane(m_ui->sixPointsHelp, "plane-up");
|
2012-06-14 17:01:05 +02:00
|
|
|
}
|
2013-05-12 11:27:12 +02:00
|
|
|
if (position == 5) {
|
2012-06-14 17:01:05 +02:00
|
|
|
m_ui->sixPointCalibInstructions->append("Place with nose down and click save position...");
|
2014-04-09 02:23:50 +02:00
|
|
|
displayPlane(m_ui->sixPointsHelp, "plane-down");
|
2012-06-14 17:01:05 +02:00
|
|
|
}
|
2013-05-12 11:27:12 +02:00
|
|
|
if (position == 0) {
|
2014-04-09 17:35:30 +02:00
|
|
|
computeScaleBias(calibratingMag, calibratingAccel);
|
2014-04-09 02:23:50 +02:00
|
|
|
m_ui->sixPointsStartAccel->setEnabled(true);
|
|
|
|
m_ui->sixPointsStartMag->setEnabled(true);
|
2012-06-14 17:01:05 +02:00
|
|
|
m_ui->sixPointsSave->setEnabled(false);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2012-06-14 17:01:05 +02:00
|
|
|
/* Cleanup original settings */
|
2013-05-18 19:36:45 +02:00
|
|
|
accelState->setMetadata(initialAccelStateMdata);
|
2014-04-09 17:35:30 +02:00
|
|
|
|
2013-05-20 10:33:02 +02:00
|
|
|
mag->setMetadata(initialMagStateMdata);
|
2013-05-12 11:27:12 +02:00
|
|
|
|
|
|
|
// Recall saved board rotation
|
|
|
|
recallBoardRotation();
|
2012-06-14 17:01:05 +02:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2011-12-24 20:57:10 +01:00
|
|
|
|
|
|
|
/**
|
2013-05-12 11:27:12 +02:00
|
|
|
* Computes the scale and bias for the magnetomer and (compile option)
|
|
|
|
* for the accel once all the data has been collected in 6 positions.
|
|
|
|
*/
|
2014-04-09 17:35:30 +02:00
|
|
|
void ConfigRevoWidget::computeScaleBias(bool mag, bool accel)
|
2011-12-24 20:57:10 +01:00
|
|
|
{
|
2013-05-12 11:27:12 +02:00
|
|
|
double S[3], b[3];
|
|
|
|
double Be_length;
|
2013-12-26 16:56:54 +01:00
|
|
|
AccelGyroSettings *accelGyroSettings = AccelGyroSettings::GetInstance(getObjectManager());
|
2013-12-29 18:58:45 +01:00
|
|
|
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
|
2013-05-12 11:27:12 +02:00
|
|
|
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
|
|
|
|
|
|
|
|
Q_ASSERT(revoCalibration);
|
|
|
|
Q_ASSERT(homeLocation);
|
2013-12-26 16:56:54 +01:00
|
|
|
AccelGyroSettings::DataFields accelGyroSettingsData = accelGyroSettings->getData();
|
2013-12-29 18:58:45 +01:00
|
|
|
RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData();
|
2013-05-12 11:27:12 +02:00
|
|
|
HomeLocation::DataFields homeLocationData = homeLocation->getData();
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
// Calibration accel
|
2014-04-09 17:35:30 +02:00
|
|
|
if(accel) {
|
|
|
|
SixPointInConstFieldCal(homeLocationData.g_e, accel_data_x, accel_data_y, accel_data_z, S, b);
|
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_X] = fabs(S[0]);
|
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_Y] = fabs(S[1]);
|
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_Z] = fabs(S[2]);
|
|
|
|
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_X] = -sign(S[0]) * b[0];
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Y] = -sign(S[1]) * b[1];
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Z] = -sign(S[2]) * b[2];
|
|
|
|
}
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
// Calibration mag
|
2014-04-09 17:35:30 +02:00
|
|
|
if(mag){
|
|
|
|
Be_length = sqrt(pow(homeLocationData.Be[0], 2) + pow(homeLocationData.Be[1], 2) + pow(homeLocationData.Be[2], 2));
|
|
|
|
SixPointInConstFieldCal(Be_length, mag_data_x, mag_data_y, mag_data_z, S, b);
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R0C0] = fabs(S[0]);
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R1C1] = fabs(S[1]);
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R2C2] = fabs(S[2]);
|
|
|
|
|
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] = -sign(S[0]) * b[0];
|
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] = -sign(S[1]) * b[1];
|
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] = -sign(S[2]) * b[2];
|
|
|
|
}
|
2013-05-12 11:27:12 +02:00
|
|
|
// Restore the previous setting
|
|
|
|
revoCalibrationData.MagBiasNullingRate = initialMagCorrectionRate;
|
2012-06-14 17:01:05 +02:00
|
|
|
|
2014-04-09 17:35:30 +02:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
bool good_calibration = true;
|
|
|
|
|
|
|
|
// Check the mag calibration is good
|
2014-04-09 17:35:30 +02:00
|
|
|
if(mag){
|
|
|
|
good_calibration &= revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R0C0] ==
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R0C0];
|
|
|
|
good_calibration &= revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R1C1] ==
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R1C1];
|
|
|
|
good_calibration &= revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R2C2] ==
|
|
|
|
revoCalibrationData.mag_transform[RevoCalibration::MAG_TRANSFORM_R2C2];
|
|
|
|
good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X] ==
|
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_X];
|
|
|
|
good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y] ==
|
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Y];
|
|
|
|
good_calibration &= revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z] ==
|
|
|
|
revoCalibrationData.mag_bias[RevoCalibration::MAG_BIAS_Z];
|
|
|
|
}
|
2013-05-12 11:27:12 +02:00
|
|
|
// Check the accel calibration is good
|
2014-04-09 17:35:30 +02:00
|
|
|
if(accel){
|
|
|
|
good_calibration &= accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_X] ==
|
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_X];
|
|
|
|
good_calibration &= accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_Y] ==
|
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_Y];
|
|
|
|
good_calibration &= accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_Z] ==
|
|
|
|
accelGyroSettingsData.accel_scale[AccelGyroSettings::ACCEL_SCALE_Z];
|
|
|
|
good_calibration &= accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_X] ==
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_X];
|
|
|
|
good_calibration &= accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Y] ==
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Y];
|
|
|
|
good_calibration &= accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Z] ==
|
|
|
|
accelGyroSettingsData.accel_bias[AccelGyroSettings::ACCEL_BIAS_Z];
|
2013-05-12 11:27:12 +02:00
|
|
|
}
|
|
|
|
if (good_calibration) {
|
|
|
|
revoCalibration->setData(revoCalibrationData);
|
2013-12-26 16:56:54 +01:00
|
|
|
accelGyroSettings->setData(accelGyroSettingsData);
|
2014-04-09 17:35:30 +02:00
|
|
|
m_ui->sixPointCalibInstructions->append("Computed sensor scale and bias...");
|
2013-05-12 11:27:12 +02:00
|
|
|
} else {
|
2013-12-29 18:58:45 +01:00
|
|
|
revoCalibrationData = revoCalibration->getData();
|
2013-12-26 16:56:54 +01:00
|
|
|
accelGyroSettingsData = accelGyroSettings->getData();
|
2013-05-12 11:27:12 +02:00
|
|
|
m_ui->sixPointCalibInstructions->append("Bad calibration. Please repeat.");
|
|
|
|
}
|
|
|
|
position = -1; // set to run again
|
|
|
|
}
|
|
|
|
|
|
|
|
void ConfigRevoWidget::storeAndClearBoardRotation()
|
|
|
|
{
|
2013-05-18 14:17:26 +02:00
|
|
|
if (!isBoardRotationStored) {
|
2013-05-12 11:27:12 +02:00
|
|
|
// Store current board rotation
|
|
|
|
isBoardRotationStored = true;
|
|
|
|
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(attitudeSettings);
|
2013-05-18 14:17:26 +02:00
|
|
|
AttitudeSettings::DataFields data = attitudeSettings->getData();
|
|
|
|
storedBoardRotation[AttitudeSettings::BOARDROTATION_YAW] = data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW];
|
|
|
|
storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL];
|
2013-05-12 11:27:12 +02:00
|
|
|
storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH];
|
|
|
|
|
|
|
|
// Set board rotation to no rotation
|
2013-05-18 14:17:26 +02:00
|
|
|
data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = 0;
|
|
|
|
data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = 0;
|
|
|
|
data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = 0;
|
2013-05-12 11:27:12 +02:00
|
|
|
attitudeSettings->setData(data);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void ConfigRevoWidget::recallBoardRotation()
|
|
|
|
{
|
2013-05-18 14:17:26 +02:00
|
|
|
if (isBoardRotationStored) {
|
2013-05-12 11:27:12 +02:00
|
|
|
// Recall current board rotation
|
|
|
|
isBoardRotationStored = false;
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(attitudeSettings);
|
2013-05-18 14:17:26 +02:00
|
|
|
AttitudeSettings::DataFields data = attitudeSettings->getData();
|
|
|
|
data.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = storedBoardRotation[AttitudeSettings::BOARDROTATION_YAW];
|
|
|
|
data.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = storedBoardRotation[AttitudeSettings::BOARDROTATION_ROLL];
|
2013-05-12 11:27:12 +02:00
|
|
|
data.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = storedBoardRotation[AttitudeSettings::BOARDROTATION_PITCH];
|
|
|
|
attitudeSettings->setData(data);
|
|
|
|
}
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
2012-06-14 17:01:05 +02:00
|
|
|
/**
|
2013-05-12 11:27:12 +02:00
|
|
|
Rotate the paper plane
|
|
|
|
*/
|
2014-04-09 02:23:50 +02:00
|
|
|
void ConfigRevoWidget::displayPlane(QGraphicsView *view, QString elementID)
|
2012-06-14 17:01:05 +02:00
|
|
|
{
|
2014-04-09 02:23:50 +02:00
|
|
|
view->scene()->clear();
|
2014-04-09 01:15:08 +02:00
|
|
|
QPixmap pixmap = QPixmap(":/configgadget/images/calibration/" + elementID + ".png");
|
2014-04-09 02:23:50 +02:00
|
|
|
view->scene()->addPixmap(pixmap);
|
|
|
|
view->setSceneRect(pixmap.rect());
|
|
|
|
view->fitInView(view->scene()->sceneRect(), Qt::IgnoreAspectRatio);
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
2012-06-14 01:14:20 +02:00
|
|
|
|
2012-06-14 17:01:05 +02:00
|
|
|
/********** UI Functions *************/
|
2011-12-24 20:57:10 +01:00
|
|
|
|
|
|
|
/**
|
2013-05-12 11:27:12 +02:00
|
|
|
* Called by the ConfigTaskWidget parent when RevoCalibration is updated
|
|
|
|
* to update the UI
|
|
|
|
*/
|
2013-03-27 13:09:48 +01:00
|
|
|
void ConfigRevoWidget::refreshWidgetsValues(UAVObject *object)
|
2011-12-24 20:57:10 +01:00
|
|
|
{
|
2013-03-27 13:09:48 +01:00
|
|
|
ConfigTaskWidget::refreshWidgetsValues(object);
|
|
|
|
|
2014-04-09 02:22:48 +02:00
|
|
|
m_ui->sixPointsStartAccel->setEnabled(true);
|
|
|
|
m_ui->sixPointsStartMag->setEnabled(true);
|
2011-12-24 20:57:10 +01:00
|
|
|
m_ui->accelBiasStart->setEnabled(true);
|
|
|
|
m_ui->calibInstructions->setText(QString("Press \"Start\" above to calibrate."));
|
2013-05-12 11:27:12 +02:00
|
|
|
|
|
|
|
m_ui->isSetCheckBox->setEnabled(false);
|
|
|
|
|
|
|
|
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(homeLocation);
|
|
|
|
HomeLocation::DataFields homeLocationData = homeLocation->getData();
|
|
|
|
|
|
|
|
QString beStr = QString("%1:%2:%3").arg(QString::number(homeLocationData.Be[0]), QString::number(homeLocationData.Be[1]), QString::number(homeLocationData.Be[2]));
|
|
|
|
m_ui->beBox->setText(beStr);
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
2013-05-12 11:27:12 +02:00
|
|
|
void ConfigRevoWidget::clearHomeLocation()
|
|
|
|
{
|
|
|
|
HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager());
|
|
|
|
|
|
|
|
Q_ASSERT(homeLocation);
|
|
|
|
HomeLocation::DataFields homeLocationData;
|
|
|
|
homeLocationData.Latitude = 0;
|
|
|
|
homeLocationData.Longitude = 0;
|
|
|
|
homeLocationData.Altitude = 0;
|
|
|
|
homeLocationData.Be[0] = 0;
|
|
|
|
homeLocationData.Be[1] = 0;
|
|
|
|
homeLocationData.Be[2] = 0;
|
|
|
|
homeLocationData.g_e = 9.81f;
|
|
|
|
homeLocationData.Set = HomeLocation::SET_FALSE;
|
|
|
|
homeLocation->setData(homeLocationData);
|
|
|
|
}
|