From 5a18205f3679492f4329306eedc7d55eb1f56cfa Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 28 Dec 2017 12:57:39 +0100 Subject: [PATCH 01/20] LP-572 Ressource cleannup lib/opmap - Fix UAV markers size and WP marker names --- .../src/mapwidget/images/airplane.png | Bin 1747 -> 1728 bytes .../src/mapwidget/images/airplanepip.png | Bin 13242 -> 3276 bytes .../src/mapwidget/images/marker.png | Bin 858 -> 0 bytes .../src/mapwidget/images/waypoint_marker3.png | Bin 1613 -> 0 bytes .../src/mapwidget/images/wp_marker_green.png} | Bin ...point_marker2.png => wp_marker_orange.png} | Bin ...waypoint_marker1.png => wp_marker_red.png} | Bin .../src/mapwidget/mapresources.qrc | 20 +++++++----------- .../src/mapwidget/waypointitem.cpp | 20 +++++++++--------- .../plugins/opmap/images/waypoint_marker1.png | Bin 1719 -> 0 bytes .../plugins/opmap/images/waypoint_marker2.png | Bin 1737 -> 0 bytes ground/gcs/src/plugins/opmap/opmap.qrc | 3 --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 4 ++-- 13 files changed, 20 insertions(+), 27 deletions(-) delete mode 100644 ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/marker.png delete mode 100644 ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/waypoint_marker3.png rename ground/gcs/src/{plugins/opmap/images/waypoint_marker3.png => libs/opmapcontrol/src/mapwidget/images/wp_marker_green.png} (100%) rename ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/{waypoint_marker2.png => wp_marker_orange.png} (100%) rename ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/{waypoint_marker1.png => wp_marker_red.png} (100%) delete mode 100644 ground/gcs/src/plugins/opmap/images/waypoint_marker1.png delete mode 100644 ground/gcs/src/plugins/opmap/images/waypoint_marker2.png diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/airplane.png b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/airplane.png index 81c73a7c4c64b6cd051923f31a1f552ea262d79d..bbf8ea43dc29f38b5ac67867df4d5b81b8118869 100644 GIT binary patch delta 1694 zcmV;P24VTr4ZsZ{iBL{Q4GJ0x0000DNk~Le0000o0000h2nGNE06ON|;*lW}5(#if zS#tmY4c7nw4c7reD4TeZV<>+;NklhhnVmoIPwcf9rvZ{sI{~Mr zsVEguq6i{2O<&R^YecDNkn++$+NiDa=-G#;Rn(?MRi)CTrE1h}*s*~$A&pcbxrtDv z2nDFZrmb3pe*y#tjJ-dzvomu~AM7|7uOZl;;#B^md6>EPo^!r?&OLwU-aEh&mav4Y zf#MXNPUn=ZTlIBB+{sMu?Azy`blvVK4qZwdLIJ>W9I<)x&EFjw9>^Uza^z9NOgyo1 zQ)8iX?VWG+_xE#LdKVnoY_{#!&;7Pw7={GErfJH(zx(~zo;`b-%0HJAy>$-xO!$W`V0|TdHt@?Ap8-ML50zFWx zZ3dAb!16+&u;@qtK&e!sFbtb&wbiI2`g^UdDS25sTr_BIPO>7@p;~PRaF5b$;{aEwkqB|0PnX75sxAJ{4`*^1y2{ ztnRMWXSRR%pvIoyA zQ>9Xw)}|;5Ow)vA+id7MRCRhiHVgxbs-eEFj_Vs5(Av_<>pDB-%3D_c2f#CD&kp}_ z*REau^$_`xj0ghdQ>LljA4PmKNHznw2_O?h0?dDPR}NyZO`tjgnhza%CAD|&ZwLTx zS-Fy*eRj7;z%UaoL9z#;=|&Niz#Iso_al}cC`5x%B>r~z@VQfMZD%9Lab}H>tL?S8 zySqCAFyJ`O3jom5(*xIaubBldj*g0(lBtIc)68P>%wt;?i0Jh*?+vC?sZ==0x+We; zr#XL<$p8Qx$Kly~#tdereZ9S3{N9t_4=0V_&))qx>GmFYA(zX=a+sUz?)Tb)Nh_MB zIW?1(Wif%q9!sZVncY~9f(6rL!9M#kWd^u1|lxPk2O*_4M?7vew9Lw>6ec)0(=&vMdWy z%1@q03WWmeMq;Y8+qTWBniz{q-+~fhW^x=yIF2JmMn;6HC`DD(005?CBMif$>q0n= zBPOqe7Ho^XAcB}#WV6|%rkR}()B%a*OmaDq_~y>9f32}tEaE3W{h3^~`qt+Fc|m_N z-Un!qq;evke|yMrobZMdVP>Uw|AD73jgEcipZ|DQKXc{`O63wwUQE!NZ@vNF_i59n zd)TsVR)j!9LnAjQlW1@6;1z9cFO>>-V&~4UT$-;f^C3ZfeJ|bjqaQz0)imw8&-g^d zJ9a!Cx$gd_nR#AeKCi)QkzHH?psQ51dj3*^;9FDn-= zT;Lr$9+y{I+S1a(Yd+n6xLPTFb^G@1qw}$2L9&+PIAZPEwU(-?w}&B`h)7XTI#hn3;z2`Q!gu6j|$XT=~1ebzPw-#)goq^>=r5^{-j8 oraDde#7)hjyX08H68<0YUnQvl@xr?^)c^nh07*qoM6N<$f+!|FAOHXW delta 1713 zcmV;i22T0F4bu%FiBL{Q4GJ0x0000DNk~Le0001E0000|2nGNE06-mTosl6EF9CB> zM?wIu&K&6g000DMK}|sb0I`n?{9y$E000SaNLh0L01m_e01m_fl`9S#kwz$gGf6~2 zRCr$PT{%lEOBgLjz3v;hgCGiuE24pl2nvE47#V9M7zmmO8W=n?F*5Q8n3;%*3kaI1 zf!n=-xN9IN2=4oCy*mAF%Q*H-_ssO`>XIs`sh;kyYdNR(s;`<*!OiOGDs5V~_1{Q;kB*MgkdP2c2>D_I0s`p3z<_W`3qXunVuUmI_xB__ zJDVIIA8W=vA|iqu92}6Oq$FX|<`5>PE)g9b9(GFvL_yZj(2!8c6PAp*xj9{+7Z(?G zW$Yv%EE&Il|JKEEb8}Ny#!dpll5uu+rigL5cw}~ zb#+DF-`{mTl4R&Y`Sxw#D-5JL2?d{F5EN?*}$?zt( z2L=Z6#@KN9LXzRlq=6*Ea9;3D&}hkUIK;|pV#W3^cSgww3JUU#ZBB3f?-PYjPfz6W z@sX%5u3<5Egs!JA?&alwB{@1eG6Y$AdOC@Vi~C|@V`IPFi;RpUp`oE}trgXsCK>3% zV=4g&hQ-Y2&CQJ_sLmj}UgN(v^}8W-ISHYZc_K^e88Sg)Vxls0th$+*nItMIN;?(K zlm0BH(!s$&nvs$5ZH<7vE$^9tL0DKAZEkL+^YioH)>}RomlhU(7ARv+0&W7}Ml)_s zP7dAP-u@&-A%j&#G&wn05@8_`Dq&e!S(HuhD1@M4rKP2%k_Zk&sD#wl*HhL`Q!+U@ zDT&}ngh~ioETfLKwKY!t6B(>C0xK&kM3P~XJh8mIOaj@U>mQ6Eq~VJI2EPuBhNa<; z0A?c`d3kyKViyu7?z62gIy&d$!S6NUJ@2OS zs-j>|0`42&uDC&~suQ3da5kHO5+&;DC(r7 zq$u50mZ=qs@f@phJih4lhJ=@w7ljn;0*9+w{KuL%cJN^h9ag<|b+Nkx&sEp?8uwT| zN^Wm&72;ukagD8-{+jUcaAo~DIyzc$nF<=gMgv!iEk3x1b#K_<;9yOQ_p!ds7UmT2 zRTrBZd@){=;Y%Q9yn{@jk^{H8x|(1Ev^&$()I_?vx;}vi_*U%j@F%Up?3?=a>lb15 zE@7J`NKsLd0dsR5T{my<1S z{vv39;`_2>mZ;bV*G`2j2)03k54G_nn0R01LZGL_t(&-o06Ea~#KU ze!6FN_Vx~UIJ}b*08$buiE*SzCCmAc#EB|ZDdi8O{3ZDn`91j!`IIjye@LZVPGrlG zoY+)MTBi5{5CnL@z3uBvcRuVcd4M3t1R>2;*WB&x?({SLbkB4T;eQfa2;qgFF~(fV z*!D7kEHql^dEvUAkxL)&Qd(mX24Db03&M@!)q;2c0$h$&F3lnh2x>qi0G0qOH@#~V zp944nFa?k`fG)){mrX5dlpX-M0$_)Twuq>sK&c{!0PX|WM{SMJ$hQOJB2L@1)*5R7 z-T={i#WeliZ0~3o^?y2PXLER4RlCNRV2sHD6!ma__;}w$!&5+B0s!!wRy_b)AbKn0 z#b50G$FIJ>_sQ)zl$F2vqmOp5+O-UtuB@yaJLhJq`a<+t)Nv7%J@1A_sk4GJeH)P$ z@96?qM@^|)*=Txe^5`&5M`KJM9@_QaJba`3{Bh1Mp6j6~lZoM>d_KC<;hk#)JOg zjfsrkA)?34vlBe`l~!Z{l%Nh2CB7ca0&A@8 z5BfI%ED`Y^Hwu=G6o5Vlqo@?fp?U(~34lESj{qDr6MvAkU=}T6n;E?d;1-D91@K2w zR=c6}%MyZBQKKTPszz0fiWu>MLKP@f6^RcVLSPkzsNl(+`xu{$G0js{zQFxo-$D0Z ze~Rv~?>bA}T^qY?HYTuPC1zpfK!!ar2{8*X2R5cO&Yo~&zfzUkQ2dgJc)?nJ(IVW; z?hwE=5P!Yzv*NEtcOKk4{_;^L9ZgVXIeg_2f?3S~l2K{ih@ zJ{)0^P7x}P+n;=fM|baGu)2bz-$N8d%pfKZm71K0bJ|!kEK;ilvZEoqd-y+JzJGo2`Q2!GIKpf+MpcyX5+JG&G!g>5 z_Xys@iy%lqP(@Hdv3;V2HsW zP*C_;PWOKNY4^td(XChi_QNvGv!}gY@A1mY%8@ZW( zn139OP?jYs3GlL@bg0FL051VS1YYXzRq(ZV4^aUVqY{szDlwZ`L~LQ1VcFDC$Cw&~ zF^G(XWm5|=Pzg8)_J8(;9e!}*+Q_GGPN&oV?smJs?e%(eY8`nNjfgrvFFX116#2;v z>1cv%JVWWLS~2mcBp|f(YAkRHh}PiR`+rmwOm(lK5Dp0JVadRn8jNqOV%Wfvfio77 zv543pVgqJ_YM!H-XGtpQ+I%KUMNx3C*TY#LQag_pCborC0p&DBC@Me~7hZb)A*xqG zB`^_$>YkOstT0eO0EL2xYPt~D_cTJp3-6*+tM93mK^3mwg~nFWqq#z%-uq{YwSPd` zE%sbR592{^Z?LnuyZ2xJ8-=0-6TvV;)jZ=ND?!1vMOYAoVMq{|VMJhrVTch}00oE$ zmKlc3b4syku5s%_BW}*IEO2LdP`ai`Onib#2O9g)WSPXIh5V}7;$ z=kLBUKRUU7@85o5bUcHq0ALUShJOj70#QJzp%(;!1VIe~2|PGB$()wf@VSa z=aym^5DW;G7%p~LzOsRxAO4BBTUTdae0g_oHk*B!B*}quu4r^WWs#x*av!Rnx#eE` z*57@UU;V+YYoj|4y6Mv~7xNs&JVlk45D8EbNNB>aNbUIEqs()ZMTsKIF@K-TAl}1R zi>1|N#BmJQi4i#mYidVd2(vJeMchl!>GzNf`xxwQNwhI2ry(Ez?yIlvpBx{5>YV%e z*4EaerKP3ftVOh0SZ1hm1tuUT!%vcH8*g9TS-VD{6^JI{eWW4`1t|ciLbairVH4TN zF|&mz-T(C0_~}3WGv>z=tbguY!C(L5KcK(43IOUQRKD`1s0dI~4@5OPm{bX&D9a+t zvgzT;;nSx_PamdfdV6_!`LoT<&D%F_+!#6MDiJva1Pzc3zzBe6=9zQuv8vwA%Ir!} z6l<0D17B5L5s5(H)-9=t0Z|miJ-f8l?SAJ8jTLJG=KX^k|dwR&h0h6+2Q~IQPm(Km8urj+L?21X04sYahx`OQ8gfx zYAe=2j4|z2zNJ`b2ABaD8Dk=2jO}zf?d})n03lWF0ytFFhzPHl$Zk0o8_Nc9r-LeZ ze{^`XPei}m+S>ZhBuVz0aTeRz?Ym#lDbz-*5fjnreB>N3x_|JZvVBff7nMJ+0@H2e z5Wq1TYrdgn z37}-d(k^mQ62p7%0Zg59(4|R^e31AC#uKyZ`!nAcVS5F>EaGCNaGY&>Jf9 zIuzRg`XGRvh3zW;DYXjVI#fSQ zpN#)({(t!CPI@#>$}}fcMW{Tc`$vFb{N`VNf`iZRpfl)Mx759AW4Dp44Q>uzzj~dL zs6(LKIX5%L%yEI@_RCnr0q7I+mD%3W`w##9^EapaBT7eORCxh~LV}=}XYfUdr*|G; z`tT60o4^=GHOno0*x35Pt=`7R@6QVH2gBv%M}M1}n}^K&!V0|%5C&igaOvU6V07mp zrAH@7M-xTy3O_HvM1Uwr6ytmQvFu&h8Ksl$jrEP*>gp=Tar~VD zQPeyxRCU_hT6q)?mv$x(o;U)*MiE36tO8#sK!PZVK~3^RZIab-So`3n9Hi6e@&4lu z6n_*#kc%jEQ6PdQ5mVKNosHqoZvN;axAQmOzd@n{0xYynC-43E=NR36hMpdDzLPSDDq49(E z=s-|sh1zT=0lfIe@xsT`|Iabqsgo@t0#RG5sN3&*_#(UCmp*5I$#cg`0RaI22YWG< zq%vgcAOHXWC3HntbYx+4WjbSWWnN))WdJfTF*hwSGA%MVR536*H8eUiI4dwQIxsLv zGmswu001R)MObuXVRU6WZEs|0W_bWIFflbPFgPtSH&ih(IxsalG&3tOGCD9YibxS# P00000NkvXXu0mjf!)xxK literal 13242 zcmYLPWmFtZ(;XzR_~H(WOK=DTU!36XPH?y2?he6Sf&>rl?y!Ln9(02R2<`+3`tkny z&Y7N`nKRR;yH3xoTem7!O+^k1oeUiS0IU!4(i*RQ=xcKYp}d|2o$-%fJ2Y2$eGdS@ z_WWN%aG-Bq1ORkZJ1HqOHCq=?7Y|z(SI7q`DTu4Pi?yAj6#)3G7HHaNX&w-X-mYIu zD#nDQE4pY9f*=}_@gW4MjI1zB5TmD}h7JF|0e1C3T65Ff2DrlZX9ROiw%JZtf3&E_Cq{7_{A0HXp+TnnP zqSLzqU{Lc%8jmMB1mG@6MC2{)0BRqA;4_Z_0tS@x2Dm7qUvLg3bBqu|A`k{VQ{O9s zLI?n;Uy@`60F^}uDadBj1d5RXvuR6g)MFx90Azo_Y=Vx? z2Z+c42xKpHMK0dfgZEfpEtS(G(n&8U6KV)zcSF_H<)C7o`9S=ZfZrU^JQvC_MK+>A95Q6xr4UquA><-nt0~+6ojOtm8%L*fshUQbcfzLKW zrUSZ9j{ky09&i6{_Wh<0Q_Oxwi?I0hCt2>X9pmMZa-MeNgGHwv zE5Wupo?DW1Zo(B$Ic==uXO>ZhpD!POZ?HWeiEX?CzS)Z*_@}aeHMT^$QDg$^c@F%( z1%S(Lm%;y-K}aFC;ajubFK6OUa>Wcli1mlhZUA5+P0yh<)hs>^0s!gaP}Xk}2-Im6Q{TyR zYs6_mwB;!;Mcokvqm5*{QiUe~p0LNL9y#vx&?a@!|1evnI=>2#MaY(7{P^g}otsQl zocF`Mg-kSozhv)6jV;bsLOA?8#P@_I^oD$DX;Ar$m{xT|OaXh;$2Lrk=3Ulm&zyKw)F zkXZ0=N9)P6(JkU7<8y-jW28m|=<#Buc$hj<5I;1QY5m0eDf`n|gYJN>DvwW|j4o|* z^`k=*s$e=B29k9pZ5j>g(O>cTymAGH@VRO>#|} zD&eou)iz&Uw8YDT^q*o;^oNy(Ri(<*iyKY1d&VFbmZZ%-Y%~s7HBnxn??xCKzpn&* zV(rd;qU??rt*$B&l;Tz3)os?eO1BnA-OhHq%lA}4+heZGx(bS0CpcsI%|c$mr_{-9 zW#mwunU$$mBVVIlBX`uxUw=|rP|+*Xt^W{;EitaZWW*$AlRWdLU{7;JbFC7+l1N!p z=x;qowL>|1Nw>6jzjNhjc441MNTHHT<+^Y0-aSPi=abfx(|zS%IZQp2W=wh%IOYtA z$mlya7ZFO%arlM0l<_cBs@y!oJZmc=wR2A7%Ytm8EKY*mn9(-2ldtfGQ~p!C)97DCFuo#|LVaG3AHx$;o9erB;uu94Tn-zxL8?-!p*F31bexu) zsk(Jb-`dN)t8dNEh{bNi+>5rwwnYTidDit!VFCl~6YbNg!!CuUksDIMbT1!Y{9fjO z$`A$w8>HA!iBLnthdaLjn*JnlA-L5|)5?iNLUE@Ap+s_6UD)nm9gXe8aY`M{?Oygw z>Wm$Bq*~Da;ty2wKj!hnL6}UD(UH1Q;z_PCdSr9lS?|2(eo1+3NZ(6mO0VbHaH|S7 zuq(V{6|3g37g-hP;_DJ0(USdUUva!;&?*AS;C74-L z`1bn=ta%EaB9MPp^m2kXgtzs%tvpImmz`4YPj9WgV3UZOFC2ZF@XgyO9h6#;j<_~f zrv=rT6Wy%(pk78lWrt9c!KtvpRs@G53~lt?$iSmtODD#vdYt+jt>*Vp1>|Ccv2pbT zaN;b&;AQ4tKD*@6E>rzEztUT(YDPLg&RYMpKKQfFUTBD&S)KJK3)>lMWwixsL#O5B z?~M$cGwVAuygR&2s`E>~NJo!V<>btFVR5Z8t!u4&E&kJ=Ypv!>cg}OCVvz?2Pfk?6(_foaipI}PpEX*ZA+d1El~ax z)zU~_e0wB^Jx<;CTyW;ij>V6qotQuNo6c3*cjw?1ZR3^-OK9~|f`9E6>OA!)N*hW} zd&%6(T-iL$+y_Go!!A{r*xcgby5FN5oEj&ePek8W;Yw@LZuKB+KF#KGHlZM+ATWsI z-!C(GX`BC^<;;dXj>}mW*mLWr%uD>9aF6he(Pf9{WfOcCU$;Xyw?W9%>Cp2~$G%WZP4^Kdfg{mYy3?8^p@>P`S8nEA!_U*liRAC(Vjq-kj{$Vk~& zkCwdb@K?TxY$Ks80RW9j0T1eFulEp3c@1R%@M8dgkZ=I__ww2w0Du=4034bDfKWC7 z5W9Rf9hC(D=7kT^5?Vg1$AN~)jvqcP61VqWX)Mj}T^|%W_^)nWl-rD1bKQj4>~s&{ z$%jOM+di73q1_>XsKA*iDb(PzASv0P5Y$30kfJQrKz1YdHtDR-0M#*-s&|pYLe&&3 zFg~W$CnlyKwfmFxg5X+Vy_j(~!K(0?erMm^VqB|EEkib`!1%*Mih%gwcQ>T4JS3rh z3F))w7k$Uh8Jue$LR4AU0nCB;URL7KAKkDe|`uTw?m(%lG1NwnIuDlh>eC~9#cU2g*= zXx)Z?2n$r7$|}z*Li~(8z?bx)hZBLuCJZ@*2#Qop^);#Ff_eSO@w}%hJpT@lXCF(#d;-UoM zofcm~xMDu11KPJc2t&D&XXjyTz7JuI2 z1kY9721!b5fM|e}^q<5sb9Qyzjw{O#WM%1(98YHgN?b$8lT_K**_&?wPQ;GxfbFf@ zr@4k_{^KUu_SzqXy6<1c0t2@DpE>&WDuaJNnBE^d^zY^KE*eNk(?_^U#w6u90EvrT zlgDpzsv>X8-aUz|AlVNfOXY16g}@=teFFXG??Omnn6y#t*!2g{f>GVzf4b%rebF%{ zO^fSwNB5%(_Fgr1xx=Ftjk?+kWk+3z+a}}Wd7Dle@V1G<4rHKHllc}6wym%Uu?!Qo zY1jy_%QZW2Lx#c!`6)?4oP>Iwk4#5SsPF5Edv5EGx@H8IZ0l;8*s=_cc0GmaXyMBf zh!p)V^;~>%gj2JGph5{(i}65RwA(mbe$5=Llm}!y0Q-xwE5^XdZtu7mBN(^m_Iz=u zmC|VGugm?uLvRAl<9;P}DY|X%Eg>#@1USBljd*c&m1N%hL@0AkjRI+KEGNb%I^2#N z>ND*WBmm_is-Uc27^fO0tRG)LVg)|bgi1d>yiaW*YT?wcIeFM~RE0yo^i zj`5>7!>yJV{t5faZf~~E;$GrI0e3J3&R8Ajbypy3Z;JMKNDz7wwb>0SfiIk#<`Dtw z=9OBz+`zLZ8eVEemf5m&4BF~1Khm&%S}VC`a5F-UXg#}j9+g6V%t8VLxklOw#zWi) z8COusj3M%E1Fj5Q6y*eX#%t2RvMol-`HY;4>fM?noB>RrJP(W6AMg(@OYdSRH&S59 zyQ5>O)Ivls_m`YHC)4eyU@x3%yyD#z-hYb-wGff6;n_erLD&9&(Z~<=hpYH5ldQ=>14M zz(25QOfo3PJ{v}vJ4eS0;s`R2t-n-3xd>t?Kx>$?RE6)5ijCfY;7uVTM9>{YDPA?y zCk4p;n^XFwZw|++5E#nEy*D1XxGfxv2umnsh6RXiIKXc}(7M*s2rvw00BXz%9Y}&r zY_avBN8%uSdplk-Es||lPK$E7`!Erqr!vJ*Unmzt*0l+M#Qi%0W&`6I8p(z!0e z5E%L2F*Ul_uHeoRI&qrm2!Q#>2AQx4F3jfs&g_$0_kDib61rTmw+q_eA;S#~4nF-UA_`gk@#Zlr7(lR?Huywh{s9=}ieCiV$0mqCp0s0Adhm zo5gtzx{2oFMZvi4jM}fxqcb`mVrCenf4+;CZ-_xng~3>{waFZLUV#$ zaZbdu)?2upWKmGh!MrZq3wuWR{bes1*uvXP38XG7ysg5R?TiYF3jef>EeJ9iLlguu zSKiNNduMYBQhaeNZrF^cX0$oBQpw(l`LKir76iNVFI$}_B5YFLj`R91w@EF1vV{{F zFAe&k9vROfYJhCLcE2fDj2BRMBZ0axCqx$NW`J)oL*mm~-`0l!OIS0@ae%HnreZZN zAs2avnM)$uptB5w!n&3#&@k*Hiax6QV6)ufFnn|Kq9C%JpY5s^$&0AI`Ftk42i5m* zwpVjPsAU@628Zg4zP4=^VRbV@?iE8<*BTdkB>27G0rsEqhvn`-41Z1v3%_s42ZNZq z>lA6dq%g-Y3!zX}zI2@w11Wp7a<87(i$44uMk44aY|_COdlM~W9H7FW`S}kwWFC}M zR(*(DaoOEgva87XjtfN-%J^?<{_@CKHnBYdJpTPaaP9`ZLr@>skvxG!5Hbnde1=_!A$quVy^4d1o@k+OtY<{Sgaa)wlx-*J^B!%D)$`{7br$tX!ILbL`VuPD;cR6YRu+E zC{`|t@mi?^S&I{f{~+UeilijV8zvHT%st8oT{DanK!mrsRZuy|)awq<{u! zP(z_1y-5;OlYYn}9yWzJTu>9<81X$H?FL0(h!fGL(>LH|Q2d$mg?z30)nQ5_yJOdT zK=w98LwixJngzbn;7Zf;ILII$G!F=^p9#)94uGTyBD(${xElSAgwG+c4cS9NXZ>+( z*t;sEmfBp6i5(H)e<6f(9BK*@@`NytOW?zRKA5BsO+i?mhUN>h%zp!u-v};(6{}?w zNE4K4AiMW{0ODMOJZ<%`KR41yDuYztF!js*+2+gBA@Miw+r?|%m;FldvgEzEn6lf# z>=iT`gK{mpa>w{m+m^-2tYVbQUOfCA{cbCwQe`wUPM~Ak@L_OC{H5Dfnf%R;1V8M( zOL!snwF)lsuknji5t0x4lM#tSbl5}IC=(CwK;Q*L%|}%{{9;t?;JhkSC?KIn`rg63 zn@}>m^3NNXFPhieL9V~A63zs(GFnq~PEg~$%Jj$tw&Sfi$Z0H_Z&VPr#VSje$W%S67C zoh$~fBL<)*DJhRYL!XZBSX_oatBJ^i9`qdr#FYRWL3SnnP0@D*k>TQ>-3W-`e5?tM zpM6X#`uAfv8mGJd$ll>Z0o3@P0cUM1#@Um*P{Cm-b6b5IM>E=(mLyKZ?i0QiPEkb8 z&SIl4F@o6|U{V8IQeXplYVtP)UY^?3lp zLM~QBjHb5r0J=@wflFW+Z`f(w#y@eN>kRR*fP>9fg7B;DWJu7vKHZNeN2ySrW%|Ig zix*49^mFi6+5aRhB7C3r*$@Y8%vZ46oPTIzb#+Cx2Vo&Hf{_RiQrJHImcP)Sp{ARE zantd~j?%D5&wm#qutKxOsD^_{P5QAechR2Z9|#m0R89bC2s)F#y;j#s4O0Ax}LG)XSZFI(|n?SB#oJq-(-|BiN6jKd*; zN-9f#kmj2=AoemoDrFv-=NVi+UEiuNwEMgN0U2u4-cD5SJg3dxrJYz`z4gUw+IVz!X%og^`m;OCr+W4LRPr5(5z467-KK zrd%sD<#CAE&Bn3s@{svsLI%mCW9`Be%m+MPo`<)0aQb7jg0D4E2LAIGcY%MxHaqPt zVlIEBD%A0tCWlPRMDnX3hKAE36jT*r=w>d*&fz;6_2D+|PqVR~!@)xdiA%jdmh2Ir zoW*?GR}Y0KfL&WM0z^O!9~cN)l&FdDN;MK;yx%cRk#qg%! zG6$g)56BVXi7<72pzHIum)q$FDnE00^ z%l4%+CXT=vpMg!oH2t9Sx$eOk8jCa07mhMGAhrYw4 zYw!}~zYe?)I%o_MWY`%vXf~l`+@u#a&+c*8HrrL54)wiG?RK3>ZO!bxb*y8sW~4zD z-pkJMuE;rfmBSnxe$4@2nZ_Sb`{La~XJlK!h@z0F7|9RL+PHxcEC$s1ti+KK1hZ#$ zo`I%*R5D~=m?b(dc4b@z;sZ81kfC#VBr}%0UQRzIFSMbr>5?e(Ce+K;;6BIn;RlXK z^X&jqL&~6QD?a7zy4JoUA(y(7H1(d_!muxqh5X|wavFK=fEJJ$-O%GH@IHp(E7ll| zAnN5H#u8m1^_PvDJnU3rA97aOIoXxk3dHQ;)umBSgC3Y@4D)Z z=lK>59CB6=ze(@JOq`)J94Y<>Ere%Utk$H%)TmBGeRre#&-NW&p084|D86DSrC2NF zcA_mb5#KX{hd%1|n!R@yy0wSi$P#l)ptqXbqebo4ox2(`hO4`_{6XUhlSXgk=kgAL zVt#$8<`u6(Sdn88SO_0UG2cNsznneoUn0^zKM1}PP(xc{&r&qh)?VUMhVvExQpb#HJN2I}y%?6>P-HC*=wE?nN87MPJh5{@Z+@U*ul~5K;iv@n)_hbRZL^ToOmA)!sWp0m6GX2 z>cq5Fmz7{K@1H%6+lEMM$d9e%DCXb({qFjXV{lKBTI|zSr{VfrZ%Cas)KxI}LG=+Z zc@P$l6CvNdz-uDPKMCv~Mr#Ftx|O!v(W7c5Zo0!K~aI zRG-epU;NwquN7a=UT$@RES;icwi^CE8YFAVuGyW4=3flj4U-@F6HV6@{?H63wp51^_Z^4Isg3dy3^1Ln{uljVXTGHVGby@3Q zD$LL4+uPe)aPKtw&+BQ#z<&sqT%KMjqt0g2tj}H^09X2fbsUPuuQfH#4$=OuvIN%L4N8$w`&Et!?` zW0w&MPBZlJK>MW5d>Ll$o%6#ArGGz0@m5>y|OLy)~DG;r~j zdSGqIWHf%`iJKyDhXIV=RezOCCEE0A$PQ`yzbqSS=tEke~nc&}blOHc# zg$fE)D(82fpM#F_J?Q))-i*0Z>{Wl}Q$NldN_)cnUrKMEWoWy;!`dUk(FR9>mN02h z2AHq-EvhbIh5NH6P(K}7z;&##=_65?W>=KVfFTsR9n@u zx=S>T40TlL5o~+@41Ms;GmRr!!5i%e!YlLG5(NEMGYnL0|nI|t!isq)l@f4?=~6N>HM{Ct=6eo zD6K!5Z*!v7cR1s|G91emxVgDGrKX}16A=>=^Z&b`tNZZqKzt)@w0LH=&!)gCk>uzM zp@|@t^puRr&B>B(IbWytHuh$YSWeSWXQ)xmhWfiR&h!gdYPeqKnS>Zd7_V7LAKT@%~t7Sz&5kCc3_t|D?00%@iN}a zt!Q+Dw|N=2dl?IO88_rs2)e*;VE!-i3je;cP5T=hp*F7^4?aIXPp+@8Um{W8L7V&g zUF7(?L|Ti?9OYc6Ft4~v8qNPGD0I@7@>+|vT z+HH(&QA`C)#Oe=Th`DvRny?y@8mxzRJ@5lWUY;cqJDO*VKt`RwN?#>ie&l?=kE>h+Do!MCFpAyTsaRm%|2IK5{B7UM;CmEPS`Nnv4@by}!Mtgzp`;LP4Ag*`y=Mzg_3{7>BWk$b!@rS&sCGOK3|o(%oswjg%PE zMqjsuJAWQK4mLKKrBZi$yTC8J_U67hD|P9Qp{QAF6{%}Yt?5mlH8M4(sx+$8HB=J0 z@g1D1S~&_l7;p*K9}3aR(sN_zd8bK+iB;!nxT|nUxAz!$Rby?FW3cl*q9tQyNId*4 zHCs9JoC=dv(0Y_GRh22bTt7^}!YRrCqOts$955#l*mQ$XL0bEyt zGnG79cXAkyM@_mt!he!6nK=&D^%3A#MLAcAQCmOr?<>F<6UYeUedqr~YVQB{vkl^4 z{ckju4y_TZk2K|MW$BUNQm`b6gVP}FptiO(DklBbL~sueB+bSiU#W&hyNYa}VAry! zS^l4qLtt^bP`ZW=K!JfO7xXj-5cKsa;%UEjOT%ep~Kn$*`c~u*O_|?8xsB zJ27M3+ykp0_h}^%!2m^Fb0ddSqwyZWlFdq07OnK{0ehYt=CfWDNL?!{qqsaR*;^?O zZ7_%?0#7nsV=6Y?-BiJszT60%rYrl*=3Bjel7)_>15(|)vY)+am8gS`z5OlK)os<) z+VHkY*yF4FuvRCyjVtwm!7!}r%hR2H-H-Of}cYgbqC( zmyTA)CFi}jgbiH^Th#%E%_P5OR?G~GN)p-s%=xMA88aN#XT~=@i))mB*5ZVm^eT?N zO~L~y=}X!X&QFX+c`$|S(1P+kY+iq0EB$qWu^z#qS!%mFVwjQK)J+x}BggcwRqc5* zIK+`?bXf=Wz$x4;fiTKStt}&WMaRs-@QGFg=~bxa%Q^XcsyIrY=?16pw1Z^CJs|E{ zPY{K~9v0h?y)v%XH(V)iVMu(oowaZ&pUxFdP^p!KVkx&?`M^YkahD>GAcmzjF#t2(wua3jW8JSaa0n zkXu1hI_2O0pFxrE-VC@ccn{)}TcMY=>wbxCn6QC1*iQ*I0wU7gYg8OcNg(sr$}t4fsnALho{S6_j7X{G+i;4Dx|`ZevKJJYG1X*7=sbtPn^ z>^`e*#lj8to-ulIIr5Q1H?nz?=liY2FEeam77?+C8yf26R@pP8%VScKfQDV*$aLYi z%k^O$+P3KD;Iz80k3n;|-!d7R@tMEy4RSZtOD5s)vu2%p9~Q+~fNgQZx8L<##R;nk zyEcaqcANr_o!-iwPDL{fg;uw2Zxi7kqwk*mFMUjMP0oqzDS2BUEpdW}m}U2o7m!o#*gt#lC3~d~T>(jN`syO! zkt2z}46~u&STnjS1JK|Yi7CMwan9;ZU!=ioQ7Bz|Nz3{-1OZDg`ht*WeN_< zQuqpFCXxlQy}v_uZM^hA3{98#qrfr=V=d!m#ebmKDN3_o5*6O5vObGsC<{sky|6yv zUYcOOe)z#G5Y^K-w*xNi$o!82*}$Q^bx{)ZC7m^qyIh0Ssc(`l8eKS7bC>U6+xbHT8grTLBa7h}8TWWH->M2d*+IOf*ah_cYoa{MvS<@EreSb9I6yHbtj8 z_H>O`r0Zdh3#|K#AW4C+Vzbv7XsIv$!Ai{{>WIMM#}WYm&vn_gx{gxrh+6xhK^-OK zcw-LY4b+gdN2~hptGR80x|M!zHob6`#wocac3Jwk`ambT0z$cYQ7H{1g*&W+Bf)ho z8=64k?*}<9JMxH|RlL}P$oG;Y(UJIpzy5^i#Q*x5@v*|Hfw5xV?t`?Z!-dUn+{EeLX^xi*)F?&E0h_i;*A zH)S%VOJ@{YYX6V|5;dyho0mprsrWO$HmhUlFi25Hb#T1u{VW&>89xiGWjFMY>dnKC z>1u^re#P<%AW7i*)5*)%K^G2r`HzpRTlsGqqXV6{1&U`hHhK`CZ< zT1bi?zA_JZ2a_xFy`LqCGs1u#d0!8L?m9?V;1QdLNInp^y`t&^`-4KMpqDG3ah`A(5PA$hqQ*V zVqOQhXJj!FdPe8W0wU&rm|%~{CEN=H=ERw1)=7C9m&!tRt&nh*>r?m}OBvR}!{r6> zbC$%R#+9P|m-qP3ilE*s4WxQF;+>lREAe(uy1yW;mb2N<{M%)yupt{g#Hi&k$HDra zYUX|>VV5?NZu@ybBr9f|9hzufalWd#HG`-AfD%(S#Yu@sc66hFj4#*tpqwdUOMtvI zlk|0V3>DCUy2(y6f>iz=63s}J#vuW5o}EF&%*RLmpl%z#H7gm``Woew=0SF#eXaW6 ze|e^NtTTOX)P1cbM+!@W!Z_eiDasr$^5NQWNn^T0w_d<}1BMy~!cB<_EpK>1xWlSi zhBRkmS1{iCu)66gwUW=jdFuYFspQ8_;nB4(4gP159!bAdtX^3}hDHH*MXE;IShhJi z+B4 z*s!8&1=KHTn<}$E6Byp=;VgNcE2HYR-`zJnGWI>c?T>xcD-LVK?~;T6EXXk>i@Vf0 z#e79kV=31$II_~ujEd3H&%7LCe2wK2d@wv9N&sy6U%$^;aA2KF_i)vPEP2H5u6maY zI^@N77@DTYN0P~7{Cp#{dxN5M5zYtn0UvP?bV__bRa@=|W9YWJYIm!TJ`HB|B{e+e zy(AclKgWJ~4Z7=(SZNK&EN7U~CZ$0o4dg&QK4|O{L*idmegO7Q;BXnrhAM?bHpFHONQ7@yqZ^OeMYBkF5Sz|FaaWc7~|t&ep_(En-*d+dFMPG3%` zEzUfsH)@XVi|dc*_I~AP*o);TF|Pa5m217a{gBN#R&!V)8xV7UA!tNN=6p93NxIfj z^76AfstykQCkpCV>Iz&NR@xs94?H|Z@iFIg)Klj8(>VN&y|&fLcqGUq))@% zx{f_V!#*lD7wkro!p#Pfn9DzZMFSRzVBKr@7!ic>sk|@Vw|DhWX^}LehmI39?tIfNpRL4 zt|MEnh^&#?DDMkYHYF7`c+~$ApNPdYJi|m6GJpc%5O)sVd;8wbaE>prx_YX`$>Ejo z=4cx)l{&#`er)`eGT}u5#=2`AuMK{nHox4g1wV|N9}%tTztL?stO{(&cQmp8^fmYr zCCl)?ffQ~(AYke3-MNi;Y=vD%y+e!BD+T_+ht=++=wwR_{#J0 zxH2~`{x~}O{5TtUsQUbnb+PF3B&Kt#YOd?GfrpyFCM{wXahGqtm)6KZXAw^}aaKfe zvR$qkj4JleI~d*c@iI$Awi;bys`g2ht3j~P!MhWt^`;2IA}_rNsAHZrbLulc&OoN-t>4BQZ|zO zG9GPrP>ebbib*q8)YiL^As(ALK zq0kwZF|NUo;n14%*B}I{FsUEqJcH=loS07i)pAWLVl}z%q^sU8*V@!Ul=rIXKLgW) z7oqzf#`%F)2*BoIdms?KadVl`?*VV?vm^62S#tj8y273{%|TRHuUoU=JI}|oxH>NF zNw$sgmPT5*XqJ+Lg~N9knb?7TF{cO`_2I1`QGjFb?OTVFu-BSgUsDCa42?{KBT1I> z?Ua={-hbZD->Jv4p8p0T`z9y9{GD|QO6|Cy&#bkg##V@Y+g0!31n+8da?;i|el5zd zZ?%7w2bzw$c+Z}`=$#xFF5b5=$BhPvsrI7!dAU-4R#^W898mIWL_eT@?tZUI31=#m zI(sTv7UefzV<##un-!|G)d~I=bE^|n!UD+RRf;I7s5o$N zaJpe!J?f}gcj$PaV-S=gL`7l6w(c#h0Xj{ELe+;QFW$Xh=`oDbd>89kjoED$dHw(VKZRuSAxKc`_xL<|Fdm(Vvz7{TJa9dj>u;hD0a#vihXU%jD z`I~~(4|-LBAFqWD8Z4ty?&rTg_3hYj2&_scU7^ zz)kKH98Y*mVd5vl-ZWKr=1~8P;)qjY1P#O%nPeDl`R47X1)X(m8=pKgw^8`OyL!h< zlWHv<{`j$}KPEb+zJ^Y_#xj*|GJ}0g4rIMcMQ97R$0oINm{u52!nsEQ));m pXP++klq;Q+_OAcGg7766@cRToXG64nq=pa)DvOC(e%Pok4KS#%2QOGzf_1_@zp2K0iM zm1IirS}u*IzJnz+(Rx;-t7egISjho?e`%{1hYo2-5hG>sd$7%)Oa;cZ849vn8b#{v zAnIx->TGkT%S^mBYip(&m6E03K)$DJBY1OIsi41|CZcOTM4sTBdB}C@OqPBCu}g*B zsYr9mY7|!`TfEzLn!Rvd%#4p^X`f3b2cHKjOC71KTIK@RJglx@;gqumf<8(TP7|gE ze&}u|Pqx)l_x`<u&Hdue-c%p)y4Z zuMe_tje0R%~p$ty%QhZhkkm znSNeu5moVVEbL#}DN-<2i)zpFFz`s-CrA~4E;_6G3CKMAIfql%=c>`C7NRSr<%KAO zaaSJ8rom2s6Q=>V84VN~62d~Q5MVrU3=S3|^&U+T%ian>giaP2 zN#CtTN4kY6Ni4h_j4*+VGpetpX-gADgoUxNSO_v+-K{94QN503UqN)R!oh|exzu~0 zn1wHdbqJ#d?+gAM@ti1uhBiGehO%Yx5S{H-v>w7l@Y^X= kt%ooId<5elZl#m|0Vk{&vLebb#Q*>R07*qoM6N<$fzc>Z4l#4` zF=$W;$ym01h8t+o7BS2=3Fwg1#NThu@hu=t@e0;YRyt+HC1~Es5zc`ruO)>6y~0O9 z?g%igs;&}qUY`oAjZCaXE!g?hd|_6D)4PzMf!nt`-eBhKH45MSw8EL=0yG047e}TDu(NLuQu16uM#ttMYCrs| zWC>|FBYB^9ibn)yY1nhAGHOQaicWzHW(N?YXELzEg&1cx`54%j7;BF)`Q_m{1W^2} zRinnBZ0a(DA!W0o)%^|>2rj{T*LEeSEJ`dMOLZ5{$yCdgN-CAz=WVLL4G21p13@BL zu$)6iLbjH!W_!vVx_gsuuD?c8)Oy)-NC!Htduc7v-uByyf{K?|CKS%hSyYUgZZTpA zUeYBNZ)t2U$E-8Ye!OJHYxVEQov|2n@8r12=k14wLT>|2+ zP>Mt5txQ*G-yiQ?r0eCYF47ox1u7}oRwMuzQiSyq<_P6dc`6JVZsc$Vm%n8x`jm3g zg2{JAkLs7d_~onmrQWfybq z)q!skk?o&+E>Lamdf8`cg{4iFOf|!Hj9C#X-ZH6oXH4*{guv^0!{mgQwQAWzS2$j| zx@T11)AprI6D$D=aBPB!GinV}HkqUA-zRDGWUd4v40dT;V+DG98@SuUD*ivmvFY?1 zgLGU!BGUy!fJ0mOJ7L5qek$({9Y|yS`wVtsa$6}peMzhJP-woF{0$n|{G@oq4{cjd z!Z|K0DHkGLc)S#`XkdRr*oJeAPw)PJpDJdWDe@nWd#ZiHPt}jI>8GpPxbm3;@m7I; zM3K<+=)2+HbjoxWaqreUIY=?m7M>C0@hcRX=cAe>ehSXy`ac^rQ=4qg}8z za!AL0zi|9{M?h(tQJd_7BMn}&kXbJ95kH)Eu>*1^^rHe*M$71zOQiRr4z%lT9#^Ch&dSN zRzYJY&lIry(7mRRiiM6zWbktr6GQM8zIv4upTKq}*jky3`O~#%o!m8P%Om#$9JiHZ z$u@)pYDgIawAf`CyEA$rzLMGU#_lkUy*b<)P^N7-^6kK4V1V(Pg9PV7{gu61URjwB zogDcG0(7}1rtZjLi33`yH41Fm&48GBbU$|g1+1iv!eC&?5s1Q@?v3n~GR72^^*k`3 zOuNK@+(J&CN4#dsLNT*=;#7WY6QaR~0)%F;B3j5c6wFD=^_R2!yagIYy#8>2%mVg; zUP@X>SESAtF^ images/bigMarkerGreen.png - images/marker.png + images/wp_marker_green.png + images/wp_marker_orange.png + images/wp_marker_red.png images/compas.svg - images/airplane.svg + images/home2.svg + images/nav.svg images/home.png images/home.svg - images/nav.svg - images/home2.svg - images/airplanepip.png - images/EasystarBlue.png - images/mapquad.png images/dragons1.jpg images/dragons2.jpeg - images/waypoint_marker1.png - images/waypoint_marker2.png - images/waypoint_marker3.png - images/airplanepip.png - images/EasystarBlue.png images/mapquad.png + images/airplanepip.png + images/airplane.png + images/EasystarBlue.png diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 010a5c393..c256f56b2 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -35,7 +35,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord, int const & alti text = 0; numberI = 0; isMagic = false; - picture.load(QString::fromUtf8(":/markers/images/marker.png")); + picture.load(":/markers/images/wp_marker_red.png"); number = WayPointItem::snumber; ++WayPointItem::snumber; this->setFlag(QGraphicsItem::ItemIsMovable, true); @@ -64,7 +64,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint) : reached(fa myType = relative; if (magicwaypoint) { isMagic = true; - picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); + picture.load(":/markers/images/wp_marker_green.png"); number = -1; } else { isMagic = false; @@ -95,7 +95,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord, int const & alti text = 0; numberI = 0; isMagic = false; - picture.load(QString::fromUtf8(":/markers/images/marker.png")); + picture.load(":/markers/images/wp_marker_red.png"); number = WayPointItem::snumber; ++WayPointItem::snumber; this->setFlag(QGraphicsItem::ItemIsMovable, true); @@ -128,7 +128,7 @@ WayPointItem::WayPointItem(const distBearingAltitude &relativeCoordenate, const text = 0; numberI = 0; isMagic = false; - picture.load(QString::fromUtf8(":/markers/images/marker.png")); + picture.load(":/markers/images/wp_marker_red.png"); number = WayPointItem::snumber; ++WayPointItem::snumber; this->setFlag(QGraphicsItem::ItemIsMovable, true); @@ -301,16 +301,16 @@ void WayPointItem::SetReached(const bool &value) reached = value; emit WPValuesChanged(this); if (value) { - picture.load(QString::fromUtf8(":/markers/images/bigMarkerGreen.png")); + picture.load(":/markers/images/bigMarkerGreen.png"); } else { if (!isMagic) { if ((this->flags() & QGraphicsItem::ItemIsMovable) == QGraphicsItem::ItemIsMovable) { - picture.load(QString::fromUtf8(":/markers/images/marker.png")); + picture.load(":/markers/images/wp_marker_red.png"); } else { - picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); + picture.load(":/markers/images/wp_marker_orange.png"); } } else { - picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); + picture.load(":/markers/images/wp_marker_green.png"); } } this->update(); @@ -436,9 +436,9 @@ void WayPointItem::setFlag(QGraphicsItem::GraphicsItemFlag flag, bool enabled) return; } else if (flag == QGraphicsItem::ItemIsMovable) { if (enabled) { - picture.load(QString::fromUtf8(":/markers/images/marker.png")); + picture.load(":/markers/images/wp_marker_red.png"); } else { - picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); + picture.load(":/markers/images/wp_marker_orange.png"); } } QGraphicsItem::setFlag(flag, enabled); diff --git a/ground/gcs/src/plugins/opmap/images/waypoint_marker1.png b/ground/gcs/src/plugins/opmap/images/waypoint_marker1.png deleted file mode 100644 index bc58687409ccce2fbc8eeea11be50e2aa60778f4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1719 zcmV;o21xmdP)004R= z004l4008;_004mL004C`008P>0026e000+nl3&F}00006VoOIv0RI600RN!9r;`8x z010qNS#tmY3ljhU3ljkVnw%H_00t{bL_t(Y$CZ^`Y#dh^hM#k0_GiZS+D^PSb^@(Q zltyU~NfD(|BLoyFH@zXWNL(N!P?5MpAb}8+p9^}$T_r987eOG@q=Aa6iV6}+L`f?O zsc3#2CvluOn|0UT-Ps-Q%$%9oIdiy}Br<8!koRWhV)V@WedqnYBMu!p#I9Ytn46oU zQmGI{5$$%HX0!Rw%F46`#Bq#L z%9T?7pjv`QFH-##u&4B2YBMd2}-3B zaUAcA2(+fJb5`12et7ClPB&ZYz*EMU^8nIu z9Hf*^sZ=`l(A1XgpWn5Us^bXKA;b!j1at-hWT`||2uAXp`q&7+_`;JsF*h>}yex#M z0Z0HL#P`P>XaBzK+l;gBlhs?;@CEhkW7p?;_0390ACkE%-czl ze6DQUAFaC%Br$CG&}~D{EPE`~KEER*)veA;eMPRA+abZPv?|t`_k?+!gsREb| zL2I~c0`8WpCkYqcB|F;_gYiae|V0GYPHCmWr1b$+`dNv-ghWjo)c#oK{{kG%;-dsSqmcp zoEHZV9^5t<4Br0kuerLq`s){7d!2rxVTe`H>2euLrNXTccVLOu4APX2Qgo7pwT;01{YDeuh%shK zhG9sr*Zbu=OIH`Z@w=l!`+bAfVB1ixfL$tp#xTrt!eK^N#jHh&b`+bV3ztPNNtSPI z9;DWqEXxAm&?}d&u72$ge-xw%NLc{O6_65b3~{FMlZ5q1(NYP&J-Z+-bi5AmC1Z>S zU`B0DL0kR?%q|n6avzOBuVj;lvWtgh-3b=aD`JhnlbRSG3H;l zQy`5ojE;`tx-P&wz_)&K>NIaHUx!K=DisitG}rW#g!Lrl?0f6x_2m_S?-^s>*c>Yv z$1#rMP_Ne+8yiCiaa3B??|*diG-)z4*fs!hRscJZ;+4fEG0gLmz_0GksZ>f~jA3$e zl5N|zF*7qmtyX*fN`J#Ye(|!vwjtLfTH|LqZ{1wwO3w%Q@dr(ijG~A*jwzK&)a!L- zXJ^^Eb?bG$=R$%rHGYO|4dY zaa|?B=|)o++ad*)y*|r@yBF^@<1))Klu`sifH8(zt;W>U6cZB@jcT>}>R+xkFvg&z z;GfMkOmU6=^`1b0G))PDfH;mRm&;5{OfWe)iR-$@FLe9#1|cTTIoIw2y!v5V$Tr5H zwI+%p!Z1V#!RY8HwrwMXc*FBN|K0V@xDnVs!uvV| z$n%^yj!B9|Nx596TCGy8Rxhlk8Bx#Ue(wGUc)RR4j?r3Uj3Li+wAL#(`h9v{AK>Eu z4FnhthbW~;(-h0Hh@uGJ_dAO>o9Ijf+;|}1=1gW;Mz7bS-EI$5Iy4k(cjJM8x8vjc zK2a3WYPD!I8a@yKBS80ofW{btAfVIfV2q*BXt27v>I18Q1GMi4{4bnRnHe0^_YVL7 N002ovPDHLkV1lo;H9P004R= z004l4008;_004mL004C`008P>0026e000+nl3&F}00006VoOIv0RI600RN!9r;`8x z010qNS#tmY3ljhU3ljkVnw%H_00uotL_t(Y$CZ^`h@4j$$A9O{yz|byvpYMx+0ACx zZ9;02*0j}V5ygg*wu(1}Vzq(=5nHN=2!f!9)+l1V@vc}QDnw9d(_l*|#kMwCEwQP( ziP>zj`JBz}Y-Z~xC871o&l`ufnvXUnGr@wh;gvDTEW`E z)N(&|&xpa@Qd7f((CY}6nz$WTU0ht{z~OV^H-~0v^qkYc7nD+GuK{0G$I!^(<8AZt zjtnEG?qj3M6AS17ZLqsg?~tx^u%nn>l(JZ9@%`tfIXYKs0uL#r<^W^?1BonXXa}}1 zI`sf|lE)Ab0xl3h9Dx9t*T_pjF-aL48{lW(dVo*fHL($RQ3z22kN^Vl-9e0x?&3Bj z$p8+}f~XG54Orow~^ zuLGvTzJoLT__s%|MdBw5Z2tQbm-cI9|-E>Cx!Aw7Q;p;f*t*Yx|Y;$%9OyggA(8;L(?+&)2^E z%|8fSA2Je*JQzA;BuSd$hY6l1laGb%h z5<-d>q?Y;p4}N)s&*pA}J(9s!>F-<(R%bWy2dcxnS5xMwrt z+b1ZEm!G~+GtGm4o)_p@ND_i5#tc&4o~?3Wxd-sW_j*Cn?K$|ChnCkEyM3IAol|Vs zGIqHzWbAwX@L2*oR743ukYKq!(8Q(s^#%-G@jSoHB zG=2N%$t9um3?WddcB%B;J$s`!F5@u9GhOV}HB_o7jh7kSx{>naNHt$79D41Y%cxY5 zWCZV=s-gPd=<7EG0)$?G-L~*8kDQUCJUPtp)Cfkoc<}UMmu|~OB`K#WEr3Hen?hNY zDv~I{?K(Ie8zBV)qb0JshLGZ|&eE!R@|R4;eY)B(2lG@(m@gZsH)q?K*^BKsKjQC>a>#B1XA5bFt$xx6lGO zMSl|C+#x`kr1+LcUr&nF z+(^+MyKA=uOrjXK=U}dMal1L{=dMsaxp?*WDgvvw1XQWQZd8c6T ffCA8ZKj6Os`Z#W=>+z`f00000NkvXXu0mjfIsHE{ diff --git a/ground/gcs/src/plugins/opmap/opmap.qrc b/ground/gcs/src/plugins/opmap/opmap.qrc index 10073e59e..348351c6c 100644 --- a/ground/gcs/src/plugins/opmap/opmap.qrc +++ b/ground/gcs/src/plugins/opmap/opmap.qrc @@ -14,14 +14,11 @@ images/hold.png images/go.png images/combobox_down_arrow.png - images/waypoint_marker2.png - images/waypoint_marker1.png images/uav_heading.png images/uav_trail.png images/uav_trail_clear.png images/minus.png images/plus.png - images/waypoint_marker3.png images/home_wp.png images/move_to_wp.png images/center_wp.png diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp index 8db51bbda..01071b9e8 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1984,9 +1984,9 @@ void OPMapGadgetWidget::onLockWayPointAct_triggered() m_mouse_waypoint->setFlag(QGraphicsItem::ItemIsMovable, locked); if (!locked) { - m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); + m_mouse_waypoint->picture.load(":/markers/images/wp_marker_orange.png"); } else { - m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + m_mouse_waypoint->picture.load(":/markers/images/wp_marker_red.png"); } m_mouse_waypoint->update(); From c3d840ad635ef1eb3569fcebf16d4849df46d88c Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 28 Dec 2017 13:22:30 +0100 Subject: [PATCH 02/20] LP-572 WP Editor: Add Apply button --- .../opmap/opmap_edit_waypoint_dialog.cpp | 36 +++++++++++-------- .../opmap/opmap_edit_waypoint_dialog.h | 8 +++-- .../opmap/opmap_edit_waypoint_dialog.ui | 11 ++++-- 3 files changed, 36 insertions(+), 19 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 2f65bde46..0b41bc21f 100644 --- a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -2,7 +2,8 @@ ****************************************************************************** * * @file opmap_edit_waypoint_dialog.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin @@ -93,12 +94,6 @@ opmap_edit_waypoint_dialog::~opmap_edit_waypoint_dialog() delete ui; } -void opmap_edit_waypoint_dialog::on_pushButtonOK_clicked() -{ - mapper->submit(); - close(); -} - void opmap_edit_waypoint_dialog::setupModeWidgets() { MapDataDelegate::ModeOptions mode = (MapDataDelegate::ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); @@ -263,11 +258,6 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() } } -void opmap_edit_waypoint_dialog::pushButtonCancel_clicked() -{ - mapper->revert(); - close(); -} void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint_item) { if (!waypoint_item) { @@ -287,16 +277,34 @@ void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint mapper->setCurrentIndex(waypoint_item->Number()); } -void opmap_edit_waypoint_dialog::on_pushButton_clicked() +void opmap_edit_waypoint_dialog::on_pushButtonOK_clicked() +{ + mapper->submit(); + close(); +} + +void opmap_edit_waypoint_dialog::pushButtonCancel_clicked() +{ + mapper->revert(); + close(); +} + +void opmap_edit_waypoint_dialog::on_pushButtonPrevious_clicked() { mapper->toPrevious(); } -void opmap_edit_waypoint_dialog::on_pushButton_2_clicked() +void opmap_edit_waypoint_dialog::on_pushButtonNext_clicked() { mapper->toNext(); } +void opmap_edit_waypoint_dialog::on_pushButtonApply_clicked() +{ + mapper->submit(); +} + + void opmap_edit_waypoint_dialog::enableEditWidgets(bool value) { QWidget *w; diff --git a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index 84f7303ea..a9e8a7b37 100644 --- a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -2,7 +2,8 @@ ****************************************************************************** * * @file opmap_edit_waypoint_dialog.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin @@ -63,8 +64,9 @@ private slots: void setupConditionWidgets(); void pushButtonCancel_clicked(); void on_pushButtonOK_clicked(); - void on_pushButton_clicked(); - void on_pushButton_2_clicked(); + void on_pushButtonApply_clicked(); + void on_pushButtonPrevious_clicked(); + void on_pushButtonNext_clicked(); void enableEditWidgets(bool); void currentRowChanged(QModelIndex, QModelIndex); }; diff --git a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui index c70b2967f..597c3e6ac 100644 --- a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui +++ b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui @@ -789,14 +789,14 @@ - + Previous - + Next @@ -815,6 +815,13 @@ + + + + Apply + + + From c8f81b9956ce7255dac4bb631d783b55487aada7 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 28 Dec 2017 20:10:09 +0100 Subject: [PATCH 03/20] LP-572 WP Editor: Add online help. Fixes + display WPnumber while browsing between tabs. --- .../opmap/opmap_edit_waypoint_dialog.cpp | 305 ++++++---- .../opmap/opmap_edit_waypoint_dialog.ui | 559 +++++++++++++++--- .../gcs/src/plugins/opmap/widgetdelegates.cpp | 12 +- 3 files changed, 656 insertions(+), 220 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 0b41bc21f..9e9af7aeb 100644 --- a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -38,6 +38,8 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent, QAbstrac ui(new Ui::opmap_edit_waypoint_dialog) { ui->setupUi(this); + ui->pushButtonPrevious->setEnabled(false); + ui->pushButtonNext->setEnabled(false); connect(ui->checkBoxLocked, SIGNAL(toggled(bool)), this, SLOT(enableEditWidgets(bool))); connect(ui->cbMode, SIGNAL(currentIndexChanged(int)), this, SLOT(setupModeWidgets())); connect(ui->cbCondition, SIGNAL(currentIndexChanged(int)), this, SLOT(setupConditionWidgets())); @@ -77,10 +79,27 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent, QAbstrac mapper->addMapping(ui->sbJump, flightDataModel::JUMPDESTINATION); mapper->addMapping(ui->sbError, flightDataModel::ERRORDESTINATION); connect(itemSelection, SIGNAL(currentRowChanged(QModelIndex, QModelIndex)), this, SLOT(currentRowChanged(QModelIndex, QModelIndex))); + + ui->descriptionCommandLabel->setText(tr("

The Command specifies the transition to the next state (aka waypoint), as well as when it " + "is to be executed. This command will always switch to another waypoint instantly, but which waypoint depends on the Condition.

" + "

The JumpDestination is the waypoint to jump to in unconditional or conditional jumps.

")); + + ui->descriptionErrorDestinationLabel->setText(tr("

The ErrorDestination is special; it allows exception handling based on the PathFollower. " + "If the PathFollower indicates that it is unable to execute Mode, it indicates this error in the PathStatus UAVObject. " + "If that happens, then the sequence of waypoints is interrupted and the waypoint in ErrorDestination becomes the Active Waypoint. " + "A thinkable use case for this functionality would be to steer towards a safe emergency landing site if the engine fails.

")); } + void opmap_edit_waypoint_dialog::currentIndexChanged(int index) { ui->lbNumber->setText(QString::number(index + 1)); + ui->wpNumberSpinBox->setValue(index + 1); + + bool isMin = (index == 0); + bool isMax = ((index + 1) == mapper->model()->rowCount()); + ui->pushButtonPrevious->setEnabled(!isMin); + ui->pushButtonNext->setEnabled(!isMax); + QModelIndex idx = mapper->model()->index(index, 0); if (index == itemSelection->currentIndex().row()) { return; @@ -98,162 +117,205 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() { MapDataDelegate::ModeOptions mode = (MapDataDelegate::ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); + ui->modeParam1->setText(""); + ui->modeParam2->setText(""); + ui->modeParam3->setText(""); + ui->modeParam4->setText(""); + ui->modeParam1->setEnabled(false); + ui->modeParam2->setEnabled(false); + ui->modeParam3->setEnabled(false); + ui->modeParam4->setEnabled(false); + ui->dsb_modeParam1->setEnabled(false); + ui->dsb_modeParam2->setEnabled(false); + ui->dsb_modeParam3->setEnabled(false); + ui->dsb_modeParam4->setEnabled(false); + switch (mode) { case MapDataDelegate::MODE_GOTOENDPOINT: + ui->descriptionModeLabel->setText(tr("

The Autopilot will try to hold position at a fixed end-coordinate. " + "If elsewhere, the craft will steer towards the coordinate but not " + "necessarily in a straight line as drift will not be compensated.

")); + break; case MapDataDelegate::MODE_FOLLOWVECTOR: + ui->descriptionModeLabel->setText(tr("

The Autopilot will attempt to stay on a defined trajectory from the previous waypoint " + "to the current one. Any deviation from this path, for example by wind, will be corrected. " + "This is the best and obvious choice for direct straight-line (rhumb line) navigation in any vehicle.

")); + break; case MapDataDelegate::MODE_CIRCLERIGHT: + ui->descriptionModeLabel->setText(tr("

The Autopilot will attempt to fly a circular trajectory around a waypoint. " + "The curve radius is defined by the distance from the previous waypoint, therefore setting the coordinate " + "of the waypoint perpendicular to the previous flight path leg (and on the side the vehicle is supposed to turn toward!) " + "will lead to the smoothest possible transition.

Staying in FlyCircle for a prolonged time will lead to a circular " + "loiter trajectory around a waypoint, but this mode can be used in combination with the PointingTowardsNext-EndCondition " + "to stay on the curved trajectory until the vehicle is moving towards the next waypoint, which allows for very controlled " + "turns in flight paths.

")); + break; case MapDataDelegate::MODE_CIRCLELEFT: + ui->descriptionModeLabel->setText(tr("

The Autopilot will attempt to fly a circular trajectory around a waypoint. " + "The curve radius is defined by the distance from the previous waypoint, therefore setting the coordinate " + "of the waypoint perpendicular to the previous flight path leg (and on the side the vehicle is supposed to turn toward!) " + "will lead to the smoothest possible transition.

Staying in FlyCircle for a prolonged time will lead to a circular " + "loiter trajectory around a waypoint, but this mode can be used in combination with the PointingTowardsNext-EndCondition " + "to stay on the curved trajectory until the vehicle is moving towards the next waypoint, which allows for very controlled " + "turns in flight paths.

")); + break; case MapDataDelegate::MODE_DISARMALARM: - case MapDataDelegate::MODE_LAND: - case MapDataDelegate::MODE_BRAKE: - ui->modeParam1->setVisible(false); - ui->modeParam2->setVisible(false); - ui->modeParam3->setVisible(false); - ui->modeParam4->setVisible(false); - ui->dsb_modeParam1->setVisible(false); - ui->dsb_modeParam2->setVisible(false); - ui->dsb_modeParam3->setVisible(false); - ui->dsb_modeParam4->setVisible(false); - break; - case MapDataDelegate::MODE_VELOCITY: - ui->modeParam1->setVisible(true); - ui->modeParam2->setVisible(true); - ui->modeParam3->setVisible(true); - ui->modeParam4->setVisible(false); - ui->dsb_modeParam1->setVisible(true); - ui->dsb_modeParam2->setVisible(true); - ui->dsb_modeParam3->setVisible(true); - ui->dsb_modeParam4->setVisible(false); - break; - case MapDataDelegate::MODE_FIXEDATTITUDE: - ui->modeParam1->setText("pitch"); - ui->modeParam2->setText("roll"); - ui->modeParam3->setText("yaw"); - ui->modeParam4->setText("thrust"); - ui->modeParam1->setVisible(true); - ui->modeParam2->setVisible(true); - ui->modeParam3->setVisible(true); - ui->modeParam4->setVisible(true); - ui->dsb_modeParam1->setVisible(true); - ui->dsb_modeParam2->setVisible(true); - ui->dsb_modeParam3->setVisible(true); - ui->dsb_modeParam4->setVisible(true); - break; - case MapDataDelegate::MODE_SETACCESSORY: - ui->modeParam1->setText("Acc.channel"); - ui->modeParam2->setText("Value"); - ui->modeParam1->setVisible(true); - ui->modeParam2->setVisible(true); - ui->modeParam3->setVisible(false); - ui->modeParam4->setVisible(false); - ui->dsb_modeParam1->setVisible(true); - ui->dsb_modeParam2->setVisible(true); - ui->dsb_modeParam3->setVisible(false); - ui->dsb_modeParam4->setVisible(false); + ui->descriptionModeLabel->setText(tr("

The Autopilot is instructed to force a CRITICAL PathFollower alarm. A PathFollower alarm of type CRITICAL " + "is supposed to automatically set the vehicle to DISARMED and thus disable the engines, cut fuel supply, ...

" + "The PathFollower can do this during any mode in case of emergency, but through this mode the PathPlanner " + "can force this behavior, for example after a landing.

")); break; case MapDataDelegate::MODE_AUTOTAKEOFF: - // FIXME: Do nothing? + // FixedWing do not use parameters, vertical velocity can be set for multirotors as param0 + ui->modeParam1->setText("Speed (m/s):"); + ui->modeParam1->setEnabled(true); + ui->dsb_modeParam1->setEnabled(true); + ui->descriptionModeLabel->setText(tr("

The Autopilot will engage a hardcoded, fully automated takeoff sequence. " + "Using a fixed attitude, heading towards the destination waypoint for a fixed wing or " + "a vertical climb for a multirotor.

" + "

Vertical speed in meters/second, for multirotors. (Will be around 0.6m/s)

")); + break; + case MapDataDelegate::MODE_LAND: + // FixedWing do not use parameters, vertical velocity can be set for multirotors as param0 (0.1/0.6m/s range) + ui->modeParam1->setText("Speed (m/s):"); + ui->modeParam1->setEnabled(true); + ui->dsb_modeParam1->setEnabled(true); + ui->descriptionModeLabel->setText(tr("

The Autopilot will engage a hardcoded, fully automated landing sequence. " + "Using a fixed attitude, heading towards the destination waypoint for a fixed wing or " + "a vertical descent for a multirotor.

" + "

Vertical speed in meters/second, for multirotors. (Will be around 0.6m/s)

")); + break; + case MapDataDelegate::MODE_BRAKE: + ui->descriptionModeLabel->setText(tr("

This mode is used internally by assisted flight modes with multirotors to slow down the velocity.

")); + break; + case MapDataDelegate::MODE_VELOCITY: + ui->descriptionModeLabel->setText(tr("

This mode is used internally by assisted flight modes with multirotors to maintain a velocity in 3D space.

")); + break; + case MapDataDelegate::MODE_FIXEDATTITUDE: + ui->modeParam1->setText("Roll:"); + ui->modeParam2->setText("Pitch:"); + ui->modeParam3->setText("Yaw:"); + ui->modeParam4->setText("Thrust:"); + ui->modeParam1->setEnabled(true); + ui->modeParam2->setEnabled(true); + ui->modeParam3->setEnabled(true); + ui->modeParam4->setEnabled(true); + ui->dsb_modeParam1->setEnabled(true); + ui->dsb_modeParam2->setEnabled(true); + ui->dsb_modeParam3->setEnabled(true); + ui->dsb_modeParam4->setEnabled(true); + ui->descriptionModeLabel->setText(tr("

The Autopilot will play dumb and simply instruct the Stabilization Module to assume a certain Roll, Pitch angle " + "and optionally a Yaw rotation rate and Thrust setting. This allows for very simple auto-takeoff and " + "auto-landing maneuvers.

" + "

Roll(+-180°) and Pitch (+-90°) angles in degrees

" + "

Yaw rate in deg/s

" + "

Thrust from 0 to 1

")); + break; + case MapDataDelegate::MODE_SETACCESSORY: + ui->modeParam1->setText("Acc.channel:"); + ui->modeParam2->setText("Value:"); + ui->modeParam1->setEnabled(true); + ui->modeParam2->setEnabled(true); + ui->dsb_modeParam1->setEnabled(true); + ui->dsb_modeParam2->setEnabled(true); + ui->descriptionModeLabel->setText(tr("

Not yet implemented.

")); + // ui->descriptionModeLabel->setText(tr("

In this mode, the PathFollower is supposed to inject a specific value (-1|0|+1 range) into an AccessoryDesired channel. " + // "This would allow one to control arbitrary auxilliary components from the PathPlanner like flaps and landing gear.

")); + break; + default: + ui->descriptionModeLabel->setText(tr("")); break; } } + void opmap_edit_waypoint_dialog::setupConditionWidgets() { MapDataDelegate::EndConditionOptions mode = (MapDataDelegate::EndConditionOptions)ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); + ui->condParam1->setText(""); + ui->condParam2->setText(""); + ui->condParam3->setText(""); + ui->condParam4->setText(""); + ui->condParam1->setEnabled(false); + ui->condParam2->setEnabled(false); + ui->condParam3->setEnabled(false); + ui->condParam4->setEnabled(false); + ui->dsb_condParam1->setEnabled(false); + ui->dsb_condParam2->setEnabled(false); + ui->dsb_condParam3->setEnabled(false); + ui->dsb_condParam4->setEnabled(false); + switch (mode) { case MapDataDelegate::ENDCONDITION_NONE: + ui->descriptionConditionLabel->setText(tr("

This condition is always false. A WaypointAction with EndCondition to None will stay in " + "its mode until forever, or until an Error in the PathFollower triggers the ErrorJump. (For example out of fuel!)

")); + break; case MapDataDelegate::ENDCONDITION_IMMEDIATE: + ui->descriptionConditionLabel->setText(tr("

Opposite to the None condition, the immediate condition is always true.

")); + break; case MapDataDelegate::ENDCONDITION_PYTHONSCRIPT: - ui->condParam1->setVisible(false); - ui->condParam2->setVisible(false); - ui->condParam3->setVisible(false); - ui->condParam4->setVisible(false); - ui->dsb_condParam1->setVisible(false); - ui->dsb_condParam2->setVisible(false); - ui->dsb_condParam3->setVisible(false); - ui->dsb_condParam4->setVisible(false); + ui->descriptionConditionLabel->setText(tr("

Not yet implemented.

")); break; case MapDataDelegate::ENDCONDITION_TIMEOUT: - ui->condParam1->setVisible(true); - ui->condParam2->setVisible(false); - ui->condParam3->setVisible(false); - ui->condParam4->setVisible(false); - ui->dsb_condParam1->setVisible(true); - ui->dsb_condParam2->setVisible(false); - ui->dsb_condParam3->setVisible(false); - ui->dsb_condParam4->setVisible(false); - ui->condParam1->setText("Timeout(s)"); + ui->condParam1->setEnabled(true); + ui->dsb_condParam1->setEnabled(true); + ui->condParam1->setText("Timeout (s)"); + ui->descriptionConditionLabel->setText(tr("

The Timeout condition measures time this waypoint is active (in seconds).

")); break; case MapDataDelegate::ENDCONDITION_DISTANCETOTARGET: - ui->condParam1->setVisible(true); - ui->condParam2->setVisible(true); - ui->condParam3->setVisible(false); - ui->condParam4->setVisible(false); - ui->dsb_condParam1->setVisible(true); - ui->dsb_condParam2->setVisible(true); - ui->dsb_condParam3->setVisible(false); - ui->dsb_condParam4->setVisible(false); - ui->condParam1->setText("Distance(m)"); - ui->condParam2->setText("Flag(0=2D,1=3D)"); // FIXME + ui->condParam1->setEnabled(true); + ui->condParam2->setEnabled(true); + ui->dsb_condParam1->setEnabled(true); + ui->dsb_condParam2->setEnabled(true); + ui->condParam1->setText("Distance (m):"); + ui->condParam2->setText("Flag:"); + ui->descriptionConditionLabel->setText(tr("

The DistanceToTarget condition measures the distance to a waypoint, returns true if closer.

" + "

Flag: 0= 2D distance, 1= 3D distance

")); break; case MapDataDelegate::ENDCONDITION_LEGREMAINING: - ui->condParam1->setVisible(true); - ui->condParam2->setVisible(false); - ui->condParam3->setVisible(false); - ui->condParam4->setVisible(false); - ui->dsb_condParam1->setVisible(true); - ui->dsb_condParam2->setVisible(false); - ui->dsb_condParam3->setVisible(false); - ui->dsb_condParam4->setVisible(false); - ui->condParam1->setText("Relative Distance(0=complete,1=just starting)"); + ui->condParam1->setEnabled(true); + ui->dsb_condParam1->setEnabled(true); + ui->condParam1->setText("Relative Distance:"); + ui->descriptionConditionLabel->setText(tr("

The LegRemaining condition measures how far the pathfollower got on a linear path segment, returns true " + "if closer to destination(path more complete).

" + "

0=complete, 1=just starting

")); break; case MapDataDelegate::ENDCONDITION_BELOWERROR: - ui->condParam1->setVisible(true); - ui->condParam2->setVisible(false); - ui->condParam3->setVisible(false); - ui->condParam4->setVisible(false); - ui->dsb_condParam1->setVisible(true); - ui->dsb_condParam2->setVisible(false); - ui->dsb_condParam3->setVisible(false); - ui->dsb_condParam4->setVisible(false); - ui->condParam1->setText("error margin (in m)"); + ui->condParam1->setEnabled(true); + ui->dsb_condParam1->setEnabled(true); + ui->condParam1->setText("Error margin (m):"); + ui->descriptionConditionLabel->setText(tr("

The BelowError condition measures the error on a path segment, returns true if error is below margin in meters.

")); break; case MapDataDelegate::ENDCONDITION_ABOVEALTITUDE: - ui->condParam1->setVisible(true); - ui->condParam2->setVisible(false); - ui->condParam3->setVisible(false); - ui->condParam4->setVisible(false); - ui->dsb_condParam1->setVisible(true); - ui->dsb_condParam2->setVisible(false); - ui->dsb_condParam3->setVisible(false); - ui->dsb_condParam4->setVisible(false); - ui->condParam1->setText("Altitude in meters (negative)"); + ui->condParam1->setEnabled(true); + ui->dsb_condParam1->setEnabled(true); + ui->condParam1->setText("Altitude (m):"); + ui->descriptionConditionLabel->setText(tr("

The AboveAltitude condition measures the flight altitude relative to home position, returns true if " + "above critical altitude.

WARNING! altitudes set here are always negative if above Home. (down coordinate)

")); break; case MapDataDelegate::ENDCONDITION_ABOVESPEED: - ui->condParam1->setVisible(true); - ui->condParam2->setVisible(true); - ui->condParam3->setVisible(false); - ui->condParam4->setVisible(false); - ui->dsb_condParam1->setVisible(true); - ui->dsb_condParam2->setVisible(true); - ui->dsb_condParam3->setVisible(false); - ui->dsb_condParam4->setVisible(false); - ui->condParam1->setText("Speed in meters/second"); - ui->condParam2->setText("flag: 0=groundspeed 1=airspeed"); + ui->condParam1->setEnabled(true); + ui->condParam2->setEnabled(true); + ui->dsb_condParam1->setEnabled(true); + ui->dsb_condParam2->setEnabled(true); + ui->condParam1->setText("Speed (m/s):"); + ui->condParam2->setText("Flag:"); + ui->descriptionConditionLabel->setText(tr("

The AboveSpeed measures the movement speed(3D), returns true if above critical speed

" + "

Speed in meters / second

" + "

Flag: 0= groundspeed 1= airspeed

")); break; case MapDataDelegate::ENDCONDITION_POINTINGTOWARDSNEXT: - ui->condParam1->setVisible(true); - ui->condParam2->setVisible(false); - ui->condParam3->setVisible(false); - ui->condParam4->setVisible(false); - ui->dsb_condParam1->setVisible(true); - ui->dsb_condParam2->setVisible(false); - ui->dsb_condParam3->setVisible(false); - ui->dsb_condParam4->setVisible(false); - ui->condParam1->setText("Degrees variation allowed"); + ui->condParam1->setEnabled(true); + ui->dsb_condParam1->setEnabled(true); + ui->condParam1->setText("Degrees:"); + ui->descriptionConditionLabel->setText(tr("

The PointingTowardsNext condition measures the horizontal movement vector direction relative " + "to the next waypoint regardless whether this waypoint will ever be active " + "(Command could jump to a different waypoint on true).

This is useful for curve segments where " + "the craft should stop circling when facing a certain way(usually the next waypoint), " + "returns true if within a certain angular margin in degrees.

")); break; default: - + ui->descriptionConditionLabel->setText(tr("")); break; } } @@ -304,7 +366,6 @@ void opmap_edit_waypoint_dialog::on_pushButtonApply_clicked() mapper->submit(); } - void opmap_edit_waypoint_dialog::enableEditWidgets(bool value) { QWidget *w; diff --git a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui index 597c3e6ac..4dfb28d2b 100644 --- a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui +++ b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui @@ -83,7 +83,7 @@
- + @@ -99,10 +99,10 @@ - + - + @@ -121,7 +121,7 @@ - + 5 @@ -134,14 +134,14 @@ - + degrees - + degrees @@ -164,21 +164,21 @@ - + meters - + degrees - + Bearing @@ -188,7 +188,7 @@ - + 2 @@ -198,7 +198,7 @@ - + @@ -214,7 +214,7 @@ - + Qt::LeftToRight @@ -234,21 +234,28 @@ - + 0 - + + + + 999999999.000000000000000 + + + + - + Velocity @@ -258,13 +265,6 @@ - - - - 999999999.000000000000000 - - - @@ -281,14 +281,14 @@ - + meters - + Relative altitude @@ -298,7 +298,7 @@ - + -999999999.000000000000000 @@ -308,24 +308,7 @@ - - - - meters - - - - - - - 2 - - - 999999999.000000000000000 - - - - + -5000.000000000000000 @@ -335,7 +318,24 @@ - + + + + meters + + + + + + + 2 + + + 999999999.000000000000000 + + + + m/s @@ -344,6 +344,19 @@
+ + + + Qt::Vertical + + + + 20 + 0 + + + + @@ -353,6 +366,48 @@ + + + + 6 + + + 0 + + + + + + 0 + 0 + + + + Description + + + Qt::AlignJustify|Qt::AlignTop + + + true + + + + + + + Qt::Vertical + + + + 20 + 5 + + + + + + @@ -363,7 +418,7 @@ - 100 + 120 0 @@ -379,7 +434,14 @@ - + + + + 120 + 0 + + + @@ -399,6 +461,12 @@ 0 + + + 100 + 0 + + Qt::LeftToRight @@ -427,6 +495,9 @@ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + true + @@ -446,6 +517,9 @@ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + true + @@ -465,6 +539,9 @@ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + true + @@ -497,21 +574,34 @@ - - + + - Qt::Horizontal + Qt::Vertical - 40 - 20 + 20 + 5 + + + + Qt::Vertical + + + + 20 + 0 + + + + @@ -519,11 +609,37 @@ End condition + + + + Qt::Vertical + + + + 20 + 0 + + + + QLayout::SetDefaultConstraint + + + + Qt::Vertical + + + + 20 + 5 + + + + @@ -534,7 +650,7 @@ - 100 + 120 0 @@ -550,7 +666,14 @@ - + + + + 150 + 0 + + + @@ -579,6 +702,9 @@ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + true + @@ -598,6 +724,9 @@ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + true + @@ -617,6 +746,9 @@ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + true + @@ -636,6 +768,9 @@ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + true + @@ -668,18 +803,47 @@ - - - - Qt::Horizontal + + + + 6 - - - 40 - 20 - + + 0 - + + + + + 0 + 0 + + + + Description + + + Qt::AlignJustify|Qt::AlignTop + + + true + + + + + + + Qt::Vertical + + + + 20 + 0 + + + + + @@ -690,12 +854,100 @@ Command + + + + Qt::Vertical + + + + 20 + 0 + + + + + + + + Qt::Horizontal + + + QLayout::SetDefaultConstraint - + + 0 + + + + + + 0 + 0 + + + + Description + + + Qt::AlignJustify|Qt::AlignVCenter + + + true + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 6 + 0 + + + + + + + + 0 + + + + + + 60 + 0 + + + + + + + + Qt::Horizontal + + + + 0 + 10 + + + + + + + @@ -705,7 +957,7 @@ - 100 + 130 0 @@ -720,10 +972,17 @@ - - + + + + + 210 + 0 + + + - + @@ -740,29 +999,29 @@ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - Error Destination - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + true - - + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 6 + 20 + + + + + + Qt::Horizontal @@ -774,11 +1033,117 @@ - - + + + + + + 0 + + + 0 + + + 0 + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 6 + 20 + + + - - + + + + + 0 + 0 + + + + Description + + + true + + + + + + + + 0 + 0 + + + + + 130 + 0 + + + + Qt::LeftToRight + + + Error Destination + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + true + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 6 + 20 + + + + + + + + + 60 + 0 + + + + + + + + Qt::Horizontal + + + + 10 + 20 + + + @@ -795,6 +1160,16 @@ + + + + Qt::AlignCenter + + + QAbstractSpinBox::NoButtons + + + diff --git a/ground/gcs/src/plugins/opmap/widgetdelegates.cpp b/ground/gcs/src/plugins/opmap/widgetdelegates.cpp index b0ff8bed0..e69fb998f 100644 --- a/ground/gcs/src/plugins/opmap/widgetdelegates.cpp +++ b/ground/gcs/src/plugins/opmap/widgetdelegates.cpp @@ -122,7 +122,7 @@ void MapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDa case flightDataModel::CONDITION: combo->addItem("None", ENDCONDITION_NONE); combo->addItem("Timeout", ENDCONDITION_TIMEOUT); - combo->addItem("Distance to tgt", ENDCONDITION_DISTANCETOTARGET); + combo->addItem("Distance to target", ENDCONDITION_DISTANCETOTARGET); combo->addItem("Leg remaining", ENDCONDITION_LEGREMAINING); combo->addItem("Below Error", ENDCONDITION_BELOWERROR); combo->addItem("Above Altitude", ENDCONDITION_ABOVEALTITUDE); @@ -132,11 +132,11 @@ void MapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDa combo->addItem("Immediate", ENDCONDITION_IMMEDIATE); break; case flightDataModel::COMMAND: - combo->addItem("On conditon next wp", COMMAND_ONCONDITIONNEXTWAYPOINT); - combo->addItem("On NOT conditon next wp", COMMAND_ONNOTCONDITIONNEXTWAYPOINT); - combo->addItem("On conditon jump wp", COMMAND_ONCONDITIONJUMPWAYPOINT); - combo->addItem("On NOT conditon jump wp", COMMAND_ONNOTCONDITIONJUMPWAYPOINT); - combo->addItem("On conditon jump wp else next wp", COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT); + combo->addItem("On condition next wp", COMMAND_ONCONDITIONNEXTWAYPOINT); + combo->addItem("On NOT condition next wp", COMMAND_ONNOTCONDITIONNEXTWAYPOINT); + combo->addItem("On condition jump wp", COMMAND_ONCONDITIONJUMPWAYPOINT); + combo->addItem("On NOT condition jump wp", COMMAND_ONNOTCONDITIONJUMPWAYPOINT); + combo->addItem("On condition jump wp else next wp", COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT); break; default: break; From fada2f659c39b3b9fa64c968ddb2955398a9d07c Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Fri, 29 Dec 2017 20:26:54 +0100 Subject: [PATCH 04/20] LP-572 Made Pathplanner editor more readable + typo fix --- .../gcs/src/plugins/opmap/flightdatamodel.cpp | 62 +++++++++---------- .../gcs/src/plugins/opmap/flightdatamodel.h | 4 +- .../gcs/src/plugins/opmap/modelmapproxy.cpp | 6 +- .../opmap/opmap_edit_waypoint_dialog.cpp | 2 +- ground/gcs/src/plugins/opmap/pathplanner.cpp | 25 +++++++- 5 files changed, 61 insertions(+), 38 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/flightdatamodel.cpp b/ground/gcs/src/plugins/opmap/flightdatamodel.cpp index 17f76257e..01756e932 100644 --- a/ground/gcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/gcs/src/plugins/opmap/flightdatamodel.cpp @@ -76,8 +76,8 @@ bool flightDataModel::setColumnByIndex(pathPlanData *row, const int index, const bool b; switch (index) { - case WPDESCRITPTION: - row->wpDescritption = value.toString(); + case WPDESCRIPTION: + row->wpDescription = value.toString(); b = true; break; case LATPOSITION: @@ -180,8 +180,8 @@ QVariant flightDataModel::getColumnByIndex(const pathPlanData *row, const int in QVariant value; switch (index) { - case WPDESCRITPTION: - value = row->wpDescritption; + case WPDESCRIPTION: + value = row->wpDescription; break; case LATPOSITION: value = row->latPosition; @@ -262,77 +262,77 @@ QVariant flightDataModel::headerData(int section, Qt::Orientation orientation, i value = QString::number(section + 1); } else if (orientation == Qt::Horizontal) { switch (section) { - case WPDESCRITPTION: - value = QString("Description"); + case WPDESCRIPTION: + value = "Description"; break; case LATPOSITION: - value = QString("Latitude"); + value = "Latitude"; break; case LNGPOSITION: - value = QString("Longitude"); + value = "Longitude"; break; case DISRELATIVE: - value = QString("Distance to home"); + value = "Distance\nto home"; break; case BEARELATIVE: - value = QString("Bearing from home"); + value = "Bearing\nfrom home"; break; case ALTITUDERELATIVE: - value = QString("Altitude above home"); + value = "Altitude\nabove\nhome"; break; case ISRELATIVE: - value = QString("Relative to home"); + value = "Relative\nto home"; break; case ALTITUDE: - value = QString("Altitude"); + value = "Altitude"; break; case VELOCITY: - value = QString("Velocity"); + value = "Velocity"; break; case MODE: - value = QString("Mode"); + value = "Mode"; break; case MODE_PARAMS0: - value = QString("Mode parameter 0"); + value = "Mode\nparam0"; break; case MODE_PARAMS1: - value = QString("Mode parameter 1"); + value = "Mode\nparam1"; break; case MODE_PARAMS2: - value = QString("Mode parameter 2"); + value = "Mode\nparam2"; break; case MODE_PARAMS3: - value = QString("Mode parameter 3"); + value = "Mode\nparam3"; break; case CONDITION: - value = QString("Condition"); + value = "Condition"; break; case CONDITION_PARAMS0: - value = QString("Condition parameter 0"); + value = "Cond.\nparam0"; break; case CONDITION_PARAMS1: - value = QString("Condition parameter 1"); + value = "Cond.\nparam1"; break; case CONDITION_PARAMS2: - value = QString("Condition parameter 2"); + value = "Cond.\nparam2"; break; case CONDITION_PARAMS3: - value = QString("Condition parameter 3"); + value = "Cond.\nparam3"; break; case COMMAND: - value = QString("Command"); + value = "Command"; break; case JUMPDESTINATION: - value = QString("Jump Destination"); + value = "Jump\nDest."; break; case ERRORDESTINATION: - value = QString("Error Destination"); + value = "Error\nDest."; break; case LOCKED: - value = QString("Locked"); + value = "Locked"; break; default: - value = QString(); + value = ""; break; } } @@ -448,7 +448,7 @@ bool flightDataModel::writeToFile(QString fileName) waypoint.setAttribute("number", dataStorage.indexOf(obj)); root.appendChild(waypoint); QDomElement field = doc.createElement("field"); - field.setAttribute("value", obj->wpDescritption); + field.setAttribute("value", obj->wpDescription); field.setAttribute("name", "description"); waypoint.appendChild(field); @@ -612,7 +612,7 @@ void flightDataModel::readFromFile(QString fileName) if (name == "altitude") { data->altitude = value.toDouble(); } else if (name == "description") { - data->wpDescritption = value; + data->wpDescription = value; } else if (name == "latitude") { data->latPosition = value.toDouble(); } else if (name == "longitude") { diff --git a/ground/gcs/src/plugins/opmap/flightdatamodel.h b/ground/gcs/src/plugins/opmap/flightdatamodel.h index 14d3f3e1c..f8ddb1cf1 100644 --- a/ground/gcs/src/plugins/opmap/flightdatamodel.h +++ b/ground/gcs/src/plugins/opmap/flightdatamodel.h @@ -30,7 +30,7 @@ #include "opmapcontrol/opmapcontrol.h" struct pathPlanData { - QString wpDescritption; + QString wpDescription; double latPosition; double lngPosition; double disRelative; @@ -53,7 +53,7 @@ class flightDataModel : public QAbstractTableModel { Q_OBJECT public: enum pathPlanDataEnum { - WPDESCRITPTION, LATPOSITION, LNGPOSITION, DISRELATIVE, BEARELATIVE, ALTITUDERELATIVE, ISRELATIVE, ALTITUDE, + WPDESCRIPTION, LATPOSITION, LNGPOSITION, DISRELATIVE, BEARELATIVE, ALTITUDERELATIVE, ISRELATIVE, ALTITUDE, VELOCITY, MODE, MODE_PARAMS0, MODE_PARAMS1, MODE_PARAMS2, MODE_PARAMS3, CONDITION, CONDITION_PARAMS0, CONDITION_PARAMS1, CONDITION_PARAMS2, CONDITION_PARAMS3, COMMAND, JUMPDESTINATION, ERRORDESTINATION, LOCKED diff --git a/ground/gcs/src/plugins/opmap/modelmapproxy.cpp b/ground/gcs/src/plugins/opmap/modelmapproxy.cpp index 0940217ff..db658f0bf 100644 --- a/ground/gcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/gcs/src/plugins/opmap/modelmapproxy.cpp @@ -233,8 +233,8 @@ void modelMapProxy::dataChanged(const QModelIndex &topLeft, const QModelIndex &b case flightDataModel::MODE: refreshOverlays(); break; - case flightDataModel::WPDESCRITPTION: - index = model->index(x, flightDataModel::WPDESCRITPTION); + case flightDataModel::WPDESCRIPTION: + index = model->index(x, flightDataModel::WPDESCRIPTION); desc = index.data(Qt::DisplayRole).toString(); item->SetDescription(desc); break; @@ -299,7 +299,7 @@ void modelMapProxy::rowsInserted(const QModelIndex &parent, int first, int last) distBearingAltitude distBearing; double altitude; bool relative; - index = model->index(x, flightDataModel::WPDESCRITPTION); + index = model->index(x, flightDataModel::WPDESCRIPTION); QString desc = index.data(Qt::DisplayRole).toString(); index = model->index(x, flightDataModel::LATPOSITION); latlng.SetLat(index.data(Qt::DisplayRole).toDouble()); diff --git a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 9e9af7aeb..93ea5b9e8 100644 --- a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -57,7 +57,7 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent, QAbstrac mapper->addMapping(ui->doubleSpinBoxLatitude, flightDataModel::LATPOSITION); mapper->addMapping(ui->doubleSpinBoxLongitude, flightDataModel::LNGPOSITION); mapper->addMapping(ui->doubleSpinBoxAltitude, flightDataModel::ALTITUDE); - mapper->addMapping(ui->lineEditDescription, flightDataModel::WPDESCRITPTION); + mapper->addMapping(ui->lineEditDescription, flightDataModel::WPDESCRIPTION); mapper->addMapping(ui->checkBoxRelative, flightDataModel::ISRELATIVE); mapper->addMapping(ui->doubleSpinBoxBearing, flightDataModel::BEARELATIVE); mapper->addMapping(ui->doubleSpinBoxVelocity, flightDataModel::VELOCITY); diff --git a/ground/gcs/src/plugins/opmap/pathplanner.cpp b/ground/gcs/src/plugins/opmap/pathplanner.cpp index dd02a6258..053d39376 100644 --- a/ground/gcs/src/plugins/opmap/pathplanner.cpp +++ b/ground/gcs/src/plugins/opmap/pathplanner.cpp @@ -54,7 +54,30 @@ void pathPlanner::setModel(flightDataModel *model, QItemSelectionModel *selectio ui->tableView->setItemDelegate(new MapDataDelegate(this)); connect(model, SIGNAL(rowsInserted(const QModelIndex &, int, int)), this, SLOT(rowsInserted(const QModelIndex &, int, int))); wid = new opmap_edit_waypoint_dialog(NULL, model, selection); - ui->tableView->resizeColumnsToContents(); + + ui->tableView->setColumnWidth(flightDataModel::WPDESCRIPTION, 120); + ui->tableView->setColumnWidth(flightDataModel::LATPOSITION, 100); + ui->tableView->setColumnWidth(flightDataModel::LNGPOSITION, 100); + ui->tableView->setColumnWidth(flightDataModel::DISRELATIVE, 80); + ui->tableView->setColumnWidth(flightDataModel::BEARELATIVE, 80); + ui->tableView->setColumnWidth(flightDataModel::ALTITUDERELATIVE, 70); + ui->tableView->setColumnWidth(flightDataModel::ISRELATIVE, 70); + ui->tableView->setColumnWidth(flightDataModel::ALTITUDE, 80); + ui->tableView->setColumnWidth(flightDataModel::VELOCITY, 60); + ui->tableView->setColumnWidth(flightDataModel::MODE, 120); + ui->tableView->setColumnWidth(flightDataModel::MODE_PARAMS0, 60); + ui->tableView->setColumnWidth(flightDataModel::MODE_PARAMS1, 60); + ui->tableView->setColumnWidth(flightDataModel::MODE_PARAMS2, 60); + ui->tableView->setColumnWidth(flightDataModel::MODE_PARAMS3, 60); + ui->tableView->setColumnWidth(flightDataModel::CONDITION, 150); + ui->tableView->setColumnWidth(flightDataModel::CONDITION_PARAMS0, 60); + ui->tableView->setColumnWidth(flightDataModel::CONDITION_PARAMS1, 60); + ui->tableView->setColumnWidth(flightDataModel::CONDITION_PARAMS2, 60); + ui->tableView->setColumnWidth(flightDataModel::CONDITION_PARAMS3, 60); + ui->tableView->setColumnWidth(flightDataModel::COMMAND, 150); + ui->tableView->setColumnWidth(flightDataModel::JUMPDESTINATION, 60); + ui->tableView->setColumnWidth(flightDataModel::ERRORDESTINATION, 60); + ui->tableView->setColumnWidth(flightDataModel::LOCKED, 60); } void pathPlanner::rowsInserted(const QModelIndex & parent, int start, int end) From 16d22e28d259fb1722f31dab6d1d9c0af66c371a Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 27 Dec 2017 16:33:40 +0100 Subject: [PATCH 05/20] LP-572 Change the setCoord() threshold from 11m to 21cm --- .../src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index c256f56b2..c559957b9 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -29,6 +29,8 @@ #include "homeitem.h" #include +#define COORDINATES_THRESHOLD 0.000002 // ~21cm + namespace mapcontrol { WayPointItem::WayPointItem(const internals::PointLatLng &coord, int const & altitude, MapGraphicItem *map, wptype type) : coord(coord), reached(false), description(""), shownumber(true), isDragging(false), altitude(altitude), map(map), myType(type) { @@ -259,7 +261,9 @@ void WayPointItem::setRelativeCoord(distBearingAltitude value) void WayPointItem::SetCoord(const internals::PointLatLng &value) { - if (qAbs(Coord().Lat() - value.Lat()) < 0.0001 && qAbs(Coord().Lng() - value.Lng()) < 0.0001) { + // If no changes from previous coordinates, return. + if ((qAbs(Coord().Lat() - value.Lat()) < COORDINATES_THRESHOLD) && + (qAbs(Coord().Lng() - value.Lng()) < COORDINATES_THRESHOLD)) { return; } coord = value; From 5b1b127ad0e51a5dd5f56bf8f69e2b20a5ff33ca Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 27 Dec 2017 16:45:43 +0100 Subject: [PATCH 06/20] LP-572 Move MagicWayPoint in map and keep inside safe area --- .../gcs/src/plugins/opmap/opmapgadgetwidget.cpp | 16 ++++++++++------ ground/gcs/src/plugins/opmap/opmapgadgetwidget.h | 2 +- 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp index 01071b9e8..2d6cfd14a 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -209,7 +209,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_widget->progressBarMap->setMaximum(1); connect(m_map, SIGNAL(zoomChanged(double, double, double)), this, SLOT(zoomChanged(double, double, double))); // map zoom change signals - connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals + connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map position change signals connect(m_map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals connect(m_map, SIGNAL(OnTileLoadStart()), this, SLOT(OnTileLoadStart())); // tile loading start signals connect(m_map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int))); // tile loading signals @@ -1031,7 +1031,7 @@ void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon, double altit m_map->Home->RefreshPos(); // move the magic waypoint to keep it within the safe area boundry - keepMagicWaypointWithInSafeArea(); + keepMagicWaypointWithinSafeArea(); } @@ -2065,7 +2065,7 @@ void OPMapGadgetWidget::onSafeAreaActGroup_triggered(QAction *action) m_map->Home->RefreshPos(); // move the magic waypoint if need be to keep it within the safe area around the home position - keepMagicWaypointWithInSafeArea(); + keepMagicWaypointWithinSafeArea(); } /** @@ -2096,6 +2096,9 @@ void OPMapGadgetWidget::moveToMagicWaypointPosition() if (m_map_mode != MagicWaypoint_MapMode) { return; } + + magicWayPoint->SetCoord(magicWayPoint->Coord()); + keepMagicWaypointWithinSafeArea(); } // ************************************************************************************* @@ -2123,8 +2126,9 @@ void OPMapGadgetWidget::showMagicWaypointControls() // ************************************************************************************* // move the magic waypoint to keep it within the safe area boundry -void OPMapGadgetWidget::keepMagicWaypointWithInSafeArea() +void OPMapGadgetWidget::keepMagicWaypointWithinSafeArea() { + bool moveMagicWP = false; // calcute the bearing and distance from the home position to the magic waypoint double dist = distance(m_home_position.coord, magicWayPoint->Coord()); double bear = bearing(m_home_position.coord, magicWayPoint->Coord()); @@ -2134,11 +2138,11 @@ void OPMapGadgetWidget::keepMagicWaypointWithInSafeArea() if (dist > boundry_dist) { dist = boundry_dist; + moveMagicWP = true; } // move the magic waypoint; - - if (m_map_mode == MagicWaypoint_MapMode) { // move the on-screen waypoint + if ((m_map_mode == MagicWaypoint_MapMode) && moveMagicWP) { // if needed, move the on-screen waypoint to the safe area if (magicWayPoint) { magicWayPoint->SetCoord(destPoint(m_home_position.coord, bear, dist)); } diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h index 02aa9d6f1..696a10fbc 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h @@ -304,7 +304,7 @@ private: void moveToMagicWaypointPosition(); void hideMagicWaypointControls(); void showMagicWaypointControls(); - void keepMagicWaypointWithInSafeArea(); + void keepMagicWaypointWithinSafeArea(); double distance(internals::PointLatLng from, internals::PointLatLng to); double bearing(internals::PointLatLng from, internals::PointLatLng to); From 121aaa08b72c6a23a73019681743752082494c0c Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 3 Jan 2018 17:05:31 +0100 Subject: [PATCH 07/20] LP-572 String fixes, capitalization. --- .../opmap/opmap_edit_waypoint_dialog.cpp | 4 ++-- .../gcs/src/plugins/opmap/widgetdelegates.cpp | 18 +++++++++--------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 93ea5b9e8..9975246dc 100644 --- a/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/gcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -223,7 +223,7 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() // "This would allow one to control arbitrary auxilliary components from the PathPlanner like flaps and landing gear.

")); break; default: - ui->descriptionModeLabel->setText(tr("")); + ui->descriptionModeLabel->setText(""); break; } } @@ -315,7 +315,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() "returns true if within a certain angular margin in degrees.

")); break; default: - ui->descriptionConditionLabel->setText(tr("")); + ui->descriptionConditionLabel->setText(""); break; } } diff --git a/ground/gcs/src/plugins/opmap/widgetdelegates.cpp b/ground/gcs/src/plugins/opmap/widgetdelegates.cpp index e69fb998f..e6bde6bd3 100644 --- a/ground/gcs/src/plugins/opmap/widgetdelegates.cpp +++ b/ground/gcs/src/plugins/opmap/widgetdelegates.cpp @@ -122,21 +122,21 @@ void MapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDa case flightDataModel::CONDITION: combo->addItem("None", ENDCONDITION_NONE); combo->addItem("Timeout", ENDCONDITION_TIMEOUT); - combo->addItem("Distance to target", ENDCONDITION_DISTANCETOTARGET); - combo->addItem("Leg remaining", ENDCONDITION_LEGREMAINING); + combo->addItem("Distance to Target", ENDCONDITION_DISTANCETOTARGET); + combo->addItem("Leg Remaining", ENDCONDITION_LEGREMAINING); combo->addItem("Below Error", ENDCONDITION_BELOWERROR); combo->addItem("Above Altitude", ENDCONDITION_ABOVEALTITUDE); combo->addItem("Above Speed", ENDCONDITION_ABOVESPEED); - combo->addItem("Pointing towards next", ENDCONDITION_POINTINGTOWARDSNEXT); - combo->addItem("Python script", ENDCONDITION_PYTHONSCRIPT); + combo->addItem("Pointing Towards Next", ENDCONDITION_POINTINGTOWARDSNEXT); + combo->addItem("Python Script", ENDCONDITION_PYTHONSCRIPT); combo->addItem("Immediate", ENDCONDITION_IMMEDIATE); break; case flightDataModel::COMMAND: - combo->addItem("On condition next wp", COMMAND_ONCONDITIONNEXTWAYPOINT); - combo->addItem("On NOT condition next wp", COMMAND_ONNOTCONDITIONNEXTWAYPOINT); - combo->addItem("On condition jump wp", COMMAND_ONCONDITIONJUMPWAYPOINT); - combo->addItem("On NOT condition jump wp", COMMAND_ONNOTCONDITIONJUMPWAYPOINT); - combo->addItem("On condition jump wp else next wp", COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT); + combo->addItem("On Condition next Wp", COMMAND_ONCONDITIONNEXTWAYPOINT); + combo->addItem("On NOT Condition next Wp", COMMAND_ONNOTCONDITIONNEXTWAYPOINT); + combo->addItem("On Condition jump Wp", COMMAND_ONCONDITIONJUMPWAYPOINT); + combo->addItem("On NOT Condition jump Wp", COMMAND_ONNOTCONDITIONJUMPWAYPOINT); + combo->addItem("On Condition jump Wp else next Wp", COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT); break; default: break; From f51e7d3688f321cc41400aa00b890c32387abab1 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 3 Jan 2018 22:07:06 +0100 Subject: [PATCH 08/20] LP-572 Fix Home position on map when OPMap config is updated --- ground/gcs/src/plugins/opmap/opmapgadget.cpp | 6 ++- .../src/plugins/opmap/opmapgadgetwidget.cpp | 49 ++++++++++++------- .../gcs/src/plugins/opmap/opmapgadgetwidget.h | 1 + 3 files changed, 37 insertions(+), 19 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/opmapgadget.cpp b/ground/gcs/src/plugins/opmap/opmapgadget.cpp index a49472aed..12319b593 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadget.cpp @@ -67,8 +67,12 @@ void OPMapGadget::loadConfiguration(IUAVGadgetConfiguration *config) m_widget->SetUavPic(m_config->uavSymbol()); m_widget->setZoom(m_config->zoom()); m_widget->setPosition(QPointF(m_config->longitude(), m_config->latitude())); - m_widget->setHomePosition(QPointF(m_config->longitude(), m_config->latitude())); m_widget->setOverlayOpacity(m_config->opacity()); m_widget->setDefaultWaypointAltitude(m_config->defaultWaypointAltitude()); m_widget->setDefaultWaypointVelocity(m_config->defaultWaypointVelocity()); + + if (!m_widget->applyHomeLocationOnMap()) { + // Set default HomeLocation in center of map + m_widget->setHomePosition(QPointF(m_config->longitude(), m_config->latitude())); + } } diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp index 2d6cfd14a..345cd3f5d 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -916,24 +916,7 @@ void OPMapGadgetWidget::onTelemetryConnect() if (!obum) { return; } - - bool set; - double LLA[3]; - - // *********************** - // fetch the home location - - if (obum->getHomeLocation(set, LLA) < 0) { - return; // error - } - setHome(internals::PointLatLng(LLA[0], LLA[1]), LLA[2]); - - if (m_map) { - if (m_map->UAV->GetMapFollowType() != UAVMapFollowType::None) { - m_map->SetCurrentPosition(m_home_position.coord); // set the map position - } - } - // *********************** + applyHomeLocationOnMap(); } void OPMapGadgetWidget::onTelemetryDisconnect() @@ -1164,6 +1147,10 @@ void OPMapGadgetWidget::setHomePosition(QPointF pos) } m_map->Home->SetCoord(internals::PointLatLng(latitude, longitude)); + + if (!m_telemetry_connected) { + m_home_position.coord = internals::PointLatLng(latitude, longitude); + } } void OPMapGadgetWidget::setPosition(QPointF pos) @@ -2366,6 +2353,32 @@ bool OPMapGadgetWidget::getGPSPositionSensor(double &latitude, double &longitude return true; } +bool OPMapGadgetWidget::applyHomeLocationOnMap() +{ + bool set; + double LLA[3]; + + if (!obum) { + return false; + } + + // fetch the home location + if (obum->getHomeLocation(set, LLA) < 0) { + return false; // error + } + + if (m_telemetry_connected) { + setHome(internals::PointLatLng(LLA[0], LLA[1]), LLA[2]); + if (m_map) { + if (m_map->UAV->GetMapFollowType() != UAVMapFollowType::None) { + m_map->SetCurrentPosition(m_home_position.coord); // set the map position + } + } + return true; + } + return false; +} + // ************************************************************************************* void OPMapGadgetWidget::setMapFollowingMode() diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h index 696a10fbc..48f034365 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h @@ -117,6 +117,7 @@ public: void setDefaultWaypointAltitude(qreal default_altitude); void setDefaultWaypointVelocity(qreal default_velocity); bool getGPSPositionSensor(double &latitude, double &longitude, double &altitude); + bool applyHomeLocationOnMap(); signals: void defaultLocationAndZoomChanged(double lng, double lat, double zoom); void overlayOpacityChanged(qreal); From fd92c900a88eb3ba88ad34bde3c2e978a2f2c813 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 3 Jan 2018 23:19:43 +0100 Subject: [PATCH 09/20] LP-572 Apply HomeLocation only when OK button pressed (ignored on Cancel) --- ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp index 345cd3f5d..5bfc300c3 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1790,9 +1790,10 @@ void OPMapGadgetWidget::onSetHomeAct_triggered() altitude = QInputDialog::getDouble(this, tr("Set home altitude"), tr("In [m], referenced to WGS84:"), altitude, -100, 100000, 2, &ok); - setHome(m_context_menu_lat_lon, altitude); - - setHomeLocationObject(); // update the HomeLocation UAVObject + if (ok) { + setHome(m_context_menu_lat_lon, altitude); + setHomeLocationObject(); // update the HomeLocation UAVObject + } } void OPMapGadgetWidget::onGoHomeAct_triggered() From b2b6e58b68381843cfb1adb9a60452aad49356c3 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 4 Jan 2018 02:44:05 +0100 Subject: [PATCH 10/20] LP-572 Handle HomeLocation.Set flag and update Home picture according to status --- .../opmapcontrol/src/mapwidget/homeitem.cpp | 6 ++ .../opmapcontrol/src/mapwidget/homeitem.h | 1 + .../src/mapwidget/images/home2_not_set.svg | 80 ++++++++++++++++ .../src/mapwidget/images/home2_set.svg | 93 +++++++++++++++++++ .../src/mapwidget/mapresources.qrc | 2 + .../src/mapwidget/opmapwidget.cpp | 6 ++ .../opmapcontrol/src/mapwidget/opmapwidget.h | 1 + .../src/plugins/opmap/opmapgadgetwidget.cpp | 17 +++- .../gcs/src/plugins/opmap/opmapgadgetwidget.h | 1 + .../uavobjectutil/uavobjectutilmanager.cpp | 8 +- .../uavobjectutil/uavobjectutilmanager.h | 2 +- 11 files changed, 210 insertions(+), 7 deletions(-) create mode 100644 ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/home2_not_set.svg create mode 100644 ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/home2_set.svg diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 5aa809b7e..6cbd9cec6 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -98,6 +98,12 @@ void HomeItem::RefreshPos() toggleRefresh = false; } +void HomeItem::SetHomePic(QString HomePic) +{ + pic.load(":/markers/images/" + HomePic); + pic = pic.scaled(30, 30, Qt::IgnoreAspectRatio); +} + void HomeItem::setOpacitySlot(qreal opacity) { setOpacity(opacity); diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index 783b30a2c..0a7ba2616 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -102,6 +102,7 @@ protected: QPainterPath shape() const; public slots: void RefreshPos(); + void SetHomePic(QString HomePic); void setOpacitySlot(qreal opacity); signals: void homePositionChanged(internals::PointLatLng coord, float); diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/home2_not_set.svg b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/home2_not_set.svg new file mode 100644 index 000000000..4eef55159 --- /dev/null +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/home2_not_set.svg @@ -0,0 +1,80 @@ + + + + + + + + + + + image/svg+xml + + + + + + + + + + diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/home2_set.svg b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/home2_set.svg new file mode 100644 index 000000000..d1faad64b --- /dev/null +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/images/home2_set.svg @@ -0,0 +1,93 @@ + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/mapresources.qrc b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/mapresources.qrc index 1bb14fffd..918e51ecd 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/mapresources.qrc +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/mapresources.qrc @@ -6,6 +6,8 @@ images/wp_marker_red.png images/compas.svg images/home2.svg + images/home2_not_set.svg + images/home2_set.svg images/nav.svg images/home.png images/home.svg diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index ea1301a24..da58d44f1 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -107,6 +107,12 @@ void OPMapWidget::SetUavPic(QString UAVPic) GPS->SetUavPic(UAVPic); } } +void OPMapWidget::SetHomePic(QString HomePic) +{ + if (Home != 0) { + Home->SetHomePic(HomePic); + } +} WayPointLine *OPMapWidget::WPLineCreate(WayPointItem *from, WayPointItem *to, QColor color, bool dashed, int width) { diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index af79774c7..46b7919ab 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -521,6 +521,7 @@ public: } void SetShowDiagnostics(bool const & value); void SetUavPic(QString UAVPic); + void SetHomePic(QString HomePic); WayPointLine *WPLineCreate(WayPointItem *from, WayPointItem *to, QColor color, bool dashed = false, int width = -1); WayPointLine *WPLineCreate(HomeItem *from, WayPointItem *to, QColor color, bool dashed = false, int width = -1); WayPointCircle *WPCircleCreate(WayPointItem *center, WayPointItem *radius, bool clockwise, QColor color, bool dashed = false, int width = -1); diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp index 5bfc300c3..7007dd15f 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -936,6 +936,16 @@ void OPMapGadgetWidget::homePositionUpdated(UAVObject *hp) if (obum->getHomeLocation(set, LLA) < 0) { return; // error } + + QString HomePic; + + if (set) { + HomePic = "home2_set.svg"; + } else { + HomePic = "home2_not_set.svg"; + } + + SetHomePic(HomePic); setHome(internals::PointLatLng(LLA[0], LLA[1]), LLA[2]); } @@ -2412,7 +2422,7 @@ bool OPMapGadgetWidget::setHomeLocationObject() } double LLA[3] = { m_home_position.coord.Lat(), m_home_position.coord.Lng(), m_home_position.altitude }; - return obum->setHomeLocation(LLA, true) >= 0; + return obum->setHomeLocation(LLA, m_telemetry_connected) >= 0; } // ************************************************************************************* @@ -2422,6 +2432,11 @@ void OPMapGadgetWidget::SetUavPic(QString UAVPic) m_map->SetUavPic(UAVPic); } +void OPMapGadgetWidget::SetHomePic(QString HomePic) +{ + m_map->SetHomePic(HomePic); +} + void OPMapGadgetWidget::on_tbFind_clicked() { QPalette pal = m_widget->leFind->palette(); diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h index 48f034365..45d4513bf 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h @@ -111,6 +111,7 @@ public: void setCacheLocation(QString cacheLocation); void setMapMode(opMapModeType mode); void SetUavPic(QString UAVPic); + void SetHomePic(QString HomePic); void setMaxUpdateRate(int update_rate); void setHomePosition(QPointF pos); void setOverlayOpacity(qreal value); diff --git a/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index 113f795ce..54bec53ea 100644 --- a/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -321,7 +321,7 @@ QString UAVObjectUtilManager::getBoardDescriptionString() // ****************************** // HomeLocation -int UAVObjectUtilManager::setHomeLocation(double LLA[3], bool save_to_sdcard) +int UAVObjectUtilManager::setHomeLocation(double LLA[3], bool set) { double Be[3]; @@ -341,13 +341,11 @@ int UAVObjectUtilManager::setHomeLocation(double LLA[3], bool save_to_sdcard) homeLocationData.Be[1] = Be[1]; homeLocationData.Be[2] = Be[2]; - homeLocationData.Set = HomeLocation::SET_TRUE; + homeLocationData.Set = set; homeLocation->setData(homeLocationData); - if (save_to_sdcard) { - saveObjectToSD(homeLocation); - } + saveObjectToSD(homeLocation); return 0; } diff --git a/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.h b/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.h index 2b298e3e3..8878b8a07 100644 --- a/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.h +++ b/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.h @@ -53,7 +53,7 @@ public: UAVObjectUtilManager(); ~UAVObjectUtilManager(); - int setHomeLocation(double LLA[3], bool save_to_sdcard); + int setHomeLocation(double LLA[3], bool set); int getHomeLocation(bool &set, double LLA[3]); int getGPSPositionSensor(double LLA[3]); From debddb5c0bd688950fb17a8c87711e7473060fd5 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 4 Jan 2018 03:08:25 +0100 Subject: [PATCH 11/20] LP-572 Enable the isSet option for HomeLocation in Attitude tab, add tooltip. --- ground/gcs/src/plugins/config/configrevowidget.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ground/gcs/src/plugins/config/configrevowidget.cpp b/ground/gcs/src/plugins/config/configrevowidget.cpp index 2fb72481e..4f03691f1 100644 --- a/ground/gcs/src/plugins/config/configrevowidget.cpp +++ b/ground/gcs/src/plugins/config/configrevowidget.cpp @@ -394,7 +394,10 @@ void ConfigRevoWidget::refreshWidgetsValuesImpl(UAVObject *obj) { Q_UNUSED(obj); - m_ui->isSetCheckBox->setEnabled(false); + m_ui->isSetCheckBox->setEnabled(true); + m_ui->isSetCheckBox->setToolTip(tr("When checked, the current Home Location is saved to the board.\n" + "When unchecked, the Home Location will be updated and set using\n" + "the first GPS position received after power up.")); HomeLocation *homeLocation = HomeLocation::GetInstance(getObjectManager()); Q_ASSERT(homeLocation); From 16cca00f2103fae75ae8328de17834747b1e9771 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Fri, 5 Jan 2018 13:41:14 +0100 Subject: [PATCH 12/20] LP-572 Make safe area user-configurable --- ground/gcs/src/plugins/opmap/opmapgadget.cpp | 2 + .../opmap/opmapgadgetconfiguration.cpp | 6 + .../plugins/opmap/opmapgadgetconfiguration.h | 20 ++ .../plugins/opmap/opmapgadgetoptionspage.cpp | 21 ++ .../plugins/opmap/opmapgadgetoptionspage.ui | 262 ++++++++++-------- .../src/plugins/opmap/opmapgadgetwidget.cpp | 26 +- .../gcs/src/plugins/opmap/opmapgadgetwidget.h | 2 + 7 files changed, 224 insertions(+), 115 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/opmapgadget.cpp b/ground/gcs/src/plugins/opmap/opmapgadget.cpp index 12319b593..2d81b99e7 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadget.cpp @@ -67,6 +67,8 @@ void OPMapGadget::loadConfiguration(IUAVGadgetConfiguration *config) m_widget->SetUavPic(m_config->uavSymbol()); m_widget->setZoom(m_config->zoom()); m_widget->setPosition(QPointF(m_config->longitude(), m_config->latitude())); + m_widget->setSafeAreaRadius(m_config->safeAreaRadius()); + m_widget->setShowSafeArea(m_config->showSafeArea()); m_widget->setOverlayOpacity(m_config->opacity()); m_widget->setDefaultWaypointAltitude(m_config->defaultWaypointAltitude()); m_widget->setDefaultWaypointVelocity(m_config->defaultWaypointVelocity()); diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetconfiguration.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetconfiguration.cpp index 724bd513b..16dccd110 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetconfiguration.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetconfiguration.cpp @@ -43,6 +43,8 @@ OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings &s m_useOpenGL = settings.value("useOpenGL").toBool(); m_showTileGridLines = settings.value("showTileGridLines").toBool(); m_uavSymbol = settings.value("uavSymbol", QString::fromUtf8(":/uavs/images/mapquad.png")).toString(); + m_safeAreaRadius = settings.value("safeAreaRadius", 5).toInt(); + m_showSafeArea = settings.value("showSafeArea").toBool(); m_maxUpdateRate = settings.value("maxUpdateRate", 2000).toInt(); if (m_maxUpdateRate < 100 || m_maxUpdateRate > 5000) { @@ -69,6 +71,8 @@ OPMapGadgetConfiguration::OPMapGadgetConfiguration(const OPMapGadgetConfiguratio m_cacheLocation = obj.m_cacheLocation; m_uavSymbol = obj.m_uavSymbol; m_maxUpdateRate = obj.m_maxUpdateRate; + m_safeAreaRadius = obj.m_safeAreaRadius; + m_showSafeArea = obj.m_showSafeArea; m_opacity = obj.m_opacity; m_defaultWaypointAltitude = obj.m_defaultWaypointAltitude; m_defaultWaypointVelocity = obj.m_defaultWaypointVelocity; @@ -99,6 +103,8 @@ void OPMapGadgetConfiguration::saveConfig(QSettings &settings) const settings.setValue("uavSymbol", m_uavSymbol); settings.setValue("cacheLocation", Utils::RemoveStoragePath(m_cacheLocation)); settings.setValue("maxUpdateRate", m_maxUpdateRate); + settings.setValue("safeAreaRadius", m_safeAreaRadius); + settings.setValue("showSafeArea", m_showSafeArea); settings.setValue("overlayOpacity", m_opacity); settings.setValue("defaultWaypointAltitude", m_defaultWaypointAltitude); diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetconfiguration.h b/ground/gcs/src/plugins/opmap/opmapgadgetconfiguration.h index 6c8206e53..df26827da 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetconfiguration.h +++ b/ground/gcs/src/plugins/opmap/opmapgadgetconfiguration.h @@ -46,6 +46,8 @@ class OPMapGadgetConfiguration : public IUAVGadgetConfiguration { Q_PROPERTY(QString cacheLocation READ cacheLocation WRITE setCacheLocation) Q_PROPERTY(QString uavSymbol READ uavSymbol WRITE setUavSymbol) Q_PROPERTY(int maxUpdateRate READ maxUpdateRate WRITE setMaxUpdateRate) + Q_PROPERTY(int safeAreaRadius READ safeAreaRadius WRITE setSafeAreaRadius) + Q_PROPERTY(bool showSafeArea READ showSafeArea WRITE setShowSafeArea) Q_PROPERTY(qreal overlayOpacity READ opacity WRITE setOpacity) Q_PROPERTY(qreal defaultWaypointAltitude READ defaultWaypointAltitude WRITE setDefaultWaypointAltitude) Q_PROPERTY(qreal defaultWaypointVelocity READ defaultWaypointVelocity WRITE setDefaultWaypointVelocity) @@ -103,6 +105,14 @@ public: { return m_maxUpdateRate; } + int safeAreaRadius() const + { + return m_safeAreaRadius; + } + bool showSafeArea() const + { + return m_showSafeArea; + } qreal opacity() const { return m_opacity; @@ -164,6 +174,14 @@ public slots: { m_maxUpdateRate = update_rate; } + void setSafeAreaRadius(int safe_area_radius) + { + m_safeAreaRadius = safe_area_radius; + } + void setShowSafeArea(bool showSafeArea) + { + m_showSafeArea = showSafeArea; + } void setDefaultWaypointAltitude(qreal default_altitude) { @@ -187,6 +205,8 @@ private: QString m_cacheLocation; QString m_uavSymbol; int m_maxUpdateRate; + int m_safeAreaRadius; + bool m_showSafeArea; qreal m_opacity; qreal m_defaultWaypointAltitude; qreal m_defaultWaypointVelocity; diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetoptionspage.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetoptionspage.cpp index 24993b51e..23cc3bc44 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetoptionspage.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetoptionspage.cpp @@ -79,6 +79,25 @@ QWidget *OPMapGadgetOptionsPage::createPage(QWidget *parent) index = (index >= 0) ? index : 4; m_page->maxUpdateRateComboBox->setCurrentIndex(index); + // populate the safety area radius combobox + m_page->safeAreaRadiusComboBox->clear(); + m_page->safeAreaRadiusComboBox->addItem("5m", 5); + m_page->safeAreaRadiusComboBox->addItem("10m", 10); + m_page->safeAreaRadiusComboBox->addItem("20m", 20); + m_page->safeAreaRadiusComboBox->addItem("50m", 50); + m_page->safeAreaRadiusComboBox->addItem("100m", 100); + m_page->safeAreaRadiusComboBox->addItem("200m", 200); + m_page->safeAreaRadiusComboBox->addItem("500m", 500); + m_page->safeAreaRadiusComboBox->addItem("1000m", 1000); + m_page->safeAreaRadiusComboBox->addItem("2000m", 2000); + m_page->safeAreaRadiusComboBox->addItem("5000m", 5000); + + index = m_page->safeAreaRadiusComboBox->findData(m_config->safeAreaRadius()); + index = (index >= 0) ? index : 0; + m_page->safeAreaRadiusComboBox->setCurrentIndex(index); + + m_page->checkBoxShowSafeArea->setChecked(m_config->showSafeArea()); + m_page->zoomSpinBox->setValue(m_config->zoom()); m_page->latitudeSpinBox->setValue(m_config->latitude()); m_page->longitudeSpinBox->setValue(m_config->longitude()); @@ -140,6 +159,8 @@ void OPMapGadgetOptionsPage::apply() m_config->setCacheLocation(m_page->lineEditCacheLocation->path()); m_config->setUavSymbol(m_page->uavSymbolComboBox->itemData(m_page->uavSymbolComboBox->currentIndex()).toString()); m_config->setMaxUpdateRate(m_page->maxUpdateRateComboBox->itemData(m_page->maxUpdateRateComboBox->currentIndex()).toInt()); + m_config->setSafeAreaRadius(m_page->safeAreaRadiusComboBox->itemData(m_page->safeAreaRadiusComboBox->currentIndex()).toInt()); + m_config->setShowSafeArea(m_page->checkBoxShowSafeArea->isChecked()); m_config->setDefaultWaypointAltitude(m_page->defaultWaypointAltitude->value()); m_config->setDefaultWaypointVelocity(m_page->defaultWaypointVelocity->value()); } diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetoptionspage.ui b/ground/gcs/src/plugins/opmap/opmapgadgetoptionspage.ui index d4fbdc6a2..b2f3f1cd0 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetoptionspage.ui +++ b/ground/gcs/src/plugins/opmap/opmapgadgetoptionspage.ui @@ -54,8 +54,8 @@ 0 0 - 549 - 401 + 550 + 422
@@ -88,7 +88,17 @@
- + + + + + Default latitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + @@ -102,16 +112,72 @@ - - + + + + true + + + + 0 + 0 + + + + + 0 + 0 + + + + Qt::RightToLeft + - Map type + Use OpenGL + + + + + + + true + + + + 0 + 0 + + + + + 161 + 0 + + + + true + + + Qt::RightToLeft + + + Show Tile Grid Lines + + + + + + + Default zoom Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + @@ -137,85 +203,6 @@ - - - - Default zoom - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 50 - 16777215 - - - - true - - - 2 - - - 18 - - - - - - - Default latitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 120 - 0 - - - - true - - - 8 - - - -90.000000000000000 - - - 90.000000000000000 - - - @@ -254,11 +241,8 @@ - - - - true - + + 0 @@ -267,23 +251,90 @@ - 161 + 0 0 - + + + 50 + 16777215 + + + true - - Qt::RightToLeft + + 2 - - Show Tile Grid Lines + + 18 - - + + + + Map type + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 120 + 0 + + + + true + + + 8 + + + -90.000000000000000 + + + 90.000000000000000 + + + + + + + Default Max Update Rate + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + Default Safe Area Radius + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + true @@ -303,20 +354,7 @@ Qt::RightToLeft - Use OpenGL - - - - - - - - - - Default Max Update Rate - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + Show Safe Area diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp index 7007dd15f..ccf4f2376 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -164,14 +164,14 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_max_zoom = m_widget->horizontalSliderZoom->maximum(); // maximum zoom we can accept m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter); // set how the mouse wheel zoom functions - m_map->SetFollowMouse(true); // we want a contiuous mouse position reading + m_map->SetFollowMouse(true); // we want a continuous mouse position reading m_map->SetShowHome(true); // display the HOME position on the map m_map->SetShowUAV(true); // display the UAV position on the map m_map->SetShowNav(false); // initially don't display the NAV position on the map - m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) //SHOULDN'T THE DEFAULT BE USER DEFINED? - m_map->Home->SetShowSafeArea(true); // show the safe area //SHOULDN'T THE DEFAULT BE USER DEFINED? + m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) + m_map->Home->SetShowSafeArea(true); // show the safe area m_map->Home->SetToggleRefresh(true); if (m_map->Home) { @@ -1104,6 +1104,26 @@ void OPMapGadgetWidget::setMaxUpdateRate(int update_rate) // m_statusUpdateTimer->setInterval(m_maxUpdateRate); } +void OPMapGadgetWidget::setSafeAreaRadius(int safe_area_radius) +{ + if (!m_widget || !m_map) { + return; + } + + m_map->Home->SetSafeArea(safe_area_radius); + m_map->Home->SetToggleRefresh(true); +} + +void OPMapGadgetWidget::setShowSafeArea(bool showSafeArea) +{ + if (!m_widget || !m_map) { + return; + } + + m_map->Home->SetShowSafeArea(showSafeArea); + m_map->Home->SetToggleRefresh(true); +} + void OPMapGadgetWidget::setZoom(int zoom) { if (!m_widget || !m_map) { diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h index 45d4513bf..23e354758 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h @@ -113,6 +113,8 @@ public: void SetUavPic(QString UAVPic); void SetHomePic(QString HomePic); void setMaxUpdateRate(int update_rate); + void setSafeAreaRadius(int safe_area_radius); + void setShowSafeArea(bool showSafeArea); void setHomePosition(QPointF pos); void setOverlayOpacity(qreal value); void setDefaultWaypointAltitude(qreal default_altitude); From 411512fa62b1061b5eae3e9017ce9ad1b491d94c Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sat, 6 Jan 2018 13:55:47 +0100 Subject: [PATCH 13/20] LP-572 Update context menu from configuration settings, max update rate user-configurable --- ground/gcs/src/plugins/opmap/opmapgadget.cpp | 1 + .../src/plugins/opmap/opmapgadgetwidget.cpp | 20 +++++++++++++++++++ 2 files changed, 21 insertions(+) diff --git a/ground/gcs/src/plugins/opmap/opmapgadget.cpp b/ground/gcs/src/plugins/opmap/opmapgadget.cpp index 2d81b99e7..3667bff08 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadget.cpp @@ -59,6 +59,7 @@ void OPMapGadget::loadConfiguration(IUAVGadgetConfiguration *config) { m_config = qobject_cast(config); m_widget->setMapProvider(m_config->mapProvider()); + m_widget->setMaxUpdateRate(m_config->maxUpdateRate()); m_widget->setUseOpenGL(m_config->useOpenGL()); m_widget->setShowTileGridLines(m_config->showTileGridLines()); m_widget->setAccessMode(m_config->accessMode()); diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp index ccf4f2376..1d71e012e 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1100,6 +1100,15 @@ void OPMapGadgetWidget::setMaxUpdateRate(int update_rate) m_updateTimer->setInterval(m_maxUpdateRate); } + // Update context menu selection + int max_rate_list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]); + for (int i = 0; i < max_rate_list_size; i++) { + int maxUpdateRate = max_update_rate_list[i]; + if (maxUpdateRate == update_rate) { + maxUpdateRateAct.at(i)->setChecked(true); + } + } + // if (m_statusUpdateTimer) // m_statusUpdateTimer->setInterval(m_maxUpdateRate); } @@ -1112,6 +1121,15 @@ void OPMapGadgetWidget::setSafeAreaRadius(int safe_area_radius) m_map->Home->SetSafeArea(safe_area_radius); m_map->Home->SetToggleRefresh(true); + + // Update context menu selection + int safe_area_list_size = sizeof(safe_area_radius_list) / sizeof(safe_area_radius_list[0]); + for (int i = 0; i < safe_area_list_size; i++) { + int safeArea = safe_area_radius_list[i]; + if (safeArea == safe_area_radius) { + safeAreaAct.at(i)->setChecked(true); + } + } } void OPMapGadgetWidget::setShowSafeArea(bool showSafeArea) @@ -1122,6 +1140,8 @@ void OPMapGadgetWidget::setShowSafeArea(bool showSafeArea) m_map->Home->SetShowSafeArea(showSafeArea); m_map->Home->SetToggleRefresh(true); + + showSafeAreaAct->setChecked(showSafeArea); } void OPMapGadgetWidget::setZoom(int zoom) From f5d36cca1bee282e7642bbe6e88add3fc6f322b6 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sat, 6 Jan 2018 02:06:27 +0100 Subject: [PATCH 14/20] LP-572 Udpate map --- ground/gcs/src/libs/opmapcontrol/src/core/providerstrings.cpp | 2 +- ground/gcs/src/libs/opmapcontrol/src/core/urlfactory.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/gcs/src/libs/opmapcontrol/src/core/providerstrings.cpp b/ground/gcs/src/libs/opmapcontrol/src/core/providerstrings.cpp index d0abe91b4..3e48a871c 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/core/providerstrings.cpp +++ b/ground/gcs/src/libs/opmapcontrol/src/core/providerstrings.cpp @@ -41,7 +41,7 @@ ProviderStrings::ProviderStrings() { // Google version strings VersionGoogleMap = "m@301"; - QString version = "713"; + QString version = "794"; QString envVersion = qgetenv("GCS_GOOGLE_SAT_VERSION").constData(); VersionGoogleSatellite = (envVersion.toInt() > version.toInt()) ? envVersion : version; VersionGoogleLabels = "h@301"; diff --git a/ground/gcs/src/libs/opmapcontrol/src/core/urlfactory.cpp b/ground/gcs/src/libs/opmapcontrol/src/core/urlfactory.cpp index aa6fa3487..010a5aa62 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/core/urlfactory.cpp +++ b/ground/gcs/src/libs/opmapcontrol/src/core/urlfactory.cpp @@ -214,7 +214,7 @@ QString UrlFactory::MakeImageUrl(const MapType::Types &type, const Point &pos, c break; case MapType::GoogleSatellite: { - QString server = "khm"; + QString server = "khms"; QString request = "kh"; QString sec1 = ""; // after &x=... QString sec2 = ""; // after &zoom=... From b92d077555ffafb37494b7e043d8df5c84ff3ebe Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 21 Jan 2018 14:52:35 +0100 Subject: [PATCH 15/20] LP-573 Workaround for duplicate Home/Safearea display --- .../gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 6cbd9cec6..b6d7747cb 100644 --- a/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/gcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -73,7 +73,12 @@ QRectF HomeItem::boundingRect() const if (pic.width() > localsafearea * 2 && !toggleRefresh) { return QRectF(-pic.width() / 2, -pic.height() / 2, pic.width(), pic.height()); } else { - return QRectF(-localsafearea, -localsafearea, localsafearea * 2, localsafearea * 2); + // FIXME: LP-573 For some reason when boundingRect is defined normally, + // return QRectF(-localsafearea, -localsafearea, localsafearea * 2, localsafearea * 2); + // the previous safearea circle and Home (both at previous/smaller size) still drawed + // into the corner of boudingRect area when zoom in. + // Current workaround is done expanding x100 the boundingRect returned. + return QRectF(-localsafearea * 100, -localsafearea * 100, localsafearea * 200, localsafearea * 200); } } From 40f669b23236a90e73cfab4c2f348ffbef51a199 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 21 Jan 2018 14:54:15 +0100 Subject: [PATCH 16/20] LP-572 Add new icons to OPMap --- .../opmap/images/button_clear_uavtrail.png | Bin 0 -> 2073 bytes .../plugins/opmap/images/button_edit_plan.png | Bin 0 -> 1527 bytes .../src/plugins/opmap/images/button_edit_wp.png | Bin 0 -> 997 bytes .../gcs/src/plugins/opmap/images/button_home.png | Bin 0 -> 992 bytes .../plugins/opmap/images/button_home_not_set.png | Bin 0 -> 1239 bytes .../src/plugins/opmap/images/button_home_set.png | Bin 0 -> 1146 bytes .../src/plugins/opmap/images/button_home_wp.png | Bin 0 -> 1613 bytes .../plugins/opmap/images/button_move_to_wp.png | Bin 0 -> 1532 bytes .../gcs/src/plugins/opmap/images/button_save.png | Bin 0 -> 1676 bytes .../gcs/src/plugins/opmap/images/button_uav.png | Bin 0 -> 1441 bytes .../plugins/opmap/images/button_uav_heading.png | Bin 0 -> 2203 bytes ground/gcs/src/plugins/opmap/opmap.qrc | 11 +++++++++++ ground/gcs/src/plugins/opmap/opmap_widget.ui | 10 +++++----- 13 files changed, 16 insertions(+), 5 deletions(-) create mode 100644 ground/gcs/src/plugins/opmap/images/button_clear_uavtrail.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_edit_plan.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_edit_wp.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_home.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_home_not_set.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_home_set.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_home_wp.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_move_to_wp.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_save.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_uav.png create mode 100644 ground/gcs/src/plugins/opmap/images/button_uav_heading.png diff --git a/ground/gcs/src/plugins/opmap/images/button_clear_uavtrail.png b/ground/gcs/src/plugins/opmap/images/button_clear_uavtrail.png new file mode 100644 index 0000000000000000000000000000000000000000..12c74c5e0fb694b07d3454a357f5360c6a0fa430 GIT binary patch literal 2073 zcmV+!2RP)ed9$nx{R)NRmDB~PTzPr9tGBl|HZK4olIrT}-On$7 z{_utk8#GVeCxpO?6J}CUAb~) z;`@Ji|8q9P-UzXwKqwUQ@jNe+%jFUwM4pzKrqHN0d4!NNdcB@a&q!aS)oSJ8a5x$W z1Pr1m%ItPK1pwll0002h)zw!Ku^9lMwYAmsaP;Bp0FXElo@iq^_MM7~3M7O8P196c zTiZF4$)r}PRNqmlRmyy8elA5(R8mqB1Vce#&^zcB1mRF;XXkAI5T4YcW&)VX1R(?$ zELad0ctHdJkR(a4*=!Oa1OWg`OH0LYIDE0YyZh9gJ9k_Y?1ZRRt7S^1l8W+C==lR z00<%iAfUhtlE>reUAAl)0szkBf8O4uX<9ZsJY4_Q8*lxH=Xt65TC<0n;C#_&G|2OO zBoq#1ELpO|x+s59ibkuU1YSS@Aac1J0%HMj&^OrA-{1d^+wHznRaG_e%m9-R&oM*H z<>D>HFD_iTFkUx)zaLyK7bw+ANHwKGBoYCy&kKM6DJdzCoSY1SKmb2&`}FSh>(@(q zdwY9YT3V*H;!{sAM3n8{zyJFgX&GC!T5YyMp-{)9SPCGdE?>S}iGalC^YMPae}rKe zp`f6^WU*M(VoZd4_wNPWZg+{TeG z48xphZ*Tv|VzC4b219Xja`Lgfg?ZV2zkj0rpY01PD=V2Nea_g1v)N?z1N^(7L_|DS zRaNETIF9e?>gv06>5?A+z-F`kWo&G0!D1-q z+U@qa0T7YY z)z#%ug!=Q^)oYh-d3B4DonVCv7cPv9`bT?Q_goiFoH%iI&z?Q};~f zU;knKheOQJRfEBhZO$^kkYY?JT(@RjRz^k!g^1wjaBxni^R}ng^NGvly3BFhXhA_i zfkAJ0-D0t9EZ$O_8i_=pwzjtZ-Tm*r`Q+Ap$q+GtrfCm~h^J4T{$y&(O-1E!IOGQo z9C+i*AJ1HGX>JJ#Q2|jz)%h~OW9QysCGd7!T&O(phbi3V3 zl~QFuM7Zy{-&$2wB>}|u7Xd&*#Cp5k-f;e-^JzEQZ~QhlH+Q`$#gv^a*2u zG3jR4%@Lo^ck8pyKRaAgQ*(8`$P=cbY-ngOW@To{S(b%xIP95mzaBXg0lDJe-43v9UTn^0)enjr+Yxt^tjz_hmw*K=~+|%KV$y_R~C(uJ(_$ZZF%H^x=2zIp_P%xu++;3;b8HbLUR+zmbPX*1x5t<)TulY>-GK zQi`G;jgOCSy?XWPAFm2Jbm-7}g+igu$;l~v`t+$^r_*(IbaWgC05Tc&6DLlz?cTln zBZ));0I066RuBYnYxU~YD_UAwxL7gu_4R2rH8q-z8#iXYFiDk4+BO@d4#fw?BYSoSn8#ZKy+lq^eQBY8D005E_;P?BZs`UAMAW1TA zCpnH|pFe*dWoKDdl(YbfqE0)V&X;VXqocDLjpk0gnD+MeD+2=qPr_|eQ&XTQsx4^& z9UUDVJv}|4fg2tkhF-7#FhLk^Fc|jRY&ISMIF3VaZ?CDVtLulP1pt82Xl&H$^&H1> zxPANfZ#Qq=)V_xB8^goH_W)pUaF90`3=P7wr2Yi}pjNA=N=i!Z*lf19M@>7(KHq+bC5OioS? zSS*%=t&fD&Y8`Yq9B~IWDKs@TWg3mf7N^MN z@}B_^48znC1mPzLLN+%yH&{_o@l43|(hTg{wM&_omv=xam1fV*&fcG!n>&5&+O=S$ z0Fg+vpCE{%1VK!*ESnPy2LBu%9}hG(HU{l>d!JY=UJk$^6d4Q#f0at5>0Ynb10Z@U z0l?wIhfiL=e%;S749_qOZ!j46*49?LN~KyG?q{)BR1Cw^ze(p}fdqi2rlzg6wY6WA zm6e5tQYMpO@7}$+3kwUsNTt$jp%Wa(S&NE_?gK#c=gs?MZ>3i!L&$MFN7L5!3l};K zAp!aM`K{sP;ZUhmnQd)t#{hf{00KDx6ciSHTDxV-`lLz*aQfR*X#n=EZZ) z&CP{OCi_4T5RPClknZt#Ff(HXNs=flQ(}608h-ym%v^%c!oosT$OZsTr_%u-Csq(e zQERp&jCM+)cW0FZE5|oyfMGLrm`SOq1+1bsdrKRN} z(chymIy#Dn4SkpK_~ z1kl&l=k|C!N91z(B0&&*tOSuA(Ceq*^Z8KCwI6XZb-QC?_ z7-rAV(2$=X;xEj|4pdaEdA-sj1pvVL^XES)FE4M{wr!hiVq${o?CdnUTrNpz?wB{ zU*R2%sQZB3Za*0a1nSP5Ig<_GV!U@RU~zE~9fST^>$7mLLxD3HHo zi`stO-Q7Be!=WQd@=0M~;YgwiSeC`S&leiJ)U;Hj$z(BqGFf_5e5@N0@Avyp$>s7J ziO3&6wmrFZYp6mv>vWTeLcno6e7H{sJ?}P`Gv>jcxz{002ovPDHLkV1gNcz=8k( literal 0 HcmV?d00001 diff --git a/ground/gcs/src/plugins/opmap/images/button_edit_wp.png b/ground/gcs/src/plugins/opmap/images/button_edit_wp.png new file mode 100644 index 0000000000000000000000000000000000000000..50ebad72b57dd27c5db0569893f92be5b8f7b6e3 GIT binary patch literal 997 zcmVpc&fhj^>t`8n(uP{3DR9Im(FN3 zx~W7NB?6*r(WmqC^A5AwoX|HlH5D@znJhk^FY5RE!-@pd)z#fhPgnwmIib>OwNUy|O3~cZf{~Gt zJ&vudElf;IpuXM-jYfmm*4K;CX!Nev>&;4=0ZEbw0L;$L;!SuO06++VtHp(Qd>cc< zg9%x%oV6gb8i61PP^;Al27_q7=E3CTBzT^OBuSJIqDz*+l;?oeYK7HmJz&#l7_?q> zCmnCMpTpqLGc+_b;B(|NOePadCQ~ZvGo0~0wr07|e4w1;}cS1v}6 literal 0 HcmV?d00001 diff --git a/ground/gcs/src/plugins/opmap/images/button_home.png b/ground/gcs/src/plugins/opmap/images/button_home.png new file mode 100644 index 0000000000000000000000000000000000000000..0a19c4d3dce348c60894ee5e7e5d939ca3ee40be GIT binary patch literal 992 zcmV<610Vc}P)=3YC z+|$A?U8NLy*qgUS3W7q^$J{*a+Eb5GTFTl&j~+V&7XKVpgq1xlD5Scewb8n^89RAB zG_lFV*ZiT|Ui`v4y!ZS4-uE+)ncvI+UszJRg`=aRl4+XXr&6ga`F#GLcK0Fe6s6N? zYMSOF05<@D5b}^x`m^i0Z~u1y%d!+o=^}t11ED9Xs@`f9;#>gRw*LeWtISKK()HEV z)qMHN7Xkcm?q-DiPAR?J3WNyY06@Gl=bV3idV2a?aOFX@bP}Ovk~rrIrSx&oJQj<+ zHVor+AbrI1yaz)=L-HpBAcWjU;Mk+l=zrO4HatB&9oBXIBmjJ~S%_uOs(KtqA87>95&)(2 zkTGUfn^&Z&Di~viqA0Igfv5vWr_&TbT{5M#;5bf+5^EwY62M0}yq% zP$+c37`qgSL>ih`L@9-B+u>X;cMyQM8ibHOW=;s%V~kxkO|xn9id0p_z`%f(%jI4G z&_xiTGV#5jIe>q&*=$?p6~*ImGBq`oAcX7%LLIA0JQ5&(A*x@Kt&F4*)y_0II6~#5up? z`~EM3gM(6ccek){tgo-5P$Y~IBA&mx%Cb$T{Jq#=|{`} O0000^jFjRQF@X!%66`WFZ6Y<< zxE2p9;Q%BaVAUoZAR&fm_Mq-zJ#kdCCVE(+F@cL{c9F;i;x0@fjRBJS_W)^VYWTB& z-7?!2=6QgD*>2mg2p6;8&a+1c6iMn4z~URD(4 zOU^l?(*&59m@r!`mfM_j4}cBM`2|^)e^C_W9U}Sy0OOp0b*c~mpeV{UBD%8Q-2iYM z!219g0F870_J4x#`FzEysyZAF#~;JP!@IfSg2CWb03T-98WCLlpDPN&nFD^`-Ej{w}tus;z+@df}KD-)6=H4xEH0G`o3BDzaN%~MlT@yvKd zQQjq@>)2ZYU0a;&iU2-_)^B$l_S@L*XxxSW48f3t$U2I2eK^h0N}<@P1A1r ze7<70+r3RhuLAfJK$j#*Uju+F%O7*jKLBt?Rn@n$E{D(OGbfWt)nKgyC#Ds~6jM<%LjJ=+%SdBW)7Txaa>oXex0N~Q4OGQmhO)BSHGuR$Y(|#01 zu>^VaxDbin-d?lA;mDf7mX;Q)EX((?SA+*3jIq&tAXy=j$)uR+5mCISr^i%PRh1XK zt*x!Z?RLjAGm;OaAk&Z}$xB2x0hkPSJP-(&Yieo=^8x5`I-Ta#)zy2kSj>dOiJoJO zy;fOSIUI>Z9^{1B2N(r#)?okB)zxLLtE&@^0-(#~a#^C$==#dairD~S2XG-1qsEYZfBX>&UKYT2onB*|)J+EDZx8IOm@O zDAxN#wARtlA-G&F%W(j7b$54{RaRF14MVXKkt7I0uiignh~G9`ue7$d3XP48#mJ)Z z@o~)0&x7;BgR-EY0PXGVC@(L6B)+e&&pt3P5RFEoHtc7gh|&jR^^1y%iaSJfPSdnG zS(ab$`~A=6n%&UQ5Mr?y;_>)F+uGVfB9TCSeSOw39*?JFdU`sPPNx?Ed~Y(Dt}QJs z?L3r;nVFft0JH#juC=xGw_E@K9?F1Gnx*`I0suV)^AP9!LjV~fdWl`6 zc{Ccm%Q^o500Urxemjq3S-#2`yS2Z+|73Z2`LKK}7K=?Y#(wMT>-$}gDT?wkfO`N0 z09j4b{9dp3=W}&HmgVOGtZACIYOz>;6-BX0AB#q#6P)vp3x&c%MNvFOpfSeSXE6PJulFb5xD|EDB=MD!5=bJ>&v zfY&5R`n){PumePN6Tq$F)&5`R#hf0!6S6FS$~nIaV81x50SH%`R|Tk474!Vy;GkAq zSqZ{yHs2RTu}PNYuNh-w0QLa9B}vjJMzzlZV68MKqJz1)Idd==WK&a9yb^*j_COTH zCQ%d@8Dm|NB)wa$_*nof<>s98{LIXZ+2L>y0QC3wnOM@B{t>V-H} z%;WLgCZacS+FH^5yWQ4Wgbs(pa&&Z*U0+{kC@zkOY>ct7*4EaAt*xzGO@Ol9 zUQV0~27}z|^3JrRNc_3Iy=^UrFquqR zJRbiZD87z~D9bt5^U?zY1KB_zU^6PJswx&27f-|(W0;tjKxb#?srj?Bvn})U^U1Zf zwPqsHH+JduEdYSsZht5U!m|K2J32b9gu~(XYO7jUSU@};M<$agUFmch>2w-yx7#qs z<#JtLT3ULP%jKSM&cCx-t?z7XY~)KFP*rso!0P}YisIvH<^WLEsWZiO*=)9SBoet( z8Nbj^G9z6ATmoDI)D6(s*a)JNAJc*$z;3r!$*8SUe@2?76^th83WY*gU0p>!pD)E4 z8XC~m)m77|THR9sD=RDSB@&4{jIp|Y+ai%jt>J@YGWkV4^)5{R0zqwUjQ8Xe?f?J) M07*qoM6N<$f_#k>cK`qY literal 0 HcmV?d00001 diff --git a/ground/gcs/src/plugins/opmap/images/button_home_wp.png b/ground/gcs/src/plugins/opmap/images/button_home_wp.png new file mode 100644 index 0000000000000000000000000000000000000000..27600f50366e6a0c1090933074f8138f961972b8 GIT binary patch literal 1613 zcmV-T2D15yP)|L63SwotI67XqDY*(?;pl5MyT8%r>`FmKduset}&-Y>SuZ{4m{WB-;=WipezY;w&sdpkoYdNuYtQ z4C$bkb6P*RE>KP@7BBzge0k1!p6B3SXI-nUN9% zLC`c!jEsy7*zNWflgX5>*XzF*2n1{We*ew!@$uL5^Yf2W6t&&w^ZnM?*jSwk!~zWr z3>s&I$mSoSeMq_xsAAJ&&g!6O?tgPeJK!&0AlLx?fv@X$&(*MA`u@!5JYBXraC@(?Au2W zrWnM*g9ks8NFu<7kM?3%#jYdfTAW4#SrFC_6Yd3D(cxA_q z9ZDXL2LPCvnW<@OYkPyHXFO0`;jMI;jG_V3^Sc_N7UB_Nubn#2Ig0D!~c z{O)i#nEA=e%gd>f5>30&XndR;05UT(VK$rBmz9-$7qdMoMfqp+q~}R z6pO`5i^XzIE|)*2)oS?wKw7O-8chCx?l*$CsnNzW%IKDwPA^kh^y6+Lo4${2qoel*2M4oiYHAb)gMr5ugvS$| zCP_|cdU|@%JCDbMtgI)dD2n)o#g#A^47{^v&x(CM-%kLLlarIaa^*^f=V`O zE-ET=hr?ltqNp?g;j34#uB)!DzDpJt7yBZS$QGKW+enfOP!yG>QmLeqlas8I%i|eq z%*|bScW`jWU{<3f^RjC>F<5sX6bf+#0s+TtHYaVXBS((-0FY+0IcbtWAizmpZA=8KaxVl9bFiUD`uqfu?@0?B24PKe!-w0P)f_8 zz-do=&g+Gm41uzdl9=fK@_GOHKfm`mA9-JZ|GLmlgoZ*PRW{4L{ouia)^s{uq0?z@ zo;`c^8-x(Q;{cBy`QN#H`{(bnSytN6&;UxM5~il6;NioE`CKmdL1$;@w>t*l^95VG zx_)#uHok(aR_nU;Ten;|7!04eaN&y|{;me+~+fO5zOnUk0 zTFC%>zR=6V!^3-8T3U+w4jw!xJ9X-mt>gd%0ec032a+U<`YaX;s8p)fk^>Y9I3NfZ z3WY*ZUmy^GR4VmL$pPx>s=ddK9skYcauxNBjg7H=eSPC42lx}hc0Lpe!_v~yhU>$_ z!;nZMK6|=WQh=J8nn8!-%=a`+uUjh=3NSP@6u)xi%7q;R007WvROgjS6+1C8v8GPb zG>%52&Hwb59KdF?Eu236)<0CxKem+I@cX#unqob`GdA9|CF-90;lBQ|7*XxyFjMwBKg!ty>6Q7Kak3%Mtfmkfw>+yK< z8)X&$YiuHfEMx~_xq39?e;x=eSKvZV*(+>*ViBZ$>Z^4 zdwY9hn`Mc%17Nq?v-vy@$D%VvTdmEwu#l`>WKs^9QtoD1&fU|~GeXn!LUr|lu6#aU zUo2}|0D8Ti@cY9^rB=nI5{c1PYg1V*`xNon`0hkvu4yi@@C!oZEsXhTj^jQrmi1hZ z!0B`n7-Pcg^-{T9mQqwGqSRvmX}xX6s0T7 z&(9+Oz|RfvS5q7a1f*B5-c%0^+?Vm(N~3`B$)G>jY~63wS$jFGeySuwu zEEb;#1=0<>)av@(Mw6-jP`ySjSCIKU2M8hHIF66SVyP!n(+jzLE~4F~X{0Esf)@ll zpG?Lo%F6ClR#v9AYQ6>lV@zDTcFjs6(fgFn&|ZC@+N{-Rr5FIjA`wCa!VJT#J`VVq zRBB;TtJU5i#bQsnNF>hl1?7|JCog5Q**qXLoL*Y~-D0tDTQy%d0TWdvkIYWBRhjqh zQ>j!Uk|beqk;#WbK{gVNBo%Vis7OS*^?JQKlgTV=G@48>I769Cl-uX?Sr~>{QYkby zlF97Uv+RBifXCw@7gy41g;J4aS6Oa(d4-QgqN@TD9t#4#BM9V;R64n&)9K==RBF-T za0mz?JTfwpi^b-ux}sY0X#QbUH=H zkH4`ilbN@zuCkoPQaLd&09k<71*dcKkvbd>^4z&|qVn=K{^Uti{8YM?Fvf_cX%b^h iVvKj>?)bm{Rr&+3c#^NrIzzz#0000m98lX$Cbku6J zz((|eG3GR8+QlWtY!BPROnfrNC2lbhmzelqG}#R9L0=k$R($}(*ar#Gq+F_{+!VS) z3YcC_d)hs0)N&bKx4rE9bn^e*KL2xmzyJRL|FOuc9IC6UEn2Pi3x;9J0U(u1^-fJq zUA}++e)m5LV6)lQh*e)!{Jz|*XscQ!^6Yycsx^qK;UUO9R8%cyF2*a0W22F zmfYOj_G8D6>B`E=mh|cG?@ymQcW!cedb+l&tE>0D0od(!om#E#IdS5IuCTBW(P$Ke z5b!*|DEQg4XE=HCKP7MqU zoY!i#Jv}`=AKUGAB~8B!D=aLe?%lh$GAAeJ#^~ti)LR48*Vl6tMYYA_aW)VLoM~@w zKQcT#JUwR*27^zFii(spO>f({aU+wRgy(sFU|=Ba_xs!56d;o*7K=3}5{W!Q$TyNC zUA5co_bH0fX8ERf?AUR_tW z^?Jo+0a%v(mgBgyZEbBWHk<8yb91x7Y&Po__+K9z8^hSx7>bLFGmC;Cfa5sh;lqc2 zT3F!Gqeqcz*RGuh@cD88BpQwW+S%Fpqup*_p-?FHR8&;xT3cH&I5-Hc_T`I^Bngp7 zWKklWPKTD3mU(NUD8g>Ht27$T4x7!kzN4dKaADk{F|4kx{<^NN?mLIWu_hXg;_~Io zsIRYw#bQ}%14}BEO5w_tD+q_fXliOge}8|nwYBv(x7)pcp)a*?f#bNZtXAt908lEG za5|m1efu`<-o5);#goY-T3T8lNfMfyn?chwHf`F(a2&VOYPA+F3t+WcYf4H=ShZT6 zSyLz!ICSU`yk0L{F4wZfU%YsM)2C0Pq@)CU_Uyr2qY^^ka5z>fmCEmz1z;HFsKenX zUg$*AG!7g%0H4o?t5=skZ$hCEPMtahtJS*X=Q5kk3YKL*HJi=Zll2n7VzDSWj{9)! z+O^7bI=v_XP1D%Fe?LS~#HCA@kV>U8wkJ=X;LMpbXl!gmX=&-ASXq`4kH=9{QUn*b+j}*w_eJmT}?21<10D-rinZym%1@4<4L1nsbsQ z30+-XP%4$MSS)Iu=Z_()`7(P;dksj2A$jYdQBJdeJZTc=k)yfb6mfE9lLhzf()UK1nl0u8yv^Yv(3!RpuN2v4<032tvk|o13fl`Fw?bzyBBDuY-u^`MS-UHzyYEpsK1027>`EmkXg#2wS#nfyrdT zs#U9?(P&^YnE?DbdZH*|XlMwJA3w&##00i)-;Rcc22j-eNjDe_;5e?Lrlw|fXJ==K z0RWn&Ybz@&ix#~@0Qvd(a5|j`g+h4v@F8y9x`pxaamca^l}d#~B7t~3j=a1)==FM3 zRaL=cGJ#>3rP2Wawr$%cw6(Q;2H-pc04&SejYgy5ZzBM#UcDN%wY8|NtpxzYVlhOc zQP4CEK@jHk$*WXeUasuu=s27KP$(1{kH>@A+1b}l@-8wM44^2g82GCP7>3DNzkdCD zNuEd~Aj>ishCwo!1k19JBnceHAr^~4rBVR^Xqr|6OWXzTDp3?MIXQ`NIE?Y}am>!n zVq|0lkw^qXLqplF~y7 z9lEt_8AJB>hGVb|24i!GFeZcHhHMNG_RszrD60RT+XEbF>n zP9zew4L88^ywmM=4|aBTeh~-+XaE33QI-}L7f)3xm63Qnu3OO~tqeYM=8SE5dHK!5 zhY$ZC2*Or|VeAaU*!S<>zu7d+r2x~Z=<4eFoMD&%#@Li) zxhP4}g@J*AZ$?K)D;8FV1_lN^2%!)6?b~-U7!0-}gpeqTaxRxU&GY=vbz<7;EBAOj zulDuzUF`4gcQptF=jP^4kB*KK(P;F`hE*brvCA|~0ssJG?1KB-X#xO5qft9ak{=y8 za^w`tvi7=IZ*MP?OeQamkB@7SNFBx*JQ0H@RG-L`Gp*`~<>0Dxs#dpezdcXoF6 z7eNqK>J$3?{_`BiwF3Z1l63y)(WCDZ1fc-{l*{FIj^j=?PF|02IPA*j^JgoS%I^Sh z#|8j^5b_2BftG~p?d{!4l4PR3=cZ|r9LH@A27?3uz|hdpv6-2fzQ%k{PfvR*y^f9! zI-O2?0pN}$4s1l&0Pg?K6-AK&VCUloO-xMOo}Hb2nIy@FTOdi&`JthqV*miLSnRiA zvG{Nc48v$Q4C9Z%!NIMM(<>ATOQva-0Um&;v$L~WtJM_KG>?Zup+}BpDwV2EPfwq7 zI2@NoMn+1ROh(OSvn86Q|3nDAr6|hUty{NVyK?1j<}d_ih(W)9)aJ%tE2?T_%%J8%$%Grl%Gc7w^fk++8Y_oU$w%SFc{pU%Phg16|jD z9UB{~0yL4Z4kE)a0ydk?XaOPs01yPBgX6fr0RU!ZW?s5{`EsG@OFt2ao*9Y>g2=|> z@q5ii|0^v0jNk#`+S=MaVOjRuLx&FegTbK3FpSqVO>=g2bxqy8dDBv3YRNz}8g;nc z?vDjQ_%s|2dnt-S6h)yud-hO1pD&!t<@CLK_x_birHm)lw8Q~bRecP@yxra1y^e4! z%i0-+IjO3u&x)oc0|Y_%1A#zG!qGJCCkSF)!}`n&)M_hU5=;`Tcsi~>?sZyzIQmIrW9*-v$3WegS zREh-vpeTweE-ubhsZ@C$k0~eM3yqD9T^M75&1Unz zc<~|?4u?YoK}0deF#x~_p?r?x@{5a$CFSMiq`_d2VT_Yco;Ss(b3T{kH_=zrAwE*I~H)_#0gb%bF-zgvU2a$t5z>yFF79I2`P=XU~3>N~JDat=3lnz->i3 zd-m+lB@#*AR%_8{ls$j`{3o5Aol*e!zD}q6NnKr?ps%m5_bma53i!4 z;**@59O2yD++PI(!GO_dd}Xy-w}b-#q|@m+wOaifwOTFRyf!*I>IHzGwY0PZ9zT9O z;C8#)TU%R?YBZW&kx10t-`}4B*wBJVBvMvUQPKM7(W4cbrhmtA+{@nH-fiIk0DixJ z>c)*5ITI5TZ>+H_D+d5r+hZY-Nc{G}g9j`7_U&s427~gfUseE;$z*4$tE&rqKHoIQ zasRYfEXlXQ0RV=Eh8#3an?^=P=vXYat>4;S(~FCXGgVbpMSJ$_ISp&=CjbDnS}iG; z%Uiu(Z)#;_1o4IFQTbl8%m!NM7ESM~=hJ0nW$jw6mRuL0 zP$+~HMeXtX{Vd0E|G0VcCbJW`*=#;+G#dX{Utcf77{kE80BqF`0D$4)VHyDb?(_K= zfk5z%LZJ`>{O1r-d_KQ0nM@`y#;dT+soxB5ZEgKRr_=4h7{j$|*I;sTa?<5;sQ@5% zix3U~A}q@$)-Ew>y#fd!o0YGy1KpD%%`TN>!OBYwyiw^WnC(wm;}}y1m)VpFVwR z2Y~l27R&0|!94W*`E$qS*mOG02?PR?W!W^J&nMOeuq=xihGB$4p@^cWZ7-#y>o+tsgsA( zp-|)z1W~gc+-NlZK3n!IoFItzHo~)Z=guAf=Kpv+o<^xu=EdXj6@nnr>jH9ea*~US zi_X&0QnIY9>?7E8N9-29jS+IW{3Eeg%wJeoaOUOZCD#S8EK5fskt-7u6O2qIJE+&| zg&QN4O64y$!Y3yu?Yo47UauF*WU@A=(@DqU@hh=dj9C|8u~?EMNxEDv*J4Xci$<+h zpV=5ZJw2TmA0JCoM1QP+eUO;cz%tB9S!Z=jT^a z6!qoo>?{iapin60T`t#2zu*6qAc$SVJ32ZF8yXtUN2AevyWRd7kH`Dk?RL}a6#xK; z$Kz3s-EOx40QPu1k!(eFVZ^y}=RWJ|>iT$KU?Ax8 z`F@?rWFFkVf1iFs004m5Y)*Q;-dC%utD<;3UftEz)mBX(mN6X90)hd-rsMG06L?RKnyu8dTFE6hE0EornVzF2(q-i?kbUK&3UN5t-urN&! z#BG8gZYL6nmsYDay%p!JUq-#Xy@btXD@>(QDuN)6V2t$yL8wYfO7e4ab2B+PIXnP> zL?V%i#bUfrD74CPoEIT9#&O&*Ns=Ce!4P@dtKE*i4NWE!pQ5M&01yK}B|@kQV=MuH z0)!C87)KF8Apn@c7=Hr*%Ph;TZkP401#I*;nM@P_2t^_hnZ467#u=KXQzDUwUYl?` ddYuCR_&0}F`srxxNOS-I002ovPDHLkV1hz692Wop literal 0 HcmV?d00001 diff --git a/ground/gcs/src/plugins/opmap/opmap.qrc b/ground/gcs/src/plugins/opmap/opmap.qrc index 348351c6c..3ddade3b0 100644 --- a/ground/gcs/src/plugins/opmap/opmap.qrc +++ b/ground/gcs/src/plugins/opmap/opmap.qrc @@ -1,5 +1,16 @@ + images/button_home.png + images/button_home_not_set.png + images/button_home_set.png + images/button_home_wp.png + images/button_move_to_wp.png + images/button_uav.png + images/button_uav_heading.png + images/button_edit_plan.png + images/button_edit_wp.png + images/button_save.png + images/button_clear_uavtrail.png images/ok.png images/uav.png images/gcs.png diff --git a/ground/gcs/src/plugins/opmap/opmap_widget.ui b/ground/gcs/src/plugins/opmap/opmap_widget.ui index ece39e353..228c3cf5d 100644 --- a/ground/gcs/src/plugins/opmap/opmap_widget.ui +++ b/ground/gcs/src/plugins/opmap/opmap_widget.ui @@ -434,7 +434,7 @@ border-radius: 2px; - :/opmap/images/move_to_wp.png:/opmap/images/move_to_wp.png + :/opmap/images/button_move_to_wp.png:/opmap/images/button_move_to_wp.png @@ -460,7 +460,7 @@ border-radius: 2px; - :/opmap/images/home_wp.png:/opmap/images/home_wp.png + :/opmap/images/button_home_wp.png:/opmap/images/button_home_wp.png @@ -496,7 +496,7 @@ border-radius: 2px; - :/opmap/images/gcs.png:/opmap/images/gcs.png + :/opmap/images/button_home.png:/opmap/images/button_home.png @@ -531,7 +531,7 @@ border-radius: 2px; - :/opmap/images/uav.png:/opmap/images/uav.png + :/opmap/images/uav.png:/opmap/images/button_uav.png @@ -569,7 +569,7 @@ border-radius: 2px; - :/opmap/images/uav_heading.png:/opmap/images/uav_heading.png + :/opmap/images/uav_heading.png:/opmap/images/button_uav_heading.png From 1fd91caa298c23019ddb3c958c19f45198841f87 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 21 Jan 2018 21:01:50 +0100 Subject: [PATCH 17/20] LP-572 Add buttons to the right: Save, clear trail, PathPlan editor, Home set --- ground/gcs/src/plugins/opmap/opmap_widget.ui | 246 +++++++++++++++++- ground/gcs/src/plugins/opmap/opmapgadget.cpp | 9 + ground/gcs/src/plugins/opmap/opmapgadget.h | 1 + .../src/plugins/opmap/opmapgadgetwidget.cpp | 62 +++++ .../gcs/src/plugins/opmap/opmapgadgetwidget.h | 5 + 5 files changed, 315 insertions(+), 8 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/opmap_widget.ui b/ground/gcs/src/plugins/opmap/opmap_widget.ui index 228c3cf5d..5943cecb4 100644 --- a/ground/gcs/src/plugins/opmap/opmap_widget.ui +++ b/ground/gcs/src/plugins/opmap/opmap_widget.ui @@ -6,8 +6,8 @@ 0 0 - 514 - 412 + 671 + 488 @@ -29,7 +29,16 @@ 0 - + + 0 + + + 0 + + + 0 + + 0 @@ -242,7 +251,16 @@ border-radius: 2px; 0 - + + 0 + + + 0 + + + 0 + + 0 @@ -531,7 +549,7 @@ border-radius: 2px; - :/opmap/images/uav.png:/opmap/images/button_uav.png + :/opmap/images/button_uav.png:/opmap/images/button_uav.png @@ -569,7 +587,7 @@ border-radius: 2px; - :/opmap/images/uav_heading.png:/opmap/images/button_uav_heading.png + :/opmap/images/button_uav_heading.png:/opmap/images/button_uav_heading.png @@ -775,7 +793,16 @@ border-radius: 3px; 0 - + + 0 + + + 0 + + + 0 + + 0 @@ -876,7 +903,16 @@ border-radius: 3px; 5 - + + 1 + + + 1 + + + 1 + + 1 @@ -1020,6 +1056,152 @@ border-radius: 3px; + + + + QFrame::Plain + + + Qt::Horizontal + + + + + + + + 0 + 0 + + + + Set HomeLocation to be used by the +autopilot or just pick the first GPS fix. + + + Home Set + + + + :/opmap/images/button_home_not_set.png + :/opmap/images/button_home_set.png:/opmap/images/button_home_not_set.png + + + + 28 + 28 + + + + true + + + false + + + Qt::ToolButtonIconOnly + + + false + + + + + + + + 0 + 0 + + + + Clear UAV trail + + + Clear UAV trail + + + + :/opmap/images/button_clear_uavtrail.png:/opmap/images/button_clear_uavtrail.png + + + + 28 + 28 + + + + false + + + false + + + Qt::ToolButtonIconOnly + + + false + + + + + + + QFrame::Plain + + + Qt::Horizontal + + + + + + + + 0 + 0 + + + + Edit PathPlan + + + Edit plan + + + + :/opmap/images/button_edit_plan.png:/opmap/images/button_edit_plan.png + + + + 28 + 28 + + + + false + + + false + + + Qt::ToolButtonIconOnly + + + false + + + + + + + QFrame::Plain + + + Qt::Horizontal + + + @@ -1036,6 +1218,54 @@ border-radius: 3px; + + + + QFrame::Plain + + + Qt::Horizontal + + + + + + + + 0 + 0 + + + + Save current map settings + + + Save settings + + + + :/opmap/images/button_save.png:/opmap/images/button_save.png + + + + 28 + 28 + + + + false + + + false + + + Qt::ToolButtonIconOnly + + + false + + + diff --git a/ground/gcs/src/plugins/opmap/opmapgadget.cpp b/ground/gcs/src/plugins/opmap/opmapgadget.cpp index 3667bff08..b677d1d6f 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadget.cpp @@ -32,6 +32,7 @@ OPMapGadget::OPMapGadget(QString classId, OPMapGadgetWidget *widget, QWidget *pa m_widget(widget), m_config(NULL) { connect(m_widget, SIGNAL(defaultLocationAndZoomChanged(double, double, double)), this, SLOT(saveDefaultLocation(double, double, double))); + connect(m_widget, SIGNAL(defaultSafeAreaChanged(int, bool)), this, SLOT(saveDefaultSafeArea(int, bool))); connect(m_widget, SIGNAL(overlayOpacityChanged(qreal)), this, SLOT(saveOpacity(qreal))); } @@ -48,6 +49,14 @@ void OPMapGadget::saveDefaultLocation(double lng, double lat, double zoom) m_config->save(); } } +void OPMapGadget::saveDefaultSafeArea(int safe_area_radius, bool showSafeArea) +{ + if (m_config) { + m_config->setSafeAreaRadius(safe_area_radius); + m_config->setShowSafeArea(showSafeArea); + m_config->save(); + } +} void OPMapGadget::saveOpacity(qreal value) { diff --git a/ground/gcs/src/plugins/opmap/opmapgadget.h b/ground/gcs/src/plugins/opmap/opmapgadget.h index bbc4f4ae9..a2be4937b 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadget.h +++ b/ground/gcs/src/plugins/opmap/opmapgadget.h @@ -56,6 +56,7 @@ private: private slots: void saveOpacity(qreal value); void saveDefaultLocation(double lng, double lat, double zoom); + void saveDefaultSafeArea(int safe_area_radius, bool showSafeArea); }; diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp index 1d71e012e..e9e7a95f4 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -216,6 +216,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_map, SIGNAL(OnWayPointDoubleClicked(WayPointItem *)), this, SLOT(wpDoubleClickEvent(WayPointItem *))); m_map->SetCurrentPosition(m_home_position.coord); // set the map position m_map->Home->SetCoord(m_home_position.coord); // set the HOME position + m_map->Home->RefreshPos(); m_map->Nav->SetCoord(m_home_position.coord); // set the NAV position m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position m_map->UAV->update(); @@ -885,6 +886,65 @@ void OPMapGadgetWidget::on_horizontalSliderZoom_sliderMoved(int position) setZoom(position); } +void OPMapGadgetWidget::on_toolButtonHomeSet_clicked() +{ + if (!m_widget || !m_map) { + return; + } + + double LLA[3]; + + bool checked = m_widget->toolButtonHomeSet->isChecked(); + + if (!m_telemetry_connected) { + m_widget->toolButtonHomeSet->setChecked(false); + checked = false; + // Default map center from default settings + LLA[0] = m_home_position.coord.Lat(); + LLA[1] = m_home_position.coord.Lng(); + LLA[2] = m_home_position.altitude; + } else { + bool set; + if (obum->getHomeLocation(set, LLA) < 0) { + return; // error + } + } + + obum->setHomeLocation(LLA, checked); +} + +void OPMapGadgetWidget::on_toolButtonClearUAVTrail_clicked() +{ + if (!m_widget || !m_map) { + return; + } + + m_map->UAV->DeleteTrail(); + if (m_map->GPS) { + m_map->GPS->DeleteTrail(); + } +} + +void OPMapGadgetWidget::on_toolButtonPlanEditor_clicked() +{ + if (!m_widget || !m_map) { + return; + } + // open dialog + table->show(); + // bring dialog to the front in case it was already open and hidden away + table->raise(); +} + +void OPMapGadgetWidget::on_toolButtonSaveSettings_clicked() +{ + if (!m_widget || !m_map) { + return; + } + + emit defaultLocationAndZoomChanged(m_map->CurrentPosition().Lng(), m_map->CurrentPosition().Lat(), m_map->ZoomTotal()); + emit defaultSafeAreaChanged(m_map->Home->SafeArea(), m_map->Home->ShowSafeArea()); +} void OPMapGadgetWidget::on_toolButtonNormalMapMode_clicked() { @@ -944,6 +1004,7 @@ void OPMapGadgetWidget::homePositionUpdated(UAVObject *hp) } else { HomePic = "home2_not_set.svg"; } + m_widget->toolButtonHomeSet->setChecked(set); SetHomePic(HomePic); setHome(internals::PointLatLng(LLA[0], LLA[1]), LLA[2]); @@ -1021,6 +1082,7 @@ void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon, double altit m_map->Home->SetCoord(m_home_position.coord); m_map->Home->SetAltitude(altitude); + m_map->Home->SetToggleRefresh(true); m_map->Home->RefreshPos(); // move the magic waypoint to keep it within the safe area boundry diff --git a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h index 23e354758..959a14892 100644 --- a/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/gcs/src/plugins/opmap/opmapgadgetwidget.h @@ -123,6 +123,7 @@ public: bool applyHomeLocationOnMap(); signals: void defaultLocationAndZoomChanged(double lng, double lat, double zoom); + void defaultSafeAreaChanged(int safe_area_radius, bool showSafeArea); void overlayOpacityChanged(qreal); public slots: @@ -159,6 +160,10 @@ private slots: void on_toolButtonNormalMapMode_clicked(); void on_toolButtonHomeWaypoint_clicked(); void on_toolButtonMoveToWP_clicked(); + void on_toolButtonHomeSet_clicked(); + void on_toolButtonClearUAVTrail_clicked(); + void on_toolButtonPlanEditor_clicked(); + void on_toolButtonSaveSettings_clicked(); /** * @brief signals received from the map object From 411b004583ef5729db31fceef86c957758a667b0 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 21 Jan 2018 21:53:17 +0100 Subject: [PATCH 18/20] LP-572 Add button_search icon --- .../src/plugins/opmap/images/button_search.png | Bin 0 -> 1787 bytes ground/gcs/src/plugins/opmap/opmap.qrc | 1 + ground/gcs/src/plugins/opmap/opmap_widget.ui | 12 +++++++++--- 3 files changed, 10 insertions(+), 3 deletions(-) create mode 100644 ground/gcs/src/plugins/opmap/images/button_search.png diff --git a/ground/gcs/src/plugins/opmap/images/button_search.png b/ground/gcs/src/plugins/opmap/images/button_search.png new file mode 100644 index 0000000000000000000000000000000000000000..8521a3ae8b5e495e44d731182d48b238442f13b6 GIT binary patch literal 1787 zcmVkrL2Mh1MAw@ z66ThT47-VE=FIK%VZm{YFYC1QlSXHxnK|b--#P#9Pf&oQlq8u#YXbm2 zAw(AP{bnMYJ-l(_h8By(*!cMPuDQ9np9VqDLIVd$B+Nw_U+p*PM<#Q z|JMM6gM;eQ(o*xid-pCKIB=li>s$^C^YgB0E=zzwRTMam10D)tN7?t3nte6O-Me?Q z6%`dfKX>ljKL{b)a^pV$1_uY#`T6-%nM~$y_4W1P!Ry!EXe^4icE6=5iV8|80Er+7 z;CUWw%fhXjx9olKxMmCCsjB*iuCA`%?%%&(Y#TsINiJTz*f29QGa8S_!xLj;&U=aX zIOiN1V^9f|Jeusnsp>qs9_jB=e)bLwDglgw}ZaANvG41bUJ;h zsi`S4J~}EA2NPV^4H)4t3?l*~9EPsz;2|AMV^CEUgyi}6?%&50fjKsU#F+1Ss?%_0HjhWp3P=|T~$>@HAV3lW8fhjAzg>A=NDBJ1)k?Y zN(qNjkag;(x#fqUnRMD?oOc3X0Jc1k6aY#}N>o)K&Bb0(Mj+N%lz$`~7|t*zZM3n(E(wzs!G5<)CTii=g-vfz3y z97n*mEm-CE?DgXcwLin!hF4oo6DPN?%5U%4w z2phI-!8Fa4#T{q!gf*8iGGlb<_4{vZ~5 znC?&C6OGNy?9rn~c4K4X-%)`5D*ymcU0rRRIC0{5DwWFo_{b49_Su-TQK_xfovB+^ zS$Vk{kH<+zM~8mx+O^?4I$ReYAGdo^5ltr`SRr-J$v@-_nh;$HBHk?N=h_B2y(fcXWO>z zy6$3GS=sMeTU#%sQmOZsmzV$8*4DndkW$ixg#{K4ht=8H*^*Q$RSy8WckiA_ zBoY}RgddB=972dMrDVOmz1^m1{%I{lGMW6UqoX6y+1dFT#FpJ^wJWRMm+RHIl#=!J z^?jJlX8*hvVt9D?tG2ebgI!%+bE_c=2G|DZwjk7vr}}Opgg8>lkNf)iFgZE70>L@Q zp+kpu4i68H0XQh7oFjw;Th{4!g*bcm?8o77_@l|m$(8(m1u-!(F`7&!tARJL1*;{c zWEU=6_}SX(FijJwRBG(x$&*Lkhy$-g2ywc*yL;CDsR8ba6gk48pD ztXwXK`}gnrnx(Kq?BrZe}DYJg9pDVDk>T|fByU@gb@4x2JjMsAYXX_ dA;brOe*<=%Ix$ze5fK0Y002ovPDHLkV1hp;Py7G? literal 0 HcmV?d00001 diff --git a/ground/gcs/src/plugins/opmap/opmap.qrc b/ground/gcs/src/plugins/opmap/opmap.qrc index 3ddade3b0..c48eafd32 100644 --- a/ground/gcs/src/plugins/opmap/opmap.qrc +++ b/ground/gcs/src/plugins/opmap/opmap.qrc @@ -1,5 +1,6 @@ + images/button_search.png images/button_home.png images/button_home_not_set.png images/button_home_set.png diff --git a/ground/gcs/src/plugins/opmap/opmap_widget.ui b/ground/gcs/src/plugins/opmap/opmap_widget.ui index 5943cecb4..d775ec2ef 100644 --- a/ground/gcs/src/plugins/opmap/opmap_widget.ui +++ b/ground/gcs/src/plugins/opmap/opmap_widget.ui @@ -6,8 +6,8 @@ 0 0 - 671 - 488 + 746 + 572 @@ -397,7 +397,13 @@ border-radius: 2px; - :/opmap/images/waypoint.png:/opmap/images/waypoint.png + :/opmap/images/button_search.png:/opmap/images/button_search.png + + + + 22 + 22 + From 0b092e15ceef10889f3df0427c7303d5ebcaf88c Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 14 Feb 2018 11:38:55 +0100 Subject: [PATCH 19/20] LP-572 Better pathplanner icon --- .../plugins/opmap/images/button_edit_plan.png | Bin 1527 -> 1573 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ground/gcs/src/plugins/opmap/images/button_edit_plan.png b/ground/gcs/src/plugins/opmap/images/button_edit_plan.png index 9bd0a70fefcf571759a48696c3f72411d0997b06..28c106deb3f6ee9533de4139bf3776f48f5b3216 100644 GIT binary patch delta 1481 zcmV;)1vdKk3#AN@ZhxXlL_t(og~eBGOjBnRKKHhuW#OwOK$+YYOE!mKwkQdV%@{Kc z$u`J7aC6z}%#dIvCJu~2bS7pSS^Pz|Wq$y5*&J z-o1M_3k3ID9fOH2E{efvJn$jFG=a&vPbJ3IS@Kp=3}VzC&L+5-`&R4RIWd|Zz)hM}P$ zCJ+c5;fs?>rSFJDqBwhLX(>ph(nA1AZo*g~g!Ye&jIb7q*tF}NlA%kU*k)9 z6GqU}(|_X<3Wd&HBr*jbCDJlQ};P?B-)6>%}iTqZp z^}x{3P~41AtJTXspYIsJnhG>DH0+j0BubJb)8^;r4V|5x-vIzlM9|jOrpeFGe@>-R zF?@clRvV-!skj-wl*U!$*ifNi&pGatXd;2Yf5TaNIdf*?4K;|@|3 zbs;vcu&{7?+qP{Xf*^hcfVW*PR~kYnDt{6oG~skQe~Wua006Jo%iG5Q0A{lpLZOfe z0KjgyA3_M7Eh;K9B#Ngf>UWBwniz(W0l*&)hvOgsfZOf977PaeK>S0B1!V=MC7rM%jGvyQc{Y8!Qd};yS@3$nKO#Ava+}eMA6#X>VJ+M zFbE;s(b0jctE)eBxm-DRyS?Rci1}c%*>Vv=$0jBwQr7yS=YZ8}{b+1#Y^0*1f&c*U z`Ft=oHukqpr|V%Drkfy$#U~X|TwJ^W0N?WYq5}H+`$wfx>0jmL<*x|@0_f}O;}#be z>t<(XpAUz_$7M3v0sufwP0fq1SAT84KnQ@hQ&$8qQ7a(N*^5EuX;JuSWJja|E535Ubr@!bD7q9_@prKN$za`Tbo zQfUDQ1Om7|Iavz;s|8%WdevJ|QE`2Ke!hHZY3VS=xQrl(4Fn|Q{Zw~%cRRx{M;^StIQV=%aJyXqaK8c~kqE5TgmWp1NCgrK zplQ0luCDG=jB$oSp-8y##9}ds#o|@Af29JUP-yPbrAuEnH#ZMFEXkcacb;kwBotsW znL+@Nkep$eNv&>ZfdI&j*g|gHn0_R2Y;2HWfC)1TyaFBtl}a^r@7}#yj^nn&6aKjc j0L*dRFg)a2_} zwJjEkx4m~S-mdnKwQeulm-OLx?m6fC&bg;2zYF|Vv2*86@qfROhe+1HrKRPfQmJf^ zNF-8eVY+T3WbRG4=KJX*D%9nvEMbX1*{mu#b>qq7=~=1#nr_V)HG0|Nt3!fjJiQ=llS zEolKA9UUD#Jw2g;8y+5pUa$W!K^Si^81~z2HXZ;tj(xPANfZ#Qq=)V_xB8^goH_W)pUaF90`3=P7wr2Yi}pjNA=N=i!Z*lf19M@>7(KHq+bC5 zOioS?Sbr>*gsqQ+)oLAdI2>^YHYqeUHDwx&#^p3kFQsXE>Dbtqgy(q?MNw~?&E^$W zt2K+~dGZBu>deecetUa+ab%ukS1|yd zEEcE8b?=VE~bfTpIV zt$($(wO^E#m4${fV&HH3;rB^3I$ZNV1P^nazZEbDG0DKJq0yzK_6c&A2yJgGzq)G;G`rA`!0QQ6g zq^73k#dFTh&4o-R`#=y7j$km5?(ujqGk;?RNs=flQ(}608h-ym%v^%c!oosT$OZsT zr_%u-Csq(eQERp&jCM+)cW0FZE5|oyfMGLrm`G4|{ z+1c66rKP3iBGKQYFgiMlhYufi9z1wZ#c|x(SV^<8mZ7F*S?H`#C=!<)DF6T{irUiC z(?i$Q)sX-Y2n5jA*XQIi4(9n>dAmT5~$bSx0RIGWu(jx@`!1?p%KPfLSZ`ihNn`~lYg6iz- zG`d_aNp*EK8!v&-fh9|ppt7L-8zTEp(9E1Nnv5(NTLc@mc_i!7aF|Ov{a2(mWxE9ZwP`& p>N}C=`Jejx`>*^H?*9+|0u(dJP`Gv>jcxz{002ovPDHLkV1muau2}#8 From 8e014c31f06ad73d1aa895363d1194c121a0ac18 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 14 Feb 2018 11:40:00 +0100 Subject: [PATCH 20/20] LP-572 Add icon set artwork file for OPMap --- .../plugins/opmap/images/buttons_OPMap.svg | 2124 +++++++++++++++++ 1 file changed, 2124 insertions(+) create mode 100644 ground/gcs/src/plugins/opmap/images/buttons_OPMap.svg diff --git a/ground/gcs/src/plugins/opmap/images/buttons_OPMap.svg b/ground/gcs/src/plugins/opmap/images/buttons_OPMap.svg new file mode 100644 index 000000000..1dd086a96 --- /dev/null +++ b/ground/gcs/src/plugins/opmap/images/buttons_OPMap.svg @@ -0,0 +1,2124 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + LibrePilot + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +