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>
|
2014-04-10 22:43:47 +02:00
|
|
|
#include <attitudestate.h>
|
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
|
|
|
|
|
|
|
#include "assertions.h"
|
|
|
|
#include "calibration.h"
|
2014-04-11 00:46:44 +02:00
|
|
|
#include "calibration/calibrationutils.h"
|
2011-12-24 20:57:10 +01:00
|
|
|
#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
|
2014-04-10 17:30:33 +02:00
|
|
|
m_ui->calibrationVisualHelp->setScene(new QGraphicsScene(this));
|
|
|
|
displayVisualHelp("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
|
|
|
|
2014-04-11 00:46:44 +02:00
|
|
|
m_sixPointCalibrationModel = new OpenPilot::SixPointCalibrationModel(this);
|
|
|
|
// six point calibrations
|
|
|
|
connect(m_ui->sixPointsStartAccel, SIGNAL(clicked()), m_sixPointCalibrationModel, SLOT(accelStart()));
|
|
|
|
connect(m_ui->sixPointsStartMag, SIGNAL(clicked()), m_sixPointCalibrationModel, SLOT(magStart()));
|
|
|
|
connect(m_ui->sixPointsSave, SIGNAL(clicked()), m_sixPointCalibrationModel, SLOT(savePositionData()));
|
|
|
|
|
|
|
|
connect(m_sixPointCalibrationModel, SIGNAL(disableAllCalibrations()), this, SLOT(disableAllCalibrations()));
|
|
|
|
connect(m_sixPointCalibrationModel, SIGNAL(enableAllCalibrations()), this, SLOT(enableAllCalibrations()));
|
|
|
|
connect(m_sixPointCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation()));
|
|
|
|
connect(m_sixPointCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation()));
|
|
|
|
connect(m_sixPointCalibrationModel, SIGNAL(displayInstructions(QString, bool)), this, SLOT(displayInstructions(QString, bool)));
|
|
|
|
connect(m_sixPointCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
|
|
|
|
connect(m_sixPointCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->sixPointsSave, SLOT(setEnabled(bool)));
|
|
|
|
|
2011-12-24 20:57:10 +01:00
|
|
|
// Connect the signals
|
2014-04-10 17:30:33 +02:00
|
|
|
// gyro zero calibration
|
2014-04-10 22:43:47 +02:00
|
|
|
connect(m_ui->gyroBiasStart, SIGNAL(clicked()), this, SLOT(gyroCalibrationStart()));
|
2014-04-10 17:30:33 +02:00
|
|
|
|
|
|
|
// level calibration
|
|
|
|
connect(m_ui->boardLevelStart, SIGNAL(clicked()), this, SLOT(levelCalibrationStart()));
|
2014-04-10 22:43:47 +02:00
|
|
|
connect(m_ui->boardLevelSavePos, SIGNAL(clicked()), this, SLOT(levelCalibrationSavePosition()));
|
2014-04-10 17:30:33 +02:00
|
|
|
|
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);
|
2014-04-10 17:30:33 +02:00
|
|
|
enableAllCalibrations();
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
|
|
|
ConfigRevoWidget::~ConfigRevoWidget()
|
|
|
|
{
|
|
|
|
// Do nothing
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
void ConfigRevoWidget::showEvent(QShowEvent *event)
|
|
|
|
{
|
2014-04-10 17:30:33 +02:00
|
|
|
Q_UNUSED(event);
|
2011-12-24 20:57:10 +01:00
|
|
|
// 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-10 22:43:47 +02:00
|
|
|
m_ui->calibrationVisualHelp->fitInView(m_ui->calibrationVisualHelp->scene()->sceneRect(), Qt::KeepAspectRatioByExpanding);
|
2014-02-06 01:40:22 +01:00
|
|
|
m_thermalCalibrationModel->init();
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
|
|
|
void ConfigRevoWidget::resizeEvent(QResizeEvent *event)
|
|
|
|
{
|
2014-04-10 17:30:33 +02:00
|
|
|
Q_UNUSED(event);
|
2014-04-10 22:43:47 +02:00
|
|
|
m_ui->calibrationVisualHelp->fitInView(m_ui->calibrationVisualHelp->scene()->sceneRect(), Qt::KeepAspectRatioByExpanding);
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
2014-04-10 22:43:47 +02:00
|
|
|
/******* gyro bias zero ******/
|
|
|
|
void ConfigRevoWidget::gyroCalibrationStart()
|
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();
|
|
|
|
|
2014-04-10 17:30:33 +02:00
|
|
|
disableAllCalibrations();
|
2014-04-10 22:43:47 +02:00
|
|
|
m_ui->gyroBiasProgress->setValue(0);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
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();
|
|
|
|
|
|
|
|
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
|
|
|
|
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;
|
2014-04-10 22:43:47 +02:00
|
|
|
connect(gyroState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(gyroBiasCalibrationGetSample(UAVObject *)));
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
2014-04-10 22:43:47 +02:00
|
|
|
Updates the gyro bias raw values
|
2013-05-12 11:27:12 +02:00
|
|
|
*/
|
2014-04-10 22:43:47 +02:00
|
|
|
void ConfigRevoWidget::gyroBiasCalibrationGetSample(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 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
|
2014-04-10 22:43:47 +02:00
|
|
|
double p1 = (double)gyro_accum_x.size() / (double)NOISE_SAMPLES;
|
|
|
|
double p2 = (double)gyro_accum_y.size() / (double)NOISE_SAMPLES;
|
|
|
|
m_ui->gyroBiasProgress->setValue(((p1 < p2) ? p1 : p2) * 50);
|
2011-12-24 20:57:10 +01:00
|
|
|
|
2014-04-10 22:43:47 +02:00
|
|
|
if (gyro_accum_y.size() >= 2 * NOISE_SAMPLES &&
|
2013-05-12 11:27:12 +02:00
|
|
|
collectingData == true) {
|
2011-12-24 20:57:10 +01:00
|
|
|
collectingData = false;
|
2012-06-14 06:07:23 +02:00
|
|
|
|
2014-04-11 00:46:44 +02:00
|
|
|
GyroState *gyroState = GyroState::GetInstance(getObjectManager());
|
2012-06-14 06:07:23 +02:00
|
|
|
|
2014-04-10 17:30:33 +02:00
|
|
|
disconnect(gyroState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(levelCalibrationGetSample(UAVObject *)));
|
2012-06-14 06:07:23 +02:00
|
|
|
|
2014-04-10 17:30:33 +02:00
|
|
|
enableAllCalibrations();
|
2011-12-24 20:57:10 +01:00
|
|
|
|
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
|
|
|
|
2014-04-10 22:43:47 +02:00
|
|
|
// Update biases based on collected data
|
2014-04-11 00:46:44 +02:00
|
|
|
accelGyroSettingsData.gyro_bias[AccelGyroSettings::GYRO_BIAS_X] += OpenPilot::CalibrationUtils::listMean(gyro_accum_x);
|
|
|
|
accelGyroSettingsData.gyro_bias[AccelGyroSettings::GYRO_BIAS_Y] += OpenPilot::CalibrationUtils::listMean(gyro_accum_y);
|
|
|
|
accelGyroSettingsData.gyro_bias[AccelGyroSettings::GYRO_BIAS_Z] += OpenPilot::CalibrationUtils::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
|
|
|
gyroState->setMetadata(initialGyroStateMdata);
|
2013-05-12 11:27:12 +02:00
|
|
|
|
|
|
|
// Recall saved board rotation
|
|
|
|
recallBoardRotation();
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-04-10 22:43:47 +02:00
|
|
|
|
|
|
|
/******* Level calibration *******/
|
|
|
|
/**
|
|
|
|
* Starts an accelerometer bias calibration.
|
|
|
|
*/
|
|
|
|
void ConfigRevoWidget::levelCalibrationStart()
|
|
|
|
{
|
|
|
|
// Store and reset board rotation before calibration starts
|
|
|
|
|
|
|
|
disableAllCalibrations();
|
|
|
|
m_ui->boardLevelProgress->setValue(0);
|
|
|
|
|
|
|
|
rot_data_pitch = 0;
|
2014-04-11 00:46:44 +02:00
|
|
|
rot_data_roll = 0;
|
2014-04-10 22:43:47 +02:00
|
|
|
UAVObject::Metadata mdata;
|
|
|
|
|
|
|
|
AttitudeState *attitudeState = AttitudeState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(attitudeState);
|
|
|
|
initialAttitudeStateMdata = attitudeState->getMetadata();
|
|
|
|
mdata = initialAttitudeStateMdata;
|
|
|
|
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
|
|
|
|
mdata.flightTelemetryUpdatePeriod = 100;
|
|
|
|
attitudeState->setMetadata(mdata);
|
|
|
|
|
|
|
|
/* Show instructions and enable controls */
|
|
|
|
displayInstructions("Place horizontally and click save position...", true);
|
|
|
|
displayVisualHelp("plane-horizontal");
|
|
|
|
disableAllCalibrations();
|
|
|
|
m_ui->boardLevelSavePos->setEnabled(true);
|
|
|
|
position = 0;
|
|
|
|
}
|
|
|
|
|
2014-04-11 00:46:44 +02:00
|
|
|
void ConfigRevoWidget::levelCalibrationSavePosition()
|
|
|
|
{
|
2014-04-10 22:43:47 +02:00
|
|
|
QMutexLocker lock(&sensorsUpdateLock);
|
2014-04-11 00:46:44 +02:00
|
|
|
|
2014-04-10 22:43:47 +02:00
|
|
|
Q_UNUSED(lock);
|
|
|
|
|
|
|
|
m_ui->boardLevelSavePos->setEnabled(false);
|
|
|
|
|
|
|
|
rot_accum_pitch.clear();
|
|
|
|
rot_accum_roll.clear();
|
|
|
|
|
|
|
|
collectingData = true;
|
|
|
|
|
|
|
|
AttitudeState *attitudeState = AttitudeState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(attitudeState);
|
|
|
|
connect(attitudeState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(levelCalibrationGetSample(UAVObject *)));
|
|
|
|
|
|
|
|
displayInstructions("Hold...");
|
|
|
|
}
|
|
|
|
|
|
|
|
/**
|
|
|
|
Updates the accel bias raw values
|
|
|
|
*/
|
|
|
|
void ConfigRevoWidget::levelCalibrationGetSample(UAVObject *obj)
|
|
|
|
{
|
|
|
|
QMutexLocker lock(&sensorsUpdateLock);
|
2014-04-11 00:46:44 +02:00
|
|
|
|
2014-04-10 22:43:47 +02:00
|
|
|
Q_UNUSED(lock);
|
|
|
|
|
|
|
|
switch (obj->getObjID()) {
|
|
|
|
case AttitudeState::OBJID:
|
|
|
|
{
|
|
|
|
AttitudeState *attitudeState = AttitudeState::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(attitudeState);
|
|
|
|
AttitudeState::DataFields attitudeStateData = attitudeState->getData();
|
|
|
|
rot_accum_roll.append(attitudeStateData.Roll);
|
|
|
|
rot_accum_pitch.append(attitudeStateData.Pitch);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
default:
|
|
|
|
Q_ASSERT(0);
|
|
|
|
}
|
|
|
|
|
|
|
|
// Work out the progress based on whichever has less
|
|
|
|
double p1 = (double)rot_accum_roll.size() / (double)NOISE_SAMPLES;
|
|
|
|
m_ui->boardLevelProgress->setValue(p1 * 100);
|
|
|
|
|
|
|
|
if (rot_accum_roll.size() >= NOISE_SAMPLES &&
|
|
|
|
collectingData == true) {
|
|
|
|
collectingData = false;
|
|
|
|
|
|
|
|
AttitudeState *attitudeState = AttitudeState::GetInstance(getObjectManager());
|
|
|
|
|
|
|
|
disconnect(attitudeState, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(levelCalibrationGetSample(UAVObject *)));
|
|
|
|
|
|
|
|
position++;
|
2014-04-11 00:46:44 +02:00
|
|
|
switch (position) {
|
2014-04-10 22:43:47 +02:00
|
|
|
case 1:
|
2014-04-11 00:46:44 +02:00
|
|
|
rot_data_pitch = OpenPilot::CalibrationUtils::listMean(rot_accum_pitch);
|
|
|
|
rot_data_roll = OpenPilot::CalibrationUtils::listMean(rot_accum_roll);
|
2014-04-10 22:43:47 +02:00
|
|
|
|
|
|
|
displayInstructions("Leave horizontally, rotate 180° along yaw axis and click save position...", true);
|
|
|
|
displayVisualHelp("plane-horizontal-rotated");
|
|
|
|
|
|
|
|
disableAllCalibrations();
|
|
|
|
|
|
|
|
m_ui->boardLevelSavePos->setEnabled(true);
|
|
|
|
break;
|
|
|
|
case 2:
|
2014-04-11 00:46:44 +02:00
|
|
|
rot_data_pitch += OpenPilot::CalibrationUtils::listMean(rot_accum_pitch);
|
2014-04-10 22:43:47 +02:00
|
|
|
rot_data_pitch /= 2;
|
2014-04-11 00:46:44 +02:00
|
|
|
rot_data_roll += OpenPilot::CalibrationUtils::listMean(rot_accum_roll);
|
|
|
|
rot_data_roll /= 2;
|
2014-04-10 22:43:47 +02:00
|
|
|
attitudeState->setMetadata(initialAttitudeStateMdata);
|
|
|
|
levelCalibrationCompute();
|
|
|
|
enableAllCalibrations();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2014-04-11 00:46:44 +02:00
|
|
|
void ConfigRevoWidget::levelCalibrationCompute()
|
|
|
|
{
|
2014-04-10 22:43:47 +02:00
|
|
|
enableAllCalibrations();
|
|
|
|
|
|
|
|
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
|
|
|
|
Q_ASSERT(attitudeSettings);
|
|
|
|
AttitudeSettings::DataFields attitudeSettingsData = attitudeSettings->getData();
|
|
|
|
|
|
|
|
// Update the biases based on collected data
|
|
|
|
// "rotate" the board in the opposite direction as the calculated offset
|
|
|
|
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] -= rot_data_pitch;
|
2014-04-11 00:46:44 +02:00
|
|
|
attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] -= rot_data_roll;
|
2014-04-10 22:43:47 +02:00
|
|
|
|
|
|
|
attitudeSettings->setData(attitudeSettingsData);
|
|
|
|
attitudeSettings->updated();
|
2013-05-12 11:27:12 +02:00
|
|
|
}
|
|
|
|
|
|
|
|
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
|
|
|
/**
|
2014-04-10 17:30:33 +02:00
|
|
|
Show the selected visual aid
|
2013-05-12 11:27:12 +02:00
|
|
|
*/
|
2014-04-10 17:30:33 +02:00
|
|
|
void ConfigRevoWidget::displayVisualHelp(QString elementID)
|
2012-06-14 17:01:05 +02:00
|
|
|
{
|
2014-04-10 17:30:33 +02:00
|
|
|
m_ui->calibrationVisualHelp->scene()->clear();
|
2014-04-09 01:15:08 +02:00
|
|
|
QPixmap pixmap = QPixmap(":/configgadget/images/calibration/" + elementID + ".png");
|
2014-04-10 17:30:33 +02:00
|
|
|
m_ui->calibrationVisualHelp->scene()->addPixmap(pixmap);
|
|
|
|
m_ui->calibrationVisualHelp->setSceneRect(pixmap.rect());
|
2014-04-10 22:43:47 +02:00
|
|
|
m_ui->calibrationVisualHelp->fitInView(m_ui->calibrationVisualHelp->scene()->sceneRect(), Qt::KeepAspectRatioByExpanding);
|
2011-12-24 20:57:10 +01:00
|
|
|
}
|
|
|
|
|
2014-04-11 00:46:44 +02:00
|
|
|
void ConfigRevoWidget::displayInstructions(QString instructions, bool replace)
|
|
|
|
{
|
|
|
|
if (replace || instructions.isNull()) {
|
2014-04-10 22:43:47 +02:00
|
|
|
m_ui->calibrationInstructions->clear();
|
|
|
|
}
|
2014-04-11 00:46:44 +02:00
|
|
|
if (!instructions.isNull()) {
|
2014-04-10 22:43:47 +02:00
|
|
|
m_ui->calibrationInstructions->append(instructions);
|
|
|
|
}
|
|
|
|
}
|
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-10 17:30:33 +02:00
|
|
|
|
2011-12-24 20:57:10 +01:00
|
|
|
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);
|
|
|
|
}
|
2014-04-10 17:30:33 +02:00
|
|
|
|
|
|
|
void ConfigRevoWidget::disableAllCalibrations()
|
|
|
|
{
|
|
|
|
m_ui->sixPointsStartAccel->setEnabled(false);
|
|
|
|
m_ui->sixPointsStartMag->setEnabled(false);
|
|
|
|
m_ui->boardLevelStart->setEnabled(false);
|
|
|
|
m_ui->gyroBiasStart->setEnabled(false);
|
|
|
|
m_ui->ThermalBiasStart->setEnabled(false);
|
|
|
|
}
|
|
|
|
|
|
|
|
void ConfigRevoWidget::enableAllCalibrations()
|
|
|
|
{
|
|
|
|
m_ui->sixPointsStartAccel->setEnabled(true);
|
|
|
|
m_ui->sixPointsStartMag->setEnabled(true);
|
|
|
|
m_ui->boardLevelStart->setEnabled(true);
|
|
|
|
m_ui->gyroBiasStart->setEnabled(true);
|
|
|
|
m_ui->ThermalBiasStart->setEnabled(true);
|
|
|
|
}
|