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

OP-1351 use two instances of SixPointCalibrationModel (one for accel and one for mag calibration) to avoid apply/save issues when using only one

This commit is contained in:
Philippe Renon 2014-05-30 19:01:25 +02:00
parent 9f50859978
commit ac61ed35d2
3 changed files with 145 additions and 100 deletions

View File

@ -93,6 +93,63 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
// addUAVObject("AccelGyroSettings");
autoLoadWidgets();
// accel calibration
m_accelCalibrationModel = new OpenPilot::SixPointCalibrationModel(this);
connect(m_ui->accelStart, SIGNAL(clicked()), m_accelCalibrationModel, SLOT(accelStart()));
connect(m_ui->accelSavePos, SIGNAL(clicked()), m_accelCalibrationModel, SLOT(savePositionData()));
connect(m_accelCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
connect(m_accelCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
connect(m_accelCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation()));
connect(m_accelCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation()));
connect(m_accelCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)),
this, SLOT(addInstructions(QString, WizardModel::MessageType)));
connect(m_accelCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_accelCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), m_ui->accelSavePos, SLOT(setEnabled(bool)));
m_ui->accelSavePos->setEnabled(false);
// mag calibration
m_magCalibrationModel = new OpenPilot::SixPointCalibrationModel(this);
connect(m_ui->magStart, SIGNAL(clicked()), m_magCalibrationModel, SLOT(magStart()));
connect(m_ui->magSavePos, SIGNAL(clicked()), m_magCalibrationModel, SLOT(savePositionData()));
connect(m_magCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
connect(m_magCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
connect(m_magCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation()));
connect(m_magCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation()));
connect(m_magCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)),
this, SLOT(addInstructions(QString, WizardModel::MessageType)));
connect(m_magCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_magCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), m_ui->magSavePos, SLOT(setEnabled(bool)));
m_ui->magSavePos->setEnabled(false);
// board level calibration
m_levelCalibrationModel = new OpenPilot::LevelCalibrationModel(this);
connect(m_ui->boardLevelStart, SIGNAL(clicked()), m_levelCalibrationModel, SLOT(start()));
connect(m_ui->boardLevelSavePos, SIGNAL(clicked()), m_levelCalibrationModel, SLOT(savePosition()));
connect(m_levelCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)),
this, SLOT(addInstructions(QString, WizardModel::MessageType)));
connect(m_levelCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_levelCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), m_ui->boardLevelSavePos, SLOT(setEnabled(bool)));
connect(m_levelCalibrationModel, SIGNAL(progressChanged(int)), m_ui->boardLevelProgress, SLOT(setValue(int)));
// gyro zero calibration
m_gyroBiasCalibrationModel = new OpenPilot::GyroBiasCalibrationModel(this);
connect(m_ui->gyroBiasStart, SIGNAL(clicked()), m_gyroBiasCalibrationModel, SLOT(start()));
connect(m_gyroBiasCalibrationModel, SIGNAL(progressChanged(int)), m_ui->gyroBiasProgress, SLOT(setValue(int)));
connect(m_gyroBiasCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
connect(m_gyroBiasCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
connect(m_gyroBiasCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation()));
connect(m_gyroBiasCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation()));
connect(m_gyroBiasCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)),
this, SLOT(addInstructions(QString, WizardModel::MessageType)));
connect(m_gyroBiasCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
// thermal calibration
m_thermalCalibrationModel = new OpenPilot::ThermalCalibrationModel(this);
m_thermalCalibrationModel->init();
@ -115,48 +172,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
connect(m_thermalCalibrationModel, SIGNAL(temperatureGradientChanged(float)), this, SLOT(displayTemperatureGradient(float)));
connect(m_thermalCalibrationModel, SIGNAL(progressChanged(int)), m_ui->thermalBiasProgress, SLOT(setValue(int)));
// six point calibration
m_sixPointCalibrationModel = new OpenPilot::SixPointCalibrationModel(this);
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(started()), this, SLOT(disableAllCalibrations()));
connect(m_sixPointCalibrationModel, SIGNAL(stopped()), 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, WizardModel::MessageType)),
this, SLOT(addInstructions(QString, WizardModel::MessageType)));
connect(m_sixPointCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_sixPointCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->sixPointsSave, SLOT(setEnabled(bool)));
// board level calibration
m_levelCalibrationModel = new OpenPilot::LevelCalibrationModel(this);
connect(m_ui->boardLevelStart, SIGNAL(clicked()), m_levelCalibrationModel, SLOT(start()));
connect(m_ui->boardLevelSavePos, SIGNAL(clicked()), m_levelCalibrationModel, SLOT(savePosition()));
connect(m_levelCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)),
this, SLOT(addInstructions(QString, WizardModel::MessageType)));
connect(m_levelCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_levelCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->boardLevelSavePos, SLOT(setEnabled(bool)));
connect(m_levelCalibrationModel, SIGNAL(progressChanged(int)), this->m_ui->boardLevelProgress, SLOT(setValue(int)));
// gyro zero calibration
m_gyroBiasCalibrationModel = new OpenPilot::GyroBiasCalibrationModel(this);
connect(m_ui->gyroBiasStart, SIGNAL(clicked()), m_gyroBiasCalibrationModel, SLOT(start()));
connect(m_gyroBiasCalibrationModel, SIGNAL(progressChanged(int)), this->m_ui->gyroBiasProgress, SLOT(setValue(int)));
connect(m_gyroBiasCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
connect(m_gyroBiasCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
connect(m_gyroBiasCalibrationModel, SIGNAL(storeAndClearBoardRotation()), this, SLOT(storeAndClearBoardRotation()));
connect(m_gyroBiasCalibrationModel, SIGNAL(recallBoardRotation()), this, SLOT(recallBoardRotation()));
connect(m_gyroBiasCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)),
this, SLOT(addInstructions(QString, WizardModel::MessageType)));
connect(m_gyroBiasCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
// home location
connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation()));
addWidgetBinding("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm);
@ -301,8 +317,11 @@ void ConfigRevoWidget::updateObjectsFromWidgets()
{
ConfigTaskWidget::updateObjectsFromWidgets();
if (m_sixPointCalibrationModel->dirty()) {
m_sixPointCalibrationModel->save();
if (m_accelCalibrationModel->dirty()) {
m_accelCalibrationModel->save();
}
if (m_magCalibrationModel->dirty()) {
m_magCalibrationModel->save();
}
if (m_levelCalibrationModel->dirty()) {
m_levelCalibrationModel->save();
@ -333,8 +352,8 @@ void ConfigRevoWidget::disableAllCalibrations()
{
clearInstructions();
m_ui->sixPointsStartAccel->setEnabled(false);
m_ui->sixPointsStartMag->setEnabled(false);
m_ui->accelStart->setEnabled(false);
m_ui->magStart->setEnabled(false);
m_ui->boardLevelStart->setEnabled(false);
m_ui->gyroBiasStart->setEnabled(false);
m_ui->ThermalBiasStart->setEnabled(false);
@ -343,13 +362,13 @@ void ConfigRevoWidget::disableAllCalibrations()
void ConfigRevoWidget::enableAllCalibrations()
{
// TODO should use a signal instead
if (m_sixPointCalibrationModel->dirty() || m_levelCalibrationModel->dirty()
if (m_accelCalibrationModel->dirty() || m_magCalibrationModel->dirty() || m_levelCalibrationModel->dirty()
|| m_gyroBiasCalibrationModel->dirty()) {
widgetsContentsChanged();
}
m_ui->sixPointsStartAccel->setEnabled(true);
m_ui->sixPointsStartMag->setEnabled(true);
m_ui->accelStart->setEnabled(true);
m_ui->magStart->setEnabled(true);
m_ui->boardLevelStart->setEnabled(true);
m_ui->gyroBiasStart->setEnabled(true);
m_ui->ThermalBiasStart->setEnabled(true);

View File

@ -53,10 +53,11 @@ public:
~ConfigRevoWidget();
private:
OpenPilot::SixPointCalibrationModel *m_sixPointCalibrationModel;
OpenPilot::ThermalCalibrationModel *m_thermalCalibrationModel;
OpenPilot::SixPointCalibrationModel *m_accelCalibrationModel;
OpenPilot::SixPointCalibrationModel *m_magCalibrationModel;
OpenPilot::LevelCalibrationModel *m_levelCalibrationModel;
OpenPilot::GyroBiasCalibrationModel *m_gyroBiasCalibrationModel;
OpenPilot::ThermalCalibrationModel *m_thermalCalibrationModel;
Ui_RevoSensorsWidget *m_ui;

View File

@ -108,34 +108,21 @@
<number>0</number>
</property>
<item>
<widget class="QGroupBox" name="step1GroupBox">
<widget class="QGroupBox" name="accelCalGroupBox">
<property name="title">
<string>Step 1: Accelerometer / magnetometer calibration</string>
<string>Accelerometer calibration</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<widget class="QPushButton" name="sixPointsStartAccel">
<widget class="QPushButton" name="accelStart">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="toolTip">
<string>Launch accelerometer range and bias calibration.</string>
</property>
<property name="text">
<string>Calibrate Accel</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="sixPointsStartMag">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Launch magnetometer range and bias calibration.</string>
</property>
<property name="text">
<string>Calibrate Mag</string>
<string>Start</string>
</property>
</widget>
</item>
@ -153,9 +140,9 @@
</spacer>
</item>
<item>
<widget class="QPushButton" name="sixPointsSave">
<widget class="QPushButton" name="accelSavePos">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="toolTip">
<string>Save settings (only enabled when calibration is running)</string>
@ -169,15 +156,60 @@
</widget>
</item>
<item>
<widget class="QGroupBox" name="step2GroupBox">
<widget class="QGroupBox" name="magCalGroupBox">
<property name="title">
<string>Step 2: Board level calibration</string>
<string>Magnetometer calibration</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QPushButton" name="magStart">
<property name="enabled">
<bool>true</bool>
</property>
<property name="toolTip">
<string>Launch magnetometer range and bias calibration.</string>
</property>
<property name="text">
<string>Start</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="magSavePos">
<property name="enabled">
<bool>true</bool>
</property>
<property name="text">
<string>Save Position</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="boardLevelCalGroupBox">
<property name="title">
<string>Board level calibration</string>
</property>
<layout class="QHBoxLayout">
<item>
<widget class="QPushButton" name="boardLevelStart">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="text">
<string>Start</string>
@ -197,7 +229,7 @@
<item>
<widget class="QPushButton" name="boardLevelSavePos">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="text">
<string>Save Position</string>
@ -208,15 +240,15 @@
</widget>
</item>
<item>
<widget class="QGroupBox" name="step3GroupBox">
<widget class="QGroupBox" name="gyroBiasGroupBox">
<property name="title">
<string>Step 3: Gyro bias calibration</string>
<string>Gyro bias calibration</string>
</property>
<layout class="QHBoxLayout">
<item>
<widget class="QPushButton" name="gyroBiasStart">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
@ -255,9 +287,9 @@
</widget>
</item>
<item>
<widget class="QGroupBox" name="step4GroupBox">
<widget class="QGroupBox" name="thermalCalGroupBox">
<property name="title">
<string>Step 4: Thermal calibration</string>
<string>Thermal calibration</string>
</property>
<layout class="QVBoxLayout">
<item>
@ -265,7 +297,7 @@
<item>
<widget class="QPushButton" name="ThermalBiasStart">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="text">
<string>Start</string>
@ -297,7 +329,7 @@
<item>
<widget class="QPushButton" name="ThermalBiasEnd">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="text">
<string>End</string>
@ -307,7 +339,7 @@
<item>
<widget class="QPushButton" name="ThermalBiasCancel">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="text">
<string>Cancel</string>
@ -388,8 +420,8 @@
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="toolTip">
@ -411,8 +443,8 @@
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:600; font-style:normal;&quot;&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="textInteractionFlags">
<set>Qt::NoTextInteraction</set>
@ -443,7 +475,7 @@ p, li { white-space: pre-wrap; }
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Steps 1, 2 and 3 are necessary. Step 4 is optional but may help achieve the best possible results.&lt;/span&gt;&lt;/p&gt;
&lt;p 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:12pt; font-weight:600; font-style:italic;&quot;&gt;Step 1: Accelerometer / magnetometer calibration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:12pt; font-weight:600; font-style:italic;&quot;&gt;Step 1: Accelerometer and magnetometer calibration&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;This calibration will compute the scale for Magnetometer or Accelerometer sensors. &lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;Press &amp;quot;Calibrate Mag&amp;quot; or &amp;quot;Calibrate Accel&amp;quot; to begin calibration, and follow the instructions which will be displayed here. &lt;/span&gt;&lt;/p&gt;
@ -966,13 +998,6 @@ A setting of 0.00 disables the filter.</string>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QLabel" name="calibInstructions">
<property name="text">
<string>Telemetry link not established.</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
@ -981,7 +1006,7 @@ A setting of 0.00 disables the filter.</string>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
<height>5</height>
</size>
</property>
</spacer>
@ -996,8 +1021,8 @@ A setting of 0.00 disables the filter.</string>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
<width>25</width>
<height>25</height>
</size>
</property>
<property name="font">
@ -1014,8 +1039,8 @@ A setting of 0.00 disables the filter.</string>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
<width>25</width>
<height>25</height>
</size>
</property>
<property name="shortcut">