Commit 85e653ee authored by Lorenz Meier's avatar Lorenz Meier

Cleanup of calibration UI

parent c07de6fa
...@@ -90,6 +90,10 @@ void QGCPX4SensorCalibration::setActiveUAS(UASInterface* uas) ...@@ -90,6 +90,10 @@ void QGCPX4SensorCalibration::setActiveUAS(UASInterface* uas)
void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int severity, QString text) void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int severity, QString text)
{ {
Q_UNUSED(uasid);
Q_UNUSED(compId);
Q_UNUSED(severity);
if (text.startsWith("[cmd]") || if (text.startsWith("[cmd]") ||
text.startsWith("[mavlink pm]")) text.startsWith("[mavlink pm]"))
return; return;
...@@ -105,38 +109,51 @@ void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int sever ...@@ -105,38 +109,51 @@ void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int sever
return; return;
} }
ui->instructionLabel->setText(QString("%1").arg(text));
if (text.contains("accel")) { if (text.contains("accel")) {
qDebug() << "ACCEL" << text; qDebug() << "ACCEL" << text;
if (text.startsWith("accel meas started: ")) { if (text.startsWith("accel measurement started: ")) {
QString axis = text.split("meas started: ").last().right(2); QString axis = text.split("measurement started: ").last().left(2);
qDebug() << "AXIS" << axis << "STR" << text; qDebug() << "AXIS" << axis << "STR" << text;
setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(axis)); setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(axis));
} }
} }
if (text.startsWith("meas result for")) { if (text.startsWith("directions left")) {
for (int i = 0; i < 6; i++)
{
if (!text.contains(accelAxes[i])) {
qDebug() << "FINISHED" << accelAxes[i];
accelDone[i] = true;
}
}
}
if (text.startsWith("result for")) {
QString axis = text.split("meas result for ").last().left(2); QString axis = text.split("result for ").last().left(2);
qDebug() << "ACCELDONE AXIS" << axis << "STR" << text; qDebug() << "ACCELDONE AXIS" << axis << "STR" << text;
for (int i = 0; i < 6; i++) for (int i = 0; i < 6; i++)
{ {
if (accelAxes[i] == axis) if (axis == accelAxes[i])
accelDone[i] = true; accelDone[i] = true;
if (!accelDone[i]) { if (!accelDone[i]) {
qDebug() << "NEW AXIS: " << accelAxes[i];
setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(accelAxes[i])); setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(accelAxes[i]));
ui->calibrationExplanationLabel->setText(tr("Axis %1 completed. Please rotate to a different axis, e.g. the one shown here.").arg(axis)); ui->instructionLabel->setText(tr("Axis %1 completed. Please rotate like shown here.").arg(axis));
break;
} }
} }
} }
if (text.contains("please rotate in a figure 8")) { if (text.contains("please rotate in a figure 8")) {
ui->calibrationExplanationLabel->setText(tr("Rotate the system around all its axes, e.g. in a figure eight."));
setInstructionImage(":/files/images/px4/calibration/mag_calibration_figure8.png"); setInstructionImage(":/files/images/px4/calibration/mag_calibration_figure8.png");
} }
...@@ -144,24 +161,35 @@ void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int sever ...@@ -144,24 +161,35 @@ void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int sever
accelStarted = false; accelStarted = false;
// XXX use a confirmation image or something // XXX use a confirmation image or something
setInstructionImage(":/files/images/px4/calibration/accel_z-.png"); setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
ui->calibrationExplanationLabel->setText(tr("Accelerometer calibration completed. Parameters permanently stored."));
} }
if (text.contains("gyro calibration done")) { if (text.contains("gyro calibration done")) {
gyroStarted = false; gyroStarted = false;
// XXX use a confirmation image or something // XXX use a confirmation image or something
setInstructionImage(":/files/images/px4/calibration/accel_z-.png"); setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
ui->calibrationExplanationLabel->setText(tr("Gyroscope calibration completed. Parameters permanently stored."));
} }
if (text.contains("mag calibration done")) { if (text.contains("mag calibration done")
|| text.contains("magnetometer calibration completed")) {
magStarted = false; magStarted = false;
// XXX use a confirmation image or something // XXX use a confirmation image or something
setInstructionImage(":/files/images/px4/calibration/accel_z-.png"); setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
ui->calibrationExplanationLabel->setText(tr("Magnetometer calibration completed. Parameters permanently stored."));
} }
ui->instructionLabel->setText(QString("%1").arg(text)); if (text.contains("accel calibration started")) {
accelStarted = true;
setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
}
if (text.contains("gyro calibration started")) {
gyroStarted = true;
setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
}
if (text.contains("mag calibration started")) {
magStarted = false;
setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
}
// XXX color messages according to severity // XXX color messages according to severity
...@@ -184,7 +212,7 @@ void QGCPX4SensorCalibration::gyroButtonClicked() ...@@ -184,7 +212,7 @@ void QGCPX4SensorCalibration::gyroButtonClicked()
setInstructionImage(":/files/images/px4/calibration/accel_z-.png"); setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
activeUAS->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0); activeUAS->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
ui->progressBar->setValue(0); ui->progressBar->setValue(0);
ui->calibrationExplanationLabel->setText(tr("Please do not move the system at all and wait for calibration to complete.")); ui->instructionLabel->setText(tr("Please do not move the system at all."));
} }
void QGCPX4SensorCalibration::magButtonClicked() void QGCPX4SensorCalibration::magButtonClicked()
...@@ -192,7 +220,7 @@ void QGCPX4SensorCalibration::magButtonClicked() ...@@ -192,7 +220,7 @@ void QGCPX4SensorCalibration::magButtonClicked()
setInstructionImage(":/files/images/px4/calibration/accel_z-.png"); setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
activeUAS->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0); activeUAS->executeCommand(MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
ui->progressBar->setValue(0); ui->progressBar->setValue(0);
ui->calibrationExplanationLabel->setText(tr("Please put the system in a rest position and wait for instructions.")); ui->instructionLabel->setText(tr("Please put the system in a rest position."));
} }
void QGCPX4SensorCalibration::accelButtonClicked() void QGCPX4SensorCalibration::accelButtonClicked()
...@@ -208,7 +236,7 @@ void QGCPX4SensorCalibration::accelButtonClicked() ...@@ -208,7 +236,7 @@ void QGCPX4SensorCalibration::accelButtonClicked()
accelDone[4] = false; accelDone[4] = false;
accelDone[5] = false; accelDone[5] = false;
ui->calibrationExplanationLabel->setText(tr("Please hold the system very still in the shown orientations. Start with the one shown.")); ui->instructionLabel->setText(tr("Please hold the system very still in the shown orientations."));
} }
void QGCPX4SensorCalibration::contextMenuEvent(QContextMenuEvent* event) void QGCPX4SensorCalibration::contextMenuEvent(QContextMenuEvent* event)
......
...@@ -36,29 +36,29 @@ QPushButton#gyroButton, QPushButton#accelButton { ...@@ -36,29 +36,29 @@ QPushButton#gyroButton, QPushButton#accelButton {
border: 2px solid #465158; border: 2px solid #465158;
}</string> }</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout" rowstretch="1,20,3,2,1,1,0" columnstretch="30,15,5"> <layout class="QGridLayout" name="gridLayout" rowstretch="1,0,0,0,0,0,0" columnstretch="30,0,0">
<item row="6" column="2"> <item row="4" column="0" colspan="3">
<spacer name="horizontalSpacer"> <spacer name="verticalSpacer">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Vertical</enum>
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>40</width> <width>498</width>
<height>20</height> <height>21</height>
</size> </size>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="4" column="0" colspan="3"> <item row="6" column="2">
<spacer name="verticalSpacer"> <spacer name="horizontalSpacer">
<property name="orientation"> <property name="orientation">
<enum>Qt::Vertical</enum> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>498</width> <width>40</width>
<height>21</height> <height>20</height>
</size> </size>
</property> </property>
</spacer> </spacer>
...@@ -70,16 +70,6 @@ QPushButton#gyroButton, QPushButton#accelButton { ...@@ -70,16 +70,6 @@ QPushButton#gyroButton, QPushButton#accelButton {
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="0" colspan="3">
<widget class="QProgressBar" name="progressBar">
<property name="value">
<number>24</number>
</property>
</widget>
</item>
<item row="0" column="1" rowspan="2" colspan="2">
<widget class="QPlainTextEdit" name="textView"/>
</item>
<item row="6" column="0" colspan="2"> <item row="6" column="0" colspan="2">
<layout class="QHBoxLayout" name="horizontalLayout"> <layout class="QHBoxLayout" name="horizontalLayout">
<item> <item>
...@@ -117,13 +107,6 @@ QPushButton#gyroButton, QPushButton#accelButton { ...@@ -117,13 +107,6 @@ QPushButton#gyroButton, QPushButton#accelButton {
</item> </item>
</layout> </layout>
</item> </item>
<item row="2" column="0" colspan="3">
<widget class="QLabel" name="calibrationExplanationLabel">
<property name="text">
<string>To calibrate the system, execute the three calibration steps below.</string>
</property>
</widget>
</item>
<item row="0" column="0" rowspan="2"> <item row="0" column="0" rowspan="2">
<widget class="QLabel" name="iconLabel"> <widget class="QLabel" name="iconLabel">
<property name="text"> <property name="text">
...@@ -134,6 +117,16 @@ QPushButton#gyroButton, QPushButton#accelButton { ...@@ -134,6 +117,16 @@ QPushButton#gyroButton, QPushButton#accelButton {
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="0">
<widget class="QProgressBar" name="progressBar">
<property name="value">
<number>24</number>
</property>
</widget>
</item>
<item row="0" column="1" rowspan="3" colspan="2">
<widget class="QPlainTextEdit" name="textView"/>
</item>
</layout> </layout>
</widget> </widget>
<resources> <resources>
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment