1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

OP-1351 disable other calibration steps when running thermal calibration

This commit is contained in:
Philippe Renon 2014-05-25 18:46:51 +02:00
parent c799d8f90e
commit 48558f75e6
8 changed files with 32 additions and 28 deletions

View File

@ -52,7 +52,7 @@ void GyroBiasCalibrationModel::start()
// Store and reset board rotation before calibration starts
storeAndClearBoardRotation();
disableAllCalibrations();
started();
progressChanged(0);
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
@ -159,7 +159,7 @@ void GyroBiasCalibrationModel::getSample(UAVObject *obj)
Q_ASSERT(gyroSensor);
disconnect(gyroSensor, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(getSample(UAVObject *)));
enableAllCalibrations();
stopped();
RevoCalibration *revoCalibration = RevoCalibration::GetInstance(getObjectManager());
Q_ASSERT(revoCalibration);

View File

@ -48,8 +48,8 @@ public:
signals:
void displayVisualHelp(QString elementID);
void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false);
void disableAllCalibrations();
void enableAllCalibrations();
void started();
void stopped();
void storeAndClearBoardRotation();
void recallBoardRotation();
void progressChanged(int value);

View File

@ -48,7 +48,7 @@ void LevelCalibrationModel::start()
{
// Store and reset board rotation before calibration starts
disableAllCalibrations();
started();
progressChanged(0);
rot_data_pitch = 0;
@ -66,7 +66,6 @@ void LevelCalibrationModel::start()
/* Show instructions and enable controls */
displayInstructions(tr("Place horizontally and click Save Position button..."), WizardModel::Info, true);
displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_NED);
disableAllCalibrations();
savePositionEnabledChanged(true);
position = 0;
}
@ -135,7 +134,7 @@ void LevelCalibrationModel::getSample(UAVObject *obj)
displayInstructions(tr("Leave horizontally, rotate 180° along yaw axis and click Save Position button..."));
displayVisualHelp(CALIBRATION_HELPER_PLANE_PREFIX + CALIBRATION_HELPER_IMAGE_SWD);
disableAllCalibrations();
started();
savePositionEnabledChanged(true);
break;
@ -146,7 +145,7 @@ void LevelCalibrationModel::getSample(UAVObject *obj)
rot_data_roll /= 2;
attitudeState->setMetadata(initialAttitudeStateMdata);
compute();
enableAllCalibrations();
stopped();
displayVisualHelp(CALIBRATION_HELPER_IMAGE_EMPTY);
displayInstructions(tr("Board leveling completed successfully."));
break;
@ -155,7 +154,7 @@ void LevelCalibrationModel::getSample(UAVObject *obj)
}
void LevelCalibrationModel::compute()
{
enableAllCalibrations();
stopped();
AttitudeSettings *attitudeSettings = AttitudeSettings::GetInstance(getObjectManager());
Q_ASSERT(attitudeSettings);

View File

@ -51,8 +51,8 @@ public:
signals:
void displayVisualHelp(QString elementID);
void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false);
void disableAllCalibrations();
void enableAllCalibrations();
void started();
void stopped();
void savePositionEnabledChanged(bool state);
void progressChanged(int value);

View File

@ -202,7 +202,7 @@ void SixPointCalibrationModel::start(bool calibrateAccel, bool calibrateMag)
displayInstructions((*currentSteps)[0].instructions, WizardModel::Info, true);
showHelp((*currentSteps)[0].visualHelp);
disableAllCalibrations();
started();
savePositionEnabledChanged(true);
position = 0;
mag_fit_x.clear();
@ -325,7 +325,7 @@ void SixPointCalibrationModel::getSample(UAVObject *obj)
compute(calibratingMag, calibratingAccel);
savePositionEnabledChanged(false);
enableAllCalibrations();
stopped();
showHelp(CALIBRATION_HELPER_IMAGE_EMPTY);
/* Cleanup original settings */
accelState->setMetadata(initialAccelStateMdata);

View File

@ -67,8 +67,8 @@ public:
signals:
void displayVisualHelp(QString elementID);
void displayInstructions(QString text, WizardModel::MessageType type = WizardModel::Info, bool clear = false);
void disableAllCalibrations();
void enableAllCalibrations();
void started();
void stopped();
void storeAndClearBoardRotation();
void recallBoardRotation();
void savePositionEnabledChanged(bool state);

View File

@ -173,6 +173,9 @@ signals:
void endEnabledChanged(bool state);
void cancelEnabledChanged(bool state);
void started();
void stopped();
void temperatureChanged(float temp);
void temperatureGradientChanged(float tempGradient);
void progressChanged(int value);
@ -206,12 +209,14 @@ signals:
setStartEnabled(true);
setEndEnabled(false);
setCancelEnabled(false);
stopped();
}
void wizardStarted()
{
setStartEnabled(false);
setEndEnabled(true);
setCancelEnabled(true);
started();
}
};
}

View File

@ -77,7 +77,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
{
m_ui->setupUi(this);
// Initialization of the Paper plane widget
// Initialization of the visual help
m_ui->calibrationVisualHelp->setScene(new QGraphicsScene(this));
m_ui->calibrationVisualHelp->setRenderHint(QPainter::HighQualityAntialiasing, true);
m_ui->calibrationVisualHelp->setRenderHint(QPainter::SmoothPixmapTransform, true);
@ -92,7 +92,7 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
addUAVObject("AccelGyroSettings");
autoLoadWidgets();
// connect the thermalCalibration model to UI
// thermal calibration
m_thermalCalibrationModel = new OpenPilot::ThermalCalibrationModel(this);
m_thermalCalibrationModel->init();
m_ui->temperatureLabel->setText("");
@ -105,22 +105,24 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
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)));
connect(m_thermalCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
connect(m_thermalCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
connect(m_thermalCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType)),
this, SLOT(displayInstructions(QString, WizardModel::MessageType)));
connect(m_thermalCalibrationModel, SIGNAL(temperatureChanged(float)), this, SLOT(displayTemperature(float)));
connect(m_thermalCalibrationModel, SIGNAL(temperatureGradientChanged(float)), this, SLOT(displayTemperatureGradient(float)));
connect(m_thermalCalibrationModel, SIGNAL(progressChanged(int)), m_ui->thermalBiasProgress, SLOT(setValue(int)));
// note: init for m_thermalCalibrationModel is done in showEvent to prevent cases wiht "Start" button not enabled due to some itming issue.
// note: init for m_thermalCalibrationModel is done in showEvent to prevent cases with "Start" button not enabled due to some timing issue.
// six point calibration
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(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, bool)),
@ -128,35 +130,33 @@ ConfigRevoWidget::ConfigRevoWidget(QWidget *parent) :
connect(m_sixPointCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_sixPointCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->sixPointsSave, SLOT(setEnabled(bool)));
m_levelCalibrationModel = new OpenPilot::LevelCalibrationModel(this);
// 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(disableAllCalibrations()), this, SLOT(disableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(enableAllCalibrations()), this, SLOT(enableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(started()), this, SLOT(disableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(stopped()), this, SLOT(enableAllCalibrations()));
connect(m_levelCalibrationModel, SIGNAL(displayInstructions(QString, WizardModel::MessageType, bool)),
this, SLOT(displayInstructions(QString, WizardModel::MessageType, bool)));
connect(m_levelCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_levelCalibrationModel, SIGNAL(savePositionEnabledChanged(bool)), this->m_ui->boardLevelSavePos, SLOT(setEnabled(bool)));
connect(m_levelCalibrationModel, SIGNAL(progressChanged(int)), this->m_ui->boardLevelProgress, SLOT(setValue(int)));
// Connect the signals
// 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(disableAllCalibrations()), this, SLOT(disableAllCalibrations()));
connect(m_gyroBiasCalibrationModel, SIGNAL(enableAllCalibrations()), this, SLOT(enableAllCalibrations()));
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, bool)),
this, SLOT(displayInstructions(QString, WizardModel::MessageType, bool)));
connect(m_gyroBiasCalibrationModel, SIGNAL(displayVisualHelp(QString)), this, SLOT(displayVisualHelp(QString)));
connect(m_ui->hlClearButton, SIGNAL(clicked()), this, SLOT(clearHomeLocation()));
addWidgetBinding("RevoSettings", "FusionAlgorithm", m_ui->FusionAlgorithm);