Commit f1fbf5f5 authored by Don Gagne's avatar Don Gagne

Merge pull request #1286 from DonLakeFlyer/SafetyUI

Visuals for Gyro and Compass calibration
parents c41a6dac cb76c677
......@@ -250,6 +250,7 @@
<file alias="QGroundControl/Controls/qmldir">src/QmlControls/qmldir</file>
<file alias="QGroundControl/Controls/SubMenuButton.qml">src/QmlControls/SubMenuButton.qml</file>
<file alias="QGroundControl/Controls/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file>
<file alias="QGroundControl/Controls/VehicleRotationCal.qml">src/QmlControls/VehicleRotationCal.qml</file>
<file alias="QGroundControl/Controls/QGCButton.qml">src/QmlControls/QGCButton.qml</file>
<file alias="QGroundControl/Controls/QGCRadioButton.qml">src/QmlControls/QGCRadioButton.qml</file>
<file alias="QGroundControl/Controls/QGCCheckBox.qml">src/QmlControls/QGCCheckBox.qml</file>
......@@ -277,17 +278,23 @@
<file alias="FlightModesComponentSummary.qml">src/AutoPilotPlugins/PX4/FlightModesComponentSummary.qml</file>
<file alias="AirframeComponentSummary.qml">src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml</file>
<file alias="SafetyComponentTree.png">src/AutoPilotPlugins/PX4/SafetyComponentTree.png</file>
<file alias="SafetyComponentHome.png">src/AutoPilotPlugins/PX4/SafetyComponentHome.png</file>
<file alias="SafetyComponentArrowDown.png">src/AutoPilotPlugins/PX4/SafetyComponentArrowDown.png</file>
<file alias="SafetyComponentPlane.png">src/AutoPilotPlugins/PX4/SafetyComponentPlane.png</file>
<file alias="SafetyComponentTree.png">src/AutoPilotPlugins/PX4/Images/SafetyComponentTree.png</file>
<file alias="SafetyComponentHome.png">src/AutoPilotPlugins/PX4/Images/SafetyComponentHome.png</file>
<file alias="SafetyComponentArrowDown.png">src/AutoPilotPlugins/PX4/Images/SafetyComponentArrowDown.png</file>
<file alias="SafetyComponentPlane.png">src/AutoPilotPlugins/PX4/Images/SafetyComponentPlane.png</file>
<file alias="VehicleDown.png">src/AutoPilotPlugins/PX4/Images/VehicleDown.png</file>
<file alias="VehicleUpsideDown.png">src/AutoPilotPlugins/PX4/Images/VehicleUpsideDown.png</file>
<file alias="VehicleLeft.png">src/AutoPilotPlugins/PX4/Images/VehicleLeft.png</file>
<file alias="VehicleRight.png">src/AutoPilotPlugins/PX4/Images/VehicleRight.png</file>
<file alias="VehicleNoseDown.png">src/AutoPilotPlugins/PX4/Images/VehicleNoseDown.png</file>
<file alias="VehicleTailDown.png">src/AutoPilotPlugins/PX4/Images/VehicleTailDown.png</file>
<file alias="QGroundControl/Controls/subMenuButtonImage.png">files/Setup/cogwheels.png</file>
<file alias="QGroundControl/Controls/SensorsComponentIcon.png">src/AutoPilotPlugins/PX4/SensorsComponentIcon.png</file>
<file alias="QGroundControl/Controls/RadioComponentIcon.png">src/AutoPilotPlugins/PX4/RadioComponentIcon.png</file>
<file alias="QGroundControl/Controls/FlightModesComponentIcon.png">src/AutoPilotPlugins/PX4/FlightModesComponentIcon.png</file>
<file alias="QGroundControl/Controls/AirframeComponentIcon.png">src/AutoPilotPlugins/PX4/AirframeComponentIcon.png</file>
<file alias="QGroundControl/Controls/SafetyComponentIcon.png">src/AutoPilotPlugins/PX4/SafetyComponentIcon.png</file>
<file alias="QGroundControl/Controls/SensorsComponentIcon.png">src/AutoPilotPlugins/PX4/Images/SensorsComponentIcon.png</file>
<file alias="QGroundControl/Controls/RadioComponentIcon.png">src/AutoPilotPlugins/PX4/Images/RadioComponentIcon.png</file>
<file alias="QGroundControl/Controls/FlightModesComponentIcon.png">src/AutoPilotPlugins/PX4/Images/FlightModesComponentIcon.png</file>
<file alias="QGroundControl/Controls/AirframeComponentIcon.png">src/AutoPilotPlugins/PX4/Images/AirframeComponentIcon.png</file>
<file alias="QGroundControl/Controls/SafetyComponentIcon.png">src/AutoPilotPlugins/PX4/Images/SafetyComponentIcon.png</file>
<file alias="QGroundControl/Controls/FirmwareUpgradeIcon.png">src/VehicleSetup/FirmwareUpgradeIcon.png</file>
<file alias="QGroundControl/Controls/VehicleSummaryIcon.png">src/VehicleSetup/VehicleSummaryIcon.png</file>
......
......@@ -53,7 +53,10 @@ Rectangle {
}
Loader {
sourceComponent: loadSignal
onLoaded: controller.statusLog = statusTextArea
onLoaded: {
controller.statusLog = statusTextArea
controller.progressBar = progressBar
}
}
Column {
......@@ -66,19 +69,72 @@ Rectangle {
Item { height: 20; width: 10 } // spacer
Row {
readonly property int buttonWidth: 120
spacing: 20
QGCLabel { text: "Calibrate:"; anchors.baseline: firstButton.baseline }
IndicatorButton {
id: firstButton
width: parent.buttonWidth
text: "Compass"
indicatorGreen: autopilot.parameters["CAL_MAG0_ID"].value != 0
onClicked: controller.calibrateCompass()
}
IndicatorButton {
width: parent.buttonWidth
text: "Gyroscope"
indicatorGreen: autopilot.parameters["CAL_GYRO0_ID"].value != 0
onClicked: controller.calibrateGyro()
}
IndicatorButton {
width: parent.buttonWidth
text: "Acceleromter"
indicatorGreen: autopilot.parameters["CAL_ACC0_ID"].value != 0
onClicked: controller.calibrateAccel()
}
IndicatorButton {
width: parent.buttonWidth
text: "Airspeed"
visible: controller.fixedWing
indicatorGreen: autopilot.parameters["SENS_DPRES_OFF"].value != 0
onClicked: controller.calibrateAirspeed()
}
}
Item { height: 20; width: 10 } // spacer
ProgressBar {
id: progressBar
width: parent.width - rotationColumnWidth
}
Item { height: 10; width: 10 } // spacer
Item {
readonly property int calibrationAreaHeight: 300
property int calDisplayAreaWidth: parent.width - rotationColumnWidth
width: parent.width
height: calibrationAreaHeight
height: parent.height - x
TextArea {
id: statusTextArea
width: parent.width - rotationColumnWidth
width: parent.calDisplayAreaWidth
height: parent.height
readOnly: true
frameVisible: false
text: qsTr("Sensor config is a work in progress which currently supports textual instructions only. Updated visuals coming soon.")
text: "Sensor config is a work in progress. Not all visuals for all calibration types fully implemented.\n\n" +
"For Compass calibration you will need to rotate your vehicle through a number of positions. For this calibration is is best " +
"to be connected to you vehicle via radio instead of USB since the USB cable will likely get in the way.\n\n" +
"For Gyroscope calibration you will need to place your vehicle right side up on solid surface and leave it still.\n\n" +
"For Accelerometer calibration you will need to place your vehicle on all six sides and hold it there for a few seconds.\n\n" +
"For Airspeed calibration you will need to keep your airspeed sensor out of any wind.\n\n"
style: TextAreaStyle {
textColor: qgcPal.text
......@@ -86,6 +142,97 @@ Rectangle {
}
}
Rectangle {
id: gyroCalArea
width: parent.calDisplayAreaWidth
height: parent.height
visible: controller.showGyroCalArea
color: qgcPal.windowShade
Column {
width: parent.width
QGCLabel {
text: "Place your vehicle upright on a solid surface and hold it still."
}
VehicleRotationCal {
width: 200
height: 200
calValid: true
calInProgress: controller.gyroCalInProgress
imageSource: "qrc:///qml/VehicleDown.png"
}
}
}
Rectangle {
id: accelCalArea
width: parent.calDisplayAreaWidth
height: parent.height
visible: controller.showAccelCalArea
color: qgcPal.windowShade
QGCLabel {
id: calAreaLabel
width: parent.width
wrapMode: Text.WordWrap
text: "Place your vehicle into each of the positions below and hold still. Once that position is completed you can move to another."
}
Flow {
y: calAreaLabel.height
width: parent.width
height: parent.height - calAreaLabel.implicitHeight
spacing: 5
VehicleRotationCal {
width: 200
height: 200
calValid: controller.accelCalDownSideDone
calInProgress: controller.accelCalDownSideInProgress
imageSource: "qrc:///qml/VehicleDown.png"
}
VehicleRotationCal {
width: 200
height: 200
calValid: controller.accelCalUpsideDownSideDone
calInProgress: controller.accelCalUpsideDownSideInProgress
imageSource: "qrc:///qml/VehicleUpsideDown.png"
}
VehicleRotationCal {
width: 200
height: 200
calValid: controller.accelCalNoseDownSideDone
calInProgress: controller.accelCalNoseDownSideInProgress
imageSource: "qrc:///qml/VehicleNoseDown.png"
}
VehicleRotationCal {
width: 200
height: 200
calValid: controller.accelCalTailDownSideDone
calInProgress: controller.accelCalTailDownSideInProgress
imageSource: "qrc:///qml/VehicleTailDown.png"
}
VehicleRotationCal {
width: 200
height: 200
calValid: controller.accelCalLeftSideDone
calInProgress: controller.accelCalLeftSideInProgress
imageSource: "qrc:///qml/VehicleLeft.png"
}
VehicleRotationCal {
width: 200
height: 200
calValid: controller.accelCalRightSideDone
calInProgress: controller.accelCalRightSideInProgress
imageSource: "qrc:///qml/VehicleRight.png"
}
}
}
Column {
// Compass rotation parameter < 0 indicates either internal compass, or no compass. So in
// both those cases we do not show a rotation combo.
......@@ -158,46 +305,6 @@ Rectangle {
Loader { sourceComponent: parent.showCompass2 ? compass2ComponentCombo : null }
}
}
Item { height: 20; width: 10 } // spacer
Row {
readonly property int buttonWidth: 120
spacing: 20
QGCLabel { text: "Calibrate:"; anchors.baseline: firstButton.baseline }
IndicatorButton {
id: firstButton
width: parent.buttonWidth
text: "Compass"
indicatorGreen: autopilot.parameters["CAL_MAG0_ID"].value != 0
onClicked: controller.calibrateCompass()
}
IndicatorButton {
width: parent.buttonWidth
text: "Gyroscope"
indicatorGreen: autopilot.parameters["CAL_GYRO0_ID"].value != 0
onClicked: controller.calibrateGyro()
}
IndicatorButton {
width: parent.buttonWidth
text: "Acceleromter"
indicatorGreen: autopilot.parameters["CAL_ACC0_ID"].value != 0
onClicked: controller.calibrateAccel()
}
IndicatorButton {
width: parent.buttonWidth
text: "Airspeed"
visible: controller.fixedWing
indicatorGreen: autopilot.parameters["SENS_DPRES_OFF"].value != 0
onClicked: controller.calibrateAirspeed()
}
}
}
}
......@@ -27,12 +27,30 @@
#include "SensorsComponentController.h"
#include "QGCMAVLink.h"
#include "UASManager.h"
#include "QGCMessageBox.h"
#include <QVariant>
#include <QQmlProperty>
SensorsComponentController::SensorsComponentController(AutoPilotPlugin* autopilot, QObject* parent) :
QObject(parent),
_statusLog(NULL),
_progressBar(NULL),
_showGyroCalArea(false),
_showAccelCalArea(false),
_gyroCalInProgress(false),
_accelCalDownSideDone(false),
_accelCalUpsideDownSideDone(false),
_accelCalLeftSideDone(false),
_accelCalRightSideDone(false),
_accelCalNoseDownSideDone(false),
_accelCalTailDownSideDone(false),
_accelCalDownSideInProgress(false),
_accelCalUpsideDownSideInProgress(false),
_accelCalLeftSideInProgress(false),
_accelCalRightSideInProgress(false),
_accelCalNoseDownSideInProgress(false),
_accelCalTailDownSideInProgress(false),
_autopilot(autopilot)
{
Q_ASSERT(autopilot);
......@@ -62,6 +80,7 @@ void SensorsComponentController::calibrateGyro(void)
void SensorsComponentController::calibrateCompass(void)
{
_hideAllCalAreas();
_beginTextLogging();
UASInterface* uas = _autopilot->uas();
......@@ -80,6 +99,7 @@ void SensorsComponentController::calibrateAccel(void)
void SensorsComponentController::calibrateAirspeed(void)
{
_hideAllCalAreas();
_beginTextLogging();
UASInterface* uas = _autopilot->uas();
......@@ -96,6 +116,9 @@ void SensorsComponentController::_beginTextLogging(void)
void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, int severity, QString text)
{
QString startingSidePrefix("Hold still, starting to measure ");
QString sideDoneSuffix(" side done, rotate to a different side");
Q_UNUSED(compId);
Q_UNUSED(severity);
......@@ -106,18 +129,151 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
}
QStringList ignorePrefixList;
ignorePrefixList << "[cmd]" << "[mavlink pm]" << "[ekf check]";
ignorePrefixList << "[cmd]" << "[mavlink pm]" << "[ekf check]" << "[pm]" << "[inav]";
foreach (QString ignorePrefix, ignorePrefixList) {
if (text.startsWith(ignorePrefix)) {
return;
}
}
if (text.contains("progress <")) {
QString percent = text.split("<").last().split(">").first();
bool ok;
int p = percent.toInt(&ok);
if (ok) {
Q_ASSERT(_progressBar);
_progressBar->setProperty("value", (float)(p / 100.0));
}
return;
}
_appendStatusLog(text);
if (text == "gyro calibration: started") {
_hideAllCalAreas();
_updateAndEmitShowGyroCalArea(true);
_updateAndEmitGyroCalInProgress(true);
} else if (text == "accel calibration: started") {
_hideAllCalAreas();
_accelCalDownSideDone = false;
_accelCalUpsideDownSideDone = false;
_accelCalLeftSideDone = false;
_accelCalRightSideDone = false;
_accelCalTailDownSideDone = false;
_accelCalNoseDownSideDone = false;
_accelCalDownSideInProgress = false;
_accelCalUpsideDownSideInProgress = false;
_accelCalLeftSideInProgress = false;
_accelCalRightSideInProgress = false;
_accelCalNoseDownSideInProgress = false;
_accelCalTailDownSideInProgress = false;
emit accelCalSidesDoneChanged();
emit accelCalSidesInProgressChanged();
_updateAndEmitShowAccelCalArea(true);
} else if (text.startsWith(startingSidePrefix)) {
QString side = text.right(text.length() - startingSidePrefix.length()).section(" ", 0, 0);
qDebug() << "Side started" << side;
if (side == "down") {
_accelCalDownSideInProgress = true;
} else if (side == "up") {
_accelCalUpsideDownSideInProgress = true;
} else if (side == "left") {
_accelCalLeftSideInProgress = true;
} else if (side == "right") {
_accelCalRightSideInProgress = true;
} else if (side == "front") {
_accelCalNoseDownSideInProgress = true;
} else if (side == "back") {
_accelCalTailDownSideInProgress = true;
}
emit accelCalSidesInProgressChanged();
} else if (text.endsWith(sideDoneSuffix)) {
QString side = text.section(" ", 0, 0);
qDebug() << "Side finished" << side;
if (side == "down") {
_accelCalDownSideInProgress = false;
_accelCalDownSideDone = true;
} else if (side == "up") {
_accelCalUpsideDownSideInProgress = false;
_accelCalUpsideDownSideDone = true;
} else if (side == "left") {
_accelCalLeftSideInProgress = false;
_accelCalLeftSideDone = true;
} else if (side == "right") {
_accelCalRightSideInProgress = false;
_accelCalRightSideDone = true;
} else if (side == "front") {
_accelCalNoseDownSideInProgress = false;
_accelCalNoseDownSideDone = true;
} else if (side == "back") {
_accelCalTailDownSideInProgress = false;
_accelCalTailDownSideDone = true;
}
emit accelCalSidesInProgressChanged();
emit accelCalSidesDoneChanged();
} else if (text == "accel calibration: done") {
_progressBar->setProperty("value", 1);
_accelCalDownSideDone = true;
_accelCalUpsideDownSideDone = true;
_accelCalLeftSideDone = true;
_accelCalRightSideDone = true;
_accelCalTailDownSideDone = true;
_accelCalNoseDownSideDone = true;
_accelCalDownSideInProgress = false;
_accelCalUpsideDownSideInProgress = false;
_accelCalLeftSideInProgress = false;
_accelCalRightSideInProgress = false;
_accelCalNoseDownSideInProgress = false;
_accelCalTailDownSideInProgress = false;
emit accelCalSidesDoneChanged();
emit accelCalSidesInProgressChanged();
_refreshParams();
} else if (text == "gyro calibration: done") {
_progressBar->setProperty("value", 1);
_updateAndEmitGyroCalInProgress(false);
_refreshParams();
} else if (text.endsWith(" calibration: failed")) {
QGCMessageBox::warning("Calibration", "Calibration failed. Calibration log will be displayed.");
_hideAllCalAreas();
_progressBar->setProperty("value", 0);
_updateAndEmitGyroCalInProgress(false);
_refreshParams();
}
#if 0
if (text.startsWith("Hold still, starting to measure ")) {
QString axis = text.section(" ", -2, -2);
setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(axis));
}
if (text.startsWith("pending: ")) {
QString axis = text.section(" ", 1, 1);
setInstructionImage(QString(":/files/images/px4/calibration/accel_%1.png").arg(axis));
}
if (text == "rotate in a figure 8 around all axis" /* support for old typo */
|| text == "rotate in a figure 8 around all axes" /* current version */) {
setInstructionImage(":/files/images/px4/calibration/mag_calibration_figure8.png");
}
if (text.endsWith(" calibration: done") || text.endsWith(" calibration: failed")) {
_refreshParams();
// XXX use a confirmation image or something
setInstructionImage(":/files/images/px4/calibration/accel_down.png");
if (text.endsWith(" calibration: done")) {
ui->progressBar->setValue(100);
} else {
ui->progressBar->setValue(0);
}
if (activeUAS) {
_requestAllSensorParameters();
}
}
if (text.endsWith(" calibration: started")) {
setInstructionImage(":/files/images/px4/calibration/accel_down.png");
}
#endif
}
void SensorsComponentController::_refreshParams(void)
......@@ -139,3 +295,27 @@ bool SensorsComponentController::fixedWing(void)
Q_ASSERT(uas);
return uas->getSystemType() == MAV_TYPE_FIXED_WING;
}
void SensorsComponentController::_updateAndEmitGyroCalInProgress(bool inProgress)
{
_gyroCalInProgress = inProgress;
emit gyroCalInProgressChanged();
}
void SensorsComponentController::_updateAndEmitShowGyroCalArea(bool show)
{
_showGyroCalArea = show;
emit showGyroCalAreaChanged();
}
void SensorsComponentController::_updateAndEmitShowAccelCalArea(bool show)
{
_showAccelCalArea = show;
emit showAccelCalAreaChanged();
}
void SensorsComponentController::_hideAllCalAreas(void)
{
_updateAndEmitShowGyroCalArea(false);
_updateAndEmitShowAccelCalArea(false);
}
......@@ -43,8 +43,27 @@ public:
Q_PROPERTY(bool fixedWing READ fixedWing CONSTANT)
/// TextArea for log output
Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog)
Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar)
Q_PROPERTY(bool showGyroCalArea MEMBER _showGyroCalArea NOTIFY showGyroCalAreaChanged)
Q_PROPERTY(bool showAccelCalArea MEMBER _showAccelCalArea NOTIFY showAccelCalAreaChanged)
Q_PROPERTY(bool gyroCalInProgress MEMBER _gyroCalInProgress NOTIFY gyroCalInProgressChanged)
Q_PROPERTY(bool accelCalDownSideDone MEMBER _accelCalDownSideDone NOTIFY accelCalSidesDoneChanged)
Q_PROPERTY(bool accelCalUpsideDownSideDone MEMBER _accelCalUpsideDownSideDone NOTIFY accelCalSidesDoneChanged)
Q_PROPERTY(bool accelCalLeftSideDone MEMBER _accelCalLeftSideDone NOTIFY accelCalSidesDoneChanged)
Q_PROPERTY(bool accelCalRightSideDone MEMBER _accelCalRightSideDone NOTIFY accelCalSidesDoneChanged)
Q_PROPERTY(bool accelCalNoseDownSideDone MEMBER _accelCalNoseDownSideDone NOTIFY accelCalSidesDoneChanged)
Q_PROPERTY(bool accelCalTailDownSideDone MEMBER _accelCalTailDownSideDone NOTIFY accelCalSidesDoneChanged)
Q_PROPERTY(bool accelCalDownSideInProgress MEMBER _accelCalDownSideInProgress NOTIFY accelCalSidesInProgressChanged)
Q_PROPERTY(bool accelCalUpsideDownSideInProgress MEMBER _accelCalUpsideDownSideInProgress NOTIFY accelCalSidesInProgressChanged)
Q_PROPERTY(bool accelCalLeftSideInProgress MEMBER _accelCalLeftSideInProgress NOTIFY accelCalSidesInProgressChanged)
Q_PROPERTY(bool accelCalRightSideInProgress MEMBER _accelCalRightSideInProgress NOTIFY accelCalSidesInProgressChanged)
Q_PROPERTY(bool accelCalNoseDownSideInProgress MEMBER _accelCalNoseDownSideInProgress NOTIFY accelCalSidesInProgressChanged)
Q_PROPERTY(bool accelCalTailDownSideInProgress MEMBER _accelCalTailDownSideInProgress NOTIFY accelCalSidesInProgressChanged)
Q_INVOKABLE void calibrateCompass(void);
Q_INVOKABLE void calibrateGyro(void);
......@@ -54,7 +73,11 @@ public:
bool fixedWing(void);
signals:
void bogusNotify(void);
void showGyroCalAreaChanged(void);
void showAccelCalAreaChanged(void);
void gyroCalInProgressChanged(void);
void accelCalSidesDoneChanged(void);
void accelCalSidesInProgressChanged(void);
private slots:
void _handleUASTextMessage(int uasId, int compId, int severity, QString text);
......@@ -63,8 +86,35 @@ private:
void _beginTextLogging(void);
void _appendStatusLog(const QString& text);
void _refreshParams(void);
void _hideAllCalAreas(void);
void _updateAndEmitGyroCalInProgress(bool inProgress);
void _updateAndEmitShowGyroCalArea(bool show);
void _updateAndEmitShowAccelCalArea(bool show);
QQuickItem* _statusLog; ///< Status log TextArea Qml control
QQuickItem* _statusLog;
QQuickItem* _progressBar;
bool _showGyroCalArea;
bool _showAccelCalArea;
bool _gyroCalInProgress;
bool _accelCalDownSideDone;
bool _accelCalUpsideDownSideDone;
bool _accelCalLeftSideDone;
bool _accelCalRightSideDone;
bool _accelCalNoseDownSideDone;
bool _accelCalTailDownSideDone;
bool _accelCalDownSideInProgress;
bool _accelCalUpsideDownSideInProgress;
bool _accelCalLeftSideInProgress;
bool _accelCalRightSideInProgress;
bool _accelCalNoseDownSideInProgress;
bool _accelCalTailDownSideInProgress;
AutoPilotPlugin* _autopilot;
};
......
import QtQuick 2.2
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QGroundControl.Palette 1.0
Rectangle {
property var __qgcPal: QGCPalette { colorGroupEnabled: enabled }
// Indicates whether calibration is valid for this control
property bool calValid: false
// Indicates whether the control is currently being calibrated
property bool calInProgress: false
// Image source
property var imageSource: ""
width: 200
height: 200
color: calInProgress ? "yellow" : (calValid ? "green" : "red")
Rectangle {
readonly property int inset: 5
property string calText: calInProgress ? "Hold Still" : (calValid ? "Completed" : "Incomplete")
x: inset
y: inset
width: parent.width - (inset * 2)
height: parent.height - (inset * 2)
color: qgcPal.windowShade
Image {
width: parent.width
height: parent.height
source: imageSource
fillMode: Image.PreserveAspectFit
smooth: true
}
Label {
width: parent.width
height: parent.height
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignBottom
font.pointSize: 25
font.bold: true
color: "black"
text: parent.calText
}
Label {
width: parent.width
height: parent.height
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignBottom
font.pointSize: 25
color: calInProgress ? "yellow" : "white"
text: parent.calText
}
}
}
......@@ -10,4 +10,5 @@ QGCColoredImage 1.0 QGCColoredImage.qml
SubMenuButton 1.0 SubMenuButton.qml
IndicatorButton 1.0 IndicatorButton.qml
VehicleRotationCal 1.0 VehicleRotationCal.qml
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