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 317c55a45..cdff3312a 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 047f9b73a..cb4b1510e 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 000000000..35cb367b7 --- /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 zcmeHs`8!l^{Qg*CjImD``_^QpFvgN3%NW}j%qChagBB8ELW(RiwyZH4vNMd5;$4K2 zvBk(XsE|tHJ(5T&N%fugpYZ+s`uUveI_Ej(T+emRb6(GVUeA5M?hL%UlN3k=1ONb} zT%0jP06NCML!(IP82>ASL3oVR+=(Tc52|1kVBBab$l|KIk15%}L3 z0ZHAq1;Lm9r4rpq03l%!(LG|~Knai}SV~$(R!&|4vR6?_8LFbHrmmr>rLCi@w-2^o zAC5S1(7@0LX^b*4H8VeCaoF;R)lq93TRXHp#=+6a*#+y0b948=6Nn_T=P@tu<0np@ z^6~ZarvwBBoj!B+TyV(w&w)sF$K+VlT&Cxf-8vEioxMg+@o|T=G zo0os1ppa2?lUZDHtF)}VqOz*Grj}J#&u+MVr}1vnz5C5A|2%lu+V-fuqx12TuBY9c zp5DIxfoFq5+~MaVqhsR}yveEQ7cXDU%+9@@fAjX;!u!P!OUwWAS3a(OTKl}d@n!St z*0=9Jwtw#Y+Wq}!6*yxC0I2D?VC=}s&^3-k;)|$1;u}9qOw35ZwLzAr;CE|2yv{%3 zlo6d@Gsq}C5Q%BZ10MKcJlqsmsCz>fclXZ4XPC&s7Xy{fmToWA#(urkHv48Z_UqS? z^1q{BSHH#y4JZd@8UOzu{^o8*ANg6-Y;xvF^vmOAUn%D1mv0)q(?qP#sGSLvU;V0n z{&=jXJu`ct>GbRF=YbS+`MHrZ!qZ17=AeHlV^Ge5T$w@3Nvdnz)h)h zA&wl({1KdXmn!bT+GwE$J)`wNG4Hh+)A`Ev26d3a=^0n%tSnQ1t{5$WD=b4(q;ZAw zb}T6z&8?Cr3F`=uWP{T(npz97l zS=~jP(T`gecm-4wAnZmR zZ{!?PKZI<5XbDMpAmg*Q8#DfsIxPZA)~LIqjg;Gx@L_agJbo`x&BS4G(KVgs$o$FN z&v6{gXgu|h8Z7cneJ7F09=cuGnR$?zK9lcDP0U~x@E!b^>FwFR5DwQ*%v7O*^V zoqLMuJX7=r(u3g|Z`Il0YQd~S{mA@H)RSV60{kDoo0TRE4dQz$F@Y=Y_ry4uLC>ua zQyeX;&T9!Nx9Jym44?qL#p~2S=3kV3qAIKaRhsOSXAUactuJ?D29&m{q;MEhcAd-< zf1T>Q1VPx+zw({nIE)p>2GQbQU6s`(7#uBbnD6Sxbmn8OW%}zZPE(jC-sQ`uIAiTfcUqAXmnP-2oU&!lqSAjE@TFzlWux!eqUnO)LS zI$Upc$*oP9cUD#;SfoJlDD2|hmN4gA1aPeqPK8=FIE($^P=Y(F)l2C)l&9JuA3R|( zYKx_yW6TuVRaWlXq%;gBOUy{&LXkXwfXGLHLX%|i^V7h$fnc@~j$JZx7Ug2!jFh23omggxNAwH3X$!=T!_t&uw*{rf2p#%iB!!7P6exS+7io+G!I~1ax^3WKPnWvaNrk@>^J(gyQrai$LH8}yxYg;6b zb>2Wjc?-|`8<&0s${yb{y%k`IMrQZ4s5M3d>D*JaCQi-k?gMk$)rQrFuISu%G=p$A zI^7l_Ai37)g5vJdH95Be{)jp-)DIy;$qt6>=mr^_F{y$Y$T}S1)f_(#ylunydVc^2 z>IZs#dW(BsFpyqJ+4?9e`VGl=(mX(i)ajhMY0~h;7~|ep>U%V+(wc>zmp%W|U}7 z!%NQivgFGAInl{nF3WpW6XK|gQ9?bmPA^j6_wufaM%pk^nvdClmVgtOy6@+sFkJ7Q ziq^Pg@dAGOJ=6t zi)$fLdH13>)};`4?>DuQXSMVURs!NQsXo~3fL|MO2-B0Y6&|xaUBE?7MT^jhv=6}@KlQ}r@{UyekxKKkZ&1sf z{e!O3kz8OpI(cac=bQ%EoZ-}au^-r9Fkn+{^;KR7me22lSB;SADeoo^f+PdI$9_O| zbRcx<_h@i&(@Lb+7mw}9WGwu}4>h_D?Y&yZ5t-u8R${1o)>l{Dmkb-%L7>w>2f2BJ zS$XK^c(EwR)%Fr@u=iUI1Q8{dD#Pat4~AZVj_YruO0Z6iMmFwMvf6{UE0y+Z*Z7Pj z7MZ4Mn&=-K=7`l1`MI(W>i0*PJHdXX+LeJcOYlFHRpUz0#^?y)CzpkxjV2 zwc~p@Bh_9%bV=$XvR47?UA6dmfCR1@2~4_RH}?LQu6_0y<<=B0sXOqi8JJA{EJy#e ziO%55gU)V6gpQlM>5Y(Zgl^s-6vCBzb$W}UjN;7{E-#PNZti<*nakbhTr0v57X2m~ z&z{{|%vZ-cJSrpZkKOV>_~bc9@1bh|Kf3N1!^Mm1-AZ}ZugZ9D7YI-W%$a`yWG{>N zHH(MRo<~Ws!U4FN&3JJ6)JaE*n7pccm8j5~%eA7g+^nx=tW}{?t}B38UIsVHxlxIJ z7|6%%kX7tcf0{gu2Fwz6#I06bmsIp#q+(S?qcne8ibI!uvFm}X4D#}e6r~^d!@@4R z*ea#u%Qq7YLbJ1On56OE-sjN^{|Fnssp84I6ylY0Yy+LSD1? znkhE^UDF}Ptvs9%LmC*MpQ4=fd?J^(d#dq8tOUbr;qx)XGwp^*P`q59w-`?yx@drv z3CKRnCSQ;~dyf!&z1ESWkCwGT=54y=X}9K(W;M^NIjn?7d_O?nW2|@SFdZd2o+UJ& z2EMqD6&~na^T!IY-ZTAz4AW{i6d-TmEeEXMWrXVWDohQyo5t>Iqu121UuS&S6r`+$ zxBI{$A%-Z9#?)-!-4uNv2`77YX(ptrdR+6*(b4WOH0)6U57Vf-Dvqe=op2>v>d*r~ z{TtyRkvku09Y(*-Vt+R`&FNpF-O_{~9I*rahU4hr?F?|!LDfsXF<8c}K%Y)R2h_cU z^b^>yTa32SOjsL0o=UY`cfke{=Df&V*EtSe2pJv5>m^7>_q{G~?~Q2oqKZ)+RXC(G zm6s54aStOZpZ5$R#<|xC&1?%`&$-t;(2{w0!D&V4k+Q?mnDdGdsAj26#gf>|X17Q?M$ciZ~(5 z10a;_^;t;KKc_sF>_Xe~49^^LD4Wih&3QErFLbAoaZ6gjHiCYVjS>E^jKxiN4W}}* zQX*9TRgeUuIj;^MEW98Jih4H|L$(xYCR(nfS|Y9}vV@#J1S1$DS|2K8XhER zy0NEBh423+c5H_!Ou6~MJuf6-{$N*50k06CQo+)6-;G6EgkK=bjv6WRu}-eg*AD${ znRr>X=PJqr4)eUE*-_`u2y9tC8qQdI_f8AMXy5qchS*QJtIPl3 zHf7L8+=0MDU01C2lukNR?7-40FY)@cvr!G7XqU2T3rq+%gMQnt$k%RaF#IC($VU(g z?>@MKelJWPBNqh)s*fa8UEgyTpQeUu=-5L%T)|s#{uqmh=^hG%WG+nmv9Hoj#7z!; zW!r18Or_yw_o_E7ZgdoL;SrJ6^oETPBqI$!=WTgd`{q-_WRk1V2=2!Ok$8n&kAC)gtpEO1jJ{ zwd1`fwqI7opl(y=#yJ5j)#5P}*~deQsLigQ0l6$65u{p=YW@b09ccMDz_@Bit?RB+`|!6OL}CifOwm{8egJD9{NZ_ zVcYC(|2V*C%X{^e{5`p*j1B27xJGCPsdCFPN@isQ@lVbdl+HPj-=EZ}iUfIHjwpPX zj+TifIxYeA?w{Z5bM?69-z&ZP@nYh?2rB8A62eclQ5arX*hqkvU^*tOxv2|Lq4O}P`p-Yw1k=3~2rh>Z{xuvd#C$=qkoO*2Ng`u=AD zcL(kveG<5-cfRUh>fh0*;;Czx*7Jl$o2oZGYR7K{?|mwEKIqBw2kj!GC7#5~;MHG+ zSjpHg2K26o?_kE)e6B0*p6W*DEv9uRXMUKhxLnmL;D%>71!wgkoEa+Omk#5FWbv^t zfz4bBuEOXYC!;XO{z50|@}6>VEndtkJ4C-vRhJdT^xZobNN*ftTBp3Ts{tVb@pHxG zFxq}`BKtYLW|aIVWhy{{={pukpDeaEJK1wRpDZBq20utE5+3FaRd}G&zl6(*=+1q( zd+`7qW#_SwM^5FG%)_g;EUCvolhM~K;_|rDc*C=C+2XUP?46#1(!=C8-5mlp$&|^} zVBx_|3Jq!!`#Q6NJs(01PwyNI28VyHCr*M^UuAGlZt$%@qy^Y{V}^nDrP~1~%CeN0 z)*hUic(_m2rLC&SBUZBof+fa1x)LQW9TspRyYCsULiZiv(@Df>?`Lad_f)5EHwk>< z{ZASmON+OYirv=(V3TK}r5~#}HXMBsSHKN zvGvpUx^=@|8w-)xE0pYVa^}0495U!#Wg@pl?U4XRKfz-rK26CoC;J;-XPAZ6Mw(j< zpTJa!t5Iu+VqUsT^L>xfgXQ0h8T7YL(5H=Jf57P45y*7z(|5OLLhFV{&h?rW z1N=s-sKA6D3iR7nu`vhe@)og~*lQN6{ZzOp%;czhqLJHy2CJ;;6Zm3b&72yfxO7)_ zi{|SmgIi3fh&$!PRX~Mrb&HnL9W^_avUR8%OR83ETA(H)Ud9Pcz83>DdlXAw>8*cL z7#F~}({M`E<_w9yXJw4sm85jmME%U60ZRJs-<&Krp5@7oaioTFHT8C2c z?RyiTvMY55e44L#LFBC?{&-0);|xCi-`?Ew@IrK4BG*5bh#wti1W_2TB*8Pg=%pqE2dPoWgF?gd}*{s8c7g)K8EE_IBVeD|UstvqWgG z!pW`4PV;x5w>NDTWSUi>)x}42@~$+H+W--8#({+~FeqL-)MLpjHu~KU@Wk9nf1i2l zKxf6bGx8j2ohhK(8IjgoL4agxsd+3(#kS3ufQMUdtyZ-*lJ=X3N~W1P`J1qDq8s}J zlpzXEM*$BJ+SL=bt{xqg?Q;rC5uH7?wd-VaZ1Ub^O+~*;p$fEjj@Y&F`z1ZNZ7M*Z z9BaRW7^HU|x2g)1PE;`jJOk^tnv% z2AmPRt;(p{Sd9Yx&gU(Yir(yKywMG10P+tH*@2W|5%Q8Qj*5)l(o+ zKF<~*(_4#5;yz!3EOXk9>h}p!gfl{^yEalW<%&Yr^hw7mN#f5^?jK}BXlrTGy!2n| zS|kwu;TR!398|!Q1UJg;cHZncS9@Qa0Yx^Hb$3T6U#lnTJAr<)vyxoya&*KV=&Al$ zvt=3SRgC|5Cs;?n^ElJG6t$Z*on16kt?p`(dfZz_?ZF8zwc85PIDKgFCi^f zKDoBF2BqZKk;eIyp_Rizio1NP-GpV42W@Xh%Jm%+=)YoB_G_V<_+Bk*d!!ACPY?2~ zjznZdi=@PYIaw^E+E5{BW{=}sk{#Fn~l8&!_iw;D3q^ z^s}~%%5(io2rG$whIO03tm`k#w$^NbAD;?@U2_0JsmJ1SLD$ig%JMoqtq(>zEIZ(0 zvlG21xr2s=%HQ^LIZaaD?^ZN%FANxRO+YN1gS-%Ldn{D!pSIfKvv0#8I{A|gRx*ox ziyc!1j$75ZX2xrWB}-)|f!rSR7X5*w2k31oGHU!!9mQS?vyJ!{&&tWRVby^*dp!<()yE&Op|S_$}y6DpXDF>(_YFpU3HyJ zz=^Yvoxr;T7eS0~l-)-;pG$Nxf2;9X55KcEp;<G6klyXDaz5D( z%;*}~v1ghZ)sepq5O1$%<3SyY2 zZcmXuw(8D;z!D9q8`eE9O0cSpk^2~(6yd?0{Mp~Y`GcS*_qmhg(L{*=i-!roc}YlW zAS0L@ohA_w6VjWfVVIMpDZ3gE+^XJ`$N4)Mv)rAp4?%WBdfBf53a>kH z6cBH*0+N~J)v!gA2-B>Kfbtd(f=Efn$*n08oG4rfQKa@+lVEW=i9fEKB4PIn0W&_U zTI(_@5Ax|CUKWQz_IskLKBnZGuM?E1hZ$EWJrnW93hkmRQA+d)5B!R_!j1Uliy~jg zY*orIRlBZ;E8R3!Z&1@&oNMjmcXG&o;h@zIUpG6oTECd*+x!#!F^Y+Q*!ioV*i%pG zu~o!aXzkon=oFAS-d_^KFU8WVXeFp&%l`f)3|lO7`Rmvd^w@nXTnjfa?2CIVO&_|t&TAW?px%~ktvWG* z7WoNJz=Co)|7A9kfXua4mr>ZWxH9=2Nr=$>{nJ29Vb3*|%{m8zcHN1x!I|zl`;8`N zq#AFXHe#N8bR&U$C@~||e&yLsq}+s_yJmS}M&`Yh-qT2eak90Vn8IEqUfME}Fj4$w zgqD%@7!mg!fumkUkEL=j&r-HNi8A?or?J^y%rnES+d7gkL6LB><_D$vgL>Q+09W|h zE_XCFZ7IxUCPKJWp+$s9SYSNh(r~jBz4Ss`+5cI1nt;k~gszNhtKOJCxRo;muJeg<&_s z>I*6;)eTBzSt%KHYy1z2%=8_GVO%eUEaCGBpg=e@&Ur8JRX*B@YxZC~h17RNU@cws z(T2F7?7G%NxFD%&@+1(}(t+Pmfpu&yk_B$lD>A~X2jgwb_>7c$QGs=30uR(8Rbkx7 z1I4qk0^6yg!AD#n*bDV=6q(;@LMpi_rEp;##h@VN+B8Y*S8A}2j>he-{yIkC!UgS0 zXLR#yGBUD - * - * 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 ac6f97d79..349ba3700 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 b8c36f9a3..33f5a6934 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; } -- 2.22.0