From 93d5ee9f39ee54331902e2fc54318ce20a579515 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Sat, 15 Aug 2020 14:12:03 -0700 Subject: [PATCH] Move Vibration to Analyze --- qgcimages.qrc | 1 + qgroundcontrol.qrc | 2 +- src/AnalyzeView/VibrationPage.qml | 170 ++++++++++++++++++ src/AnalyzeView/VibrationPageIcon.png | Bin 0 -> 8381 bytes src/FlightMap/Widgets/VibrationPageWidget.qml | 153 ---------------- src/Vehicle/Vehicle.cc | 62 +++---- src/api/QGCCorePlugin.cc | 10 +- 7 files changed, 208 insertions(+), 190 deletions(-) create mode 100644 src/AnalyzeView/VibrationPage.qml create mode 100644 src/AnalyzeView/VibrationPageIcon.png delete mode 100644 src/FlightMap/Widgets/VibrationPageWidget.qml diff --git a/qgcimages.qrc b/qgcimages.qrc index 317c55a459..cdff3312a2 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 047f9b73a6..cb4b1510ed 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 0000000000..35cb367b79 --- /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 0000000000000000000000000000000000000000..8ab5a003e4a97023e9683f848cb19d80d7aca0bd GIT binary patch literal 8381 zcmeAS@N?(olHy`uVBq!ia0y~yU}6Aa4rT@hhQrHLPB1VqFc&*{hH!9j+-L1P+nfHmzkGcoSayYs+V7sKKq@G z6axb@Lx4|+>;M1%8Aicq2#nMa;8x!Lkb!~We@T#EFaskKGYcylI|nBhHxDl#zkr~S zu!yLbxP+vXw2Z8ryn>>VvWlvjx`w8fwvMizzJZ~Uv5BdfxrL>bwT-Qvy@R8Zvx}>n zyN9Qjw~w!%e?VYRa7buactm7WbWChqd_rPUa!P7idPZhec1~_yenDYTaY<=ec|~Pa zbxmzueM4hYb4zPmdq-zicTaC$|AdK?CQq3EN?fQ+I zw{G9Ld++{(hmRgVdHU@6i5BX?Jc_=Irnp-nOWs@{Ri?|?{CVaB@4a&ESnu!5$Zgn_t?7BI|t4rCz=V} zKAXmL)i%+L>+HTXr_=ncH#wf{J+7j~mAL4=q?+k=U7stmr$pQiy4s3gvffbPu*!C zXgWiWD^V$nC-zHw=Zg0)7D=ehnsw=9$czlD7QaV74JMjQ$lGKss+2dbY^tioETTq&^crB3)lD=9XosDL=L)~k^ZuX zM=j~u#qLuvGdyliyC-tU<&@!9?Nkpv#HSFIgr&Ej`P^pBe~$imwV|5SE;MX}6rg#6p3+(oDjV;+J;|%{U?9`2N`e zmt*2z7V`SIn5hufm_!%BA zT$~eLpLB)8iHFQ5NbeHLyl8RG!7I_J+*Ej{)XNR_%_~ndao*(h$uYQ; zz`*>9L3kba%rmJR_mg>6==-dgbvE6|J4&%6SRz2sXT`guB3F*+I8kP;X3pT-UTWbt z#T0LMJBB_x)bc`dnURp9_3TE`LoMm2rIrO>|)pKY2!S}kyWm2vyoL~AM?2-0er%JZlYJ} z&bejW3aXU5(dxzMqv5x(`>?>Q$18c*Hi-wnU=;59Sn^TB$+*XhpW%Iw1e0*vw5uf> z4fqo!-Itm+SZho<(DE>7mnC1~Oy7s%YYLQFEe#T9_?RaPObQD*me^Vra_a!g^@)Ac zOdTz%0(MGjpIv%^TWv@5%T@A+3}>9;jL5WUeQ3~_`qv{oUqR-4@J%^w-lYLt!Z#F4 z!Y*?y{Ly!4kwn-p?ba@x84KhV@9q|CTNZNfn3nF!k_OHd50!TPmPoW{IdwPUEjw53 zM7`U*b#HD?+HPO9;=5SKHsP19)h!QGbhfr zXMx?)fV%?OZ+sQ!^&7kmJ^AFE`x6%sRtvjzZLNk znDy~Wmw@EkmzP~w4Cb7g7!jV&RV*;;=9Ne63R-QK)|Y*F&#Sd|!@6xDw-i)#UnW(_ zEmHiZ`&WwR|Fgguy|i*oqWpRN*Qx&P|K6dT|ZUW1t(a~|Hs=N@4Ql`|JFaJg-YBHXSlhCD=_t?GT5gb zTpqq+i*v5-iV_D6scRQ5Uix;TM&F>L`N3r!F7D)r^WQ~&DT%a}d@JLbx$b2V+eiN& zmz%sauYH$kRcd)8v&)))<~tiUqxE(*Fa4hCt$EMImCE5Ncvtt9kmS2swqlW*owH75 zM%+IrqE#%|#{c5r=@U7*k{2|77|rr>U!!mDw@^Uw#Ht12>WYhF&o@jnX_GhB&^djO zZCTKZet|8^)r-yC)qb}*&gGJy74TC+x@wM-p;H0V-byCPHO9=+?DBkzJ_(qWFt)Db zIA~B+qGEKNnP*KEcSSkp)Z&c`owz>Muzc6D{k6}~DD>}6o^|$nq#c(ENS|7}IfOQXjvq5b0S z%*qoUzS9DCO}}*YLsq_)@`MwTBBumzq<%@1FuHVe%Cl!@mwZy)W7U63)nf_sR3?_M zEVV0ciOzf>>*cy*ZjgG#7k{nT2_9vvt#TZ%ynh*Lvd>)ZJLi(!jk%ZZKMa(ds^;+` zm&;ioAkMT_vgJ%M@6vn*pT(bQdFEY-c1vUvlJ;B3!uZy+ep+6C&u7!6uNh;!Uouo& z>O58Ku|~YrlH-NXuMjEcwx7mZ%NTA2{$jUz>HSnn2nHTE`KJr*3fhx5+XvAFMN!8h$zRzsCi%T^m@M8nK-2&MW40iR@c+ zLH?iZxdVAlYC9%ha#^GNnq6!D;fvlOR!Xf&Tt`3Tb1|=e)v`Z#jq7e}l(x*4 z*VH-d$n{s#r!{})RGxJ@(xq|bUQ=f$$L65{NQhW z#pbb6zqRPc)`n9_yCN<~l}5gn@?uY_{i`X=Vlt<`p)5S2ooxzQFuX#y3^z*rk)4D-PQ&H{p@iS{QUu;1YwDxUe0hi!^Tr^nmu*&B)nZE-J)UH0O+BmdBsB1c{*>I6TN>qk zS6ne++VD4M*N;5mE55Osp}CDN|GZwta8w6M@@De2#(j9~pcS9I)Ul+9|J5?VDRGWY zU!Mh4N*}TeS=aVOtM%cBWQM7M5t`{ju~*(S?^+Say7ZpM8%M2=YbV~aUm?TzvWjcz zhsS|h;Ym|tSHF0)I_8R_dT`VghE7?Bmqkm=CVFvuxCgB`(ZoML=w;v4wu>hNt~fr{ zwCz$!x*t5VXG+nupdXyK#6qkN?5;Y!a?6pdotIxMDiXh9sk>TJwkIWT=@#Rlmkv)u zEq?Sl#aC?So_aGPdA~($&79s{&w{+{Qxs?VP04f8S{}5MlW*SA0G9WDOO52}cg*)= zTeR-yluNoE@3^&$C!Cra(%0I2T4Tz=-PSAablIEyo2NHzi|gG>jknHuywmcUJJCsV z>e~ko6u74D{P4zCOFeO|@{1?FS9G@r{Swj4@qTHiA|CCL=*Yt-bv;0%CB1m%o0ig^ zC6kQFdNcqz2xlibw!q6s0^TEY*Wcys-Icr`3!T1v9)*}8?@tZM_>WqeldVhysK zf9aves|v0111FP3x*lGQUs2N%RdxB~=M~O!OHKGRP1i5_WHD*i%u|{LMRu(#KV%t9 zZ4bB|VPz>->elQ!<(IUz2jjv8dn>BULwoU$ZTC=3l{r}QU{MU;4=GwIFdKBt)R6t61*(aq*8NR7XGPN#= z0((yO2Y2K*eLbRf!87~{FKg%&zUEIVQ=iUO+$b0FkJ0^mumo@Zx5Y-X(l_cfV{2}6 zlpbR6GTyx4%YqUyq21F?Sr(L7wH8%eo`1^t#)YRPMdq(sjJ&oxuKKP$b^C-HpF_Si zEuOnVHe`#& z)jRCdCF)DXR<&5t$DG>X@**wc38 zTleLoM{-*9)X#UjYwTrHm(}ETW%3WS6ganS;UzY?J8nODPE?BmS$BJ($C3Z1Ykmb#qyQLUhu zb*WQM!el9~|E=un10?wP>lSV@p7iqEm&k9I_C>^R*PkJ${4is-#njy!8*5kEaPzNQ z9Kcn+c7@Jaw;<&ie&@Fw+_fn$ZC6S2>hcwT=JbAzb$F^(QNYsLrDI{;bn3Xrx|{kw z%a0yUT6=80L2TWrw$-0CN{{}MTX;!U&Sd!|#&hcyeez#&VRokIezxqCy=S)UWIi`5 zG^mp2_3tTO+!Y^nTlW=wP=B<@1y%Dd-hlT*D#)r3=51N73X zdf9Io_5M0Ed5&esy#u>8i3iW%@0VK|z~e5wQifA?cTZ;MR!P0oUpkpQ`R|qoUFLdy zqw`eshZiz&KO?I-8_bXdq#LkzO z6xDm=xX*m$2Z3**wNfLFzYXzgbN@O$@CB3l-j#d!*mnlc^n0JAb~&w#Z;zDQO51By zlTV%dkfqe>SWv`0^%%^9Xl^@(ZS2MPM>$Bj9NxbXdEjEzyI~Hgu>Gv*K zO82PGva@m@-Wh9M{@897V%L(sJW!*3^86Jg4U>IO&9vM9NO{@m@DC4*ys8s>=Y@1V zxY-xN^wN3^Uao z9hpM+rRt^x&79hLf3H)je#LjSR>cB?j#K*|th$-A?DW};!zMEs;?FHC;i&sA+`7u9 zqFlRG$fBaltKQ=E(GpD-HDg=927O=cl{P(BqXK3!$@eWbVCUPnXp{V%y(hlRkYx5t zjH+RnAGc_eg7|6~$E6Z>IlfDIm#|$GdGxd3dKKg4M{Eom{b%x3A6|ZMN>$R-)hlCI z?9+l@u)aJWvaeA*-B>ow{1{ie5%0XFc;5QOMpCP7+@CW1_-NGnaKgD|MpAJ{?j=e6 z;a$y>`a&$1`Mz5~hOZE`Ee^cmS$ubj$10GuKhvx^1bScRAKjp31e$$xe^rqRb7j9b@OFE9J%FOLK%<9=LhE zy|7`{A)g;546UbPmVD!y8vMY2_QJ{HMiW#YpUZ9Cm8VK+QoD74k zrkqllA+oI}SkkWZ)V2?=W4MARUUJalKfJ`K@zj~8BF_$Px79fEdEzM#E%5_Oio}|$ zh4)>Jc3a3D^mERse+Daaw#{k0%lF@Ii2;Y^ld!;!e6GotxOvv_|JgnLP{xuC>{BHT zR?aKZ#JMnMk!8xr8c?$!YmTX&WB<{AW{otEUg}$W*?4Dnj zd{XNPIpMIXNbpEl$SsAL(kt#TF0MVSVCQULAN-;(5yK{sdHJ#wCl}<2Azy=`V;t;2TW`|vMb;x%dw+Nzv$2FPnZ?>vf+r{ zvQHd6-PcUNytU_ewO{0y(#9k$@k17sllR#+FPOJ1pyh~Ku%*B;Py1hGtWCRGoFs)- z#e1d(OQ`!!ySP4&BdeZk>Q0Z8aIO1?ETo+GZ*vIfU8O0aH1YCE8~(>HEPj~?AM{;# zLB8{j>r*QU_e$=U=Ob9Y8?+{=d=i_wI3dQ?t3J=6;CaA|E|+J)H`$I|P5km)f@QmP zYlWTJ7T&3q2In@_FVerQw4=&fv*ch~-=a@qJ-c_mIBwJOkeRD_!@}1q?r=WN)Bp96 z?N9-K>%|)vB(#gF^i)a0 zKkC|r)xQP%=7~H@sGYn*hUM|u*I!=wv?P0L-$cx?6a7iUvio=R~oUGcU|>-yn}tCR29bZsbE95Asp zDsFj^Nl*Ar?iVLpIlP0lWCKpG582lG@l9gYCVQvPysi5pu1^bjcDSOPV{eDKTgJRa z0WGCp7Z@=f+r1|8OM=y*V#8LWHLs<#$`Af1V7HZM{qV+pp^^COifN}_8rZ$@x{C+0_Ts*%PlH0?6GHlk;QRn%H}Cf;(s10YsDt~ z$qe*$cUKO1A1u*gx@mgQO`c=R>n~q4$CLSAfQGDfPfg z!DH+HEG_wDb?E9mFUGp>((=ZX%lX6Z zn<2Lj{Fr7vU$4yJL|dT7!7SaCIt`o;;!6T1woZ_BPUH)F?YC4!twFEkgWaKPv%I9& z6sb<#oyc_J*Th?YIqvFk?cH$da>%&`&LoSibsTrOMcR_5W`>ltb0(E%?N%-c57s#9 z#ha}W^7Igk(NwS0+Lm>ok+n4&%%^G^9OPMMB>C`mj~Dxz0==on6Pq%2fSn#o>cp+koog@ z2dTL(3;%d)RUc?sdN^fWx{vpg%ilt>K*7m!oO($rNMBGyDdU zZ!6i1#ncwZ9!+RFl(OZp#F>o-l50KZG;V1r}){`~w zFKs`YXmo$>m)GtyI4maC?d1_>eEZ^huR)+eznv_YJ8NNsZI_wu3Imo4>qanepO<`}tdkU5@L0 zS*66SX0=KD^5XA_i=N0ud%TwCX)dtY9hHwe5m?HFz(T zrE}WCFHeeQWc=i|eaR)PtNX%}(dWn?2mZRI&RNf2ICA=2iE-r5YwMil{K8Rx#)_LJ ze&zK|opUlv!X~l`TlQbR$!>75m~pP?L6`IQO3L_rzB~!N6sqXM;=5?^tTqF|5Eu90 z#6>T7tg5)wx~wi;6g3E(66>p;eP5YLY>G`DeF571Alft_wp}oXFTJ2Pk_RL!qGd!y2uZ(3E z&I~u&dd^_tHsjz~(|Lt+-y2O$G!Wb_AH3p*jM^(V!=2s - * - * 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 ac6f97d792..349ba3700c 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 b8c36f9a35..33f5a6934f 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; } -- GitLab