From b24ccc27c9f809f8551854d1a70b0cba0ffddec7 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 30 Mar 2022 13:27:41 -0400 Subject: [PATCH] px4io: add RC update monotonic count and cleanup unused --- .../crazyflie/syslink/syslink_main.cpp | 12 +- .../extras/cubepilot_io-v2_default.bin | Bin 39456 -> 39348 bytes .../extras/cubepilot_io-v2_default.bin | Bin 39456 -> 39348 bytes .../navio_sysfs_rc_in/NavioSysRCInput.cpp | 6 +- .../durandal-v1/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes .../pix32v5/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes .../mro/x21-777/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes .../px4/fmu-v2/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes .../px4/fmu-v3/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes .../fmu-v4pro/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes .../px4/fmu-v5/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes .../px4/fmu-v5x/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes .../px4/fmu-v6x/extras/px4_io-v2_default.bin | Bin 39456 -> 39348 bytes msg/input_rc.msg | 9 +- msg/px4io_status.msg | 9 - src/drivers/px4io/px4io.cpp | 84 +++--- src/drivers/rc_input/RCInput.cpp | 22 +- src/drivers/rpi_rc_in/rpi_rc_in.cpp | 7 +- .../snapdragon_spektrum_rc/spektrum_rc.cpp | 5 +- src/modules/mavlink/mavlink_receiver.cpp | 7 +- src/modules/px4iofirmware/controls.c | 243 ++++++------------ src/modules/px4iofirmware/protocol.h | 47 ++-- src/modules/px4iofirmware/registers.c | 3 +- src/modules/rc_update/rc_update.cpp | 30 +-- src/modules/rc_update/rc_update.h | 2 +- src/modules/simulator/simulator_mavlink.cpp | 2 +- src/systemcmds/tests/test_rc.cpp | 2 +- 27 files changed, 167 insertions(+), 323 deletions(-) diff --git a/boards/bitcraze/crazyflie/syslink/syslink_main.cpp b/boards/bitcraze/crazyflie/syslink/syslink_main.cpp index d2faf8d2d9..00dc1e145b 100644 --- a/boards/bitcraze/crazyflie/syslink/syslink_main.cpp +++ b/boards/bitcraze/crazyflie/syslink/syslink_main.cpp @@ -525,16 +525,9 @@ Syslink::handle_raw(syslink_message_t *sys) crtp_commander *cmd = (crtp_commander *) &c->data[0]; - input_rc_s rc = {}; - - rc.timestamp = hrt_absolute_time(); - rc.timestamp_last_signal = rc.timestamp; + input_rc_s rc{}; + rc.timestamp_sample = hrt_absolute_time(); rc.channel_count = 5; - rc.rc_failsafe = false; - rc.rc_lost = false; - rc.rc_lost_frame_count = 0; - rc.rc_total_frame_count = 1; - rc.rc_ppm_frame_length = 0; rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK; rc.rssi = _rssi; @@ -548,6 +541,7 @@ Syslink::handle_raw(syslink_message_t *sys) rc.values[3] = cmd->thrust * 1000 / USHRT_MAX + 1000; rc.values[4] = 1000; // Dummy channel as px4 needs at least 5 + rc.timestamp = hrt_absolute_time(); _rc_pub.publish(rc); } else if (c->port == CRTP_PORT_MAVLINK) { diff --git a/boards/cubepilot/cubeorange/extras/cubepilot_io-v2_default.bin b/boards/cubepilot/cubeorange/extras/cubepilot_io-v2_default.bin index 0179a993e62b05e6a1b9749cd20c99b5318d1afa..c12e9682d1e6b9a4151436da12a3250f11e7a99f 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)u;b@f$U zT~%E#`+Jz4ZU*;s;)OV;#E=Iz zt@y7Pn@O2s8vM2?3b47mQ&FmjTloP(CB2(hsB3e%ouVCKewnu`WPpjZ>_M980P_Hr zkS{|6j6)<}gpJpgdyw&c7t0}5+mBqwFk%@q=BM{{$Ao`|#~^;4oXcrz6)fUc$>c`F z8_d-`Id^AbX?pm`efjSu|UGHBiGL{^P*EUopHI)0Nb< zr(EYMdcKBBb}4wQNU1>lSAmqy9FFB=VUKJH@{-h;2btvovLI$6Gd)255R;)@A24$L zKk_d%++N>|__G1>KQXEC7T9V2b-udY?%<-hc<%A#m|rUqZ%jtad4C&+j5mf;We(I^ZbjhcoB@>LoF{@u|HZAXhPLP1~#B zl$?%>6|pI|4<#joDtP?l3Ef2OBs+BvD>1*@PkzyDWZsj>>crPmoNppc#9pL<(}R=e z`cm7x*&)WBzeZ24Goel?_4qY#H+guhI}xQv|2U`xyST2l2Z^74$~@ zL=o}(Ma*yT_}vEkqv&0CnK*$QNr`S{RfshMWB^P7sE3VK0@ecLvB2|>$w(91i!v-D_2owqbjx=*%oO)w( zuZoM{;?Do)R`eE!q5W2Lh%>QI7Ty#|d1|_9dLHnQ<*5Y?^)Lfn6`hq*HNDWIJ=nup zq{lU~@ON=OjHvBZS(EK~Ade3`+P-VsaM87PdeMV@d!wOkFSNZ++^Lg_c6o-u)ZE{z z(wby9bn5KKybj(H+FXs<=IYU2QPv19#oi3Et|c?miopJCPMbFNRk6nd_Q}W(TFQTM zujI#~n{G3?kd_hyXCN*qSK1nQ*$lg7{cf^^wHc`}wY{?NxvWf8U6h4s_nC@WPTM~! z2wBj{`oMT!xvkNu)j_%TO|HoC-D``N6IVtcvR9)eFI(5X#e2=(Pm|YZ9j!vRL!R6 zk*QfzRYBb*ZCMSGV8&&{HusNGu4HAV7z6jtH+XbnZvq!@Rf8U<*kwT?Y1t1vH0)zJ zv0rb0YDM}D%>2ilZvUC;i1Md<8aJso!AiNm@~v1w5Az%EcNIztek}u(|19}^b^@H# zS03_yc6vyU53}EZYMsl@)M7p$DzCC!hJDzLdF&x!#$@2^7D=u#y%O=2r@szC>=yu3 zpg2R%89{9A9<~n`vw6Z0s3a`81jMc6&~UwqwtgTs_9=(w1j{`l*_-xCV?^v4<#g<}L(hDzbg$V8Lod zWIR7;vRBxiwzu1$wmemkTEO?V@K zjJ<={pm^?rTNXM=Uruf0|H$`vvSi^k5|ukY?Ec34Cy~{;55~VOtHC+l9(-%tWUl-+ zTK!f#;-8es-*d~ECYh*BQ$cKFL{ekQE!ZSq5Rn=0I&f3N>?nW5H82jblR2l$0s^(m zbS2*h&+gxD`O`h67V@Skg>iVvfN4tBdlE9Fb6BqfLFES0Ib=}lX+)3_pmepKfpThq zr02cZiuiQDimT~F!?uvTwMMRx(>;Lr71GgiVQ2t$8SAGvgvr*;K*Iy7?6oZAC`SCF z(%Zmc0S+d}fwH54!=lQ5j&f*$qb|td0FGhb=oq2E;rJEDWa;g67)0#v0nIoC@Dad$ zf#F)j=bT2a9#WQXV!oBgv-t;^$7B*WemwJ z^%7MR7HnV}a$P1@3UZP}zrmi=xyRmS53Af`tFUvn0sF4%n{e$e6TSI?IT!tiwb@1$ zucTkcCE2gLsdM_sKSB=~4ZD-<^8dRG@Ds+cF6|Mn+aeL ziMnvSi8?hZVu-WKVy1_1PHwy%^H2E7K)@xSS^d5-Fn1C-u2;yy!h99w%^<%od;kK+ zKYGY#g*90NKGwd*3F7YMDGcAs6S7-4l}V zx1@JM_Bh&yhO|MO_%z#jVA~}nJ_q_FlDiXL)ZK6X)PgkT-Wco7W6Ab_@SQ|nDauM3 zlvK6@&*DQdq*tPh!iG|HD<{fo$u*cE;kMFJN?w-WZLzd z8MrFtJnk>z2h@3N2s{#n8zKRLnGK(Do@iLyFtinbT0 zgV6OE=74b2hYTNGk1qnJQ*>?dwWe!Jv_Y|Dm?fbf4Cl3_`=3F5+J1%oz*1RwJJ5Z% zcnoGfhC4B_JToCMPgIu9t{OS}Xcd2ES2ehN*N>nV$?zJafV6C_r4Yqf`HEF#<{Sv5I>)!74(v5gbK-dI_=e?xu z4+t(7>6((>dbpnk7@;*0+*mFk6w8^F@54(%RTB`Ng;1cRKTgEqe&O}NEm)Ni-l_p% z^(nEpy+z4wE05yXGZy<+g!n0bHD~X9yT!rE!a)xwW}@c4112D{rDbl8?640M2_Q>W3%%o15KO{e+Pqk<)bfvK351=Mg@%d|Ww+zNF6 zFs%j~B;h6bC%6ooCo{_yGMfXWt1OF|=^+=(rhxvK zWEEG^9Xgx=FVBGR2fs2^anT4DEJVKQz92qkexWnP*2sM-KGqlzKJ*i={K3aQ_NY>o zmkw-&w_sa9xacv0@~SwWn?_0j;eYJ{o>;yOoaQ*|tT@qB>Pr#TS zgzSOuQjaIXZ0)kB(*mdDmG{H1a4*W0gq^3g{S27# zU3S!&Y=*Z5nOt3Q&y=@SCq&CavxXrlM`ws{tyGnpEtpr}fKYUrwyxwE z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYrX3F{5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou{xQe@PK*{N)w0%%&57M?l=|!NG-F*#8&wFW(1Rf6o#4iWP3`88l ze3mDw!`aZ$rDmh{yi{B2i0)AE>A)pH3g9s@Y-eySe7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@fasIk1l1R_oQ>4nmO0x+#QnqHRg51HzT_e^AJ^vYs}%h zOC1l`R@qKE7pT*Krz0f!99=qHu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?LBH9Q0XKV#cems6>nnr zY~PdaDV;rcK4~?&8g75GCNZzXl?acuw})fFZAg-~FH0P2dD!g>_G1*}_U!nKcjQVp zO(_ih@RSCz^8lzQZUFWIn86F(+DpdINo`#d6W+2uyyo#q#@`OA&rdL}8JuWbH%Plq zy84XKJM^G+@l_>6-tT(h_@CQVp6n_gdB161#W$kpNOld}iZUM(HAn>H(>)0z$TKb3!R2C*hGJSVnwlfweaPw&}LKb`9-?;#Nd z$6N{}CfJuXoOgdCKDL8$j;)b|J$^Vk&1Z1c5Whjv3}elSVNFzy$b{b+g1Pqp;Eu4G zY#KwqJKX98h_&eqe|3iePB3)4L#;f(FK#N3<*o2z2Y3&F*@rY?AgT3Grc!zeFqIgU zUP*7=$XMhR0#f?)^m;>GOZO2_^1QE`oEJiJ&c)ipOd;oSQJ5*#rWms5jVZG5zVC=L zmbXMTIg|BqP&e{{@k=^lV5f0aZ%}OTZ%OMw_s!pQe*E?GnXMv z&5sz(BYkrpjU0eps1jK|0{lGDKe7mqkoHFw;w*CQk*etDff@&`zXcov!uW_xp7)#3 z7O2sF&y&7+*32f)MAj#;UTiSg%14qF26)AkKmhs`JPhfm5FJ|vNY4E1)DY2N4`VAJ zv23tm9zhL5O#?N=d*Ep?KOSBsKgq;7e?i(?BE6FIb=?u7K8Fmf{ZlAAy1;a|W1bMa z;L%o^qql){V%~r}Jz%)V4aXa{A1igv4?)A198@Q|>zhDA6BQOdwCz>VY<^WNHpdu_ z)?gBO1QB?4+ar!Bhr=MJuuN9(80>6v(iJs1_5mL2mjI0Q@B=gDOaFhvE=1ecO)UIN-w>P+))6b)c; zsF5gjv_^Iq+Lk)U^64rIKc?+4n6D+_uZnq%uZsDNe-_6#?t|%fR}Jw0bnNTgC+3^m z`%0aQ!OGkppkEws-Y4cc436~RWLlW4M`U&+@-d+nUfuTDy%9}2VALHjBH;WTbksdC z>i@Pn`i4{E4CyL{KM{ajwFDNY+yeH=Y-_AI=DT%E<5S!!sohq-*VXMC5!1X* z@y-uTAP21I=t^-z;)Sp@k904?g!oeV8}W;Q%h%C_V>cCHphb#BH<|F9x<{)tu31%a zXS1!w+9ap3wJyfw4DJmXvYg%J_)LT;b_k^-1DdLH;jAyfS&e23(D-S$@BC$SO6oD1 z9KZYko;@5FrNi%4cSHvW_*kqMiee0r!}-jY*U^FS!;!<|6`0TQgbw3SWYoB-c&v(d zQ*%J=(GsQ=(h*Sk1n$@`8(OEWj8T-{8mmInA{A&w7-Zf7HUT3w_bpIHnK8kMOfXRx zf@we*V+@!iTf^T&pqwT=I$@-j=4t7KwLA_Db&o0{t4IJBf-FJ`f!|vfRGfS@Pxl|U4u1sqi))DTX*yYaOqFD=(@Y!BHNa>!kDPI-QI5jBP&f%I~?3uGyV9Uo%wHQq+0UnWk2pWA#g5>7vx+Wc9H; z8}dj^%%CLjMcx=AYp$GfaM7*brOm!TL!xlba>sm{eY?VkO}`X|NUG9@1({ zOxS$V;5;Al!?}EGE(EfCwZ2vdDIYI6YD>i1$)~oo)+=5Ei2U?9O?rIo=Wb+rZ*V3@ zzp}YStXJ2(1pZKh^h0cI2RuRV2LmZ!LsLPM*f&GaAYkh1sOzKZ_66Vz02cu!K%Kfk z>MPGf-E`0PP6piEtLC;Gdw?Wt(HlpDZoV32s<{I0F!vsJ2(sMpp7Z?cI#am2Jo3C5 zY6cInZ7ESewvIF{nufn42No6JspRaU(%7y(8g^(;HCM0X^~eiLwG;i~G`y9REsl-a z=1qqSPaO@0biyXmv^X=v9$W$gFOM7WC{MUVUk>SLUSD|aSd4EnakcYtCV77`tG*2D zKJ^AUv$zibNK%?gLw|yvw09_3)Rc|Gy0H3M_%n;OL)`#if>Sm2v0YRu{6%94~ZA%n~v zw3w7D06S*=Vd=z>MxUAU3X$ZYrAg60!pi8pC=Xj`cv?f2FHOR&Wb@LaX~8y-ey}}e zeK4b%e_d#3gV(MsEGDy;nIhLoXvfm-9QXzUDFU)>Sz`3ClwYUh_)gRj+efK{^e&r* zKPPvVJ*f(An=E=VfqB|T)<1a=Pb6vfZ4#=!?!sl9uO0+?N)7 z5k5r@Eq}drmcM@FDDnt1{50P82z7w}1egQ74{$l)ZGflV<2wb}==zcIK>4fRas$GH zE^Jf`l?D6e`Rjr$M!*HYkpXxtVAfxD_s@WnVT|p7bwG~*9OtiT9Z^9+>#rG60*-)& zB)}TzFb=R1z6sMek4IPz6pDSmx)BXv0bWfFw+9+M!ejnX{0mUZ?qX=04ZIY8AEfA@ zR0kA_F9#`!P$~lo#naCQNopvT0Eyzyf|L*_6##|ezXd5;C}jbK;uF5IyU_^iJwl3~ z=DTUlBm9|ceY#qWz+UsANm*INAVeCM z&n1gj-iT=PKLVc+wLZ)b`pLZJ8PRk6GvP^f&07ndSs~ zr?ELxWFkIs?|&Y?==k$tn0_zje@g<*)@X&F_Wy&o41Q~Yzk!bOz|THP-4LV}0d?|! zNBP{XWH-1~?0PrDwzw5+tosn`(G33}a+n-mwG=|hsMVA3*Q9!N8z$t_)lcGur0}^U zJd;d+F4Hzu3^8nVYpm^J6;fG~T9E07LCi(hV7^fN*8LugbPQkvNR*Da0dD6Js2>G* zAK)(ld!X$!z_$P)`;jIOU@pK$fWPb~XP(Q2PjP|gGV_0sReN?ph#S*_a@P+&*I5g> z?aMNyRCHEbt7{Tl@ML^*X!R^D;s;5?n(gpk2H&hPq^*+^tUE=HO=@X%cK|msIfiJj z*v?oO;Yp%jn^r>?Mi)vKNf&kjCZF&o(o6-Q3w{=k8ZlgFK7{F9KpO|W>na5_^DEU1vI zdftFPB|D#gI`Y>%10-_20Xs`Z7rQ$g-M#wZXFR38daM@b3oH19{yn@MuWY3)u!Ol>D#^5dcB?Yrxvx z(0T)8=@l2L2=0*WFC>Bl4!G`6O7<8z|pjocLDvjMh|K7+e6f(P^n9=(KbhaZskqph47@W4pPH+zv>zNr9NQL%9p>^aHKMAL|> zUtulOp^B#5Yp*2dUdhjS_?e~8pxk9ERxVnTi;T~%U9lnucsgew4F$^IH;PH#t50-q zeYF~=%v=rsngZ}8z!1PWfC~VB1NaB|`F9KTbb7FR{{_XpvJx-_-2L$ONgBr3O@8;s zI?W+?vI3DMGf6zT`^VLqW+3diPuQ|+b&v!0G|Cab`weEtUUGc*ym%N1I$9(IuO87QNpEMYbJza z6kJ#v6bO+hx^j4sgt&wlgNpu@zx$aWxFE7dQHEpJeF>5G=6dg|p1{xjzWjcb>aMQt zuI{d`s;)OD+L@LU3_jC}AIF(b`LM9lUo5fl|8YGiv7t~3{f`Uv>|zk-3`HD5h}-=R z(!SXKBK{l3CrP1d8vJiijm0P1TUAq3(al{56?AM_rm4u{_egexh27q^pwmqFm-~_S z0zf~&zsTQ%{mlDr@^wgVY@G+0-tFOd#Obb{dreD`%>TlLWTIwXu$$QMybF(t6loEt(}qus$r@G<u|-ESYY&j;qLUa`H+dD%Kf2pLjD8H) zEcGJ;I}nYKu+Wd86bq#Vfl?}z9`UmSF$f#Fuj?#GsOhfjXtb;O1y8aAI*l17JmWL2 z#o3xmc#5%(){(z`am+59R4<2AsreIb#@txM_95<&6XzXr6m-Lx3%`0vRBUci+J<2qQ5`D8&yI0*EJ z1oO9M@yNgktrEuYd}?nn?7W6Uk0V})U?v2?C_i}J{>XO zQp8rb%8s(xE0j75)cg0#nETa*gsxKsAcEEz2J{#yj69uJN}kFu2;Zx8{En(E=S-jw zz2t-ZvYES-S|^*o{AO|S@|&}YQzd4q8QL0^)YhX0j?YSF1TDxWb*I@4JZ-rlkKx~U zg>pTv1pX5j7LrdP#8m3-I8Se@D?>dcBrPrv^!hu6EQm|VS>P+Q+WABqW5h@D>acLm zedPwipd4P-IJL@XGum->%@xjm8Zkl)ITn{zAK}X=$HG=mtRW3>rT3V<$*!`clp`VD zhf|K(<5rlg2@aK!j&?yww}!$lKk7>ZjD_v)RKSY(f?^EN8x$r*eDsd1P#RxfH`{xD$?pZP^x9Hs%Wu+wW8fD zEa(e2$1}&NG3t91X@7ums!XxNx)XizKer>dI*g6CBb}o=Wf89bwfGeEkzAy$A>j#Q zt7~8eDixiTQnek>p>eoFo&lH3;%?<97*W@uwkFuez~)?c>pHJ)$9Y#9saDax1s##l zb^zMGC)*Pyg?`~4fb|B}O8%ZODsq@7!WzaW+UsDOpC`X3N*thiozzTzn4YhJ*Iq) z2R20BO|+HM{iRI*dza~|e0QV()9}_P;!XLF&B=DgvBBrFo$>653wPSK!geX*b(zdg zdXQDbg+6jLDHRH(K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R;nSaT87ST%!T#xzh7BTXSxR)hIK%=OunW@8E0rk#J*qA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){Hf|pJ7XF8#Uf6m!xng)I z=v7Ig$3P~h#3#}tV0mo^YyG7SEKZ66E_9)nUiW2kK3S2XpQ?yYc{ngFI*TGMIi>5S z7vIJy;u9X0FKEq&(jrfb&D2SKz)uRDN!?EkjVw;}k<%&nJ@${laJv-B@S*aXi@H^o zci0oaIezX{8A9P2p7*PhLi?}*u9(lnGk~}G=%fW;&rlb>f`w0f%Y_(J&`rHBwO_;i z-}aI@#?+9!F4RL6_DC+-YJ5N)xFzH(V|BP9wzv^j*F8*0OHE_G_L8d9INVE~NS%N` zBh9JtQ|TT|>KJ8Bv@7Bp-et>7u=*c8zZA0;ygRj15#NRdsE(Vv@nNt8QgH&y>v}Oy zYmEvSN=*sc>c!lTpq+_nX<+4BWwxK=Q|+MZLWlhCwk@DD)cS%)*f75nG;8zlEefds z^DUDZV^ZQ2@#m8lgAmsXK=&7?8h9$jB!#@67NKiFTP>OiLMogok8P zXEZ1-crcl0)04oZxMh+RD1eGqr9T{o1T1r%MPLj3e)4{L++-x2@(+vjKdwKNJRcZ- z_7AH!GX2!2gV^H?IE9X0Y*ekf1dgDQ;Eam!_4jzv6>%wfBx7#KJ*n5+M^0tj7cdsM6{Vx(;xF8V+xNAv7r9{^rY~}s4>vU=%RzH%UjWaEojUd6F-iRoqz<+_d$`^cN*9xds%)?E0YmB0}Y&3XRP5UM?MlFd~XAX z1vpFr4wMlI92RxPD$1b)4%tgN9KbP(OwSsX_U}Ml>OKj_bsFGHfO{K(;Z(1HI-Vpi zW@R&beB{Hdw-`ny3$k;Wav#}|J*J-O+q9wxWC2)pKhmPJ`=?Ns&GHuTEwR!s_UKmQ z#$!dQK1ECpIPO&Y?{IB&5ci30OKUis)9_r6pc;(^#5z3+e0-mSQb|g^O1F9?q|+;$jLDinUfwOj7ibAc;2-s zZQEdE#6dXMfO`5#T23bOu7}j*#NvMPWX=TU&mPi}6Ek(KXE0#22VC)X<)8hqK`4c> zes%+;P$y37Dr-FW-OmO%V`#v!pMZ<4?ZATDO9pe&Cmxf7QZ&{GF3#3{U2E}+6Fx>g z+`m!(+u-q{`%%9R0ER*|7{2UB!Xc3%_ZXtf!l>y%ypzwhVN= zdbGhi0_Khfw^T{q$<0wyUK6>LI|0IqZiz&VEl;oUa`x45mrLBV5v5QA8E0d`>H9^C zZ&;!OUBodqpYg&GkIlj-$WLSA@j>Drn-NF*&_F(5r=I3o4{g89;tR64(@P#OzYu$` zxuFT%tL%rC zfDE4Y?M|Vw32rru2w^EaSF_KL3gx-Lw({_`8G&p zf|r|LT+}UfG_Ga&?L`qhcg|ve5u*77uZFj`zP;7~?Jvl@l!od$53R-bHy5eDH}igR znM_?rNdLpo;un|5f(uXRE^>XlG}HD@9pa=wTBz-lBvbXkKz+~Fn7Yoz6Ow9?CaJzRL21C-@46%{FmGs0wAJumNegQHVuV7{OYU3n zH;+1ry?p3Jco{YL#j_q0xIQ)Sby2_O7Y}>bq>#&Wh`C-i>5ZPJ>;yOoaCShHL7gPa ze+idtH#|1HmruCE%+}7UFJ9J!Uhs==dB{g4arLi45JK5%S}owPJxUAw7a_W!=Fl(J zcj>xAAfUm#3QS>*#8_i(T8My6poxDxrTk(Zywis3A^h-TYw^kdw|+KIm%uQ`fZ_0q z-*}IXRu4pw72^v>_{FawD4^Qm7eDVJr^hEvRK#gM6^{lI7&Op==Pi75APj|#f2nBB zBGo{c>P{bBbG_HZr+`yY#3PD{ucJ|E{)F5DzxZAkGZ3LN3K6Px=&RTpG#99fty4<@lDZj+Rvo}LnzgX@i`zKV@`^6&fWd6ti8>}ACGbus@^OsWQ zk_B|=hGc;`$AO>+T*#p)RC670(?;-y&PXbJwO^dx71ik%U-88DGXr`mKGhwGv#VyLEzD2B8D=(Wgi57 zEZ@?)>4h*Wl|U9tWf}+~c=V13X{NXh^;CiCELc!szj)|l+PYj|P+d2bkCa!W;{EN< zRE%cv17zFuvG_Xq+w^4P8Mh8%>%(9nrzwn3E1{IXR=qQQHrR015PLY5sDvMhdwNd& zW=X>}Rj7m+UTi47a}asO?XdsFcV36mRu82$L#ZJ^+YY6TKr6hn8%oc6AdK`v5CabN z2>_!%?668W>y2n~RyVb2xQPARDyBFhn^Xb^Ts|)rHu*#LU}3Hw3qkPWz3Q*NqlB%j z-O+6-D-C!_r zDqK@rv0zaV2Noug)|n>NkYg43Vdm#pL*9I_0N+P0Kltic_0IFfcX<7QqV0Xz<%&4U zzs+^#wknbpA|N>t=5x482SaNQ6iw>uavFymwWMX%$S}Y|E{@ON%m``ZlUa$3Mj`#P z(o^43N?h~-+;{CME#l??&?Wr~un)itzH(zT$(o&1zcMOx&GVrX=1(%M@6}u!Z(7ki z(X^_UcCGAx#^mXnY_;{X91`C4z_G2`Ta?gKH27}qoZ=s)AxA>b>Dv+J!%`Sh1IO;W z9LYVFJHHgqDIRVcfj*azLu=Ic|0o@HSU@=~px(V+I_3t?;d%)LIzQ(*EHMFA&SJPBY2 zco*O$IPfsowDnM?8%8&hZXVspf{x0;k;o(Z<&^0uRmMt3`!Uelob$ELOF>x|^!AW! z?M0jylC8I~ebqybg{DMBe9wE#sULDIuXQH$>IEjEbg)KMt-YhH(Dsbx_2ip}M&b|2 zuMg#9&U{H#zkJN2WYHT1|Q9khu>hM?UIPAAeM0 zy$wr{wq+|u<^Z+yE;Vf_B#EwLWFwsq&kz3+dZ7|z`5JHoF+8#m50S=49>*qf^^wxZ z2B1bm>lVQKVH3V4ljl4i?0_2W*FZYwSkwOEnaFuX&V!BFwxYoVl@U&*05SmIKp0L( z4TJt)lFYdoNs}d`J%lTUe6Z1mh4E0sP}2r#*%EnnZVZIgNsx}7J1_aXL~qw637MOM zG#8MOvwsC;M;rK&Mo0z_Ja2wIO|9EtclN)Iw2J}5ovc1SW9RWa=e(fY3u?$Wv?#-> z%JS*G$EpkLjId8RTERe?SPhwIMtDVe2Wn|D1`ovumt{uyNdc8Dv4DaX*lfj%4adE= zZ(EBGR+6HhMgNK?`EGD3yN!N;~YOKDuK6J;Uc8%MFgs^(UP@6*{MZ4E`59wV%pnnO^C zz>1rtbaS&iom-q8bTJR6W>xWQd{~~N5cU8Wiw3po_oOlAE@z?z3D+F;C=D442eq2_ zq+B2-0WqQhWt@Z+sCu=A`(Xu@Qd%oqx|#PuxkSohrI#)cHfa9TKoWvML1CD_Ku)#>X!-__i8y&JJDG|rPknOB>E>0QV z5$`qlyaNh-5w6c~8|$Ynk5Wy!JyMO%L!H_ndes**_28JoRcK=f*av{E(BJ^fK_k5t zy@08;w*XHHl%3EUmaFEQ~rkAwdLrGzTi=$1FN<$}Lhta@3>Fo!jT z9Mwy~D9VV*By0FU21X?G7#4n&kV#wLQz~F}@Bj{O2Bp|n`pdT{XWG!j51J(tXmB} zX|osvx|WH<2Xa;LH3Hs-+8$o0#~M6|PJOWG>bEF&+K}plZqNjJ#u0(Rrz_1;c3rKr zx|MG0@TD5KHVHiT;^3cMblORLt>gMNlyN_Qk{7Sh9i&@KcaZvbxOR<>luZzA?Ww%n zcJ2mKN^{_|Z>m+VREPF;)jRiUR2ML}t3nn_6wa^{9FR$g?}s!C1dzvXvD)pG3va1| zhcBk!eKP+FIBLlyXqRhnM7kVEy3+Jv53=V!Mqs^@0p)lrgTRY;)8QLE{#1@keZ z2OGP9!=YbZsRxc-Jmrb)>2fZsjO~G*dVSrY9e?4Q+Ge%l9Bp6T+Pu~-XR=y#fio(y>-m{dNw zP8Ju-MHOmJ7I%>L$H!XhByEn^XLP}m(h7K=-P!GYZk<~ zLYbk0Qr|tb53Ieu6P&2#;sumuoDp9QX*wqotR%;ljCYdhwo$c*By7->Zv(#$`E6NW z(FCshUVQU5_yl^6+#5ltA24;<)P>V)^#kA=05<`~L!G*E>hiBcz5T8)`2;W$&XMYc z(;!{7bKzKs%z741(ZAmr_?YlfUDt|jf6 z@Wnw9x03p$qa%Npb1GS0Xhlu>PD*`^99cRIe@<>JeIn`Jim2bFUnvhB9|ei3Whtt| zesPV5Jp063*i7{HpW>+ql$m~Y83BU?`B~oCNuOI|NW_zwVfO}7#MeK1W%j%|P_@}pgkOllbG{gh` z4m!jEJ_pY&`iydmlYGPYE8x&V{c~uk9y(p)7PEZA_@e+XhBgE6QrsS(#6l?+C=?$J zP)0*30w@$ueaeP;^il0t&@j0Y@TiaErIRG*LopZgB%i zd%8@c10RAy$jYZH)mkXVkWZdAGVp2Z+SBQ#S&$~7M4B2K#V7H91TDQc7#A!OdNPnklLE^Z?Bep399t_u_k>zf2HhKElDSA$!izyj&!eUNz(vdzP zozIq%hnL?B>+wATAKc&pER67zs=67GulQ!dOU~e}fd3bP{7*7{MSS+g05vo~{S>HQ z`q1w+b!ie4_NA+39Tt}Pa$p#*2Mb+fpw1du=%f96J%#Xp8}PqOM~Tc1P)`M@D}eeu zS+^oS_#_BqfnS?+lI9gl@J*sxISKzCGG%20ewlQyd?InKwAnS<+9(yH7;8LO={WfA zALr!Cqe3v)#KKi+wgM^0_@YY-Jf%ntJSh7be0z$7PiEQDPp(ri{%L@J!B*0F*2B&1 zf_e|YM*trKgtQ=SF2GEH=K&4?d;u^Bkn{%mVpSHtO$Jt_<@77+{d>VcN3BI!>w8zV zRzUvjJB3n;Tg$9v<)hc)$@o^^$_L?l)LBxzdMDmQzFlp^bwpg9h!>KPYm%o@0jNM! z7%D);8%X;m!21AHuzv!kLahcI^Ck!am&|1eWF{B#D3Zt_7ETnS^f~g*UgSZB(h!P0*cMb~@xQuqwJjDvS%t_k^<_YM)V` zgvSL0fHpcU<)hP5F;W4j7&Ks-ZbrZW6?eU6kADhH{&m8uO zi849SI7YwY5Yk4R(08!MAUd*Qf`kXj?Z%9lx7=Bfc*MZ?i90Cp5!Nfh@2$+6 zsy16j&~Fhmxg5rO#eYLibn|$a{qLK%Fk8K3_LeHFB5!P&5UnyBo~7eMR9H%}{&ZL!uWJgb$}CQz0=4 z>BIKKtr09f)1LE^h%@OgI57OOj3yP;|AnKW4pn5i+g?tl@5sr@TDolc!qr*G^z52t z%Q9(uUlr0)pyf+<@k7rnd4?R?@mM?aGLI9NtVG%?06ziz3UCA9-vAc?E|DdFemof5 zB%;8!|N7@iTIQoRlJr`o)(k%#10qL$dL@QzeQl*yf>-vgdxV(1D+3%L{4mE~_rA_V XHxqu}oG6Se6A@A%C9BXs807x~Vwx`3 diff --git a/boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin b/boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin index 0179a993e62b05e6a1b9749cd20c99b5318d1afa..c12e9682d1e6b9a4151436da12a3250f11e7a99f 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)u;b@f$U zT~%E#`+Jz4ZU*;s;)OV;#E=Iz zt@y7Pn@O2s8vM2?3b47mQ&FmjTloP(CB2(hsB3e%ouVCKewnu`WPpjZ>_M980P_Hr zkS{|6j6)<}gpJpgdyw&c7t0}5+mBqwFk%@q=BM{{$Ao`|#~^;4oXcrz6)fUc$>c`F z8_d-`Id^AbX?pm`efjSu|UGHBiGL{^P*EUopHI)0Nb< zr(EYMdcKBBb}4wQNU1>lSAmqy9FFB=VUKJH@{-h;2btvovLI$6Gd)255R;)@A24$L zKk_d%++N>|__G1>KQXEC7T9V2b-udY?%<-hc<%A#m|rUqZ%jtad4C&+j5mf;We(I^ZbjhcoB@>LoF{@u|HZAXhPLP1~#B zl$?%>6|pI|4<#joDtP?l3Ef2OBs+BvD>1*@PkzyDWZsj>>crPmoNppc#9pL<(}R=e z`cm7x*&)WBzeZ24Goel?_4qY#H+guhI}xQv|2U`xyST2l2Z^74$~@ zL=o}(Ma*yT_}vEkqv&0CnK*$QNr`S{RfshMWB^P7sE3VK0@ecLvB2|>$w(91i!v-D_2owqbjx=*%oO)w( zuZoM{;?Do)R`eE!q5W2Lh%>QI7Ty#|d1|_9dLHnQ<*5Y?^)Lfn6`hq*HNDWIJ=nup zq{lU~@ON=OjHvBZS(EK~Ade3`+P-VsaM87PdeMV@d!wOkFSNZ++^Lg_c6o-u)ZE{z z(wby9bn5KKybj(H+FXs<=IYU2QPv19#oi3Et|c?miopJCPMbFNRk6nd_Q}W(TFQTM zujI#~n{G3?kd_hyXCN*qSK1nQ*$lg7{cf^^wHc`}wY{?NxvWf8U6h4s_nC@WPTM~! z2wBj{`oMT!xvkNu)j_%TO|HoC-D``N6IVtcvR9)eFI(5X#e2=(Pm|YZ9j!vRL!R6 zk*QfzRYBb*ZCMSGV8&&{HusNGu4HAV7z6jtH+XbnZvq!@Rf8U<*kwT?Y1t1vH0)zJ zv0rb0YDM}D%>2ilZvUC;i1Md<8aJso!AiNm@~v1w5Az%EcNIztek}u(|19}^b^@H# zS03_yc6vyU53}EZYMsl@)M7p$DzCC!hJDzLdF&x!#$@2^7D=u#y%O=2r@szC>=yu3 zpg2R%89{9A9<~n`vw6Z0s3a`81jMc6&~UwqwtgTs_9=(w1j{`l*_-xCV?^v4<#g<}L(hDzbg$V8Lod zWIR7;vRBxiwzu1$wmemkTEO?V@K zjJ<={pm^?rTNXM=Uruf0|H$`vvSi^k5|ukY?Ec34Cy~{;55~VOtHC+l9(-%tWUl-+ zTK!f#;-8es-*d~ECYh*BQ$cKFL{ekQE!ZSq5Rn=0I&f3N>?nW5H82jblR2l$0s^(m zbS2*h&+gxD`O`h67V@Skg>iVvfN4tBdlE9Fb6BqfLFES0Ib=}lX+)3_pmepKfpThq zr02cZiuiQDimT~F!?uvTwMMRx(>;Lr71GgiVQ2t$8SAGvgvr*;K*Iy7?6oZAC`SCF z(%Zmc0S+d}fwH54!=lQ5j&f*$qb|td0FGhb=oq2E;rJEDWa;g67)0#v0nIoC@Dad$ zf#F)j=bT2a9#WQXV!oBgv-t;^$7B*WemwJ z^%7MR7HnV}a$P1@3UZP}zrmi=xyRmS53Af`tFUvn0sF4%n{e$e6TSI?IT!tiwb@1$ zucTkcCE2gLsdM_sKSB=~4ZD-<^8dRG@Ds+cF6|Mn+aeL ziMnvSi8?hZVu-WKVy1_1PHwy%^H2E7K)@xSS^d5-Fn1C-u2;yy!h99w%^<%od;kK+ zKYGY#g*90NKGwd*3F7YMDGcAs6S7-4l}V zx1@JM_Bh&yhO|MO_%z#jVA~}nJ_q_FlDiXL)ZK6X)PgkT-Wco7W6Ab_@SQ|nDauM3 zlvK6@&*DQdq*tPh!iG|HD<{fo$u*cE;kMFJN?w-WZLzd z8MrFtJnk>z2h@3N2s{#n8zKRLnGK(Do@iLyFtinbT0 zgV6OE=74b2hYTNGk1qnJQ*>?dwWe!Jv_Y|Dm?fbf4Cl3_`=3F5+J1%oz*1RwJJ5Z% zcnoGfhC4B_JToCMPgIu9t{OS}Xcd2ES2ehN*N>nV$?zJafV6C_r4Yqf`HEF#<{Sv5I>)!74(v5gbK-dI_=e?xu z4+t(7>6((>dbpnk7@;*0+*mFk6w8^F@54(%RTB`Ng;1cRKTgEqe&O}NEm)Ni-l_p% z^(nEpy+z4wE05yXGZy<+g!n0bHD~X9yT!rE!a)xwW}@c4112D{rDbl8?640M2_Q>W3%%o15KO{e+Pqk<)bfvK351=Mg@%d|Ww+zNF6 zFs%j~B;h6bC%6ooCo{_yGMfXWt1OF|=^+=(rhxvK zWEEG^9Xgx=FVBGR2fs2^anT4DEJVKQz92qkexWnP*2sM-KGqlzKJ*i={K3aQ_NY>o zmkw-&w_sa9xacv0@~SwWn?_0j;eYJ{o>;yOoaQ*|tT@qB>Pr#TS zgzSOuQjaIXZ0)kB(*mdDmG{H1a4*W0gq^3g{S27# zU3S!&Y=*Z5nOt3Q&y=@SCq&CavxXrlM`ws{tyGnpEtpr}fKYUrwyxwE z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYrX3F{5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou{xQe@PK*{N)w0%%&57M?l=|!NG-F*#8&wFW(1Rf6o#4iWP3`88l ze3mDw!`aZ$rDmh{yi{B2i0)AE>A)pH3g9s@Y-eySe7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@fasIk1l1R_oQ>4nmO0x+#QnqHRg51HzT_e^AJ^vYs}%h zOC1l`R@qKE7pT*Krz0f!99=qHu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?LBH9Q0XKV#cems6>nnr zY~PdaDV;rcK4~?&8g75GCNZzXl?acuw})fFZAg-~FH0P2dD!g>_G1*}_U!nKcjQVp zO(_ih@RSCz^8lzQZUFWIn86F(+DpdINo`#d6W+2uyyo#q#@`OA&rdL}8JuWbH%Plq zy84XKJM^G+@l_>6-tT(h_@CQVp6n_gdB161#W$kpNOld}iZUM(HAn>H(>)0z$TKb3!R2C*hGJSVnwlfweaPw&}LKb`9-?;#Nd z$6N{}CfJuXoOgdCKDL8$j;)b|J$^Vk&1Z1c5Whjv3}elSVNFzy$b{b+g1Pqp;Eu4G zY#KwqJKX98h_&eqe|3iePB3)4L#;f(FK#N3<*o2z2Y3&F*@rY?AgT3Grc!zeFqIgU zUP*7=$XMhR0#f?)^m;>GOZO2_^1QE`oEJiJ&c)ipOd;oSQJ5*#rWms5jVZG5zVC=L zmbXMTIg|BqP&e{{@k=^lV5f0aZ%}OTZ%OMw_s!pQe*E?GnXMv z&5sz(BYkrpjU0eps1jK|0{lGDKe7mqkoHFw;w*CQk*etDff@&`zXcov!uW_xp7)#3 z7O2sF&y&7+*32f)MAj#;UTiSg%14qF26)AkKmhs`JPhfm5FJ|vNY4E1)DY2N4`VAJ zv23tm9zhL5O#?N=d*Ep?KOSBsKgq;7e?i(?BE6FIb=?u7K8Fmf{ZlAAy1;a|W1bMa z;L%o^qql){V%~r}Jz%)V4aXa{A1igv4?)A198@Q|>zhDA6BQOdwCz>VY<^WNHpdu_ z)?gBO1QB?4+ar!Bhr=MJuuN9(80>6v(iJs1_5mL2mjI0Q@B=gDOaFhvE=1ecO)UIN-w>P+))6b)c; zsF5gjv_^Iq+Lk)U^64rIKc?+4n6D+_uZnq%uZsDNe-_6#?t|%fR}Jw0bnNTgC+3^m z`%0aQ!OGkppkEws-Y4cc436~RWLlW4M`U&+@-d+nUfuTDy%9}2VALHjBH;WTbksdC z>i@Pn`i4{E4CyL{KM{ajwFDNY+yeH=Y-_AI=DT%E<5S!!sohq-*VXMC5!1X* z@y-uTAP21I=t^-z;)Sp@k904?g!oeV8}W;Q%h%C_V>cCHphb#BH<|F9x<{)tu31%a zXS1!w+9ap3wJyfw4DJmXvYg%J_)LT;b_k^-1DdLH;jAyfS&e23(D-S$@BC$SO6oD1 z9KZYko;@5FrNi%4cSHvW_*kqMiee0r!}-jY*U^FS!;!<|6`0TQgbw3SWYoB-c&v(d zQ*%J=(GsQ=(h*Sk1n$@`8(OEWj8T-{8mmInA{A&w7-Zf7HUT3w_bpIHnK8kMOfXRx zf@we*V+@!iTf^T&pqwT=I$@-j=4t7KwLA_Db&o0{t4IJBf-FJ`f!|vfRGfS@Pxl|U4u1sqi))DTX*yYaOqFD=(@Y!BHNa>!kDPI-QI5jBP&f%I~?3uGyV9Uo%wHQq+0UnWk2pWA#g5>7vx+Wc9H; z8}dj^%%CLjMcx=AYp$GfaM7*brOm!TL!xlba>sm{eY?VkO}`X|NUG9@1({ zOxS$V;5;Al!?}EGE(EfCwZ2vdDIYI6YD>i1$)~oo)+=5Ei2U?9O?rIo=Wb+rZ*V3@ zzp}YStXJ2(1pZKh^h0cI2RuRV2LmZ!LsLPM*f&GaAYkh1sOzKZ_66Vz02cu!K%Kfk z>MPGf-E`0PP6piEtLC;Gdw?Wt(HlpDZoV32s<{I0F!vsJ2(sMpp7Z?cI#am2Jo3C5 zY6cInZ7ESewvIF{nufn42No6JspRaU(%7y(8g^(;HCM0X^~eiLwG;i~G`y9REsl-a z=1qqSPaO@0biyXmv^X=v9$W$gFOM7WC{MUVUk>SLUSD|aSd4EnakcYtCV77`tG*2D zKJ^AUv$zibNK%?gLw|yvw09_3)Rc|Gy0H3M_%n;OL)`#if>Sm2v0YRu{6%94~ZA%n~v zw3w7D06S*=Vd=z>MxUAU3X$ZYrAg60!pi8pC=Xj`cv?f2FHOR&Wb@LaX~8y-ey}}e zeK4b%e_d#3gV(MsEGDy;nIhLoXvfm-9QXzUDFU)>Sz`3ClwYUh_)gRj+efK{^e&r* zKPPvVJ*f(An=E=VfqB|T)<1a=Pb6vfZ4#=!?!sl9uO0+?N)7 z5k5r@Eq}drmcM@FDDnt1{50P82z7w}1egQ74{$l)ZGflV<2wb}==zcIK>4fRas$GH zE^Jf`l?D6e`Rjr$M!*HYkpXxtVAfxD_s@WnVT|p7bwG~*9OtiT9Z^9+>#rG60*-)& zB)}TzFb=R1z6sMek4IPz6pDSmx)BXv0bWfFw+9+M!ejnX{0mUZ?qX=04ZIY8AEfA@ zR0kA_F9#`!P$~lo#naCQNopvT0Eyzyf|L*_6##|ezXd5;C}jbK;uF5IyU_^iJwl3~ z=DTUlBm9|ceY#qWz+UsANm*INAVeCM z&n1gj-iT=PKLVc+wLZ)b`pLZJ8PRk6GvP^f&07ndSs~ zr?ELxWFkIs?|&Y?==k$tn0_zje@g<*)@X&F_Wy&o41Q~Yzk!bOz|THP-4LV}0d?|! zNBP{XWH-1~?0PrDwzw5+tosn`(G33}a+n-mwG=|hsMVA3*Q9!N8z$t_)lcGur0}^U zJd;d+F4Hzu3^8nVYpm^J6;fG~T9E07LCi(hV7^fN*8LugbPQkvNR*Da0dD6Js2>G* zAK)(ld!X$!z_$P)`;jIOU@pK$fWPb~XP(Q2PjP|gGV_0sReN?ph#S*_a@P+&*I5g> z?aMNyRCHEbt7{Tl@ML^*X!R^D;s;5?n(gpk2H&hPq^*+^tUE=HO=@X%cK|msIfiJj z*v?oO;Yp%jn^r>?Mi)vKNf&kjCZF&o(o6-Q3w{=k8ZlgFK7{F9KpO|W>na5_^DEU1vI zdftFPB|D#gI`Y>%10-_20Xs`Z7rQ$g-M#wZXFR38daM@b3oH19{yn@MuWY3)u!Ol>D#^5dcB?Yrxvx z(0T)8=@l2L2=0*WFC>Bl4!G`6O7<8z|pjocLDvjMh|K7+e6f(P^n9=(KbhaZskqph47@W4pPH+zv>zNr9NQL%9p>^aHKMAL|> zUtulOp^B#5Yp*2dUdhjS_?e~8pxk9ERxVnTi;T~%U9lnucsgew4F$^IH;PH#t50-q zeYF~=%v=rsngZ}8z!1PWfC~VB1NaB|`F9KTbb7FR{{_XpvJx-_-2L$ONgBr3O@8;s zI?W+?vI3DMGf6zT`^VLqW+3diPuQ|+b&v!0G|Cab`weEtUUGc*ym%N1I$9(IuO87QNpEMYbJza z6kJ#v6bO+hx^j4sgt&wlgNpu@zx$aWxFE7dQHEpJeF>5G=6dg|p1{xjzWjcb>aMQt zuI{d`s;)OD+L@LU3_jC}AIF(b`LM9lUo5fl|8YGiv7t~3{f`Uv>|zk-3`HD5h}-=R z(!SXKBK{l3CrP1d8vJiijm0P1TUAq3(al{56?AM_rm4u{_egexh27q^pwmqFm-~_S z0zf~&zsTQ%{mlDr@^wgVY@G+0-tFOd#Obb{dreD`%>TlLWTIwXu$$QMybF(t6loEt(}qus$r@G<u|-ESYY&j;qLUa`H+dD%Kf2pLjD8H) zEcGJ;I}nYKu+Wd86bq#Vfl?}z9`UmSF$f#Fuj?#GsOhfjXtb;O1y8aAI*l17JmWL2 z#o3xmc#5%(){(z`am+59R4<2AsreIb#@txM_95<&6XzXr6m-Lx3%`0vRBUci+J<2qQ5`D8&yI0*EJ z1oO9M@yNgktrEuYd}?nn?7W6Uk0V})U?v2?C_i}J{>XO zQp8rb%8s(xE0j75)cg0#nETa*gsxKsAcEEz2J{#yj69uJN}kFu2;Zx8{En(E=S-jw zz2t-ZvYES-S|^*o{AO|S@|&}YQzd4q8QL0^)YhX0j?YSF1TDxWb*I@4JZ-rlkKx~U zg>pTv1pX5j7LrdP#8m3-I8Se@D?>dcBrPrv^!hu6EQm|VS>P+Q+WABqW5h@D>acLm zedPwipd4P-IJL@XGum->%@xjm8Zkl)ITn{zAK}X=$HG=mtRW3>rT3V<$*!`clp`VD zhf|K(<5rlg2@aK!j&?yww}!$lKk7>ZjD_v)RKSY(f?^EN8x$r*eDsd1P#RxfH`{xD$?pZP^x9Hs%Wu+wW8fD zEa(e2$1}&NG3t91X@7ums!XxNx)XizKer>dI*g6CBb}o=Wf89bwfGeEkzAy$A>j#Q zt7~8eDixiTQnek>p>eoFo&lH3;%?<97*W@uwkFuez~)?c>pHJ)$9Y#9saDax1s##l zb^zMGC)*Pyg?`~4fb|B}O8%ZODsq@7!WzaW+UsDOpC`X3N*thiozzTzn4YhJ*Iq) z2R20BO|+HM{iRI*dza~|e0QV()9}_P;!XLF&B=DgvBBrFo$>653wPSK!geX*b(zdg zdXQDbg+6jLDHRH(K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R;nSaT87ST%!T#xzh7BTXSxR)hIK%=OunW@8E0rk#J*qA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){Hf|pJ7XF8#Uf6m!xng)I z=v7Ig$3P~h#3#}tV0mo^YyG7SEKZ66E_9)nUiW2kK3S2XpQ?yYc{ngFI*TGMIi>5S z7vIJy;u9X0FKEq&(jrfb&D2SKz)uRDN!?EkjVw;}k<%&nJ@${laJv-B@S*aXi@H^o zci0oaIezX{8A9P2p7*PhLi?}*u9(lnGk~}G=%fW;&rlb>f`w0f%Y_(J&`rHBwO_;i z-}aI@#?+9!F4RL6_DC+-YJ5N)xFzH(V|BP9wzv^j*F8*0OHE_G_L8d9INVE~NS%N` zBh9JtQ|TT|>KJ8Bv@7Bp-et>7u=*c8zZA0;ygRj15#NRdsE(Vv@nNt8QgH&y>v}Oy zYmEvSN=*sc>c!lTpq+_nX<+4BWwxK=Q|+MZLWlhCwk@DD)cS%)*f75nG;8zlEefds z^DUDZV^ZQ2@#m8lgAmsXK=&7?8h9$jB!#@67NKiFTP>OiLMogok8P zXEZ1-crcl0)04oZxMh+RD1eGqr9T{o1T1r%MPLj3e)4{L++-x2@(+vjKdwKNJRcZ- z_7AH!GX2!2gV^H?IE9X0Y*ekf1dgDQ;Eam!_4jzv6>%wfBx7#KJ*n5+M^0tj7cdsM6{Vx(;xF8V+xNAv7r9{^rY~}s4>vU=%RzH%UjWaEojUd6F-iRoqz<+_d$`^cN*9xds%)?E0YmB0}Y&3XRP5UM?MlFd~XAX z1vpFr4wMlI92RxPD$1b)4%tgN9KbP(OwSsX_U}Ml>OKj_bsFGHfO{K(;Z(1HI-Vpi zW@R&beB{Hdw-`ny3$k;Wav#}|J*J-O+q9wxWC2)pKhmPJ`=?Ns&GHuTEwR!s_UKmQ z#$!dQK1ECpIPO&Y?{IB&5ci30OKUis)9_r6pc;(^#5z3+e0-mSQb|g^O1F9?q|+;$jLDinUfwOj7ibAc;2-s zZQEdE#6dXMfO`5#T23bOu7}j*#NvMPWX=TU&mPi}6Ek(KXE0#22VC)X<)8hqK`4c> zes%+;P$y37Dr-FW-OmO%V`#v!pMZ<4?ZATDO9pe&Cmxf7QZ&{GF3#3{U2E}+6Fx>g z+`m!(+u-q{`%%9R0ER*|7{2UB!Xc3%_ZXtf!l>y%ypzwhVN= zdbGhi0_Khfw^T{q$<0wyUK6>LI|0IqZiz&VEl;oUa`x45mrLBV5v5QA8E0d`>H9^C zZ&;!OUBodqpYg&GkIlj-$WLSA@j>Drn-NF*&_F(5r=I3o4{g89;tR64(@P#OzYu$` zxuFT%tL%rC zfDE4Y?M|Vw32rru2w^EaSF_KL3gx-Lw({_`8G&p zf|r|LT+}UfG_Ga&?L`qhcg|ve5u*77uZFj`zP;7~?Jvl@l!od$53R-bHy5eDH}igR znM_?rNdLpo;un|5f(uXRE^>XlG}HD@9pa=wTBz-lBvbXkKz+~Fn7Yoz6Ow9?CaJzRL21C-@46%{FmGs0wAJumNegQHVuV7{OYU3n zH;+1ry?p3Jco{YL#j_q0xIQ)Sby2_O7Y}>bq>#&Wh`C-i>5ZPJ>;yOoaCShHL7gPa ze+idtH#|1HmruCE%+}7UFJ9J!Uhs==dB{g4arLi45JK5%S}owPJxUAw7a_W!=Fl(J zcj>xAAfUm#3QS>*#8_i(T8My6poxDxrTk(Zywis3A^h-TYw^kdw|+KIm%uQ`fZ_0q z-*}IXRu4pw72^v>_{FawD4^Qm7eDVJr^hEvRK#gM6^{lI7&Op==Pi75APj|#f2nBB zBGo{c>P{bBbG_HZr+`yY#3PD{ucJ|E{)F5DzxZAkGZ3LN3K6Px=&RTpG#99fty4<@lDZj+Rvo}LnzgX@i`zKV@`^6&fWd6ti8>}ACGbus@^OsWQ zk_B|=hGc;`$AO>+T*#p)RC670(?;-y&PXbJwO^dx71ik%U-88DGXr`mKGhwGv#VyLEzD2B8D=(Wgi57 zEZ@?)>4h*Wl|U9tWf}+~c=V13X{NXh^;CiCELc!szj)|l+PYj|P+d2bkCa!W;{EN< zRE%cv17zFuvG_Xq+w^4P8Mh8%>%(9nrzwn3E1{IXR=qQQHrR015PLY5sDvMhdwNd& zW=X>}Rj7m+UTi47a}asO?XdsFcV36mRu82$L#ZJ^+YY6TKr6hn8%oc6AdK`v5CabN z2>_!%?668W>y2n~RyVb2xQPARDyBFhn^Xb^Ts|)rHu*#LU}3Hw3qkPWz3Q*NqlB%j z-O+6-D-C!_r zDqK@rv0zaV2Noug)|n>NkYg43Vdm#pL*9I_0N+P0Kltic_0IFfcX<7QqV0Xz<%&4U zzs+^#wknbpA|N>t=5x482SaNQ6iw>uavFymwWMX%$S}Y|E{@ON%m``ZlUa$3Mj`#P z(o^43N?h~-+;{CME#l??&?Wr~un)itzH(zT$(o&1zcMOx&GVrX=1(%M@6}u!Z(7ki z(X^_UcCGAx#^mXnY_;{X91`C4z_G2`Ta?gKH27}qoZ=s)AxA>b>Dv+J!%`Sh1IO;W z9LYVFJHHgqDIRVcfj*azLu=Ic|0o@HSU@=~px(V+I_3t?;d%)LIzQ(*EHMFA&SJPBY2 zco*O$IPfsowDnM?8%8&hZXVspf{x0;k;o(Z<&^0uRmMt3`!Uelob$ELOF>x|^!AW! z?M0jylC8I~ebqybg{DMBe9wE#sULDIuXQH$>IEjEbg)KMt-YhH(Dsbx_2ip}M&b|2 zuMg#9&U{H#zkJN2WYHT1|Q9khu>hM?UIPAAeM0 zy$wr{wq+|u<^Z+yE;Vf_B#EwLWFwsq&kz3+dZ7|z`5JHoF+8#m50S=49>*qf^^wxZ z2B1bm>lVQKVH3V4ljl4i?0_2W*FZYwSkwOEnaFuX&V!BFwxYoVl@U&*05SmIKp0L( z4TJt)lFYdoNs}d`J%lTUe6Z1mh4E0sP}2r#*%EnnZVZIgNsx}7J1_aXL~qw637MOM zG#8MOvwsC;M;rK&Mo0z_Ja2wIO|9EtclN)Iw2J}5ovc1SW9RWa=e(fY3u?$Wv?#-> z%JS*G$EpkLjId8RTERe?SPhwIMtDVe2Wn|D1`ovumt{uyNdc8Dv4DaX*lfj%4adE= zZ(EBGR+6HhMgNK?`EGD3yN!N;~YOKDuK6J;Uc8%MFgs^(UP@6*{MZ4E`59wV%pnnO^C zz>1rtbaS&iom-q8bTJR6W>xWQd{~~N5cU8Wiw3po_oOlAE@z?z3D+F;C=D442eq2_ zq+B2-0WqQhWt@Z+sCu=A`(Xu@Qd%oqx|#PuxkSohrI#)cHfa9TKoWvML1CD_Ku)#>X!-__i8y&JJDG|rPknOB>E>0QV z5$`qlyaNh-5w6c~8|$Ynk5Wy!JyMO%L!H_ndes**_28JoRcK=f*av{E(BJ^fK_k5t zy@08;w*XHHl%3EUmaFEQ~rkAwdLrGzTi=$1FN<$}Lhta@3>Fo!jT z9Mwy~D9VV*By0FU21X?G7#4n&kV#wLQz~F}@Bj{O2Bp|n`pdT{XWG!j51J(tXmB} zX|osvx|WH<2Xa;LH3Hs-+8$o0#~M6|PJOWG>bEF&+K}plZqNjJ#u0(Rrz_1;c3rKr zx|MG0@TD5KHVHiT;^3cMblORLt>gMNlyN_Qk{7Sh9i&@KcaZvbxOR<>luZzA?Ww%n zcJ2mKN^{_|Z>m+VREPF;)jRiUR2ML}t3nn_6wa^{9FR$g?}s!C1dzvXvD)pG3va1| zhcBk!eKP+FIBLlyXqRhnM7kVEy3+Jv53=V!Mqs^@0p)lrgTRY;)8QLE{#1@keZ z2OGP9!=YbZsRxc-Jmrb)>2fZsjO~G*dVSrY9e?4Q+Ge%l9Bp6T+Pu~-XR=y#fio(y>-m{dNw zP8Ju-MHOmJ7I%>L$H!XhByEn^XLP}m(h7K=-P!GYZk<~ zLYbk0Qr|tb53Ieu6P&2#;sumuoDp9QX*wqotR%;ljCYdhwo$c*By7->Zv(#$`E6NW z(FCshUVQU5_yl^6+#5ltA24;<)P>V)^#kA=05<`~L!G*E>hiBcz5T8)`2;W$&XMYc z(;!{7bKzKs%z741(ZAmr_?YlfUDt|jf6 z@Wnw9x03p$qa%Npb1GS0Xhlu>PD*`^99cRIe@<>JeIn`Jim2bFUnvhB9|ei3Whtt| zesPV5Jp063*i7{HpW>+ql$m~Y83BU?`B~oCNuOI|NW_zwVfO}7#MeK1W%j%|P_@}pgkOllbG{gh` z4m!jEJ_pY&`iydmlYGPYE8x&V{c~uk9y(p)7PEZA_@e+XhBgE6QrsS(#6l?+C=?$J zP)0*30w@$ueaeP;^il0t&@j0Y@TiaErIRG*LopZgB%i zd%8@c10RAy$jYZH)mkXVkWZdAGVp2Z+SBQ#S&$~7M4B2K#V7H91TDQc7#A!OdNPnklLE^Z?Bep399t_u_k>zf2HhKElDSA$!izyj&!eUNz(vdzP zozIq%hnL?B>+wATAKc&pER67zs=67GulQ!dOU~e}fd3bP{7*7{MSS+g05vo~{S>HQ z`q1w+b!ie4_NA+39Tt}Pa$p#*2Mb+fpw1du=%f96J%#Xp8}PqOM~Tc1P)`M@D}eeu zS+^oS_#_BqfnS?+lI9gl@J*sxISKzCGG%20ewlQyd?InKwAnS<+9(yH7;8LO={WfA zALr!Cqe3v)#KKi+wgM^0_@YY-Jf%ntJSh7be0z$7PiEQDPp(ri{%L@J!B*0F*2B&1 zf_e|YM*trKgtQ=SF2GEH=K&4?d;u^Bkn{%mVpSHtO$Jt_<@77+{d>VcN3BI!>w8zV zRzUvjJB3n;Tg$9v<)hc)$@o^^$_L?l)LBxzdMDmQzFlp^bwpg9h!>KPYm%o@0jNM! z7%D);8%X;m!21AHuzv!kLahcI^Ck!am&|1eWF{B#D3Zt_7ETnS^f~g*UgSZB(h!P0*cMb~@xQuqwJjDvS%t_k^<_YM)V` zgvSL0fHpcU<)hP5F;W4j7&Ks-ZbrZW6?eU6kADhH{&m8uO zi849SI7YwY5Yk4R(08!MAUd*Qf`kXj?Z%9lx7=Bfc*MZ?i90Cp5!Nfh@2$+6 zsy16j&~Fhmxg5rO#eYLibn|$a{qLK%Fk8K3_LeHFB5!P&5UnyBo~7eMR9H%}{&ZL!uWJgb$}CQz0=4 z>BIKKtr09f)1LE^h%@OgI57OOj3yP;|AnKW4pn5i+g?tl@5sr@TDolc!qr*G^z52t z%Q9(uUlr0)pyf+<@k7rnd4?R?@mM?aGLI9NtVG%?06ziz3UCA9-vAc?E|DdFemof5 zB%;8!|N7@iTIQoRlJr`o)(k%#10qL$dL@QzeQl*yf>-vgdxV(1D+3%L{4mE~_rA_V XHxqu}oG6Se6A@A%C9BXs807x~Vwx`3 diff --git a/boards/emlid/navio2/navio_sysfs_rc_in/NavioSysRCInput.cpp b/boards/emlid/navio2/navio_sysfs_rc_in/NavioSysRCInput.cpp index be17b084b3..3f0ddfb332 100644 --- a/boards/emlid/navio2/navio_sysfs_rc_in/NavioSysRCInput.cpp +++ b/boards/emlid/navio2/navio_sysfs_rc_in/NavioSysRCInput.cpp @@ -119,8 +119,6 @@ void NavioSysRCInput::Run() connected_buf[sizeof(connected_buf) - 1] = '\0'; _connected = (atoi(connected_buf) == 1); - data.rc_lost = !_connected; - uint64_t timestamp_sample = hrt_absolute_time(); for (int i = 0; i < CHANNELS; ++i) { @@ -145,11 +143,11 @@ void NavioSysRCInput::Run() } } - if (all_zero) { + if (all_zero || !_connected) { return; } - data.timestamp_last_signal = timestamp_sample; + data.timestamp_sample = timestamp_sample; data.channel_count = CHANNELS; data.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM; data.timestamp = hrt_absolute_time(); diff --git a/boards/holybro/durandal-v1/extras/px4_io-v2_default.bin b/boards/holybro/durandal-v1/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/boards/holybro/pix32v5/extras/px4_io-v2_default.bin b/boards/holybro/pix32v5/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/boards/mro/x21-777/extras/px4_io-v2_default.bin b/boards/mro/x21-777/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/boards/px4/fmu-v2/extras/px4_io-v2_default.bin b/boards/px4/fmu-v2/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/boards/px4/fmu-v3/extras/px4_io-v2_default.bin b/boards/px4/fmu-v3/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/boards/px4/fmu-v4pro/extras/px4_io-v2_default.bin b/boards/px4/fmu-v4pro/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/boards/px4/fmu-v5/extras/px4_io-v2_default.bin b/boards/px4/fmu-v5/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/boards/px4/fmu-v5x/extras/px4_io-v2_default.bin b/boards/px4/fmu-v5x/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/boards/px4/fmu-v6x/extras/px4_io-v2_default.bin b/boards/px4/fmu-v6x/extras/px4_io-v2_default.bin index cef251c5f50280243052c56143c4d947afe41965..3db45ccdadf8d5e7395ba1aaf08590efeabc9e42 100755 GIT binary patch delta 10003 zcmYj%34ByV(s=iqBa@3v4w4DE-ehu2G6|WG2*Dssu9ss135N)HFc82&Q33)Rku?(n zIEXInwzxpRML`8|7jm&g2$Nmi&wEWk_T&7Ei#h`8zJ%kwx!(I%Phdau`_)t*)!o(A z)m7E?vcHGv>1J?GCtiqiO8l5#2~El}v6# zyun=ELtc)oOGbRM%-XYUB8)OC5v%ECc$0`(%olqJA322?>m}pIEK3$)!GYz?)tX+! zGh&=s)1TIhSbUg{C&$LTrbPURL~5d@K;eu;oKaJuFf5VJqP}42B(h68mC2RJdF@1I zhD5Z{wlOPxxC5D(%UA7)Pmsuq(aFpw0kStbkGT{epGC99R|7R1;y(`j`xV2hF1|q^#LQ- z|0DlW!|nCWh(8-3{}YoMZ-JfWU+1ga?G7%Ai{~C+j`_6`@y2AtocFhJ$arH&HLMG3 zgh?eoF~^=@zV(wEu`9yVUZgj349|FpEiR7XJIK1YRA$>L@;aawPIVuTdjdCx`H@~Z z9ET9E@?$9JpoD^@3@G`0%Heo~_5D9;Er`E;vbne2uHqhBt{m2?&9LC>K0^yOsW0GC zLo=-(^mQ+Z-+@yNfv|cN*W+Q#?d8fL#2#?sq63bSemHafuU-=4tWJDA#rY=EMC?TxI6XLd zzK^Mkwd0~#TXQvXSx8%Qk&@wWd&r68^!)Wwnbppv*cbyoT-1#DgPtqb5yt#+pVBa; z-e5D>v8nM2Yaalm{W}Rs$!z`BmtBMTd0w496L7Nch`qzEu%*`^{%0RfKVl!Z%4kh? zC=5l-41dd$Wex8{e1Sg`Fy3dQe-ypzE)yq^BPr3XtO~JafDC{s0QIoZO2ArxoLr=dfz4M!TM5*Y z0rCKJ085LI=F^9eW-QSBV=~gj_M!~SNPYPdz0!(aQ^Fp0d037)Mlao$k0Z?-n5W*@ z+^gauxVZEGxfQ*|VQ9Y<9pX&vlZ7`$Ql6Twnw|$VWO-^qLp`iOxuUDmR!uLAXb+BX z7U^+~Ec{)Z4>M|eRn}yC9?0VZkGAjHHe7VAonG|d*xqR9+Y5c~6L;#QqFtV0Fg5r0 zs@Wwz+zARFpM>OR+bDtZT{4v?8!So71L^eO2u7fPFIZgO>7N z+$;I9=%(9DE~KTzz!`{3%9XYTUN*ySS-+bsVQoe#Ol_|$d@d_fRTpJp+I^y8mecl+ z3PKiiGWm&3W#VNLp`QiXch*A|>ocJ6u7|v=|03y*4;5S>p9lY~_g8JA&ZY!a!@$THMR8#%n2<-&$>m?S(T&8hqfcD(?dh2L;A2$Eby zc4j;r@^7z5rAme~l0Z_CnMoy7irQW!H?PxSXF-Z*#riyPjlPm|*y(+ZmK6H%8ir>@ zRciPU)?@yEB_qcGJ`1Dze=LDD&`Ep+^O5pOJ|30yQ{O;28XZ3zAlj^qulf5 zJTf(Fsw$}4q%Er<63n=a*yjGxmMdAADaOFP^9>%I*qgw`Th*Y)DRxmPp2kh;O|VkxuY4<3(8K)3`(1_7f?vx3~Os_{|O5c>rH z6)4Wob4CzbyNB(=#cZB11S$zEmw>pH92%}y(cTZl#y;inoM5>}Bs+}hV=(`wXzYsv zQq1oa$$&963-eVTYz*O+4gL43IuE>fw@Yn`8Omu<4%dJYEA|j&&fJCIOhvY@94uI^ zh>Yh4P4)`g)An{74BR|=W5MKu9aM`ycWu5E?flsNe^VC2sPW?6t}W1xjNcAvK@;8x zAY<(w9>k`9JbKnk-p(jYQ?n54*qd{z+tY?t}4f%W7~=w+G+aHkm8G zjaI+aj`$~K^7q_wrb#Ah(^L@K7?ISNatk)e7er*nyAIscFgwa$aSe<^>}1aAvVcJC zGUep^;Mx7#Eq}VF)I#1gr7#XJ88A)BdQU=zbPnrvAgJ6xI)@BuJ&g!50<>MNXP}%K zAnAE8wjw^=ui|Pt(XcHfZ>^Cl$94Pml%GtlsWDtj$UDT)#Q zsPr~aSb%~FQlRW;ps=X2pQ997pr{K{IDlfcpOgr&K}ok*l?s=F(eDq$-eOkliv&+>!Y_j9PEBaKb-HT(UVt0odmw?+5}QH z_UV9UrBBldXS-J0A7qUDJU)S`3Q&CxMf|@$7;P*pc!<#kNOQqNMj0T73esbL^1pAB zyI!Jd!h#KKL$1r@N|vFAY!!CSHelaXeG{(TWuiAfFz2Elu{PVN z;+6F4xFq{^H+4=Q`A6s>qhWWFUH*TUK|Uy*v3__RrBlyN>k4oX3fqUntRXz;?eoBh zXnHYU>L>4+vnF1ULekaND0ZB!|3{4_ApG8iTd)X4D|0g%3dB z_(u=a+FC`aNcQZk{Ksg}vJ6LN7L**zf% ze@l8NWRIg`Xh<8hiBGeg2ew^O;&Y%+BDp)^Mcw`GPc2Ae?v1hTJeF(^2;WKMm7=Vq zK}lsh@GL$QL#{o`5W~t?f(%W|K(j?N`LamQY>^0GlpeC$YlfYiC5gq^G>k8P{wajQ zI1mP>0O`*Y8LQ5wfzV(*IPvd5+Kd%*Iy>S&Jb_%luIu{l*Tc9`iZy+|?!R=eUj+4x z2l*lX5s@@ka3GsGBJ~EM1@Y5Q;Nd8Rfsax&_r5iJP^se%rbkpFeG2#8IK}WmHR3x1 z)?KZb^I zG!SpL$U=*Y984;SER}ojpa#nsBP{tGxt>&wi%4PeSYwu)(fOX9<#N*yztc}WPNrSY znSrWO&g1^#4rg8NWbSWnqN^OQl!c8hQdgO*lZDkm<9KOsLuzrQg;U-LgU$hXSya|T z;RA{MvohWoD_ZEL!GrE~BZn;0`z{MP;GcD!xg63XUJEOh^pg`@4UAfQnkcKYrf7R{ zItX2#VGamKeaP_9_4p!iIz`tOUu(LyL>m-ahFKE&!Ejz%y8ju}r|nnR4=k01w*%dG zi^pK*W4IF&%QF)K^F(Fo?5dHok5=(#c2$GRcl`)@kqoav3P=l>JTtKu*52tSS(D~w znQD<{GeA28U2M1_8uvT71TKXG@5lFe+kpE!5;^`*t}-CpmdJMxHA3MtiIhxzHm1a@ z=ETnSmY$m*Mx~w!2x}yAVrt$**b9VDV*g4$Oyvces8I`|pE zFCEwlZ^5>JaM5D~NuHSCfRO3S^<)HhvE*$Ge*p!^4jyCkT%pMWtv z2-ySQr5;a&+1ht)>m_ygxq#5)A(zX?6}$twOwB@Lrv*;QEANM2;a-$02|G_~`x!9f zyX>el*$i(BGP%0qo+)puPKcI;Xb&1?Hciii*tufTR;_sSCAYtG{tyGnpEtpr}fKYUr_O9d^ z1i?0Jhq2zb@yrQox~t4^EVb$33#!n_hmMFe zN$3hp6qS2Fud3l9&MVI>;PjjYmK_f%5J~tbK+3E3#!14ufO1$FUdYYk4i76Czwj?F z8L6sNNH9h`W&!oO1l{(dcGN2P zMjzH!-2D^s39ou-=?y43gQa~?YWL=F6?eBm=|yNOyZaiHp7+um2|OMGh+htn8HhN9 z`7BRVhqIxhOU*{@d8xM45#6ES(}7BY6u@I**v=p?e7}tN?*k2Y<%rcyuXJ>g^7%s$ z%8=d}Y1t;p!L6~r%q6z8@t7IcJj%*M?@8x8HFK`XxjQ8JYs~A2Z$@?{<{_#S*Ot+JhTE>NcdO-D%bIl2kTu*Uo7^mEsdA-1An5c4+!w7jicNlnAg;T3?@jHw3E!n0*KK|L^7{213yB3+n5%15R_tEC}NNACGRv&%pQa) z4N1QSOmkE!h@29*1|EfeBR20JHv?r*Py8}b%q+ljNzu$gJdP}#IVtgD{~Ojf>OQ>A zVB(b7j;;z`sUQx_7m(hWMg^}`kgGHQfkVhUvr6z3^3AN*Th-gYuDHv^?k(RoWP$@t z2)yL}=$0Z{$wwiEALDnpt46|`_Lff?I_Wg<7DbXWDdMDK?Y-7KXr+r-6t~?hSG&I6#LxB=J;U@W^kf$-5?!0 z>FP5^@6dzR#aEROdB5w0<9}{fd9tf~- zoO3CZnBZ8}aNhlm_}C6gIkrX;_W0rGG@rp$L;MCwGmJGShBZ++A`^aR2-e#FgFC`% zvS|$c?r^IYAl9Zc{M8)>IKj~E4z=9pF6xW*^dofuz<$nM&y?z*J&X zdL_MeBV&SwK`@SR2 zSl$xVxH+}(!^_QW!B@!<&kSK@v+KL@$!LUiGJz%>Bj z*4@r%UW*k&^tyY6?Wa3nN`{oqO;l0ZMlyeHTC~ZpI`+7z^tCNTn*CcaG6q{?@3m$w zLz-U)pTK&t!DK5RNmdx(6;lEM=vVMCq_aYFY#AUq^RrV!M1wty zt$@U`!G?JRH4HTk)DZ81r^Wnuc$NGl6X*N|X>W=2O48SLM~M0yGO+efq3q}a)7_4F zLhyn|TWOBo2GWUn1M>8M;UYI2Z`gjU)Hy!{4PSClo#?J_0tro2SoqMkS4Fe=Rk7F{ zV>nuaN#qek;Mr}DIHDX5gPg)LS-oShv&l(0YI5uYI%JA)Eyk75oC`X&QUP1Ji~W-zY*)-3fXZ8SlH*uWeu=I1yvA3>{Kh|v;~V$E^1G`B_43I}-VrPz$ea`|RF~rX4Wr4ww;e{ti0p z9+>riTOEDFC@Oq#beeqD0D?ie;2RtjydI`9I1h?SM~rEcE5=}Ogmi#qZ7c0lcbNLJ z`cnGnSj1m(AiiC`=KO@Fw~MYhqK?6fe7g$b(vPH36Qks&-A+DQH3K%MG20n_om5fF z@S)&OApl_bl~Ng0nE-}#6~mthK(1N>i&Jg^`((B?Rvh!)x~1_cZk5z-E8pwt_Kk>X zUZ;5HhbE8%R&;cwxFPXESei$=mtjJDsr-%j#lYq3Xu`3ZiZIY3#iE-`cuw7;RT|f< zs<^Y+R%30F)7V-UV{!)fh74KG?s9x4!W27%(vbm8)wyui7vQW$vju4UwA*+7GP)%7 z7)_2}egMxNj*HUa_o_Rh0|b05Rt!ZkhRET3=F98oK=|Rv;qeO0=XgSgaVRosTva?) z#k;9Fp!R49(+cSbsC)ukP?;%i56CPbK(o6HSbirC4hlaXG6_HgWfD1vPV}rlbxi7`!)*Vr9 z#J?k*2SI%}PD4OQicomMU%9Tqnz~Up?YgZy`U1H0CtP&*Q(@-_bRp7B8M6SR)c1nu z+Z|anS@v4prLHsAnJP%;JLlX`DSqD&4i0cvh~gY(x7SL-?_@^*J23aF<#AULU$z`x zg2!$uH80mKx~U4a!s(P(xz95Ck`zgpE*EkX*UFn}hu|QNK-BP7`Qv9#f^B&G+)3x2 zkOk*nBn1l-TG!Xdg5OpTo}|VZd{mS3!&?@`x*0{yv_-23yVs*0Y;rytGQ))pCxODD zc(yJUD0Xm^M&~-|e7a8Oq9bFQ54`ewuA^&qC(hRl6}1#~o^+=>LBIgB}Z+Ecsu#jmezX3YXFg-KBq~Kul?MOOz#cO z1?I1#D<4XcGHo2pR-TT^)6ORNcM+d;#DhzyzpM z7f5~Od8nK2+1|;3n|syVmSYc)ge`jGXwc19qf9kdz#Zn^;|@WV8{TuCe_dw^cb7+= zH$%S!M$*xtWKmN#4(s09q`)(21AV-zU_!TqjE@bOtwyd$9BY#W z1LQK0ar#g^FGtnUwDwD*Im!k;S)=i(#H<;ZQ{U7m_Somyy}|kmsOhBW%joL7h>4=qiK{t-B%>!Lhtq2Xx_S-vz0x020EkER9tK>ES{ znDxPoYW{Vhp$%TUvap!UUS^71C!rlnyK~?h45SFiwq=RY!%}{olH)s3M{FN$C8T%R zH2gWav+PM#aNA_jlL^ezKC=GFgLooIvwxdJ7oc4kWq1D!I2q>H4p;~65rE_THLW8mC}{mPBTB## z(2)dK0|UkZR>C)7`sVQn%b|s0pRaC216Y7pQ^W0nMvw5Ae-!@$EoFBx^vwoZioXxG z=%7>wEfil4wj@HS3|c6jem2;ohGGdcQT$o3B?L+Z&_eOwf-PDoWkCzYCwyghqY>77 zgcLu`chj0j_%qr1bhR3Rz2-y7zn-pBfm2}BBy)v`Je2T+(w5x6$IUH6CFL`Rduy*jX~=xN^h^9RJWqXL_8ZtgK=X zB8|)ElEo`;M6~%Iflr89ALa-BWM1=(=sEtG@T9utt%ct`(7d0_UzKE<8f^VC*t!W? zU-qLrjm?=N6Y+_A|MT!g$Da?=^m{S?TM}rtMl1Yu{2#n!@LLP?4Rn?Ve)iGU4Z+qT zXr27uSw43w*$r+LyWY*PEp7!H>plc~G{ZlL943cXErn1rYV{=iHK|_Rh6(v}^^PG?I2lxxX9_Tv_@GU^dex%6*mNU~-1URc zb=E>|`?5@1DmtsJ)isGNcrv~@w0f2n@q?sc&35=NgKyRt($>id)}129CbhJ>JAfLQ z97A+eY-cRY@FdZ%O{<}dQAR0~l(7r2_=Go+W-0(>_*uY|Sta0i0OkVFO>6~xKQS}_ zb+Tb?Id~!0+LZV~sGb0z%{0GTq4z_`Mn=|V0AC5~im;zp*BPRp^2`LsN==L5^PJASizg zSlb&~Z-6Yl;vyBn9kTs}M3BJY7iLFyN(ijU%SaU7@wI>xKTIMwBw%NE<_3i#O9#WL zg{M=ld23XEC^Nr-@_pvSx4LJvrsBdN1JFm8rIMh_Qa0kCOxd78)RtqrxsBWoNVG~q z71`&gR@Xp}KaAXPe8w!6$?>)YOtDO2Ha@{9;ong#t3*cKnbJ!;oLOL(} z(v|B>jH*Mq3+?m?*8|E_<|1>*Cq&Amr#&w=`2f;H^~ClnkIWX8R!k5-hTLk;j(^RY z3+XWogq_}yW9EKZdc#Z1o5nGK>Ni=&(9}B3l}2zr;fkN^*)##aLcZLznOWy2b2iuG zTjb5nrE#NFN^pjfUo*X=&m%PZ2)~()9L;@ZK;{$jlihD`iBjU8?%tOLoI_KG7$HQ{ zh^k*6&#qmuA_r(XXCMs)O5Zn%N#3hZ zbZ>pN8mG)$4gZ<~@Fl#@J1M z_s2TTA$YPvBTHtIcyjlTt2NEgu;YHimR+lZ6tJgJium1cFgx~=}fBLj>8 delta 10088 zcmZ8{349bq_Hb2C&t!6uNhXAlvnP{dl8`Wv06|bDSLc{Of}nD#0|6WrC0xq2WBt8w#n=|F}@kE(USVP{bjGxZUp{ z?ThU%;=f^hk`$_@!GD8lEI!%Zs+yvTZtg;;pkvE2O+^;JN3tUf*u z0Qv#`MgAV_XWn;{uS0TU>paNxZV$&JPS=fkj$_0zW-J^z)gBdk7LUNfTT&LUt59)R zI4F^uVXrgxCh}5vWdar|CC;8&mnpNMNLBv$i|A19A8WZBLGm*v(>rlSp~QR7fC+I3pf_#B_XP_yuEU>WGjiSnLNiU;(o;fv_^#_Mcv1|CX;zl6PXP%c_k`U z_nmCwyRQq|s)yFsAz`dSzKBYSDS?^h+z`qd?G8SIkKrGE5(|9_@kFIYY2*eTnQr!} z2Vz5NpwlrjG3!q<_sis_epyJ28yUKqg~A}c#<8^Y0NO-8J}@2 z&emMQQ;c;qkNoY6V|L-BdO4&@&7W{H=Efqn4{?W_IPZ|7pd0pF_|;3IVsn!sKSDkE zFg0C=if8#)UN7P7tWFf4U`E1Ki98lN5lduG>_aRPh(vyi-Nc-d$;#2M7D#U(?d}6e zI~5u;R?Nr3ri7kEJ(mB<+wSJ;I@Ej^zpfPtPe|mWyq0<-Op@pt*THnmCkr~lfuTnv z7{4`(M+Qb{l{mhj8>b+HB5v%|b+9}ZKJ#i@1EMP2^dXb`G64*WB zBDT6!c9hLtp{27xynnxpxnEsK=sHyZENGo!P#ztyqn-z+X(esflFs>Dn+LtUei+IrN$@ma}?patHf?lilBr!_a^G5q_k zP_D<7z<=VxLh>num`c4J=jm;AWvHiwq{ZcdTz{vK1#u}k3w(uEJD+G{jQB`i9Tv{H zuiQWwgu}}kr&bwlMmx@~xx(2`BSwfJ$KulJBYYXg}{1_cW9BBSD6>0SyDAh7pRkYZ^TG4J6 zCiI1ypHJ)$9Y#9sZ`On1s#!4 zcL3_XC)*Pyg?`~4fcXaIO8%ZODsq@6!WzaW+UsDMpC`X3N*thiozzTzn4YhJ)(S$ z2Qoz7O|+HM^`%7rdza{{e7C0n(eTnJ;!XLF#mRQYvBBrFo$>653wPSK!g49%b(zdg zdXQDbg+6jLDHRf>K5{PUYvzcXv?NEXTl0}Nnsg>lV;R9B5nuAA$TNP9PpQB{mYX#m zdQK6~lAYW%+R#hRaT85+U!wu&zS8|QTXSxR)hIK%=OunW@8E0rk#J&pA2A!!!^Znq zekNbe%i>5sS!6IX(LS=7PY%`W){7H%H;7XCv~FD$*ATroTp z^r|G$Z6K3V;uGl>u)MZ|wf@ou8Yjg72fENpkNYw?pR7pHPgTUHJRGPNokbCsoYHmE zgKy&$@d*#h7qsR>YLTbKX6mFi;3tKSr0%DRMi!^~$mx{(9{We2yIl$;_)z)HMa?S9 zJM0Ny96$G}454rg&->L$p?%l@N6cs98Nl0obkG9OXQ&Hb!NMoLaXGU zZ+pocV`@lV7wVw`dnA`^H9nvYoD%Ytu{vB4Til4N>mDviOHE_G_L8d9INVE~NS%N` zBh9JtQ|TH^>KJ8Bv@7Bp-et>7F#8`pzZA0;ygRj15#NRhsE(Vv@nO&eQgH&y>v}Oy zbBziaN=*sc>c!lTAf1V6X`tm>WwxK=Q|%z@LWlhCwk;qtRQrNO*f75nBy02VDGI3o z^(~VbV^ZQ2@#m8lgAmsXK-U+i8hFaZB!#@67NK3+*zwn3ggE2@lDp z&S(%^uwXLLrYC_(amyqtkN^>_N`E*E30USji$E9n{p9`hxXDO3>n0yWcsO32foJ{FbW;L*r-}{2@F9a!5J0d>+jK|E8=}F;{QDdN<(M1m}*BBT`pYxEXGGADN zg>tW&FKov-)SJ5>}B~mtxQJj3^Z_Bow0_a6!}Pq@VyNb z7N9T%C{RWuP*~I%t0;vIC}c0CZ~(<9GCgZl+P?#Nsrw{s*J*$+0q!jXhF!e^;&_t0 zn3c`!@sSU+-eMS;EXdAf%6()<_LzDqZ_|n*kOg4X{YZ<>?w>+UHp^SUw!})m*rQvG z8;=#K`V=uaV7OE5zr(T7f!`;(Ev@0OTMv1UchWN%3hC;uKZHsH`7-Y>ZJS|HO`Wm8 za+XKi3cI*Q*L|1OQPem2)Bi7tZV#2jU|C!}Oh?v@xt}@XAt%R7WKMdBFeXLc;(6Dm zv~7c)5eM#E1M2A~X*rq9yB<=L6N~%FlQ|QZKYK_^PR!J`p22|99&p9mm4Eib0-+Sf z`q>SXLX9}htE};0cRw58jG+O;egY1*wgU@pFB!~9pLk3TO3_#&xHwz)b*;rOPWTx0 zaQ{aAZ-d2)?nnJP0O$%)XZW%o36}u=0V0;0n@vp?U1RVr3!|n7@lHP1j)eqoA*^r# z$k7Jx2pBsa%u*$JCpSk;X-(u(?gVfvx+M}dwmiMY%h^}MSuSzYN|ZtsWSor!qwg0j zzG03IbP>nce8vk~JT?oTAU}V{&ZHFrc=_Z&~K`$eapoHwU4tNp}hjs+t)a-4y=&qoTzr39HhW?=g-WZ}3BsCaSQ zx~aMjoWg=kdfw4&z3-a`=-h3Rhp1yq-C1hnfo{45wiHE z8<{+pb=|TUdWyXAKuZ0-kEt;TE)N6qCW{Zc(@Ne2zgi8>#VJtR1>MmS4)uv!<=eoO z32ttFaZ$I_(YTi7w--h5+&PQ=Meybmyc*u#`u17})W0C}QW~o3JhT?y-&~~r-pu>O zWimA#A^i_SjbB_M3obmNyU6wJ(oEYsb%>J!ez9LHJ1N1cZGnbC=WMVcGi7RlB#SJz zeMA;ai-X?pmw$ET+>olTNTwDiKZ;M}LEQ--`x=0Iy_>u`EsK>!i<_L8Rs)F`H;J`8 z8&%}f@KS5z+7q`vi%2>ri?2vzuVu_cS^OAWcBy;05Tf?LS<$LR=vye%z-Bw38}~gLJNB|HE|iGJ!a>(?bx10tgKd;ZRbj05ThM&6Xp+dX!gMHoL?W*i zj)BB9sr`$>a%}XAD}4WQ`Nd~_*I_6%8}O*ut1dIlIGo>h9P9%bSNu4$1}<#H>CAjD zIaNFrWJ~Q+^9Aj}1F3Ki^NYu2Hc9op2~q>ze%B>wfq6q~qOFGiN?K6k7b6ssUUJ`p zzj@S2?Bzo*!p*3`FP`<7!1SqkuZ!9>zj)ZgCWTz4UCi~eNpJK#WhX#MfU*O;3~D4< z{!2JyyWz6oy?nwQX0~=-eetp;^nzb}%R@dYiK~AVoDfP@(`o^O?NM6bUj*-hszbk6 z-=*sg0fz?jDo}+r5@U_EX~6?Ffh7KMmGX;ua8Db~hw#Ift;Hw*-~8D?UIN7&1B$~h ze&anlT0Ia!R*Wwk;TOLKr+`X_U;Mm_oF1PvQ4y#4R6H6;V9-Ddp11JLfiM&{{-vTh zi&O()sylsj&h=gsp8`fj5sxS)zK(jO`4e&r{Nj6E%s_<7C`72%p|4`c^ne4E(p>Z+ z|MNwZ)!*kAn?b~p>2mMJr2G;K&)y7S{bIS7?4M9o?-z@_lldb9Y_NJj&!h+u%wI~G zOBRr!8#(!&n0q2u^DloQ4$ zCi%#w@)F>3hliXkuT1cZwVq69?-yV4s9`G8h93T49AC-%#Q*UUb44sMO)LlMj8kOw z#PkTb@_~llYe%gK=DM4Hi;CQVmZMs`Ok~coO zTJpHwf~$$zy6FX7$1G{Qj)lWPWCWf!y$sPhY>l;3Wkq!{Rqj-=yWCW<%i=yT-)rDf zRnQSpm1d_`*+oh?@I!BYd&mHL3Q1fKT=+iiuboa zQ!$#w50Gus$KvbcZ_|^FXWTmQtq+5SoTe~Bt%OqkTJ_HK*`UK&L+s&Lq7r^2?&&%8 zn|T18$@joER{u zPXHMGVTV=1S#Ly>v%0BG!$s`hRx!m9*`yLUpz?XKu*n~?2McrkSO|g}?^S>G9VKjK z?T)54QZ%;@3r~~Q8OeA)>6sucZ@0AC9J+6c zV}fmkt;;!2oeVThK?xTq)09DtXa4jHH;_?ZT-}R>c$ucR7ioJo6_uUCf&nf<)g|~m zd8c}L=sZvMT4c;{90 zQ{kH0iUo^`IIu8@w9YiCh8(NN4>Lc<8uI3Y1^7O4`N3Dms&}3*zQgMe6m9RzE?2}+ z{%x)^w^fm>5COr7FrUL!Iv84eplDKGm(w`ps3k44Muq_%a&dhAW=2ROpUg^RGz#gT zm7e;RQsSZ);J#~5X%ROEfKKUOfPDaFu$3E|N!IM7`jt_kYn~6CFn^M1eXr)?c+-mB ziKbP(v}tAkGbT^pWUH;8<&f~U2exh1-lBw_qQQ4-=M?`a4LK5ePT!6&AC|(98Yp(( zrAY3v-1((=PVsQv2=uvx99pBk|3~St!vex-0rBqj(mpqM4%bU4(D*seVTlQlaz>*q z(VA43Xics&+7A|Woa@B`e2V5am8v3P+^CW;B z;9Y>1V8g>;(bhwnE*M=%x_ERU3py$XMyw;h}s~4Dv(!m;4wf2s(LfbQ%*OPA^8i_w7 zzdn?cK?k4%&IViq5Nh4$j2v>TQ1#K1>JfK-+~m{?9GUX)Xf>ssL*_o59QmkEef&|0 z^)@U)+Lo;tnFFPzcT3ZjLXhY>MmEy<@ci&Ep%p4YmahRf5W^!2@epZzj zY=F{esNDj1KP9l#yhV% zhVS}a11KV>mo+>CYUij_>of`~V5JKt8m+PjPc*zNrJAFRED1lRswd$C=_-bV9m8a9 zW$>|u<#e{;18FKcUq-0#IQZE1W+{!Ub)qaJeB&qIh@O?Uaq^+Sy(_@5LQ*{Ue z5twnalx}Wzr*n(5gD&R5(5xz+jStIn6v7%HW6_{i{hl<&+~rKPAmN&$9;G2;;h@SNpuSV^&-T$(zc<~5;AG)drAeY4j#b4%^(!}N`Ltl!t>28j6&i&&iN2>-n+tm$PbbJxX3!w0fKvgojJ zFl-isK-MyG_&}}-UL)XcsO{l}daS{d=+Fm?u6~Phrwyq-=mtrkdmItye7e#sW!Kd@ zt6S-^4j-z4Ym>lYFAo0MMTecl*E+6WLmBt;CwcK2T|v6UbOot>hhx|1NZAD5)}G4C zZRc(qZNO@GREWQO(d%R*!dKZ22IPSe1roj}*|^0!rkJzT1!CSi+ERGdfP`%j zg`_v10t<$mgH$g{OBJBsx()_z3O5yG8g-fa{3&QoCr%5knoaK?w?1Xb-bI||U%*Vs zLGtmUN_YhfuALIR;2_e{)><;XHUkH@uc=kxOj8@lS90APe|=sE7yr z9W;mod=9Q#^cv+BC;5i)S3seK{O3?pJ#@OpEoS+K@kaq#40Q&erMNv%5(}wVD53ah zpky?pBA|rg>2CyzG?3Il5yg80B|(t#0~-|Y43y{~H3TITZv`BQu)!_f^3p&F&AG)5 zB<<-kjSg%G3Lz_>u2gFw8ACpK+Q`7u*0rb8O|u|OLJMhVY!siw|KYUs-eBM|#`K0% z_{14LlD{mK(T0$D%RXf;c}dbUzdare&2%7Q96$-A^8rr%gqxhfTLJ$Uq4=L<`il7Mje*k8Kuff|>Bs`gAOFy|zLI0-#{sl`($5{_2 zw+r$;03QK-3=qm6p@5sQ2#$1s$~(Wv%aB z)mj1Zv+opIQruc*Eh`_r7Ei{v`c^&&?@?z-@#>v;6Zv+v5!VrMbs}C!My^SoN*SOG zQD!Iu6>lKzn*i?vP{#fVm@>5*aLk*)2w=*r8!*|prU+jnJ!=wU`l0AcfL;LlGE!{t ziRb-fa7`*cMMgcBhr@{VIb-DeZn~lOOLRkq;Gx|^>Yw|Q`XV&i*p8o{fTO>V=0e13 zu2L;*oQZ`9AQ|ayuUtCn|PnnDagFF&aJ{iOJIHYd<82lP(UOy!~A37`mmQFwEE+D4Ts-2~04W~W{L0<)qsq|CS=eUCZ&q4pW| zNqAg<0jQ(HQaU;;Wg``UvO#^Ot;hHAoA_N2nU=-pNwcF&GY4wILdi|XS!Sh7K5UrB zl*lA%(_>6De9f|HC3ccuHyufT3LbHpBVMr(0>`13uiRjw)J^POw8tyDeQXl*J#*MA zCd%YQ;~4#pLr5EOLf^q21MkR+2@)P8w;MBJ-g0L_;1L7iC+?uYBdk}1@2$+6=-8>#f|NG`G%vLX%y`>7P$QxUxL=RK3UvTjLl@CfnPdLl&0aw@<;fi{9)+MEk5S??gle%Us3o)GvuE4km!X4;lrWHR0vE$ z_^>^3YXpnWwCB7e;!OGl2Zk@pXi!o8UpN}_kVTfe_2p#xj-0HlrOTEtT%CnX&#qav zER)vvRUs_}n!a=wKlIF!XUL%)kF_%|^Eh$IN~FC4@DsqV05<^s4R8VA5?S)+$AiI4 zA_{E#uYaDTWj<;nNv~CE&G6|M6msOJS7ON4*H&sJxMlCUR}iyzWq<;hAEx;0-q)Gv WX2S2A6NQmwB0>s;WEJ{@PW~@R3NDHO diff --git a/msg/input_rc.msg b/msg/input_rc.msg index d26c31ea0f..cf194c3b49 100644 --- a/msg/input_rc.msg +++ b/msg/input_rc.msg @@ -1,4 +1,5 @@ uint64 timestamp # time since system start (microseconds) +uint64 timestamp_sample uint8 RC_INPUT_SOURCE_UNKNOWN = 0 uint8 RC_INPUT_SOURCE_PX4FMU_PPM = 1 @@ -16,22 +17,16 @@ uint8 RC_INPUT_SOURCE_PX4FMU_DSM = 12 uint8 RC_INPUT_SOURCE_PX4IO_SUMD = 13 uint8 RC_INPUT_SOURCE_PX4FMU_CRSF = 14 uint8 RC_INPUT_SOURCE_PX4FMU_GHST = 15 +uint8 input_source # Input source uint8 RC_INPUT_MAX_CHANNELS = 18 # Maximum number of R/C input channels in the system. S.Bus has up to 18 channels. - -uint64 timestamp_last_signal # last valid reception time - uint8 channel_count # number of channels actually being seen int8 RSSI_MAX = 100 int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception bool rc_failsafe # explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly. -bool rc_lost # RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usually means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. Will remain false, if a RX with failsafe option continues to transmit frames after a link loss. uint16 rc_lost_frame_count # Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality. -uint16 rc_total_frame_count # Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality. -uint16 rc_ppm_frame_length # Length of a single PPM frame. Zero for non-PPM systems -uint8 input_source # Input source uint16[18] values # measured pulse widths for each of the supported channels diff --git a/msg/px4io_status.msg b/msg/px4io_status.msg index df072e71c2..5eb74deb76 100644 --- a/msg/px4io_status.msg +++ b/msg/px4io_status.msg @@ -13,17 +13,10 @@ bool status_fmu_ok bool status_init_ok bool status_outputs_armed bool status_raw_pwm -bool status_rc_ok -bool status_rc_dsm -bool status_rc_ppm -bool status_rc_sbus -bool status_rc_st24 -bool status_rc_sumd bool status_safety_off # PX4IO alarms (PX4IO_P_STATUS_ALARMS) bool alarm_pwm_error -bool alarm_rc_lost # PX4IO arming (PX4IO_P_SETUP_ARMING) bool arming_failsafe_custom @@ -39,5 +32,3 @@ uint16[8] pwm_disarmed uint16[8] pwm_failsafe uint16[8] pwm_rate_hz - -uint16[18] raw_inputs diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 7927c623e5..d20657410a 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -202,6 +202,8 @@ private: hrt_abstime _last_status_publish{0}; + uint16_t _rc_valid_update_count{0}; + bool _param_update_force{true}; ///< force a parameter update bool _timer_rates_configured{false}; @@ -546,14 +548,14 @@ void PX4IO::Run() SmartLock lock_guard(_lock); - if (hrt_elapsed_time(&_poll_last) >= 20_ms) { - /* run at 50 */ + if (hrt_elapsed_time(&_poll_last) >= 10_ms) { + // run at 100 Hz _poll_last = hrt_absolute_time(); - /* pull status and alarms from IO */ + // pull status and alarms from IO io_get_status(); - /* get raw R/C input from IO */ + // get raw R/C input from IO io_publish_raw_rc(); } @@ -1119,12 +1121,6 @@ int PX4IO::io_get_status() // PX4IO_P_STATUS_FLAGS status.status_outputs_armed = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED; - status.status_rc_ok = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_RC_OK; - status.status_rc_ppm = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_RC_PPM; - status.status_rc_dsm = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_RC_DSM; - status.status_rc_sbus = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_RC_SBUS; - status.status_rc_st24 = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_RC_ST24; - status.status_rc_sumd = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_RC_SUMD; status.status_fmu_initialized = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED; status.status_fmu_ok = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_FMU_OK; status.status_raw_pwm = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_RAW_PWM; @@ -1134,7 +1130,6 @@ int PX4IO::io_get_status() status.status_safety_off = STATUS_FLAGS & PX4IO_P_STATUS_FLAGS_SAFETY_OFF; // PX4IO_P_STATUS_ALARMS - status.alarm_rc_lost = STATUS_ALARMS & PX4IO_P_STATUS_ALARMS_RC_LOST; status.alarm_pwm_error = STATUS_ALARMS & PX4IO_P_STATUS_ALARMS_PWM_ERROR; // PX4IO_P_SETUP_ARMING @@ -1178,12 +1173,6 @@ int PX4IO::io_get_status() } } - uint16_t raw_inputs = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT); - - for (unsigned i = 0; i < raw_inputs; i++) { - status.raw_inputs[i] = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + i); - } - status.timestamp = hrt_absolute_time(); _px4io_status_pub.publish(status); @@ -1198,11 +1187,18 @@ int PX4IO::io_get_status() int PX4IO::io_publish_raw_rc() { - input_rc_s input_rc{}; - input_rc.timestamp_last_signal = hrt_absolute_time(); + const hrt_abstime time_now_us = hrt_absolute_time(); - /* set the RC status flag ORDER MATTERS! */ - input_rc.rc_lost = !(_status & PX4IO_P_STATUS_FLAGS_RC_OK); + const uint16_t rc_valid_update_count = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_FRAME_COUNT); + const bool rc_updated = (rc_valid_update_count != _rc_valid_update_count); + _rc_valid_update_count = rc_valid_update_count; + + if (!rc_updated) { + return 0; + } + + input_rc_s input_rc{}; + input_rc.timestamp_sample = time_now_us; /* we don't have the status bits, so input_source has to be set elsewhere */ input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_UNKNOWN; @@ -1232,37 +1228,19 @@ int PX4IO::io_publish_raw_rc() channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS; } - input_rc.timestamp = hrt_absolute_time(); - - input_rc.rc_ppm_frame_length = regs[PX4IO_P_RAW_RC_DATA]; - if (!_analog_rc_rssi_stable) { input_rc.rssi = regs[PX4IO_P_RAW_RC_NRSSI]; } else { - float rssi_analog = ((_analog_rc_rssi_volt - 0.2f) / 3.0f) * 100.0f; + float rssi_analog = ((_analog_rc_rssi_volt - 0.2f) / 3.f) * 100.f; - if (rssi_analog > 100.0f) { - rssi_analog = 100.0f; - } - - if (rssi_analog < 0.0f) { - rssi_analog = 0.0f; - } - - input_rc.rssi = rssi_analog; + input_rc.rssi = math::constrain(rssi_analog, 0.f, 100.f);; } input_rc.rc_failsafe = (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_FAILSAFE); - input_rc.rc_lost = !(regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_OK); input_rc.rc_lost_frame_count = regs[PX4IO_P_RAW_LOST_FRAME_COUNT]; - input_rc.rc_total_frame_count = regs[PX4IO_P_RAW_FRAME_COUNT]; input_rc.channel_count = channel_count; - - /* FIELDS NOT SET HERE */ - /* input_rc.input_source is set after this call XXX we might want to mirror the flags in the RC struct */ - if (channel_count > 9) { ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, ®s[prolog + 9], channel_count - 9); @@ -1276,11 +1254,6 @@ int PX4IO::io_publish_raw_rc() input_rc.values[i] = regs[prolog + i]; } - /* zero the remaining fields */ - for (unsigned i = channel_count; i < (sizeof(input_rc.values) / sizeof(input_rc.values[0])); i++) { - input_rc.values[i] = 0; - } - /* get RSSI from input channel */ if (_param_rc_rssi_pwm_chan.get() > 0 && _param_rc_rssi_pwm_chan.get() <= input_rc_s::RC_INPUT_MAX_CHANNELS) { const auto &min = _param_rc_rssi_pwm_min.get(); @@ -1292,23 +1265,30 @@ int PX4IO::io_publish_raw_rc() } } + // regs[PX4IO_P_RAW_RC_NRSSI]; + + // (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_FAILSAFE); + /* sort out the source of the values */ - if (_status & PX4IO_P_STATUS_FLAGS_RC_PPM) { + if (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_PPM) { input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_PPM; - } else if (_status & PX4IO_P_STATUS_FLAGS_RC_DSM) { + } else if (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_DSM) { input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_SPEKTRUM; - } else if (_status & PX4IO_P_STATUS_FLAGS_RC_SBUS) { + } else if (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_SBUS) { input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_SBUS; - } else if (_status & PX4IO_P_STATUS_FLAGS_RC_ST24) { + } else if (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_ST24) { input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_ST24; + + } else if (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_SUMD) { + input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_SUMD; } - if ((input_rc.channel_count > 0) && !input_rc.rc_lost && !input_rc.rc_failsafe - && (input_rc.input_source != input_rc_s::RC_INPUT_SOURCE_UNKNOWN)) { + if (input_rc.input_source != input_rc_s::RC_INPUT_SOURCE_UNKNOWN) { + input_rc.timestamp = hrt_absolute_time(); _to_input_rc.publish(input_rc); } diff --git a/src/drivers/rc_input/RCInput.cpp b/src/drivers/rc_input/RCInput.cpp index 071a678d0d..4bec4a26a4 100644 --- a/src/drivers/rc_input/RCInput.cpp +++ b/src/drivers/rc_input/RCInput.cpp @@ -48,12 +48,6 @@ RCInput::RCInput(const char *device) : _cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")), _publish_interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": publish interval")) { - // rc input, published to ORB - _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM; - - // initialize it as RC lost - _rc_in.rc_lost = true; - // initialize raw_rc values and count for (unsigned i = 0; i < input_rc_s::RC_INPUT_MAX_CHANNELS; i++) { _raw_rc_values[i] = UINT16_MAX; @@ -203,8 +197,7 @@ RCInput::fill_rc_in(uint16_t raw_rc_count_local, } _rc_in.timestamp = now; - _rc_in.timestamp_last_signal = _rc_in.timestamp; - _rc_in.rc_ppm_frame_length = 0; + _rc_in.timestamp_sample = _rc_in.timestamp; /* fake rssi if no value was provided */ if (rssi == -1) { @@ -244,9 +237,7 @@ RCInput::fill_rc_in(uint16_t raw_rc_count_local, } _rc_in.rc_failsafe = failsafe; - _rc_in.rc_lost = (valid_chans == 0); _rc_in.rc_lost_frame_count = frame_drops; - _rc_in.rc_total_frame_count = 0; } void RCInput::set_rc_scan_state(RC_SCAN newState) @@ -531,10 +522,6 @@ void RCInput::Run() fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, frame_drops, st24_rssi); _rc_scan_locked = true; - - } else { - // if the lost count > 0 means that there is an RC loss - _rc_in.rc_lost = true; } } } @@ -600,14 +587,13 @@ void RCInput::Run() } else if (_rc_scan_locked || cycle_timestamp - _rc_scan_begin < rc_scan_max) { // see if we have new PPM input data - if ((ppm_last_valid_decode != _rc_in.timestamp_last_signal) && ppm_decoded_channels > 3) { + if ((ppm_last_valid_decode != _rc_in.timestamp_sample) && ppm_decoded_channels > 3) { // we have a new PPM frame. Publish it. rc_updated = true; _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM; fill_rc_in(ppm_decoded_channels, ppm_buffer, cycle_timestamp, false, false, 0); _rc_scan_locked = true; - _rc_in.rc_ppm_frame_length = ppm_frame_length; - _rc_in.timestamp_last_signal = ppm_last_valid_decode; + _rc_in.timestamp_sample = ppm_last_valid_decode; } } else { @@ -730,7 +716,7 @@ void RCInput::Run() _to_input_rc.publish(_rc_in); - } else if (!rc_updated && !_armed && (hrt_elapsed_time(&_rc_in.timestamp_last_signal) > 1_s)) { + } else if (!rc_updated && !_armed && (hrt_elapsed_time(&_rc_in.timestamp_sample) > 1_s)) { _rc_scan_locked = false; } diff --git a/src/drivers/rpi_rc_in/rpi_rc_in.cpp b/src/drivers/rpi_rc_in/rpi_rc_in.cpp index d565bac27d..18aca8c89e 100644 --- a/src/drivers/rpi_rc_in/rpi_rc_in.cpp +++ b/src/drivers/rpi_rc_in/rpi_rc_in.cpp @@ -115,14 +115,9 @@ void RcInput::_measure(void) ts = hrt_absolute_time(); _data.timestamp = ts; - _data.timestamp_last_signal = ts; + _data.timestamp_sample = ts; _data.channel_count = _channels; _data.rssi = 100; - _data.rc_lost_frame_count = 0; - _data.rc_total_frame_count = 1; - _data.rc_ppm_frame_length = 100; - _data.rc_failsafe = false; - _data.rc_lost = false; _data.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_PPM; _rcinput_pub.publish(_data); diff --git a/src/drivers/snapdragon_spektrum_rc/spektrum_rc.cpp b/src/drivers/snapdragon_spektrum_rc/spektrum_rc.cpp index 228b422500..2b518b6f83 100644 --- a/src/drivers/snapdragon_spektrum_rc/spektrum_rc.cpp +++ b/src/drivers/snapdragon_spektrum_rc/spektrum_rc.cpp @@ -184,8 +184,7 @@ void fill_input_rc(uint16_t raw_rc_count, uint16_t raw_rc_values[input_rc_s::RC_ } input_rc.timestamp = now; - input_rc.timestamp_last_signal = input_rc.timestamp; - input_rc.rc_ppm_frame_length = 0; + input_rc.timestamp_sample = input_rc.timestamp; /* fake rssi if no value was provided */ if (rssi == -1) { @@ -201,9 +200,7 @@ void fill_input_rc(uint16_t raw_rc_count, uint16_t raw_rc_values[input_rc_s::RC_ } input_rc.rc_failsafe = failsafe; - input_rc.rc_lost = (valid_chans == 0); input_rc.rc_lost_frame_count = frame_drops; - input_rc.rc_total_frame_count = 0; } int start(int argc, char *argv[]) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index d3c4a8fc47..51b605d6a0 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1996,12 +1996,8 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg) // fill uORB message input_rc_s rc{}; // metadata - rc.timestamp = rc.timestamp_last_signal = hrt_absolute_time(); + rc.timestamp_sample = hrt_absolute_time(); rc.rssi = input_rc_s::RSSI_MAX; - rc.rc_failsafe = false; - rc.rc_lost = false; - rc.rc_lost_frame_count = 0; - rc.rc_total_frame_count = 1; rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK; // channels @@ -2063,6 +2059,7 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg) } // publish uORB message + rc.timestamp = hrt_absolute_time(); _rc_pub.publish(rc); } diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 7d22df983c..2d02e8353e 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -56,7 +56,7 @@ #include "px4io.h" -static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len); +static bool ppm_input(uint16_t *values, uint16_t *num_values); static bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool *sumd_updated); #if defined(PX4IO_PERF) @@ -72,117 +72,92 @@ int _sbus_fd = -1; static unsigned _rssi_adc_counts = 0; #endif -/* receive signal strenght indicator (RSSI). 0 = no connection, 100 (input_rc_s::RSSI_MAX): perfect connection */ -/* Note: this is static because RC-provided telemetry does not occur every tick */ -static uint16_t _rssi = 0; -static unsigned _frame_drops = 0; - bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool *sumd_updated) { -#if defined(PX4IO_PERF) - perf_begin(c_gather_dsm); -#endif uint8_t n_bytes = 0; uint8_t *bytes; bool dsm_11_bit; int8_t spektrum_rssi; - unsigned frame_drops; + unsigned frame_drops = 0; *dsm_updated = dsm_input(_dsm_fd, r_raw_rc_values, &r_raw_rc_count, &dsm_11_bit, &n_bytes, &bytes, &spektrum_rssi, &frame_drops, PX4IO_RC_INPUT_CHANNELS); if (*dsm_updated) { - if (dsm_11_bit) { - r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_DSM11; - - } else { - r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_DSM11; - } - - if (frame_drops == _frame_drops) { - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP); - - } else { - r_raw_rc_flags |= (PX4IO_P_RAW_RC_FLAGS_FRAME_DROP); - } - - _frame_drops = frame_drops; + r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_DSM; r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE); if (spektrum_rssi >= 0 && spektrum_rssi <= 100) { - /* ensure ADC RSSI is disabled */ r_setup_features &= ~(PX4IO_P_SETUP_FEATURES_ADC_RSSI); *rssi = spektrum_rssi; } + + r_page_raw_rc_input[PX4IO_P_RAW_LOST_FRAME_COUNT] = frame_drops; } -#if defined(PX4IO_PERF) - perf_end(c_gather_dsm); -#endif /* get data from FD and attempt to parse with DSM and ST24 libs */ - uint8_t st24_rssi, lost_count; - uint16_t st24_channel_count = 0; - *st24_updated = false; - if (!(r_status_flags & (PX4IO_P_STATUS_FLAGS_RC_DSM | PX4IO_P_STATUS_FLAGS_RC_SUMD))) { + if (!(r_raw_rc_flags & (PX4IO_P_RAW_RC_FLAGS_RC_DSM | PX4IO_P_RAW_RC_FLAGS_RC_SUMD))) { + uint8_t st24_rssi = 0; + uint8_t lost_count = 0; + uint16_t st24_channel_count = 0; + for (unsigned i = 0; i < n_bytes; i++) { /* set updated flag if one complete packet was parsed */ st24_rssi = INPUT_RC_RSSI_MAX; // input_rc_s::RSSI_MAX; *st24_updated |= (OK == st24_decode(bytes[i], &st24_rssi, &lost_count, &st24_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS)); } - } - if (*st24_updated && lost_count == 0) { + if (*st24_updated && lost_count == 0) { + /* ensure ADC RSSI is disabled */ + r_setup_features &= ~(PX4IO_P_SETUP_FEATURES_ADC_RSSI); - /* ensure ADC RSSI is disabled */ - r_setup_features &= ~(PX4IO_P_SETUP_FEATURES_ADC_RSSI); + *rssi = st24_rssi; + r_raw_rc_count = st24_channel_count; - *rssi = st24_rssi; - r_raw_rc_count = st24_channel_count; - - atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_ST24); - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP); - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE); + r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_ST24; + r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE); + } } /* get data from FD and attempt to parse with SUMD libs */ - uint8_t sumd_rssi, sumd_rx_count; - uint16_t sumd_channel_count = 0; - bool sumd_failsafe_state; - *sumd_updated = false; - if (!(r_status_flags & (PX4IO_P_STATUS_FLAGS_RC_DSM | PX4IO_P_STATUS_FLAGS_RC_ST24))) { + if (!(r_raw_rc_flags & (PX4IO_P_RAW_RC_FLAGS_RC_DSM | PX4IO_P_RAW_RC_FLAGS_RC_ST24))) { + uint8_t sumd_rssi = 0; + uint8_t sumd_rx_count = 0; + uint16_t sumd_channel_count = 0; + bool sumd_failsafe_state = false; + for (unsigned i = 0; i < n_bytes; i++) { /* set updated flag if one complete packet was parsed */ sumd_rssi = INPUT_RC_RSSI_MAX; // input_rc_s::RSSI_MAX; *sumd_updated |= (OK == sumd_decode(bytes[i], &sumd_rssi, &sumd_rx_count, &sumd_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS, &sumd_failsafe_state)); } - } - if (*sumd_updated) { + if (*sumd_updated) { + /* not setting RSSI since SUMD does not provide one */ + r_raw_rc_count = sumd_channel_count; - /* not setting RSSI since SUMD does not provide one */ - r_raw_rc_count = sumd_channel_count; + r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_SUMD; - atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_SUMD); - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP); + if (sumd_failsafe_state) { + r_raw_rc_flags |= (PX4IO_P_RAW_RC_FLAGS_FAILSAFE); - if (sumd_failsafe_state) { - r_raw_rc_flags |= (PX4IO_P_RAW_RC_FLAGS_FAILSAFE); - - } else { - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE); + } else { + r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE); + } } } + return (*dsm_updated | *st24_updated | *sumd_updated); } @@ -218,6 +193,8 @@ controls_tick() * other. Don't do that. */ + uint16_t rssi = 0; + #ifdef ADC_RSSI if (r_setup_features & PX4IO_P_SETUP_FEATURES_ADC_RSSI) { @@ -229,45 +206,39 @@ controls_tick() /* use 1:1 scaling on 3.3V, 12-Bit ADC input */ unsigned mV = _rssi_adc_counts * 3300 / 4095; /* scale to 0..100 (input_rc_s::RSSI_MAX == 100) */ - _rssi = (mV * INPUT_RC_RSSI_MAX / 3300); + rssi = (mV * INPUT_RC_RSSI_MAX / 3300); - if (_rssi > INPUT_RC_RSSI_MAX) { - _rssi = INPUT_RC_RSSI_MAX; + if (rssi > INPUT_RC_RSSI_MAX) { + rssi = INPUT_RC_RSSI_MAX; } } } -#endif - - /* zero RSSI if signal is lost */ - if (!(r_raw_rc_flags & (PX4IO_P_RAW_RC_FLAGS_RC_OK))) { - _rssi = 0; - } - -#if defined(PX4IO_PERF) - perf_begin(c_gather_sbus); #endif bool sbus_updated = false; - if (!(r_status_flags & (PX4IO_P_STATUS_FLAGS_RC_DSM | PX4IO_P_STATUS_FLAGS_RC_ST24 | PX4IO_P_STATUS_FLAGS_RC_SUMD))) { - bool sbus_failsafe, sbus_frame_drop; + if (!(r_raw_rc_flags & (PX4IO_P_RAW_RC_FLAGS_RC_PPM | PX4IO_P_RAW_RC_FLAGS_RC_DSM | PX4IO_P_RAW_RC_FLAGS_RC_ST24 | + PX4IO_P_RAW_RC_FLAGS_RC_SUMD))) { +#if defined(PX4IO_PERF) + perf_begin(c_gather_sbus); +#endif + bool sbus_failsafe = false; + bool sbus_frame_drop = false; sbus_updated = sbus_input(_sbus_fd, r_raw_rc_values, &r_raw_rc_count, &sbus_failsafe, &sbus_frame_drop, PX4IO_RC_INPUT_CHANNELS); if (sbus_updated) { - atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_SBUS); + r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_SBUS; unsigned sbus_rssi = INPUT_RC_RSSI_MAX; // input_rc_s::RSSI_MAX if (sbus_frame_drop) { - r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FRAME_DROP; sbus_rssi = INPUT_RC_RSSI_MAX / 2; - - } else { - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP); } + r_page_raw_rc_input[PX4IO_P_RAW_LOST_FRAME_COUNT] = sbus_dropped_frames(); + if (sbus_failsafe) { r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FAILSAFE; @@ -277,56 +248,51 @@ controls_tick() /* set RSSI to an emulated value if ADC RSSI is off */ if (!(r_setup_features & PX4IO_P_SETUP_FEATURES_ADC_RSSI)) { - _rssi = sbus_rssi; + rssi = sbus_rssi; } } - } #if defined(PX4IO_PERF) - perf_end(c_gather_sbus); + perf_end(c_gather_sbus); #endif + } + /* * XXX each S.bus frame will cause a PPM decoder interrupt * storm (lots of edges). It might be sensible to actually * disable the PPM decoder completely if we have S.bus signal. */ + bool ppm_updated = false; + + if (!(r_raw_rc_flags & (PX4IO_P_RAW_RC_FLAGS_RC_SBUS | PX4IO_P_RAW_RC_FLAGS_RC_DSM | PX4IO_P_RAW_RC_FLAGS_RC_ST24 | + PX4IO_P_RAW_RC_FLAGS_RC_SUMD))) { #if defined(PX4IO_PERF) - perf_begin(c_gather_ppm); + perf_begin(c_gather_ppm); #endif - bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count, &r_page_raw_rc_input[PX4IO_P_RAW_RC_DATA]); + ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count); - if (ppm_updated) { + if (ppm_updated) { + r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_PPM; + r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_FAILSAFE; + } - atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_PPM); - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP); - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE); +#if defined(PX4IO_PERF) + perf_end(c_gather_ppm); +#endif } -#if defined(PX4IO_PERF) - perf_end(c_gather_ppm); -#endif - bool dsm_updated = false, st24_updated = false, sumd_updated = false; + bool dsm_updated = false; + bool st24_updated = false; + bool sumd_updated = false; - if (!(r_status_flags & (PX4IO_P_STATUS_FLAGS_RC_SBUS | PX4IO_P_STATUS_FLAGS_RC_PPM))) { + if (!(r_raw_rc_flags & (PX4IO_P_RAW_RC_FLAGS_RC_SBUS | PX4IO_P_RAW_RC_FLAGS_RC_PPM))) { #if defined(PX4IO_PERF) perf_begin(c_gather_dsm); #endif - (void)dsm_port_input(&_rssi, &dsm_updated, &st24_updated, &sumd_updated); - - if (dsm_updated) { - atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_DSM); - } - - if (st24_updated) { - atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_ST24); - } - - if (sumd_updated) { - atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_SUMD); - } + (void)dsm_port_input(&rssi, &dsm_updated, &st24_updated, &sumd_updated); #if defined(PX4IO_PERF) perf_end(c_gather_dsm); @@ -339,81 +305,40 @@ controls_tick() } /* store RSSI */ - r_page_raw_rc_input[PX4IO_P_RAW_RC_NRSSI] = _rssi; - - /* - * In some cases we may have received a frame, but input has still - * been lost. - */ - bool rc_input_lost = false; + r_page_raw_rc_input[PX4IO_P_RAW_RC_NRSSI] = rssi; /* * If we received a new frame from any of the RC sources, process it. */ if (dsm_updated || sbus_updated || ppm_updated || st24_updated || sumd_updated) { - /* record a bitmask of channels assigned */ - unsigned assigned_channels = 0; - /* update RC-received timestamp */ system_state.rc_channels_timestamp_received = hrt_absolute_time(); - /* set RC OK flag, as we got an update */ - atomic_modify_or(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_OK); - r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_OK; + r_page_raw_rc_input[PX4IO_P_RAW_FRAME_COUNT]++; - /* if we have enough channels (5) to control the vehicle, the mapping is ok */ - if (assigned_channels > 4) { - r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_MAPPING_OK; + } else if (hrt_elapsed_time(&system_state.rc_channels_timestamp_received) > 200000) { + /* clear the input-kind flags here, but only when disarmed */ + if (!(r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) { - } else { - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_MAPPING_OK); + r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_PPM; + r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_DSM; + r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_SBUS; + r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_ST24; + r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_SUMD; } - } - - /* - * If we haven't seen any new control data in 200ms, assume we - * have lost input. - */ - if (!rc_input_lost && hrt_elapsed_time(&system_state.rc_channels_timestamp_received) > 200000) { - rc_input_lost = true; - - /* clear the input-kind flags here */ - atomic_modify_clear(&r_status_flags, ( - PX4IO_P_STATUS_FLAGS_RC_PPM | - PX4IO_P_STATUS_FLAGS_RC_DSM | - PX4IO_P_STATUS_FLAGS_RC_SBUS | - PX4IO_P_STATUS_FLAGS_RC_ST24 | - PX4IO_P_STATUS_FLAGS_RC_SUMD)); - - } - - /* - * Handle losing RC input - */ - - /* this kicks in if the receiver is gone, but there is not on failsafe (indicated by separate flag) */ - if (rc_input_lost) { - /* Clear the RC input status flag, clear manual override flag */ - atomic_modify_clear(&r_status_flags, PX4IO_P_STATUS_FLAGS_RC_OK); - - /* flag raw RC as lost */ - r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_RC_OK); /* Set raw channel count to zero */ r_raw_rc_count = 0; - - /* Set the RC_LOST alarm */ - atomic_modify_or(&r_status_alarms, PX4IO_P_STATUS_ALARMS_RC_LOST); } } static bool -ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len) +ppm_input(uint16_t *values, uint16_t *num_values) { bool result = false; - if (!(num_values) || !(values) || !(frame_len)) { + if (!(num_values) || !(values)) { return result; } @@ -441,7 +366,7 @@ ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len) ppm_last_valid_decode = 0; /* store PPM frame length */ - *frame_len = ppm_frame_length; + //*frame_len = ppm_frame_length; /* good if we got any channels */ result = (*num_values > 0); diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index 73c82dae9d..18314ded07 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -98,29 +98,19 @@ #define PX4IO_PAGE_STATUS 1 #define PX4IO_P_STATUS_FREEMEM 0 #define PX4IO_P_STATUS_CPULOAD 1 - #define PX4IO_P_STATUS_FLAGS 2 /* monitoring flags */ #define PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED (1 << 0) /* arm-ok and locally armed */ -#define PX4IO_P_STATUS_FLAGS_RC_OK (1 << 1) /* RC input is valid */ -#define PX4IO_P_STATUS_FLAGS_RC_PPM (1 << 2) /* PPM input is valid */ -#define PX4IO_P_STATUS_FLAGS_RC_DSM (1 << 3) /* DSM input is valid */ -#define PX4IO_P_STATUS_FLAGS_RC_SBUS (1 << 4) /* SBUS input is valid */ -#define PX4IO_P_STATUS_FLAGS_FMU_OK (1 << 5) /* controls from FMU are valid */ -#define PX4IO_P_STATUS_FLAGS_RAW_PWM (1 << 6) /* raw PWM from FMU */ -#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 7) /* the arming state between IO and FMU is in sync */ -#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 8) /* initialisation of the IO completed without error */ -#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 9) /* failsafe is active */ -#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 10) /* safety is off */ -#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 11) /* FMU was initialized and OK once */ -#define PX4IO_P_STATUS_FLAGS_RC_ST24 (1 << 12) /* ST24 input is valid */ -#define PX4IO_P_STATUS_FLAGS_RC_SUMD (1 << 13) /* SUMD input is valid */ - +#define PX4IO_P_STATUS_FLAGS_FMU_OK (1 << 1) /* controls from FMU are valid */ +#define PX4IO_P_STATUS_FLAGS_RAW_PWM (1 << 2) /* raw PWM from FMU */ +#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 3) /* the arming state between IO and FMU is in sync */ +#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 4) /* initialisation of the IO completed without error */ +#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 5) /* failsafe is active */ +#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 6) /* safety is off */ +#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 7) /* FMU was initialized and OK once */ #define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */ -#define PX4IO_P_STATUS_ALARMS_RC_LOST (1 << 0) /* timed out waiting for RC input */ #define PX4IO_P_STATUS_ALARMS_PWM_ERROR (1 << 1) /* PWM configuration or output was bad */ - -#define PX4IO_P_STATUS_VSERVO 6 /* [2] servo rail voltage in mV */ -#define PX4IO_P_STATUS_VRSSI 7 /* [2] RSSI voltage */ +#define PX4IO_P_STATUS_VSERVO 4 /* [2] servo rail voltage in mV */ +#define PX4IO_P_STATUS_VRSSI 5 /* [2] RSSI voltage */ /* array of PWM servo output values, microseconds */ #define PX4IO_PAGE_SERVOS 3 /* 0..CONFIG_ACTUATOR_COUNT-1 */ @@ -129,17 +119,16 @@ #define PX4IO_PAGE_RAW_RC_INPUT 4 #define PX4IO_P_RAW_RC_COUNT 0 /* number of valid channels */ #define PX4IO_P_RAW_RC_FLAGS 1 /* RC detail status flags */ -#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP (1 << 0) /* single frame drop */ -#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE (1 << 1) /* receiver is in failsafe mode */ -#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11 (1 << 2) /* DSM decoding is 11 bit mode */ -#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK (1 << 3) /* Channel mapping is ok */ -#define PX4IO_P_RAW_RC_FLAGS_RC_OK (1 << 4) /* RC reception ok */ - +#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE (1 << 0) /* receiver is in failsafe mode */ +#define PX4IO_P_RAW_RC_FLAGS_RC_DSM (1 << 1) /* DSM decoding */ +#define PX4IO_P_RAW_RC_FLAGS_RC_PPM (1 << 2) /* PPM decoding */ +#define PX4IO_P_RAW_RC_FLAGS_RC_SBUS (1 << 3) /* SBUS decoding */ +#define PX4IO_P_RAW_RC_FLAGS_RC_ST24 (1 << 4) /* ST24 decoding */ +#define PX4IO_P_RAW_RC_FLAGS_RC_SUMD (1 << 5) /* SUMD decoding */ #define PX4IO_P_RAW_RC_NRSSI 2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */ -#define PX4IO_P_RAW_RC_DATA 3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */ -#define PX4IO_P_RAW_FRAME_COUNT 4 /* Number of total received frames (wrapping counter) */ -#define PX4IO_P_RAW_LOST_FRAME_COUNT 5 /* Number of total dropped frames (wrapping counter) */ -#define PX4IO_P_RAW_RC_BASE 6 /* CONFIG_RC_INPUT_COUNT channels from here */ +#define PX4IO_P_RAW_FRAME_COUNT 3 /* Number of total received frames (wrapping counter) */ +#define PX4IO_P_RAW_LOST_FRAME_COUNT 4 /* Number of total dropped frames (wrapping counter) */ +#define PX4IO_P_RAW_RC_BASE 5 /* CONFIG_RC_INPUT_COUNT channels from here */ /* array of raw ADC values */ #define PX4IO_PAGE_RAW_ADC_INPUT 6 /* 0..CONFIG_ADC_INPUT_COUNT-1 */ diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index d8166d1dbb..aa55779c5b 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -106,8 +106,7 @@ uint16_t r_page_raw_rc_input[] = { [PX4IO_P_RAW_RC_COUNT] = 0, [PX4IO_P_RAW_RC_FLAGS] = 0, [PX4IO_P_RAW_RC_NRSSI] = 0, - [PX4IO_P_RAW_RC_DATA] = 0, - [PX4IO_P_RAW_FRAME_COUNT] = 0, + [PX4IO_P_RAW_FRAME_COUNT] = 0, [PX4IO_P_RAW_LOST_FRAME_COUNT] = 0, [PX4IO_P_RAW_RC_BASE ...(PX4IO_P_RAW_RC_BASE + PX4IO_RC_INPUT_CHANNELS)] = 0 }; diff --git a/src/modules/rc_update/rc_update.cpp b/src/modules/rc_update/rc_update.cpp index bb2d711d66..ca9fb0345a 100644 --- a/src/modules/rc_update/rc_update.cpp +++ b/src/modules/rc_update/rc_update.cpp @@ -372,16 +372,14 @@ void RCUpdate::Run() if (_input_rc_sub.update(&input_rc)) { // warn if the channel count is changing (possibly indication of error) - if (!input_rc.rc_lost) { - if ((_channel_count_previous != input_rc.channel_count) - && (_channel_count_previous > 0)) { - PX4_WARN("channel count changed %d -> %d", _channel_count_previous, input_rc.channel_count); - } + if ((_channel_count_previous != input_rc.channel_count) + && (_channel_count_previous > 0)) { + PX4_WARN("channel count changed %d -> %d", _channel_count_previous, input_rc.channel_count); + } - if ((_input_source_previous != input_rc.input_source) - && (_input_source_previous != input_rc_s::RC_INPUT_SOURCE_UNKNOWN)) { - PX4_WARN("input source changed %d -> %d", _input_source_previous, input_rc.input_source); - } + if ((_input_source_previous != input_rc.input_source) + && (_input_source_previous != input_rc_s::RC_INPUT_SOURCE_UNKNOWN)) { + PX4_WARN("input source changed %d -> %d", _input_source_previous, input_rc.input_source); } const bool input_source_stable = (input_rc.input_source == _input_source_previous); @@ -400,7 +398,7 @@ void RCUpdate::Run() bool signal_lost = true; /* check flags and require at least four channels to consider the signal valid */ - if (input_rc.rc_lost || input_rc.rc_failsafe || input_rc.channel_count < 4) { + if (input_rc.rc_failsafe || input_rc.channel_count < 4) { /* signal is lost or no enough channels */ signal_lost = true; @@ -503,7 +501,7 @@ void RCUpdate::Run() _rc.channel_count = input_rc.channel_count; _rc.rssi = input_rc.rssi; _rc.signal_lost = _rc_signal_lost_hysteresis.get_state(); - _rc.timestamp = input_rc.timestamp_last_signal; + _rc.timestamp = input_rc.timestamp; _rc.frame_drop_count = input_rc.rc_lost_frame_count; /* publish rc_channels topic even if signal is invalid, for debug */ @@ -512,8 +510,8 @@ void RCUpdate::Run() // only publish manual control if the signal is present and regularly updating if (input_source_stable && channel_count_stable && !_rc_signal_lost_hysteresis.get_state()) { - if ((input_rc.timestamp_last_signal > _last_timestamp_signal) - && (input_rc.timestamp_last_signal < _last_timestamp_signal + VALID_DATA_MIN_INTERVAL_US)) { + if ((input_rc.timestamp_sample > _last_timestamp_sample) + && (input_rc.timestamp_sample < _last_timestamp_sample + VALID_DATA_MIN_INTERVAL_US)) { perf_count(_valid_data_interval_perf); @@ -529,10 +527,10 @@ void RCUpdate::Run() // limit processing if there's no update if (rc_updated || (hrt_elapsed_time(&_last_manual_control_input_publish) > 300_ms)) { - UpdateManualControlInput(input_rc.timestamp_last_signal); + UpdateManualControlInput(input_rc.timestamp_sample); } - UpdateManualSwitches(input_rc.timestamp_last_signal); + UpdateManualSwitches(input_rc.timestamp_sample); /* Update parameters from RC Channels (tuning with RC) if activated */ if (hrt_elapsed_time(&_last_rc_to_param_map_time) > 1_s) { @@ -541,7 +539,7 @@ void RCUpdate::Run() } } - _last_timestamp_signal = input_rc.timestamp_last_signal; + _last_timestamp_sample = input_rc.timestamp_sample; } else { // RC input unstable or lost, clear any previous manual_switches diff --git a/src/modules/rc_update/rc_update.h b/src/modules/rc_update/rc_update.h index 426ffa02ee..22d36178a1 100644 --- a/src/modules/rc_update/rc_update.h +++ b/src/modules/rc_update/rc_update.h @@ -181,7 +181,7 @@ private: hrt_abstime _last_manual_control_input_publish{0}; hrt_abstime _last_rc_to_param_map_time{0}; - hrt_abstime _last_timestamp_signal{0}; + hrt_abstime _last_timestamp_sample{0}; uint16_t _rc_values_previous[RC_MAX_CHAN_COUNT] {}; float _last_manual_control_input[3] {}; diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 2e2ea3c69b..747bf315bf 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -649,7 +649,7 @@ void Simulator::handle_message_rc_channels(const mavlink_message_t *msg) mavlink_msg_rc_channels_decode(msg, &rc_channels); input_rc_s rc_input{}; - rc_input.timestamp_last_signal = hrt_absolute_time(); + rc_input.timestamp_sample = hrt_absolute_time(); rc_input.channel_count = rc_channels.chancount; rc_input.rssi = rc_channels.rssi; rc_input.values[0] = rc_channels.chan1_raw; diff --git a/src/systemcmds/tests/test_rc.cpp b/src/systemcmds/tests/test_rc.cpp index 97f7065115..686cdba2e2 100644 --- a/src/systemcmds/tests/test_rc.cpp +++ b/src/systemcmds/tests/test_rc.cpp @@ -118,7 +118,7 @@ int test_rc(int argc, char *argv[]) return ERROR; } - if (hrt_absolute_time() - rc_input.timestamp_last_signal > 100000) { + if (hrt_absolute_time() - rc_input.timestamp_sample > 100000) { PX4_ERR("TIMEOUT, less than 10 Hz updates"); (void)orb_unsubscribe(_rc_sub); return ERROR;