diff --git a/qgcimages.qrc b/qgcimages.qrc
index 317c55a..cdff331 100644
--- a/qgcimages.qrc
+++ b/qgcimages.qrc
@@ -189,6 +189,7 @@
src/AutoPilotPlugins/PX4/Images/VehicleTailDownRotate.png
src/AutoPilotPlugins/PX4/Images/VehicleUpsideDown.png
src/AutoPilotPlugins/PX4/Images/VehicleUpsideDownRotate.png
+ src/AnalyzeView/VibrationPageIcon.png
src/AutoPilotPlugins/Common/Images/wifi.svg
src/ui/toolbar/Images/Yield.svg
src/FlightMap/Images/ZoomMinus.svg
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 047f9b7..cb4b151 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -273,7 +273,7 @@
src/ui/preferences/UdpSettings.qml
src/FlightMap/Widgets/ValuePageWidget.qml
src/VehicleSetup/VehicleSummary.qml
- src/FlightMap/Widgets/VibrationPageWidget.qml
+ src/AnalyzeView/VibrationPage.qml
src/FlightMap/Widgets/VideoPageWidget.qml
src/FlightDisplay/VirtualJoystick.qml
src/PlanView/VTOLLandingPatternEditor.qml
diff --git a/src/AnalyzeView/VibrationPage.qml b/src/AnalyzeView/VibrationPage.qml
new file mode 100644
index 0000000..35cb367
--- /dev/null
+++ b/src/AnalyzeView/VibrationPage.qml
@@ -0,0 +1,170 @@
+/****************************************************************************
+ *
+ * (c) 2009-2020 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick 2.11
+import QtQuick.Controls 2.4
+import QtQuick.Dialogs 1.3
+import QtQuick.Layouts 1.11
+
+import QGroundControl 1.0
+import QGroundControl.Palette 1.0
+import QGroundControl.FactSystem 1.0
+import QGroundControl.FactControls 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Controllers 1.0
+
+AnalyzePage {
+ id: geoTagPage
+ pageComponent: pageComponent
+ pageName: qsTr("Vibration")
+ pageDescription: qsTr("Analyze vibration associated with your vehicle.")
+
+ property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
+ property bool _available: !isNaN(_activeVehicle.vibration.xAxis.rawValue)
+ property real _margins: ScreenTools.defaultFontPixelWidth / 2
+ property real _barWidth: ScreenTools.defaultFontPixelWidth * 3
+ property real _barHeight: ScreenTools.defaultFontPixelHeight * 10
+ property real _xValue: _activeVehicle.vibration.xAxis.rawValue
+ property real _yValue: _activeVehicle.vibration.yAxis.rawValue
+ property real _zValue: _activeVehicle.vibration.zAxis.rawValue
+
+ readonly property real _barMinimum: 0.0
+ readonly property real _barMaximum: 90.0
+ readonly property real _barBadValue: 60.0
+
+ QGCPalette { id:qgcPal; colorGroupEnabled: true }
+
+ Component {
+ id: pageComponent
+
+ Item {
+ width: childrenRect.width
+ height: childrenRect.height
+
+ RowLayout {
+ id: barRow
+ spacing: ScreenTools.defaultFontPixelWidth * 4
+
+ ColumnLayout {
+ Rectangle {
+ id: xBar
+ height: _barHeight
+ width: _barWidth
+ Layout.alignment: Qt.AlignHCenter
+ border.width: 1
+ border.color: qgcPal.text
+
+ Rectangle {
+ anchors.bottom: parent.bottom
+ width: parent.width
+ height: parent.height * (Math.min(_barMaximum, _xValue) / (_barMaximum - _barMinimum))
+ color: qgcPal.text
+ }
+ }
+
+ QGCLabel {
+ Layout.alignment: Qt.AlignHCenter
+ text: qsTr("X")
+ }
+ }
+
+ Column {
+ Rectangle {
+ height: _barHeight
+ width: _barWidth
+ Layout.alignment: Qt.AlignHCenter
+ border.width: 1
+ border.color: qgcPal.text
+
+ Rectangle {
+ anchors.bottom: parent.bottom
+ width: parent.width
+ height: parent.height * (Math.min(_barMaximum, _yValue) / (_barMaximum - _barMinimum))
+ color: qgcPal.text
+ }
+ }
+
+ QGCLabel {
+ Layout.alignment: Qt.AlignHCenter
+ text: qsTr("Y")
+ }
+ }
+
+ Column {
+ Rectangle {
+ height: _barHeight
+ width: _barWidth
+ Layout.alignment: Qt.AlignHCenter
+ border.width: 1
+ border.color: qgcPal.text
+
+ Rectangle {
+ anchors.bottom: parent.bottom
+ width: parent.width
+ height: parent.height * (Math.min(_barMaximum, _zValue) / (_barMaximum - _barMinimum))
+ color: qgcPal.text
+ }
+ }
+
+ QGCLabel {
+ Layout.alignment: Qt.AlignHCenter
+ text: qsTr("Z")
+ }
+ }
+ }
+
+ // Max vibe indication line at 60
+ Rectangle {
+ anchors.topMargin: xBar.height * (1.0 - ((_barBadValue - _barMinimum) / (_barMaximum - _barMinimum)))
+ anchors.top: barRow.top
+ anchors.left: barRow.left
+ anchors.right: barRow.right
+ width: barRow.width
+ height: 1
+ color: "red"
+ }
+
+ Column {
+ anchors.margins: ScreenTools.defaultFontPixelWidth
+ anchors.left: barRow.right
+
+ QGCLabel {
+ text: qsTr("Clip count")
+ }
+
+ QGCLabel {
+ text: qsTr("Accel 1: ") + (_activeVehicle.vibration.clipCount1.rawValueString)
+ }
+
+ QGCLabel {
+ text: qsTr("Accel 2: ") + (_activeVehicle.vibration.clipCount2.rawValueString)
+ }
+
+ QGCLabel {
+ text: qsTr("Accel 3: ") + (_activeVehicle.vibration.clipCount3.rawValueString)
+ }
+ }
+
+ Rectangle {
+ anchors.fill: parent
+ color: qgcPal.window
+ opacity: 0.75
+ visible: !_available
+
+ QGCLabel {
+ anchors.fill: parent
+ horizontalAlignment: Text.AlignHCenter
+ verticalAlignment: Text.AlignVCenter
+ text: qsTr("Not Available")
+ }
+ }
+ }
+ }
+}
diff --git a/src/AnalyzeView/VibrationPageIcon.png b/src/AnalyzeView/VibrationPageIcon.png
new file mode 100644
index 0000000..8ab5a00
Binary files /dev/null and b/src/AnalyzeView/VibrationPageIcon.png differ
diff --git a/src/FlightMap/Widgets/VibrationPageWidget.qml b/src/FlightMap/Widgets/VibrationPageWidget.qml
deleted file mode 100644
index dea85a5..0000000
--- a/src/FlightMap/Widgets/VibrationPageWidget.qml
+++ /dev/null
@@ -1,153 +0,0 @@
-/****************************************************************************
- *
- * (c) 2009-2020 QGROUNDCONTROL PROJECT
- *
- * QGroundControl is licensed according to the terms in the file
- * COPYING.md in the root of the source code directory.
- *
- ****************************************************************************/
-
-import QtQuick 2.3
-import QtQuick.Controls 1.2
-
-import QGroundControl.Controls 1.0
-import QGroundControl.ScreenTools 1.0
-import QGroundControl.FactSystem 1.0
-import QGroundControl.Controllers 1.0
-import QGroundControl.Palette 1.0
-import QGroundControl 1.0
-
-Rectangle {
- height: barRow.y + barRow.height
- width: pageWidth
- color: qgcPal.window
-
- property bool showSettingsIcon: false
-
- property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
- property bool _available: _activeVehicle ? !isNaN(_activeVehicle.vibration.xAxis.value) : false
- property real _margins: ScreenTools.defaultFontPixelWidth / 2
- property real _barWidth: Math.round(ScreenTools.defaultFontPixelWidth * 3)
-
- readonly property real _barMinimum: 0.0
- readonly property real _barMaximum: 90.0
- readonly property real _barBadValue: 60.0
-
- QGCPalette { id:qgcPal; colorGroupEnabled: true }
-
- QGCLabel {
- id: title
- text: qsTr("Vibe")
- anchors.horizontalCenter: barRow.horizontalCenter
- }
-
- Row {
- id: barRow
- anchors.margins: _margins
- anchors.top: title.bottom
- anchors.left: parent.left
- spacing: _margins
-
- Column {
- ProgressBar {
- id: xBar
- height: 50
- orientation: Qt.Vertical
- minimumValue: _barMinimum
- maximumValue: _barMaximum
- value: _activeVehicle ? _activeVehicle.vibration.xAxis.value : 0
- }
-
- QGCLabel {
- id: xBarLabel
- text: "X"
- anchors.horizontalCenter: xBar.horizontalCenter
- }
- }
-
- Column {
- ProgressBar {
- id: yBar
- height: 50
- orientation: Qt.Vertical
- minimumValue: _barMinimum
- maximumValue: _barMaximum
- value: _activeVehicle ? _activeVehicle.vibration.yAxis.value : 0
- }
-
- QGCLabel {
- anchors.horizontalCenter: yBar.horizontalCenter
- text: "Y"
- }
- }
-
- Column {
- ProgressBar {
- id: zBar
- height: 50
- orientation: Qt.Vertical
- minimumValue: _barMinimum
- maximumValue: _barMaximum
- value: _activeVehicle ? _activeVehicle.vibration.zAxis.value : 0
- }
-
- QGCLabel {
- anchors.horizontalCenter: zBar.horizontalCenter
- text: "Z"
- }
- }
- } // Row
-
- // Max vibe indication line at 60
- Rectangle {
- anchors.topMargin: xBar.height * (1.0 - ((_barBadValue - _barMinimum) / (_barMaximum - _barMinimum)))
- anchors.top: barRow.top
- anchors.left: barRow.left
- anchors.right: barRow.right
- width: barRow.width
- height: 1
- color: "red"
- }
-
- QGCLabel {
- id: clipLabel
- anchors.margins: _margins
- anchors.left: barRow.right
- anchors.right: parent.right
- text: qsTr("Clip count")
- horizontalAlignment: Text.AlignHCenter
- }
-
- Column {
- id: clipColumn
- anchors.top: barRow.top
- anchors.horizontalCenter: clipLabel.horizontalCenter
-
- QGCLabel {
- text: qsTr("Accel 1: ") + (_activeVehicle ? _activeVehicle.vibration.clipCount1.valueString : "")
- }
-
- QGCLabel {
- text: qsTr("Accel 2: ") + (_activeVehicle ? _activeVehicle.vibration.clipCount2.valueString : "")
- }
-
- QGCLabel {
- text: qsTr("Accel 3: ") + (_activeVehicle ? _activeVehicle.vibration.clipCount3.valueString : "")
- }
- }
-
- // Not available overlay
- Rectangle {
- anchors.fill: parent
- color: qgcPal.window
- opacity: 0.75
- visible: !_available
-
- QGCLabel {
- anchors.fill: parent
- horizontalAlignment: Text.AlignHCenter
- verticalAlignment: Text.AlignVCenter
- text: qsTr("Not Available")
- }
- }
-} // Item
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index ac6f97d..349ba37 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -1266,9 +1266,9 @@ void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
_gpsFactGroup.lon()->setRawValue(gpsRawInt.lon * 1e-7);
_gpsFactGroup.mgrs()->setRawValue(convertGeoToMGRS(QGeoCoordinate(gpsRawInt.lat * 1e-7, gpsRawInt.lon * 1e-7)));
_gpsFactGroup.count()->setRawValue(gpsRawInt.satellites_visible == 255 ? 0 : gpsRawInt.satellites_visible);
- _gpsFactGroup.hdop()->setRawValue(gpsRawInt.eph == UINT16_MAX ? std::numeric_limits::quiet_NaN() : gpsRawInt.eph / 100.0);
- _gpsFactGroup.vdop()->setRawValue(gpsRawInt.epv == UINT16_MAX ? std::numeric_limits::quiet_NaN() : gpsRawInt.epv / 100.0);
- _gpsFactGroup.courseOverGround()->setRawValue(gpsRawInt.cog == UINT16_MAX ? std::numeric_limits::quiet_NaN() : gpsRawInt.cog / 100.0);
+ _gpsFactGroup.hdop()->setRawValue(gpsRawInt.eph == UINT16_MAX ? qQNaN() : gpsRawInt.eph / 100.0);
+ _gpsFactGroup.vdop()->setRawValue(gpsRawInt.epv == UINT16_MAX ? qQNaN() : gpsRawInt.epv / 100.0);
+ _gpsFactGroup.courseOverGround()->setRawValue(gpsRawInt.cog == UINT16_MAX ? qQNaN() : gpsRawInt.cog / 100.0);
_gpsFactGroup.lock()->setRawValue(gpsRawInt.fix_type);
}
@@ -1338,7 +1338,7 @@ void Vehicle::_handleHighLatency(mavlink_message_t& message)
_groundSpeedFact.setRawValue((double)highLatency.groundspeed / 5.0);
_climbRateFact.setRawValue((double)highLatency.climb_rate / 10.0);
_headingFact.setRawValue((double)highLatency.heading * 2.0);
- _altitudeRelativeFact.setRawValue(std::numeric_limits::quiet_NaN());
+ _altitudeRelativeFact.setRawValue(qQNaN());
_altitudeAMSLFact.setRawValue(coordinate.altitude);
_windFactGroup.speed()->setRawValue((double)highLatency.airspeed / 5.0);
@@ -1385,7 +1385,7 @@ void Vehicle::_handleHighLatency2(mavlink_message_t& message)
_groundSpeedFact.setRawValue((double)highLatency2.groundspeed / 5.0);
_climbRateFact.setRawValue((double)highLatency2.climb_rate / 10.0);
_headingFact.setRawValue((double)highLatency2.heading * 2.0);
- _altitudeRelativeFact.setRawValue(std::numeric_limits::quiet_NaN());
+ _altitudeRelativeFact.setRawValue(qQNaN());
_altitudeAMSLFact.setRawValue(highLatency2.altitude);
_windFactGroup.direction()->setRawValue((double)highLatency2.wind_heading * 2.0);
@@ -1399,8 +1399,8 @@ void Vehicle::_handleHighLatency2(mavlink_message_t& message)
_gpsFactGroup.lon()->setRawValue(highLatency2.longitude * 1e-7);
_gpsFactGroup.mgrs()->setRawValue(convertGeoToMGRS(QGeoCoordinate(highLatency2.latitude * 1e-7, highLatency2.longitude * 1e-7)));
_gpsFactGroup.count()->setRawValue(0);
- _gpsFactGroup.hdop()->setRawValue(highLatency2.eph == UINT8_MAX ? std::numeric_limits::quiet_NaN() : highLatency2.eph / 10.0);
- _gpsFactGroup.vdop()->setRawValue(highLatency2.epv == UINT8_MAX ? std::numeric_limits::quiet_NaN() : highLatency2.epv / 10.0);
+ _gpsFactGroup.hdop()->setRawValue(highLatency2.eph == UINT8_MAX ? qQNaN() : highLatency2.eph / 10.0);
+ _gpsFactGroup.vdop()->setRawValue(highLatency2.epv == UINT8_MAX ? qQNaN() : highLatency2.epv / 10.0);
struct failure2Sensor_s {
HL_FAILURE_FLAG failureBit;
@@ -4375,9 +4375,9 @@ VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent)
_addFact(&_verticalSpeedFact, _verticalSpeedFactName);
// Start out as not available "--.--"
- _directionFact.setRawValue (std::numeric_limits::quiet_NaN());
- _speedFact.setRawValue (std::numeric_limits::quiet_NaN());
- _verticalSpeedFact.setRawValue (std::numeric_limits::quiet_NaN());
+ _directionFact.setRawValue (qQNaN());
+ _speedFact.setRawValue (qQNaN());
+ _verticalSpeedFact.setRawValue (qQNaN());
}
const char* VehicleVibrationFactGroup::_xAxisFactName = "xAxis";
@@ -4404,9 +4404,9 @@ VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
_addFact(&_clipCount3Fact, _clipCount3FactName);
// Start out as not available "--.--"
- _xAxisFact.setRawValue(std::numeric_limits::quiet_NaN());
- _yAxisFact.setRawValue(std::numeric_limits::quiet_NaN());
- _zAxisFact.setRawValue(std::numeric_limits::quiet_NaN());
+ _xAxisFact.setRawValue(qQNaN());
+ _yAxisFact.setRawValue(qQNaN());
+ _zAxisFact.setRawValue(qQNaN());
}
const char* VehicleTemperatureFactGroup::_temperature1FactName = "temperature1";
@@ -4424,9 +4424,9 @@ VehicleTemperatureFactGroup::VehicleTemperatureFactGroup(QObject* parent)
_addFact(&_temperature3Fact, _temperature3FactName);
// Start out as not available "--.--"
- _temperature1Fact.setRawValue (std::numeric_limits::quiet_NaN());
- _temperature2Fact.setRawValue (std::numeric_limits::quiet_NaN());
- _temperature3Fact.setRawValue (std::numeric_limits::quiet_NaN());
+ _temperature1Fact.setRawValue (qQNaN());
+ _temperature2Fact.setRawValue (qQNaN());
+ _temperature3Fact.setRawValue (qQNaN());
}
const char* VehicleClockFactGroup::_currentTimeFactName = "currentTime";
@@ -4477,12 +4477,12 @@ VehicleSetpointFactGroup::VehicleSetpointFactGroup(QObject* parent)
_addFact(&_yawRateFact, _yawRateFactName);
// Start out as not available "--.--"
- _rollFact.setRawValue(std::numeric_limits::quiet_NaN());
- _pitchFact.setRawValue(std::numeric_limits::quiet_NaN());
- _yawFact.setRawValue(std::numeric_limits::quiet_NaN());
- _rollRateFact.setRawValue(std::numeric_limits::quiet_NaN());
- _pitchRateFact.setRawValue(std::numeric_limits::quiet_NaN());
- _yawRateFact.setRawValue(std::numeric_limits::quiet_NaN());
+ _rollFact.setRawValue(qQNaN());
+ _pitchFact.setRawValue(qQNaN());
+ _yawFact.setRawValue(qQNaN());
+ _rollRateFact.setRawValue(qQNaN());
+ _pitchRateFact.setRawValue(qQNaN());
+ _yawRateFact.setRawValue(qQNaN());
}
const char* VehicleDistanceSensorFactGroup::_rotationNoneFactName = "rotationNone";
@@ -4521,15 +4521,15 @@ VehicleDistanceSensorFactGroup::VehicleDistanceSensorFactGroup(QObject* parent)
_addFact(&_rotationPitch270Fact, _rotationPitch270FactName);
// Start out as not available "--.--"
- _rotationNoneFact.setRawValue(std::numeric_limits::quiet_NaN());
- _rotationYaw45Fact.setRawValue(std::numeric_limits::quiet_NaN());
- _rotationYaw135Fact.setRawValue(std::numeric_limits::quiet_NaN());
- _rotationYaw90Fact.setRawValue(std::numeric_limits::quiet_NaN());
- _rotationYaw180Fact.setRawValue(std::numeric_limits::quiet_NaN());
- _rotationYaw225Fact.setRawValue(std::numeric_limits::quiet_NaN());
- _rotationYaw270Fact.setRawValue(std::numeric_limits::quiet_NaN());
- _rotationPitch90Fact.setRawValue(std::numeric_limits::quiet_NaN());
- _rotationPitch270Fact.setRawValue(std::numeric_limits::quiet_NaN());
+ _rotationNoneFact.setRawValue(qQNaN());
+ _rotationYaw45Fact.setRawValue(qQNaN());
+ _rotationYaw135Fact.setRawValue(qQNaN());
+ _rotationYaw90Fact.setRawValue(qQNaN());
+ _rotationYaw180Fact.setRawValue(qQNaN());
+ _rotationYaw225Fact.setRawValue(qQNaN());
+ _rotationYaw270Fact.setRawValue(qQNaN());
+ _rotationPitch90Fact.setRawValue(qQNaN());
+ _rotationPitch270Fact.setRawValue(qQNaN());
}
const char* VehicleEstimatorStatusFactGroup::_goodAttitudeEstimateFactName = "goodAttitudeEsimate";
diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc
index b8c36f9..33f5a69 100644
--- a/src/api/QGCCorePlugin.cc
+++ b/src/api/QGCCorePlugin.cc
@@ -276,7 +276,6 @@ QVariantList& QGCCorePlugin::instrumentPages()
_p->videoPageWidgetInfo = new QmlComponentInfo(tr("Video Stream"), QUrl::fromUserInput("qrc:/qml/VideoPageWidget.qml"));
}
#endif
- _p->vibrationPageWidgetInfo = new QmlComponentInfo(tr("Vibration"), QUrl::fromUserInput("qrc:/qml/VibrationPageWidget.qml"));
_p->instrumentPageWidgetList.append(QVariant::fromValue(_p->cameraPageWidgetInfo));
#if defined(QGC_GST_STREAMING)
@@ -290,14 +289,15 @@ QVariantList& QGCCorePlugin::instrumentPages()
QVariantList& QGCCorePlugin::analyzePages()
{
if (!_p->analyzeList.count()) {
- _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("Log Download"), QUrl::fromUserInput("qrc:/qml/LogDownloadPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/LogDownloadIcon"))));
+ _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("Log Download"), QUrl::fromUserInput("qrc:/qml/LogDownloadPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/LogDownloadIcon"))));
#if !defined(__mobile__)
- _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("GeoTag Images"), QUrl::fromUserInput("qrc:/qml/GeoTagPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/GeoTagIcon"))));
+ _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("GeoTag Images"), QUrl::fromUserInput("qrc:/qml/GeoTagPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/GeoTagIcon"))));
#endif
- _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("MAVLink Console"), QUrl::fromUserInput("qrc:/qml/MavlinkConsolePage.qml"), QUrl::fromUserInput("qrc:/qmlimages/MavlinkConsoleIcon"))));
+ _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("MAVLink Console"), QUrl::fromUserInput("qrc:/qml/MavlinkConsolePage.qml"), QUrl::fromUserInput("qrc:/qmlimages/MavlinkConsoleIcon"))));
#if defined(QGC_ENABLE_MAVLINK_INSPECTOR)
- _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("MAVLink Inspector"),QUrl::fromUserInput("qrc:/qml/MAVLinkInspectorPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/MAVLinkInspector"))));
+ _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("MAVLink Inspector"),QUrl::fromUserInput("qrc:/qml/MAVLinkInspectorPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/MAVLinkInspector"))));
#endif
+ _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("Vibration"), QUrl::fromUserInput("qrc:/qml/VibrationPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/VibrationPageIcon"))));
}
return _p->analyzeList;
}