From 8671adc41877b53e69e5fedbab94554893d7f718 Mon Sep 17 00:00:00 2001 From: LiuYongNan <844550332@qq.com> Date: Fri, 3 Apr 2026 21:41:13 +0800 Subject: [PATCH 1/4] boards: add NewBeeDrone PixNova board bring-up files and Rev5 sensor configuration --- .../newbeedrone/pixnova/bootloader.px4board | 3 + boards/newbeedrone/pixnova/default.px4board | 104 ++++ .../pixnova/extras/px4_io-v2_default.bin | Bin 0 -> 40160 bytes .../pixnova/extras/px4_pixnova_bootloader.bin | Bin 0 -> 46764 bytes boards/newbeedrone/pixnova/firmware.prototype | 13 + .../pixnova/init/rc.board_defaults | 15 + .../newbeedrone/pixnova/init/rc.board_sensors | 97 +++ .../newbeedrone/pixnova/nuttx-config/Kconfig | 17 + .../pixnova/nuttx-config/bootloader/defconfig | 95 +++ .../pixnova/nuttx-config/include/board.h | 566 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 87 +++ .../pixnova/nuttx-config/nsh/defconfig | 332 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 +++++++ .../pixnova/nuttx-config/scripts/script.ld | 229 +++++++ boards/newbeedrone/pixnova/src/CMakeLists.txt | 75 +++ boards/newbeedrone/pixnova/src/board_config.h | 518 ++++++++++++++++ .../newbeedrone/pixnova/src/bootloader_main.c | 62 ++ boards/newbeedrone/pixnova/src/can.c | 142 +++++ boards/newbeedrone/pixnova/src/hw_config.h | 128 ++++ boards/newbeedrone/pixnova/src/i2c.cpp | 41 ++ boards/newbeedrone/pixnova/src/init.cpp | 291 +++++++++ boards/newbeedrone/pixnova/src/led.c | 235 ++++++++ boards/newbeedrone/pixnova/src/mtd.cpp | 136 +++++ boards/newbeedrone/pixnova/src/sdio.c | 177 ++++++ boards/newbeedrone/pixnova/src/spi.cpp | 89 +++ .../newbeedrone/pixnova/src/timer_config.cpp | 80 +++ boards/newbeedrone/pixnova/src/usb.c | 105 ++++ 27 files changed, 3852 insertions(+) create mode 100644 boards/newbeedrone/pixnova/bootloader.px4board create mode 100644 boards/newbeedrone/pixnova/default.px4board create mode 100644 boards/newbeedrone/pixnova/extras/px4_io-v2_default.bin create mode 100644 boards/newbeedrone/pixnova/extras/px4_pixnova_bootloader.bin create mode 100644 boards/newbeedrone/pixnova/firmware.prototype create mode 100644 boards/newbeedrone/pixnova/init/rc.board_defaults create mode 100644 boards/newbeedrone/pixnova/init/rc.board_sensors create mode 100644 boards/newbeedrone/pixnova/nuttx-config/Kconfig create mode 100644 boards/newbeedrone/pixnova/nuttx-config/bootloader/defconfig create mode 100644 boards/newbeedrone/pixnova/nuttx-config/include/board.h create mode 100644 boards/newbeedrone/pixnova/nuttx-config/include/board_dma_map.h create mode 100644 boards/newbeedrone/pixnova/nuttx-config/nsh/defconfig create mode 100644 boards/newbeedrone/pixnova/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/newbeedrone/pixnova/nuttx-config/scripts/script.ld create mode 100644 boards/newbeedrone/pixnova/src/CMakeLists.txt create mode 100644 boards/newbeedrone/pixnova/src/board_config.h create mode 100644 boards/newbeedrone/pixnova/src/bootloader_main.c create mode 100644 boards/newbeedrone/pixnova/src/can.c create mode 100644 boards/newbeedrone/pixnova/src/hw_config.h create mode 100644 boards/newbeedrone/pixnova/src/i2c.cpp create mode 100644 boards/newbeedrone/pixnova/src/init.cpp create mode 100644 boards/newbeedrone/pixnova/src/led.c create mode 100644 boards/newbeedrone/pixnova/src/mtd.cpp create mode 100644 boards/newbeedrone/pixnova/src/sdio.c create mode 100644 boards/newbeedrone/pixnova/src/spi.cpp create mode 100644 boards/newbeedrone/pixnova/src/timer_config.cpp create mode 100644 boards/newbeedrone/pixnova/src/usb.c diff --git a/boards/newbeedrone/pixnova/bootloader.px4board b/boards/newbeedrone/pixnova/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/newbeedrone/pixnova/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/newbeedrone/pixnova/default.px4board b/boards/newbeedrone/pixnova/default.px4board new file mode 100644 index 000000000000..f5bc995d2cfe --- /dev/null +++ b/boards/newbeedrone/pixnova/default.px4board @@ -0,0 +1,104 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y +CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_PWM_INPUT=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_HARDFAULT_STREAM=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y +CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/newbeedrone/pixnova/extras/px4_io-v2_default.bin b/boards/newbeedrone/pixnova/extras/px4_io-v2_default.bin new file mode 100644 index 0000000000000000000000000000000000000000..145089ae0d7c21936cb60cc5c39501280771cf92 GIT binary patch literal 40160 zcmeFZi+>YU-amfkl1tM<(+kiWG|3c98^A(Aig*c0JG4!;DDEx-t^-APN)f8)T37c= zps3;EE`sZWR9&>Xi=rzD)Q74yDC@45bvNO%PoW@PQ6sIF2`yyWw8{5U&-vWX7{?OR>~t88(R*6;R)_u=QO-xT%EKd!vToR^^7-F~ZdLhIJf(ggBK|`xF&$4MCPIj5>Z?TW z#qUTvDVpxO`sM;@nUpO|ubN(cbxoPXOKDP;Jnbf@!f;vAR9B&Vy?vrIPM)l6dSLQ^ zd-gc`Jm8)@PMV1OBjYAYMK?{AvgM)ycTvTFdsen&u4SH@B{I*EX;V%!yM5j~*`g?H zo`m~=bZhe7vm$X~(C=Qt@9&xeIniQBJqj+0;K zP8?^RW3Fd@_xDhmk+o;z%E48Di{MHlafQcSkIO!WBXtV7k8$NmO$&&hCybp-nRZ@r zW+{Bi;eIyzwxG>LlyuD^waCcnZud_Yw~0)cPkTA6*OCF^_`W~mH*TS&Kf`lcC8dUr z!~O3Sr(g9Z(G6);p;xazV&IfC&e@y79k4rl_1xc3>&~Iy^v~>Az~`T!?TD%KYo$fh zq@OseRvjjochG*F)1ju>$-rTU@1nczT#(h)0VlP7oiDRp|#35(iJLyj_CE62T|4&`+&(Fk38*nXzO~7S?S01HJqa3ZdC;nDMk-m zw%=&ZHe-H-8zPElA;kf0|3B)N(mK0kMxgbKj%qS`-=%nHD>qTYIY1UUflXRN-$~cXh%vJ1IJk`M{MtS0GUMkmGZ0v383^2$ zP1*Wr{ zscvG9M?Srx_QutV)?}|;tUtEqU-E&d(!V%`Qwlkz>|fGSy|b5O8P~Q*=7If-cBspZ zOmRUFG+MtyT|rW;Y(Q^igDGC;fO}EK+E1j6wL8>$lG-2)*ca*XmMltLp1Bq<57^f& z0>o^w-jBNVXG1Nk^VTku52!yk*?U=sK_ZsJzBc@7T3~ED>$urYvs^4I3bhx_furUfmlThvX7d;Z$nv3mcrr}^l~&209?Bg=p63vW{R zl(ZlFI*dMy?VDB~SKWjt{}?*1dP)z6O{B$<7C5eMGZoqb%eXMZ8vI1~v+6P7Dm8Wz z({QM~ofBJS@5K%4?`SZJudTiz;JvtOy*6OKz+^q+$P27ha!7fnu=ai39S!wsQ%(Sr zplVyJQqgOKwRbEhrtd=n-q{D-cwZQsjQ1Bpq-1X3DRp`2J}+ad8*ty3=C2zd>xhu$ zd`hi1k&vF8s>z$aPnXft@!hJqh^(EvGsUitpO?fuOVm$JG{M_0_-Xzp70BTBKs|P6+ zxj{kYs3X(}Yc=9d$F-x7Tze%XGbdIN@VL!`bZjHWjz`9fSk{6Hj9J)Yzg|RlB3YER z+_KgxQdr+zcTBP*_Fs|*Em|Ir=wg<&#B>ajCdq@2NsRE4x{Lr9rR8)M7Ov_OItvF| z_1DmqbC}b9r1{a+`QESBmUeLaOFQF{Kg5YO5>P`#8C2^A9$iF=ir0QXXSMSL_K8X0 zXAmW>TG!ewW-+_;1Jz?EO3B~})L?`Xk*y|*VbCOY0ap)$PK@m-wZv?~iakF<%(|+0 zWcP>`GX~!uNv>Z!a*rQ)gWf`4tJ_r zBZrbnm>0Vr6q%TlL*5DLlFsdv*yf!i-Ll*6#2T(&Cny}Z1pF+krm39>+2SqD9)~u- zl<912*vLkLbxOQ!67#|xd>?1rLekAn`APfbb`#}d`|Z-B@-%PT9q-GnQ|^)}zy48XaI(1n`j3_7qo2RW3M3o~W-)x#_)ro%tCD z8`MExD(&PXi^P4paP7hMEUu?;ec!KfPg3}FHt>Ca%7!PzRU#WUu^6vq z+WFzS2JwY(Eo)J9?C-#_URU>jJzPg?r}^FedXKw5#Y15L%p~1vY&V`UmRDqOeVaHg zEIGN0%bls%e?%!v=q*NxVsDI#w?YR5?{Sx90VWM(Ecj5F8qy}7+(LgS-O2@d7j64( z2H^>J<0PBWm_Ei*!USn3gYR zS2JbZgqb(tD4Cq;DiJfQQ%w^kqR8pYz&R2Qc z=NQxdFVa(harL-}k?6@6q-QZtOs`BN`VF|U+TB8f$h^vfme$A1JIO9YmNa z+a!}nX`8~JZ`Zo=WqQ%IO6p0kn>lcaN$OOek9>0{kghoqWo(*k|_e}Av< zB#Nkx7dVNoRV2g!Hlh#}<0_{I4HZv1NH|_bf|QOkRL1qBgHxHh!Jx6zF$urtu_|*T zu??b}SW4T+x{jSEw{3Hz1V32b0uJGZL`sKFxB=8t+W88o`n~05F&tuM7M5^fJr}}n z(9$hm1Ag*6(I0N05E9Hm@69d+Y*oXdWx!WqJ25e@5G5KT)`NaxVs~lw-=Xr+Cd$ji zddSQC#$5}DbuduBx>%$fxyjzTDrdp8^J-n?*8PK%N~igl*}UixpA`2wy8L7^=*^debaob%DL}q>HJ##ZATca4m&I3@h#XV$(lLA`qi6MW_zPi*3)2*uvUc0z`!MDCg zN8i{*#=N6p`+_R$?m)~Wa{FQB{PvJ)H62o?7>&LZ-v);{(4|f_GBfqd4h@zVGks6e z*<1FaPM6A?G6#CrYXSzVE|{s<({ub|Od6F*WoEq_8e<&{W)8U5=lBh#fe@K`DCm<( zNkw3moUPb-XYevsC}d`FM+1e7j!H*Q@zHVOzM|ljaMNcB@BggH1}MHZg*+;|Umwl} zK8s@s3|jq{e)R@$$UhXKzmq-KG1~S8_W+{{dHUDDuL53``7QDt4Vth~ZwEF~fY03S z>CMbFHss{mVh|9)B2j@zQ&Hm)mAZI#tKf-oua+dcGG}G;BW&iYfY3juI5fz z#ie-uCbV=_s@IA&Z(PloQQoj?0c|(E>0f|i0{>Yk(w;7oaIKbvmuY^g@~%g`_414I zJbRY2O>%in4a_U7GJA+=B{uf7seve$M*igJ4N{95bn0x8$BN4u#)*7*d}0oN9MMg> zp_@!|1&F|dkHdajN~V>P`o363& z;?_*xZih8kg&vDih~giibn=Ih&$kIrWcu<^mg8S1SBV9F4tCo_CsF=1GSN$S544*& z#l{~-%7G2Fg(>50{vZ+7D(Sj)%fq1uWR1dWj)vAX5L<6xqV&M>P>2w$!GadqE#A>^ zgDV}F9WOrY1(l3ifx14e{!pb5Oll*u5_?p6oG99n4I;7j1~uUv!$OQXb%dX!ba%mm zuNGSryPmED-BVui!+v)T-I2M$S>n8&eewjA$?wu}C&m4F<7N|M-5;T%0L+QqSWe`HuQX=*p!FG=d7 zyoWJ>Z=|f)+BVu(2KW}Z%AU(yg|5^ehc)1Amw5`A7CM#WD`Q<`+B0IIJoXe_qvOL? zO0kdE4g9K!C}krjfw}Jd0}ky`$`zL;xS|p`4+>qUIUib?gm3;Q%^ERHw0S>~oml%% zB#p3DqIwo6io_$I4=10C@O*mo*@)+V4igLD)@6w0z}!C)zp}L%B9(R@j@BEGdhZXz zjuBbqpYV{C;(k;WfNMZGziy!WJ_g$FQys*wg5SfR03H^PtcbNW&+}3`&n9h6)P^I< zFW#a40$$`%erv3Lv^lU<#E3WTi6&R(}=RgZIkPzM!8Mulg~+(9vj-Epr7j#R&i73 zt_8+$Zh9a z#nwIOh4>P!@&;&|$C9wkR#;B&KetU2j?dQng-4lbd{_Neli1c0kK7i&w=RN|=! z?@mO)w+LfSuHE0?rYoZXKZ9njEd`yfiVDq)O?#4=Cp6LD&C!IWZ?0c$Zfb3ylGFz8 z7JnRcyqrR`EQYx}nw$%z-L2YT^St|`{_u66ZL4|Jiq-kP9jiWCW`ay>OK?@DjPCfh7EPGZ zbou|-@@Yr~&+ec9!M6Qa-K1`j)GNr8!lB311jLXJ_Kri~SZshoxH-mB`Mlw(ClYgL zxY5VFvTMN`j;{mfwtWuGBXFC|cWx7<7G`#`FXoyqNVfj@I`EP0;zVFAU*#udcF)KD zV_qf7Blwj9t$}GhwfV?-{w|A>p77(I+5lS?Hd1mtqAWWETS^HHr@MG@i9Au zx0$h}K_YM)s6OwMi1HzN(wyr2S`Um)dYhTYZGiTcXah@3gzrVnQW;xG2gxsh?e)xX zPKUAc>XQE8r4V=}$6S}KGFNAI5KCUuh0xU{Ljh=+wt|=9yu7V>R79!^4eW`FQd#KHi`Pg>Rj(_lnX4#R>C6u`BG@xV{si4Q{69mSnA@Bq=7~(%4DZ#&YS1Wh&CJZJZ9{>k1!_Bo z-I3RPb%{Q3RgJYe8#rl-HA0@w57?y1E~{K1bIn)Vt`CwabHv&Xi?|ki`h)X?|KL3P z%aY|eqT0!aCooQ`gZ~4Vz4{%{S$fdmy}D#VFdlg?&NaX7J-3;I_RZO{15?B{nG~h= zSWwOeo~qOw`}`y+qJ3J#W1)KaDzQNPB*coJ;v&Mwm_aJ{H#!gQqY%Y;_V1H;XOx2- zEd0<6tUqY{ekxBGVeU(Q>k?P27L0GRmEU!y!RlN_?xJdl=W(xMq|Q{an=fU@n1;Ns8GW1bvZGz7)P0a54k$dNM#3OI07ExELue#*3tF!H-?*rnHDA%TZlk(;$U>Y-( z=nF7@tySNi)|FCot6EyR)XVlAW^VN&6n(f@9*5%pR+(8s8z=NmMY z5?jh?c!4(=P`0Qesq<0)0W+`Fm$ix5E(X63F^Xd_40ta0H-J8Q)EB%t^8O*WVozyW zz|avfUU_@ED@~jzH(@mwME7|6wsP=1u{K@cRk=mp?cgA((}=FeDmohlsim=AI?_l? zZBjWf#ZXKo`pBxuruOz_o65_2AUjJ~4;zlpq*k)#3^AEjCM8RGClO35HL&RFH!;eC z>cK$^Ayx(4@jJRNNME8)Djg|r55~EPLjkI<#3P@?`AJ&v)K+z+gHKr1@bV-)@WeWu zT9czvZNa7ZeVixXM}4`;G1n?v;DhHpRN8QET1ISRPp7#G?bIQ_ zCJHMVC9Eb}64U3QBDpUC*%{z84fCb2d;nN9faNEbVVPwTsn$g4Egl&g2Q;Jlg3Xi1 zryRF=^7*kRlG*_+Psr%0{b#Hqa~*u2@giSuXsY|Wkgi?!>T8I3fAm5>8_j}O6>@vs zVkfg*2A@4T%q6UI;bYs4m#M;tE}!lT|g$csJD_4cTf+}zHz)?$&}nc6y2 zWOf=_$XM>k0Z_@OK3fr~Mk{#gsvxs02b1@s> zo%$;=UjKr})_cSmq6XG}p?F5M?jg$IL4MM;-B$EIVF>G^aN4x)$Gx|TbD^0sN+Tqx zCQ;gidReD_20ITv{y}rkOz{@fAj(U?qjP8c(UMh8prTQL@m- z=a9`-F>Ng|32~Zgl~3zZ^`+hN&!wcdgz{%*!cSD}D{CMC zo)qg+XO%Lg+KT5L8p4br7I`Rk zTg9iK%q8R)rB4#Tyw-z>y5re~?orOB z4`zsa7Q`a+Vod2C$M-?Tq=p#q8b(POg0~O*TjR=+OTFBB&c*}}!_T}{Vd39P@>5>a zxAU$qd^s{fe1j-AA>sw!X^gfrw&$3k*(h(sOx`xRTjpS?7{Mn~!6(bX&wk`kiq|Qh z^P&_`c6-|#=|Mrx_wJTokPQ{PrNv$YXyV>MVv?lGJTnJ&|M?JK#VAV$F8~wcNH~-) z$3NSo11D+MiYrY-X^r#ZcJOg)R5OXkE+@*yxD}pJ9&yZrkn9@h^NhlekjecNml`D$ zIM2?^gMGT>K19OXH$iin<*ok}W8+~>)Za&hecIm0N&Vr!N0;KelNLX_}ZuuN z5?+6-l4&qRX`RwO#rfCX!?K%tOEzBi5u^d<(4y_BRYbO{!op*TmTiq$uv@4vhf1A? z;`I4kjK&|6`-t|bwoeepyR_i&6XkfMU^v~|xO$%S679Vu2_-u{Bfw41hF2^*xN5ao zHaJPqs+HY|5r~q39iIWLshwtd)oM#G!+syK$lub{$N1sa26_7dd|)mgxc#sDKSd$A&_Il(zIRbDLhG81V_59}10Q$xLC zUqW*|9%W2tN9A?P71ElRo^80_Yk6pkLmTA6IZSB>_Mu```5u#4B*UYuOdXYlG`0(y z1vq~&_uyRU&(U&2Kru}l$#81$iS`D4Um+^%ieE7D+^I1d*U=z*!^Z5+AD$r}cMGSInR7vbD5;i7k z{Vi_o$U#3u`D;9^cq$2+GLY>?yg2zxSI%VD`BkZv%Dg4=5^0sZTlxySRS8vs_CE1eKwE8&n>w7h-w(T|D`1nI@RGDh=xJ1kfxn2M z5su{k|Lc|h2ei6<)XzYy{|Xwh^Pe6e*7gAMTh^V#T>mjt+`LC7$}2-!vGjml&N)Do zc36=&2G(I5pS)4(ms{ZxV1(l4t?;3?NH+Nh#^;v*hza;bF@6}kI3Fvl4ktAiG9@0_ zKZIJI3q zYBYDPq;0Pi*U6<1Yr|>Gt_A4-aoYbmv_SlS-MNFi5pcRz=PiP@TNliq1xdg|nh@IPt?11`n zElJ-XY&(=DcW&(=x?{^hXRC&J%3olQ#v+dlfy+wN4xsYQ*#2ki6RKfeZdLJ4QE5EV z@(vNGF3-XnnS=fQ_J{>`u-43&7^QuL2o_OmX7T*S2$hwPy3msuP$uW5HW8I`G(HxO zTuA8KvB+~nqq=`W-^MD9@^ub0r42HxQxiHq@|^^3WszzUr>XEs)G-llk$e&R-w2yJUv_$tL!@jP-rqrYQ5v5A*ENyv>kHm{txnY(_5GOpdP(6*oeClJZWZN z%K=h+^%Zdwr%Zh~e;O*RUL%c_KTy-$%&bWrl;?z_Q+rCqnb@&U%1d*Y6B+W1jy6a3 z=?uBJBfI*Gyl+BA(I6@zkIYphpNhq?HIUm;V-MZCnLSU+PdnQB81AJ$j(?$#XP%V4 z4O&GFDD%_kYtm>um*$XeApWE-JGNGkUEawenSzYXYj?v-mE~=fiH)3T>ZCArN0Ykp zhJ>!{ltt+esmUZ9!Y57pJC68Y#F3XQVCChNni$;mZ%o{voFL$puo-=Y1Nx3@H= zVU07y)(*;xw+`;D-`j}YmupsZOiJF@^$qoiXClj?54_&JsIR5G)7jYO_$GiHDwSH` zq2T9<%#sTsZLPjtxFUxFd49u!+=VcJs^$qL>HI zZKc@`=UR|4cYbVHeLc;YYiay+A}>x>bee~~&c=O?u_uo-mcSEEu=llbPW-&Fq~i1X z6^*y%uc*(#z9d2vUSosEnsNbm5^9=T0;{EV3LtzpN_Ek~AK<(&3TG4G)Q-a01poV) zAAD+v!ZcFOmn{n34eP1ZACJ5cpIT9*==kONR`Dz`36`ku^- z&bwRgK63Z+j`6Tj>js`*x98&XO~4DOucurFz8b&1F<0D!sCG}Iv7+bhT4XW)I(Dvc zdE@76QY*5g`i9Tf2=GoXS_#eSzH@7KuY?WG;=V$$oLjR*f}ba`UySXJHN2QA_IBjK z-rDHM3+C3E<%|R`%USUL`P>=EfFiXPlQa@}CML)nM$E%rHP$Ry>9#C^cg}s^?v=*Q z`FFp!rq;6IZd$wN?vY4K?A)4U-E(U+iMn*ub8D!-g3=YGf$I4Q+JSdY5nf(HGpSa* z32)(=gjP1XtB7C~>+g<7-i{^P8DN()BF*!;MZFx;@W4-S5HgQ-F(T}BO8lzAatFPv2!V@@tGBbtd+boyc!g?Kz1_kn&ia(!cCJ3s2*$cA1 z{ARZR4~Vf)P}yZYl11g0AFnU~;%Udr^)(yWSBUlHyOPcr+R6`gL{$0vDC_)FYUvY80PuDD4g*>WC7J3B zlB;hF=)zf=$vAQGhGQ-?4&;Hx+kt`Wj?(@fil+%<>i~*#|71dihny%wsRgi=cy~ zdS8T%Xz?t{PqmFbx!2d~Tb^6L$Wl?|HjP5XITyKUfAiw?9)1?hEugrdZ%X1t-dCZ& zloZ0|Pk0w5%VtQFc;x2zRM7`q9|;wRAHYf;gLl+Nl;fpV2T|@tZOR+z8I-IJy;KEh z>5_A#p-?L1C)ZIW>G6gW^^hotRd{RQYhj@4e1%LtR-$JmQe{@$>UDctVDaY328q^4 zLG;pvGMktBtadtvg0M6W(S8VQ5LQP1U&j)Oj@q=qAk(+EdaKa)Mn|1O*l~VFc1gJs zYN4D6PQb=VSsm}42ftphH~~@MJefJOBULKvs6ju7DV8BmR*Hm{;DWdOzU}axr%Ldi zb8MB3z4BWuK5A+xg1_2q=K5l>00tFfIW5g%+>qK@hEo+EcM8pO5!dtIuo@cJ1bn@T`FG^kpdY%^V z?a^Y9*-f9c>UGi>RGB?om`$a1z7Js4^#-#jz9)8sZ%kj< z^;X!H?g(V#Zc4WY-U0T*oV6;H}u z)SI5(m8fS|dN))LxF32R?^dU$;vGSjVD$iL__1g5&~H&HCraIGFPD;slH9ZKD{vL71Mhrh`_=;YsIDF;8(PVJmisK)u(?GU~cFITr1O422AxFu+@ONkGl_CG_73~Ou`lUniXi= z1~KbQQjGa7x-U#vK{0YE$TJ|B)s7W?4i+^sspi`1JEhT`pkwkuS_(g_@=v$H!tKNi zQmRD)pHI~w*Se=KCFM@6$SKXIh+^2oe{n;K7~ZQa9NIGEzVN=g;)0RQvl~lbrG~kn zpkx?mNuFW^rF6RW`&<=S>X_?FK{0=Fmkb=PDN&50HT0OlyY4)NN!JFv4)=wBy8qC} z=s&Co`>OLl_PsWWSGt0^VqNdK`zYkw=_;>%B7nDRQ~kM!t)=*?eIHMtWg9~j8wLM{ zjkm&!(~A`?*Xp|!dtfbl=g`LCcfu*@i@H)uZs|JvHLEO{u@L`E3l}=*SVox*^Ex&_ za}7QV(a{D+M`PfDF^ETfdjAfe0$uBO(2btJWv~=0~jW&T#j^dMHoYMnITrLi^ zLWBJ&yZ~fZDt5C|&Xf5aOv1vyG@=hVu|i#12B(_bPNStelndN30q4MBXWamQ-!bSD zf;`#0YeA9=u(Nk9`0gvc<*%Xl#94^(?G~%>R}AG1xa*i8GlTT7Gd}Xwh2~$-a(TU6 z`i%oMZ}gASBL@z`frH$V`;pJ<80hvoUh|VFzs#enWeJpy(k$&MBgo8tU;MbzdU|hP z3in>+hoIMq71X0JB}iH)R{Zg+55=<>liZo@UuBI5zd%v=ZDG5(x z6Xb|q%p4&17Wf&n1%Akb(F+&Z=s0JJZHhQm)SNCY^En7|zb~9@>P+#@DT{=DR(3H& z+nElKDL5UgGG^06>YJl^Vl-n6ybez^c0FFbt8sF|?z>hkMbyW(xmBk-!60*lD0=mp zUX#}9*NW5RZ$es}5`&zBUyZSVcbl!HBauBSwXY_W(X1n(URWvImGlEzOJk86V?+?{ z?zx8`vxt+=-4&1gbSMIkAC1t*A~TT-G}LYEj78QZ{Dg<)#)g8tr(oS=i)5qrWZXIk+>^qhp2s=BjwY04X+e625}@}fev&-_bnooz=!+>tnD)@Tl$f4 zt7EH}a=J=nX2c^;q7HYe3boB~YtJdj6ne53zP`f-*w2go%N)y8o2jmME5r8jnLA|@ zbFAZimAFyE#P@x|FIvo1+$mAt;8Hw2|HIQ6iS`*m)PkNeI3{+75T~9>PfVQ-QYgT| z42vqEaqtQtNe#20I~QQ-=%#(u^?uARQcFsYBu6Tx&&g5fQ*spgbVhoCW<~3jp?>my74-N45$dga+UMKe&7a>lmfv1A>X~tbI?UT#AHfZPbU^lk` zPP!g?p5|T{c$(#==aX?NYHi^B;Siaw5oe>{H_`8mQ{?KayGJ7TCi>pjT-O`Y|0mv4 zdrlu_Fqbb;qCr;uNaTS84v=pzD}caiTBMqY4qhOwqSLZ{Oa|%G8VMp`JapQT$j@Wh zy+wSv|2pwp0*0QD(oQ2V1Uj(><>fdXlHE_P$-#mvQgE?HDgcf<{mt^#jjDWEkrolQ9aTehDu3 z7~;?W%R8%~z`IgT^X^%|15b!3ASVa;d1c7YE2HOpW+B%~fi0sIAKmXh@VNZofrbMf zM{$7WA%017OuEZtvU8n`43;^tGIq{uX!Kr?xgGiND$4X+2{1(KUI49AIH_g!Uc6D{ zU&|A@k6(0Hr3NWW)P(h#OF>ffO#&b1Lq|5VVir!3X9u#--^V)U#BOUI3<;9FsL?{>cq1}!_?Jn6Hi)@b@dZLMZM8=jL zoY#<#mC)`g?;waEB{MJS$%>v(Eb=g7pn#4)gTLeW??a{7`(wn%_v4gJ)GU_3Dxjx3 z`AKQrXK)q|k@;O@r=~R?F@UPrQ?zs%;^I2Q2(Gj@;*sw7kM_pcgA>{{qm~FxOrkf< zso}``BR|?h)W>hMQ`4ci=BFDV`e`Q!?k| zetF@6F&1RBG7>$p2+zLIbU@B)nCa~voqK+eO}yJJ8#?kEQagD38i`yzbWpCB4@g`+$_kLBiMV$ z^Yzo*E$t)^GJXoh>Tcu%E4L16M0WbPGw?mX5|8``&SD^|sCAcY?LcN9|BC}em?stY z%m+Bm1(mo5A@l+vdiH+446{nPVD@Hdq|9J)^Y zCK1(N2(R+ZgUDv-ZUf%hfVW2Et(A9bzyoMZawKvic8>x4ZzRGZ`|Jh(DtRYr?nKR> zVt>_9 z?8bQ!nj=w+)9%D1JZMBd4UK-7RaP*0Ib?l7YkaUjBs_?W%~4-|dAk#y-lZL!g_+FB zc@LUIzB(4!6sJB<;X!z8CSOd{HMYb5^2h;i!6Q#$lqK?t4){W5QXffHPd=h|^p_D{ z9b!uBNj@)@)KCphn}vh;T}FK>45F?|JA9;5xT`X1Gpj9fDxw&vl1oxLGi9H5r)oSr z?vd9j)ssJwkE!G^VxN<*?_f-er11|5QsIMnV!ilP2$4K#(t~Pf5i*jJ{#Y85C~r>_ zb?`y7P;)R{&a^EYCi6i>uY%NS@* zRHvi3xg2L`9HeoESmgX$#D6{Vfsw^~Hk_E)1UM3XQ+WSRd0*6b1n=KycE(7=JMyiM7x#GC^=U2&c`R}; zMo$k?*)|iin6JLDo>EJboyG=6A|0KyG?7WxN$1rB+8QfXP8z2&=|=Cm{L@rN?HrDr zQ7?vAmqAQ=tl2}#xKD*>Prn{E19!0q1OFJZX9iZhF?Y02)6iU$+z=u~KMN@b(>$r-nA`@B zR{Thpcl-pR0y#?`lB^Xe-q+@``eK6PV)5b9M#^4Xd-;4E@bi; zkUyUE+U7_}ei)DZc8~!+e}l{cBTgI+M^6601$TH;MMDL0Fv@nqhN1G46H|I{!Xb^v z$y8zu2N<<;Kp`#CZ}@62%D;efx0ayFnuBJ0I@2uY(l73#tGv=WBcPeqt?vgd+2) zcaSI@9j}M=Y4@Dx|4xc=a>ka|joe7}46?|eO9=SZ0z9zG`{pymmX8wq6(z~{w>s+k zoLtj_Z1jpr$ti~ zbJ~1-$!5F5aPqC3v~YZeTgln5-GOs)8(s^uY1dX{=J}$kqK`u7ji!WO@>TS*6)!ka zPF|Obv)?n_3b)|})FvC)^6M&A<`J{KH_blDODw1D$To368+e@Uh<`?5BDT8V6M2le zt~c}M!l8|7do(sYHd^o#eKbw6q&a#um3tk!lfTXd6f@bQdmZG$dG}M|v^>;P#zu{( zM^rk#reaT}ZghP1=pOKllWwEITOIs(&bex-Z6Ek4Y=)of<=Z^t?!>zZyWzoBtU4y&ZUCgA`LYdoeCBrDE)iq9OLeb9NHd z50^N{rB(Jam9JIuL)<_L-~}Flwcom5tF&L(=4Q*UuXwpHO#`UIW1|_%;O8Cuov*St zt@0H>{p(x?v%CN3E0y=1WarYFDVq7cWPWq#y|78Q)ovNm4cGQ^X_JR^19iOxHy@0~ z1`CI_0fyWP(~zz|C8{5K!amVyOLO+}6)#q@L(By-#Pp|}Ea>BT_;O0Cj=oqao_rr2-HH_;W zTvU%@l*Ms2cRnnAwi~D8oLii<_R=&nT`TY8gIX6^l%cvkG(#%d@r5-EF;u+7{orjYMG6EG^v5r(HDW!|p_`PZjkbvr0tOns!ukiZINW zotJ)3qLI%AYcITk`vvH{wHK!2>DxhjZzW-@e1O(@9&i3ONUnP9rnkgH;w#8ib6$E5 z@7^CIc-o4m&OydJ|I$-2bUNAmfd%lizR22h_l&oiqK`Pch5I&zOP%AaF8 z!1xB)B1R*-e}MOQqwwkjl8eHd+q?l%EUzgVX&S7Lwm%lr1sW%^LBa&=-&7X#p9_=@O7>-w|u-EA{>* zm4>64dsC5}pFh}%uXCk7^9phiXG`}=cYDSwtk#skBE?hj;JlkoU=^~Q4y%%n zy%|+5wMU09GS@J(|KxbePt0_c=$PNDg*AV2WXKGBAQ{rTT?NQB!Ko^#BUDhu$k!Kp z{8~vX7fyf5KSTUW_y(rhS>@Nw_{dl+p^s}a5N*^-Z6SO+4j#kA_e=<*r!@RQF41>^ zM*jwVZ5U;r;l4e<5i6ccahYDw5lX`*JQv_vh&DyI7u8J0Ombz9BO^fXnRv>RQUj)& z%&wAVor&vnWEO%#jt$wcgKSMWb2qXd5f(kp>EzWc2VYG|U|-K9G3OsR`=`6MWbW-y zdFi0ax(})Z`{k$VxYk1C*}m?3(^ojOHCiGvCipxKq*j-Sh<3Q+k%^$S=SJM3;mLQu zqWe(A6~IOJrHZ-GnCLL>R2FJrzfKS#+f&Y}O?&cgrrrZa`CRSsYI+GredmVY0q-sc z{2w*Pz(<@o1%1p-xmcU`EmdzciJN_l@+Z~g?H?`eM;4iWYIl&f#W%GOmpdMMOVt|B zhd9@B?lx8HF5K{0h~kyvdXAMsu@U}=UE-|3J=RHqYpgP~6wvnlzprNcDw(fy4*PUg zrfXNFJ&3(D(&}ohIdYz5c6#F2cTUC5?Q}EBzmIlnSu=4(YBt- ztAoF(*-0TBaIf3x{yMbn$9h*0^Ol>FHBWbWDo+Jwsu}q5)9qGcSE0Mf!_08|?C@~9a9sZ)Bn|Zgyo8w8%=Eb`TbGBY^@u*b>3%EBAjZ_`W~ZeFxM_TF z(6iZR?&bMmH#7TNAB`;hEA+M}M;kf*j{9P0{4{dmkM6TyYm_w0%xkM&zWe2ufBN&6 zUw-+Xb-#Y{$&L6&vK0>BCt}Pb!N-PhRy`Zqr7oC_mE?mfpz-qpym?%i`|qK39$s0` zbHHhVbDd|Y*5O|VP1}TDFZu3wzZ(jBW^UdLsYAbP)f0O&bnxPb>ygioZ`6HwZ*Fn9 zKi9k;HFo&izVAZUd1+~)?Ec)TC@b3U341J{m+wROZ@g~{WI*)}^z)bD9UG3!~! zZ-OON__pEjme8O3xeOj&H&$sGZozB?M49sW{4~DjZBLOmv5NI?yMKxA=eg@IAl5W% z6RSKOUGx7jrdfPBjMH?=9dTpF6m^_^StvS6r&0G$LuA_ef!p5r!bznCG;?Ms@Qx>rpj8r0Z6TBFc!zx0K3u`^jVmVAJHt{1X;&Z>Lec1TZZtvnW`eLgs}7w5%j z+xzguCTf}xx0vXf)HKmm*d)lmcXS*jCY#LlE#PdDS^g;BOrsi)pH-J_r+tlsB$kkW zk8dRl$w;JySG#UsTp#VN(FvAyQPI5Gs@WvVsR$lf;3?Y!YQ)i6?QS(5H# z9lo?@nuxseDANNeBei+(jl;DQTzP?|9$@j_EX3_9FD%3t8gj+VS}Mf_Id}d?&Lss5 z*3}{nMY=`=Io-AiF+l;@Zc98nbh_h9J(U-Ja!VGXxjBB$j2y^;SLdHi@TP^xT%s_h z;hySx#*;DNzLyJ9IvI)_=xp_5DJHZbW{r#YCuA~{+XTtX;B1PY&gV9?!#9@Tht|1t zHB?K{CA1W(vk-w%UKmb(Z)yH7lC)I%|5JbSX#F#&U-dOZjHth^J*zhBX5`7p*@+YGJP9*$1(*fW4sjltwR&A!|IF+ZB6Hz#`NIiD6v~72B+2ht9egz zJQ5o=dfg}|J*Fn=zrp#s=AtS_xshRKOupGgRy6UjA2&FzI%!myhks@FEmK2X9keaG zk9##9xehUk&$`)G?imwS*Cenzg=Tg)2bgv`%Khw4_W8`J`=Bj2hNd+AJ#-n8m~bex zqG`KjOfA`AlJ)r3a5NDMHOYC1&qpH%Rh-RH+?XMa6%aqg1I5qnxL-^6KkgJ)d5M%Sr@O8(<;!F7h1#*z z!;xR8*U)|j8NntwE);+olHa-f$GgN&=Sjzs)?gB3o8Pf$*1M2783l<((U_Xmfy|9R4|Jv9wG20((ne#Msktb-#HJnTk98&Jz*n*&1B#kD#5>FCAsMvTAbh zwPy-P7T_3<6VhYo*_+ZPJEinexBdg4fgJM)jg$g@lNVz0ASK{n=f4|FV$M>^$`42<~`fsRt%Ae)V za9>}0!_D>JSVoTb&#lRFJ1^+j1D-s`oxx1uni^*3oT~JFWG9iw?xWr)oXLrA6c2fg z=2Gz6Pt@ns>+tn~8v`>f^&X1P=hSi|DZV~HHNkqf&9hX;94~U^xnYBjp1g+sucjjJ za*E-M3 zn_qxFQlr*;=vO)G-3NffY|gHfZg@hSTAC^FJJa{kY?^L zp2ksJvdZ;Qx0rL_Idz(;-a|?d!E#fY|4mK$Ge$W>+ThUolXIe&rL(GcKc`MFeQt2N zX{AlqWy8okM>QXtdn0g61jhxv?sc4}KHw>|-ya}X5n=uXz2B9aVi{yAFx8Cj?Tb~DZXsdo#AxCk5YU8y)-ZCHGxD_wYOTprdrVa@!s zM*q7r=Pz3{nMa)$3K$o9IuK{g)wsWb9vL&u_o~P2YO4fy3|RshiM$yi%)v_YSn0b% z9k5YWralL}yDG<>9NYT88~YOQri%6bIVWk7CTW{CEu;&OHnenwE^JbfG-=Z%g#ra- zQ_>AuC=e)UL6jh%L0o_evZ>YTy$CLC0i|p~yng0Pg7|A@0=8u z`@i1b&GSrVIdf*_e6xS^eeXQWji^_0z9dM))J!nS_Yu^?2*z(ep~lgmDsYK zj2L6*hzVT_--VVwTJf5$`R^uJU*blnf2V6A_z0FMVV2{dYBZn!6#gq|jTbnE^Z8!k z_H3qkAJ7ft^G>PX@t~h84fP(R@pGk8`84F8!uYvH3mE4JH#3^%pXFqHu40Wjp=;E; z$5BI+_HsT4wdW-+%~WC?-au>L+mkf-R)Ju+p~N!SK{0CT4M`a9X3%!p-&o$pzqsRyduI_yQozTO^s^{hJbam4(%52Y_!4cDo@)w#{+HAnGI zqi*ThI_nJ4((`rJoub9(A2B|XCvYj4LZI_+(&_NugB>98t+Othi1k{P%C^wDbdt*U z;SH@I&CIXiszmmM7y~Dv@6}m91VZ(KyafeHJlkxbZ$#K=s8*S7-VaX4?1m=njwH=# z)oEBEhWh|HI?{wPRrf8lqI^sDhzfItpYQ87_Z2{bGYzw@M{2S#%0N^5Fzu>q0x zbQ&%UKU!%G2D;D!>{MA`;N==8<)vYy32jK_f)$YGkD&Y5n~((vZv*FQ{?iz37~h>Z zPoLh`Ox@CN9JDkPwP{?QHa8WkV^u>6_JtU)0bm@Iq=L}_=ct zM&p3=YNnYCA7e*pnAtd61D+DNO`4p0%zfPfeZzBoaN0ViFTI*1q+)jn`P$~?2guMN zlhlUMbX-n+KFSPj#L34+aq#(w{wE6liTemi zI0wWHdV<^sDKc@+eaNrlPH^r=4!RHU@oZ z%?KgRSbe#L;&r|=-+TSqx|Y9dK6?hXsvWZT88eeZg3<9^)3HYsAnJy(ItYjI;)z%vJ5wiCPuMh_jJu z$0sXrQnbVwN!%DSHq&}@b^)VI#FziY{_@vwK76fj>P^(EwPxs3`52yQ1kIomu*n?- zi6FY}1E;{b{s@&(V`F_=BcSsE+@cvIK~Cio2o0w;$)tzId}Ivl6bUcRU0MY?}w6nq|s zfiEU8Zfs2Bg0%96XMpje;er$tXM-X)0ZEfk%w9Xv6UPD%zEz&bK#Ghg^sA~GA~eEP zUfSs!3PC?TBzNw9&)pP=E%-I?`A`<$*j+Z(n8qpiuO+r;(7qYXIxSI)@^&|(pNEG+ zUyDhW#&Q_lJX8vRk3;D#|HEl9y{ADin7Lf1gJddX{zXn-W0*Cnov>k+G%i@J&}%rz za;m*rxDavpa8r-Bb26x*%W9&m}Q9ytA5vw zhTbk0xEa8h#;I9~%2rd{Tudc{y!d9cf84D%610lfai-`%Yq39~sG%e_t67w!2OkTF zwCQQO^z?K>hA}aRX}g9F6jMX7ICBv9;Xbmt>_D7>x}Sh_(&nbrJZPA7_$oGYlG=iH z-|)$J;_6Gv6H+P3-O45!v!?GQPB@v$MBGJJj?QCZ@Kz8R*1`!bpJDA&KCIsGF?w`} z@JIgty2HDo)f#%bH{A}+o0Ykh^F0|61?oxIUa31I52v4LQ#q-kpuN!F-zD;&!VOmo zpe1vXNZf?m+W3?K|HB|UnKiU;IRQx)7Z4CX6*Bvni%pNhdj(fCq zjtsZ_#zk?~`JquVxM+D^M(-T_F54?u7BOtD{$;GaXL4dQGgimVS^X4|xyA0OT;=NQ zcB%9!qT?#x!r3Q6%4vvL2b&!xb`yk{`a?{sr*fsMQ9o{PjMCN18<-^4&g^32eOm<` z9|{KV6J)YLW&Q@deLXiLQSM^o{w{_8T-qu~t>bPxrgcT-2K~{#sLX~H5~-f5Hwk*Fu?>u;`F8Lej(gWPPu;J(Do8avMF}qi2Mue|H}LRu}9M@H^djCK8p#By-=+ zPTH~`_G>!Q5^N9}UvG@C2#paY4wBE^jy9zA3(Q!g%>gGeyga=DC|>iCO4hr0>u-<* zl!2EwxECBNt*84#+a5?HCeU2^pWkX>FxPQflYz;*-K{uEY&1=}E*@wY{D)NwQpG7Q zYnLK5S?}fRBIt(*HIm&xIxh0veHxOg z?7pak$~w!`T<{syOlk)HL2=wkKxC69db)!>iMS^K()Ece?dR}~J3+P0x~j7jpZ#|C zb~nN{)>Yv9_RAXDfHZs#=kt>xGx04S+gn3EXH^|UklVqqh?h!NRQGtA9V~QYnQ^S? zZ3n$4O=^16Ax!xDh18r>obLNTZ}zLc6rM}?k^}s#&zKbK4?lA`A|GYrRCYm}pPh+& zq4|^a12`>{wbogO<(>^Iw#Y26Sy;_e4sUqR1t8|+X{wYa3;1AVmJU#??q<%i#+&ah zakaiyu8e=hHYMU!Q%G(k7nCf}EOgNQ=bEnN@A~H{7XVwfcqQ|od`7~0NWz?kZUP1{I0!YJR2^2{hdg7VQQ4^)MHr7Aap$H{SbXWog# z%}=B_B&Vl)_#F|r-@$nyIl(4+3*S!EoHAE#5|}bg0=2|6Q2k7?)kL|ipO|nWVzw3~ zs53bEy-HIL@Z+hhZDywx{qcpvG=F9dk@GntJ$%w}VlS)g$_ z78w`iwVIXCb5fdxn(K}Qx#fAXYP)JHLM}Ek<7#vtn`P#2nte1E9VN!1{Lt$49Oe$_ z-ql8g;&fuC=de!eeB0uvW=71gvm<~dW+5ZA&b^k}m5lSi?FWEQsOx2%>>YVhJkEXP zQBQ+Yes!hfB`aD!WJA#7R?lRiv3Z3X`D#IXu_QZ7=n@EhTtXkgS?r5Z`kjuFm4Y$h zOf)q0Ygg*q6$-}rzvVW$IoXUD^0t-H;HK2A3}*#h<`R`2sLp&` zkDJDQ4{?w6$7SW8IA|$Nx06uHU)|ti-&Q5j^2Hmju8g&*qG%btBf{z#w5*bsyd`~R z^8<<_zm;=;OUX*9OCbGo2}j+g`JHxW;QvwNy7s@6a0nmw9X@Uu;x7EHgr7Nt>eUV( z^(qIeu6792O2=mOrKjaYy#@A}Pd>SC|Gs_qNx;*MWG(HG(e5Gz1?^g_>?doPbW7tc zdMgZVHwB9(JykEPNrR@?7K7rI<6LH~V2d~*25m>=YQv&!<2F~Xc)Edx)g`rA2pPuSDr zSR2dOnb`2wsm3|xsm8>n2=lZ&Wwj<#X_mBwgGbeEFPI2f0IR3_6;CY2t~4`H?+|{; z9%;zWxr7#*X8zK#Zt&oQp4JSs*$h10-=Lew@b3U~!7?7{(Uwc`rbqMdp0Gz5A`RnF zf)BaFj+Rlbabs6KdPjJ=cTUB}b|&BF;1p zH8ynU0>Z0N_X_DHlCTXa#^Rg^%_<^9r?v^g~n~1UJ+*9#$_f8IvC9^ z-DBWHY(hVvJW*xCM8q1v`Rt;;plTAo%3jrwi!eDyL-Y;V#_XKXYUUoMqj}j>^i#s^ zL^!l@(>B5`)hNvitMAFLbFF0yb%hy0yP##hMQPq&E!weS{zj9%J_)*KgRUQ4|!#L4|{ndq8qc6~MP(;|mhNwqN9?db} zy~r~P@Y@5YfNOTxLqpk--qeP1?1Zb12;&CM06K(KgAO^kbHy_dR4}N+tJhGSW}E_8 zn!R7I#M2i&&@5~t30v)fIZuEiMO&$u-xUeel$S>9ht?OZD_TDcu-j+B%!8rzwjDOD zvqaecf_WT<)@1|iW+zhQ?h2dMt2OSwoA$E2`10KQH~pK7OHYCPl! z1&4=u6G#_*Uaf1~Z2-Ewj{5uO=bumTbUzMVsO|!cl$NuqY+z#(&9;2Sh|@T=dLbvo zAS&Mj94VA?7`}1#mfS7*zSb+;ZoXjrUqWifyzB(XY>uj|!nkX}#1@3_^@&E%f z%I;t^h_iGLFwcH+;P&H_%OX_qLQZs2+xdn?QyqYN2F#ErVA3E>p!s%AKpd4<)>}@^f%ZIZcDUuxJRY2IZz~hYxCJ*Dmm)A!OX9BDn~?VVx=|P8QAGWa zk!)srMX6gk_9VUCz~8Q{o|U_mW7=lV(YXC@Y~=)Pa>!B3-Tt>B6;8-*VJed*NFX&o zK=Q7hqdiXVnTdZl@cv1Ud^bU@YrvmkMt|-QIDZukP1x7`4{&P&1A;FoMg##t@LyHh z&TFaPK33oi@(qNX4ZVX`VSxT5xZz5J{N?2JRqOqB*KuU?)yFV%u>x>3{C6pF3Xi*t z1wD5E-C<@%6R-<(i&Vk|>0s2;T&!<*=_cG-@$PRFj2hQZK}tVEQ%rThaJE?q8hHZ2 ze~}v;Y`ptIOtoNmm_7VAno{cj`iJ+(@bBycsIPT5y6ITz4u5zyWid^4l$-Wirfq7%PklCJ|;h%nTS_ z_8bzAZxd@h*ZsAdBo4+XOvl&AI|W_erqGeN0D7HdC>@P8{Af(a;(>R>*mFad$|K@O zUf|wB`%hA@=tskerD?+uP4b~oyiKBgQRaSQfo=BX%X!C6~wH`?mBx3kHdmV3~F2)`jWc0(1o+OOCD2z?z z6dcd^Nvt{40RQ`y)rygz!iF$P&e28GjxOB(glBAjdR6KeFQO| zM$CLS^+T?t-;XhOWQT*^cYW0{_BhR((R?alphHeki`LDN;T~;9O>2R!LpRprq(O5$ zPh_C2_VnFW>(i9yolOD^hx0AY=PdL)wYVdS-pI#D4;rsV${DXaQ2E-(yy}(I;G?`#G!7l1KOF9<Qw~ zHUwv=O1%#!xi<&5xDH_bTp`e?U)$H#@DlR!B&qCi1~JlFjTyBP80Xf!R4yc$N~MG( zOZE#o&I_oPKjZefiTes7{PY4~z=;zjE>^Oem!+5v>=BYs-u!5u(#oXmZuC!3S{`X7 zYVR!N>9+Jy+DzzL_HNMbs)l98njU_Q(iyl`>9Pa_Kwfci-fZ33IYAf|$?99CmCqSg<}PHLpRl4fP|LmN#u8Ev?cL32Z3H=mFV2z8t5PHfRkeH^>H2{ET%p#0;utXt4BVC3|PF#QBa+N!dQmq=o6voJ3E z0v+2k?XoBp#&w`@VjSqXGk_llk{yyJXlJUKl;F6RF$Ph+0X6zD9V=7Mv+>aFFO7m~Dvs zEk}B;uXU47a%pUnFy7}vbi-JT_|m8`#s+Y6O7C2{wnlT~+DX1A{D56CP{pBpGO3r& z&~fM!BkrKq$xGY-g$LU7;=N>xr#rNd>@0_#Y}OsmH5sIz@4O@0hgOdkF99y#kIh}z zm?%G&S}yNsmPc^HpV03GELIfyc7K5~PL4f$TPwSJr|xnK6F0=p#;NUrO{|8tDCDCK zG736aB_!hJALmr+u(jTPu%@f=oi|)E!GpR7Gr%2J4>J2wn$Cah8s5X~fPacmZ=*D# zbfNU5<0GXn9b5|ybn#Y>YI07;A4>bnzGr#pfq>)4qwo*g( zYveS8(tp_ zK$nD6`)pP05^fdcVJ)#W6>EumJtCUtQ{FsZ>(7G&atA#d8(2<;kF=*%6gItaGh?Z5 zTnc6<#u=5&|NO%S&&DlWF8es3QP5leezJ3r{T$OU4!E#X_Lxd)+=T3tR?vf+p}>bL zfsfvFTjFxu*yz1)O9H)KDht7BfiZWOB8^SDaJs`gn2UrGQkXbh!AN<@@cmLw~K2n|#Bb^(cmu7aPcr?**9Oe>zYd!dEF$MSw# ztRb=jx4UypvcP^7d!ehq80EUR_2PDb1Sh?Zp8Spjb@I9(#hg9;MK2B%m2Z*Ldh0D3 zoS*_?Gw#C+GgBN1dKca;AR7X;xmu7x(Ft&Zw+}a9b9e7qs>izL&uAw<{sHYoihTtW z=;=Or!VLNkKn>gjNlBbRBtgR(yL#e`;Zm{Mq%EzWYwc3prg&n^A*lhVSA^CVkgo^> zIh#Qg+vO77(|d3DkS4mD_ph2Q?&k5kdb?wR+UolH7l#y_^{0`F^#qB6mN9Z(cY?0V zDPDjHHU2Bk?N8Y1R#8d9x@ExA=jpnko?`5%a7ReFAs!MIVICjQ-Y?EeS26Hqh%*FZ zfZ*a?x(d^}>_ANZH(ag#JMPj`%Hv%4PE2p=>2B#!H^r7~8w9|;7PQ6kI9IcQK)NHF z;&03Vu0k?s=*7y2a(g(g!3k27mD5ScBrCEJu~WKue&Y%ff_a1ZGA; zjzVIP9JeI&0z>pPCpiw>E@+&0HD@>qHSkLv1<)` zCw@@t0T(IIcAT0lv8f?FV9ws`BmsCMUt-H;^V=t@we3^XYsQ_jwYWS2ZTqRo&~EP{ zC<_rV;~u;egwgGi4JFl@vrhrVFoQ(8S=TA(MiV!Cdv1FQ(YgpJY|n?5in{%h*_^!< z=_7tVYts_&dIOkoJ$AbDu0c3<*a*)hfiyh5$4>bm&pYJ(UkkYoe6Q4=j94mL3jSN0 z@#R<()7)vf2iovoATex#8>S%GPN~E+>)3#1`mUha2r7ZjzrCk*_G#(&;H!9-7A_0Y zW7~*rE$FW!Lnu`RTY=EGrah{1O}nOYfgPIZ#VsAmk`HVxstj$8HbZ;ZHd_}8X>N?L z$d{(5cCOK?aCccC{25(n`pz{Oz_8TOlqT3;b1`fNctDB{Ir-3~7J!4{!guJ|^SL@x zhn4_KI6!%}-ep-MI;)iww5KpE-sp>;($es!`ofwQCC(+<4uX@GSQ~xs=N8<2cl#}1 z6f}0oQ4ezGJ{v&|Pt~dP$82`3O7E?OwJ4RyW0o>0wN&KXU-0Ct|<^UYe}q4%hNu{MV8%bBR44>=~w7~qbkxX9)P!zVhLl= zu_8)M4NXbgWkGD(j=+nwfojlH)#~Q96S)Lb)H}E983Ue@h&G%^vNVjwl_Kt4KPU@& zX?d)Lx#$6`Z9T>Y$W1uk(@Si1E=ytEO(Hnvex_40uCC)$q2eNgHd&HMTPAIxSos#H zp|7v+V9DLq&mx@0qR%I{=hN1F_c`Bsb;Q4=(bZQVJ6qsLfm@zPAFnnzMt%Q3mOhdnE#(RD+ ze|+yao-Ku$i}e2Ly`p7{9v+jlXawxJ5PcQrISVWUx;L5iIQpu|yN%2b*T#Pi-U^ zK<#gluLAZdhOpFLFCYSHBOxJdD#PnT{hvyRh}s~&7&hI%NT~mXK;jGAbQKtaur2Ec z6B+E<=oli0ee$Cu;s?8J{wU%PoA{0=0kE49@B`Ba$x)i6j?>hTnvp)bEx~o-s1FV4RxIvSRUkDVdlxah!VIva&LD^om4v zWzn+vWmU`JmXhcyDJdNny+U0zKDj!&T3zI|=6S6}u`F7I z7THPwd5dZn`};*A&JEgsHw>+1JEx4&QCbYlNoZ@l)r zb?uWiFTAvCm^yBF`n{u4ho}Mv2!wvp2PV&a$e5p{TT)&$uWI>Yt2RFOlx5r2-Fq6| zvmJhWU)}3HPz(6syN;he_~?sIE`NRY90*`qvFy>+Q|_NTV`82@Gj#Akg%2x}N5+hZ z9X~E@>lRPFWIx#`SNCLtJ1uNfqv-a8S3Q~i^`U)SWfO!Pkvycx@>V# zab;O)zYo>z^)@d@-K`*!i7-=Oro+sH$$-g%L6vGF6s(qSXQLN0iL{dM{v_UKv_BF& z0}t)@pV0e^_Feic>GvnRi-yxQseRYb{!QI9J!_-&eq|p#J{%1K|&({{Htd5}>t7 zNiasGQu3ofT{wMW=G@FIeL-f{+`?%Y)3WAHpHw(=l0GX_jqT$9|1`T`+T5J1jLfX5 z%T|I&zi(Xh>b3d`|E@|B~O zPpJOlA~upxC#egJlx*2cma88ws;nsGYfC-3sAOT;@_!G{`8|B<3@_nJk(|D~XmJ(N zE`3lfm6DQjN@z8o7wUF4tzi73OVyM{-aO|ORa7EZoT;Nti}`Vq5ez}An!pd+tO#=q z@c@31kqRNC<3j@IR7QM+0hrs?@LfP8#+$^$NQl5!!cM^4HiS-l#1~4JQsSXq2lJZ; zbDKAPInwv*Pu~ye`y>4Tq#uCv75(WekbYo)`hiG42^h5g7M;4|3 z`>&+9xX3j3p$F&8hJ^J4_fMZzICV0A7+-yUpE@Q&@^n1pPOdXLFKTM;JP$~WR zPo|&oUwz zA8$Cj?*1K>%9DE+magh4zVp+WvZo8?Fu@lpMI|NU1Kc~linoeh313lB-(aPK`ds&Yr8?#nYrFKT;^y>+#+HFd?DD_LLoeR*l- z_~!j@C0~dcN4}Y2nex>q1B&dnLtO_WHKz~UzjND>F9O~;e)#3XY^=oUGq>@A{G*}Q zWercQUNRyuzkJ62K}8>oPn!4M=8Q`Zi{@n2I8jayER)qR(I^jyXpSMt8v);fOC>E_payS_ZT;ChAr_JzeG4c7T@+Yg(* zu1XSS{xC?8HaB0o@62ky%l9tznY=H99i~voPCTiWpNT$H{=k6^OVqyS<~6Gj1er5jNU!Pl?vhqZQ;h6(PpM|ZPcdWK$N%ZLN%BOC7 zMEl^t)~I_qG9aKV8&fA@TKD&-6Np-nGeNF4OeH?!+c zmF|w|Ect0q-GUX;nnmoJBHuj|M*DYcm@i(Ye1P~ok!RZ$yz20G?<6!lIyU@0`R?ah zw)&ko|HJ#gURoV_<)Z9d%h@M&-<@-D2QHT{UibBoe-1dYc6LnDt#2QxU-C%y`>JcR zBv$i+0MDoCqIq*<;Lp5V_I$-V#oSrX!lJA%DhE`5C$0UZ#qXx7d|9T4186f^(t z-2+VaiP;so7av)CU*3Y|cP`EP^1?jX6|FP9bxh$q$KL$M%SXRi^F?F!bX=QO?a8ABh^^5hV07|H`&7tC#c{&6(@ za2m#H@yGv|2<%M=tK~iTV+RokV6j>_`JZ4gA@>qi%X{!A974!s!fN5~gj)4Ll+ X)A#=FhWu{R^tGrg4>p#39QgkqC*?Zt literal 0 HcmV?d00001 diff --git a/boards/newbeedrone/pixnova/extras/px4_pixnova_bootloader.bin b/boards/newbeedrone/pixnova/extras/px4_pixnova_bootloader.bin new file mode 100644 index 0000000000000000000000000000000000000000..ecad9c2da1b48cd4236116e9b50905951e3b6946 GIT binary patch literal 46764 zcmeFZdwf&%{XhObmt1bf}O*ofT^<;68KCeG+K*K?<{@YM{k=LJK)<+UEOwC&g{bevjYp zzuzC>)U{(5gpCs`_vXkTOh@AZG@;Qv1`K*oOID<^jS;K!;DzUo)G zr^tLF>;0-frtW$15s?i@>{tCs^;2YBVtm_-FLhgY9GP)>xU^FIR55#rTs?H;(r{_? z>yazEtu`wyAK&Kg*EYEOV;buFlNzcE52#6&wt0$kO3}HD_opPMnPiULYj0>HCSoM= zuZJf&)4ug(LNSr+Lqtv=B=UEMh`esFt-tiAZT)M1S}J!7XOtZ?O)|rt#Qlu&!dUu+ znK$wfIc9{&<4|tu2x)skPqGehB&z`zhMbjklxV9l$=z|S&Q*+jr`|lvDe7#lZq{?6z`@ZKgqJouP#1`J5BFkLY?%U zgu5L*B3Zi#eG_lC%WAX`Z$>Z8_5qt6twqv1_)zEV$jO^`B6UU?$SReO%(u%dat~zr z(1soJ_kN@;y?Gb%%q}q*lU!#M9eS!k&pG7OWlcjJx-3@CXZ1OQzB9^w7`JV)eSn~E z_n~h~>GNZFe(WUDXOuEJFLwKY8{f-rJe%-5JNk_LGQP|7JIx=dFB#>N|D`_U9ji;W zAzxV*d!)LMuGW6;?rXCTGy9o&*?!VSZ0u5H=1!7qvypi$rxSr$Grphj=Ut))}58&IHh#s-6g!cg!>iTui!4@F5~_g?w{d4 zfcrq6t~J_!;wFn8{%W+BkT4Twh_1RYe8qYUdu}rk+@`Pkb@h+EwF$eZzF*fsp?iXJ zVhPqiKdFHma6ew-VP++{lN%oQobV8Ve*dg#GjbpI@CNIlNr1MGlDq7!!){W8D>&9Bw6#Gz?mU$m{V&t8Z z+-I8T4i5)^6Ilyd*4jMQ_o>m+&y1DkB%zmKdYWP#tc#YhwuY~4Izmht#Ye6^wK482 zG1;%?ELvqwLMqm*$G`SCU3F#`vwxeNy>Q^#Q`MLKSovIL_ced?EpuU2{^w)wu1DS- zy|!i}(-oV4;oovTU|}vW`G5U7=Ns!7asyLPY(h+cG2oHZ8Gu8;Uh0e+U#kmmZ;rhu zUbIMYEg53Ai`hZsYf84n>>={GP-+Virb`x=LFA5Dv7WC)<}S6~A@f{)e`-S%Q{@3W z(S4bR78=k(HTG4*47$#VW?l2F3kL!^K685Pc`o2`aM#KmaV|#ShWLS07cpdX-#uM> zHe;bRKcgT%@}9^#*H!-yr}Jm^3(F#J`~4g7G=5=q;#WsfZlT|wXzuZ8oV0boOB?@p(yhf6k4uLu>r33b z@vfPU%1}&OSRrw8BDXw)3*-ysx%geKGdh zNpzg69Cn3I-;LZlCo$=Y;|ysoB5Om$lu*nWh|Gmhi|MqIahD)(bU5U0#|flmfx^zp zx3sNp^a;3JOFkprbl$&=A=*}4Da~$y`CX;Ri{W5t*wB(V{laB3i@h+(#U9bMrb(t= zhD~!R{*-3&b-sBw$rtNLa}D~d3!~#bqfDQ1Mls(-X(9R6zI?;T6cIUZFzXP}{%H-9 zqixoD*_>E!T1$sXyOzkA3NdI~W7l#{T4(IqBv;8=1#?XMO=++G(}qt!R)74&hBNVJ zKH2n1@^qq#O-!9MMKF`L!~MVz&CD?(^9u7WX^lSfIj%0uQ9^lteZo`DGnW!%`u@h1 zq%iXcu7d%F{ZHu`m*q@zj;70VNy$8b>tMjlnsb8ZK2=`&dui{kxW8SBlNTxcJR7cQ z-JVN&asZbRseGjJNd{6iNY#*uNGV7uB$=idq?mCu#UaIMX-b2XhNG!Oq!L>%$(bzZ z3&{bpZoSb%=8pgT6dm{fm+_f%=5*09qRmW$!pwO1&vcabrWQQdpIK1aJAT1K z{h13&dnbqw_h*Wwy%P(i{>;MCUVTwze`Zl>@1){K`ZJ45d(%p)`ZG&Pd()k(`!k)i z|E0Yd3sL7s(K-A0932mz^Ybn`UpLyK_k#hReaC-eeE(0Y!RLgp*Bqwh>AIn>!i{>O z>&Ua%lf)29v{qc&W=5Vf%3zo96tbF$T%yqbjbW1G@akkHkrU^7nL9XzNoR8MKarc~ z_cBv|sd=Nx;$`m;6m|udqyOZ7&4ON)IH4^yGgWjbe3eP$`uKQFPRiMf+O@JqqY1J0 zJ8fK!P_Vg;zk}vra@bFz6&R@^UekSLSzDd(SIM$+ zo;`(39zQ+c!`#-dCCwmzuv~~AqLfvA1Hh%znRu*5ShFfIdzzk zcMQi&5BkUqzDsRry_9cbQdx{vj3h!d#SwivkoeLS^&U<#4_`rI#rMkYE7!ANO3&NbBH{D(={KzWa z?!3M9)MZt!TIi|gm-8PChuA>W+R|3`SQGNnC6 zOqswd9BL)U;SFMv0}BZ@UVUD>|$w8q1u@y;c{tPiAm+W?oShG8Jhpb zSZR4J*APnVq(o?l{s$=YZ116sN8^O*-L8M!rKWl&AdW$~O%fti%#? zo(L(MW07k~OO*E|23;#NZ+}zDW@5SK`^wMA&f$RnM!ol;{`}@dXFS%Z8oT7s$N^8^ zHV&LUYteXrC)G>)?3{P498WaeX3? z^d`=&xTE;F^lfjQqpUu|X3dX4z}A|HDsP?ThqBhxMk|=%X+< zdC044r9JroJyAz`GBgtD33x(c81^g86U9kRHFnixDIB~boam`qJQ2g!P5Rab=bCvp-br0lRkR9cPFBdaNQ^_AZw zeMx)9U%?)tbES7$n>c@aokR;%^)M%)#5Z7qYN>V^LZK{+W9f`UJ(1!H7C9 zvx9q;lj}yAy)<_Ug;x(VnWonQ>WO@-!U5Jk_l1Lfpo5=|wUggmADv;7+W_eUV{ng+ z0i5(B>pi9?x7yV{E?{7+Em}bA8zX$TLClf@ehzRNoo$1dkGbQXu8+dpHzY9drt$+L zQ8?4JvX*!sh0JfSsH(Wv&se?$_0nN~zIL3nb;JXQ;-Zv_$)bCTlTD+B7ADUCN)?5Y ze8@zUN{$m_YIrgGXn~cJb)$?~Bi7P(DE9kCe}s+Ko79$MUv>>2C<5&m9C3Lpl0ocw zuu2jhB0}RTM$QODaN)FL-Sqy7lwE_msC-A~2+}2;BPv}AkED3?Pd3=KzSB)q;>`8r zNXuQ1Nc&vf{&Y$9e-C>sS6hLZ<+`2pVTKv2Rk2TJ3P!B}FM-F)CaEwF=?-Hra&bHBp+KKIyLThO!Tu)Y_!aXR{lYl2b4)fqeGMhCou`j4!`uH-*OA%v5)))@9N4}&q^J8y`30Njf zIhPri`wO4l*dVIJo#HGpQ@o&<4-mO$ke_l#7uuCMHIdCj{FL~v=RAwWx!B{3{4~C* z@D=nLsg!fy_t13zps{@E{_KH}K=e`ZWpDM!#aJkPZ zq>LEOD#Xgn$uCKg8tmh`bW%GoNX1}Y33zGq0$;d^t}*71%2uegP$SLH?7!ah3&m#3CY(0Xvhb9=T4as`*- z-~$D0PklJp3Qljcl5vEQ?;H#VmC!`&K~9bd@q+N9aF7fy6}bpZGIJQ~oBkv~If)tJ?CMbmmBQYTFiZuc#48)_Ad4)SK1=|Lz?w5}#AH1B-7T z7BlWSK3!z<@sNET+uPwt}=Q^J)r7dFDEY@W~@(FsSAE-pKzMVD_9Wl zt(Dc}vfrujrQcQfOs&Z56ynKgzZ1Nu?uIVz z8&rdlla(7ZEWbGgd`Zt32gF7=w--Z=5@SHGl2%kMmli7qtFxtN+pjC5T$0w8B)(c0 z4*o%5tPS?Be2hWyGk{D^{^5`^#*3WX#*68y@f~-xxFxg4@f2fWeR-J8rXh;+G9xtn z(a3+xP|r5U0IBGy*FiqRZc>QH4M|Vs)Jx#8HgXom*Dg{1ippS7euDBkbRW>VjQFQi zmdHP9!CRBI`Lia@X%zL~Y>tDoAhJG8c@SN*-bhP58a8+ur4^MNv}-!>b8+D3vaCe@ zd4d;ebQ+VJNR{mqyELOMjf$8KJq`BKM3Qqph5Ci)KABZJn zDkonVq&!cYs@Lzm%+5}8F{b5@RTt(rZ7gD-SXBezh^nRTdQO?pe~B?V>fc!%Ql9AFfR*(rslnBBEzyx7&mN-H1IMD)4b z)4bIovmEzWIQaYUr+$uNpgQs`PAs-WC%HVtlF$_c-k-T6%~pn8s`s1#->q*WhL0kA zC05!n=%;&??p-<#{n2*m2<1>I=kg8Ra=epFO_!K?oGq@1NH#?%i|VBtt5Q64jvpMQ zobg;h11tB85(7Bu2u_ILg8#5bi0mHy=N=*EJlMo;#@}!ah1bK6r8n)it9(%oa;?0T zW=bQXk-GJh=e8 zwLSv3;b7a>62%1NpAyB`Tzo?w=D=;Jeaz~(Nc(YaB5=LPM7kf3S@e-Gy7hb;pAmfV0O~~TgLwXfHZw( zaVQuOB!|*^3_SL`xK81^!BY|8_U26z zL%E`7z9~hfJ~F)}I{VBXs>L@x$w2bBUCENJV*iYT9@*vz2VYfQsZ8|<8xGky$Q&Nv zocz`-=^EtNWXP%MlEaf!#LCZvyIXY7CFyLeys<4Z*WcpUHASB_v2t~oT4~HJdW`wt zh}Hux_igs-A^R2P(}B>C0qvla9<=n zHJsl9No4k^%SqTHpwZzk!Fj(EmLr&i1oV+y$zgMg0WvKsj|=Ntu$Sc52CpLDs=)#1 z%T<_<4B+0x2zGvIkj_RpsDGQ{U~RJ+GDKH|)=-K-45Ps>M;QDc7>RxdwXm}C&%(sq z0bIa9Yfc1hNiwir9V9ol?o8F6g zP*Gl|J~|GSm=CD<6?g~8yr3|w{2p-D>T;@mpwvp&Tu^BcM}zMHpG9Hq$#)ta z*jM^k{^dTN+3Wh!rz)m(e>C#CE6P<8Xl3QP^AUM?+(H5SXP-o-GI#8A2~vt@zXTin z1xh7Zxobp_(($!UiY?gZa!3nY?a|=eG63E@jrK%ew3e46 zwJi0-7PIo(&`h~p(e=!4)r;xUWj~Kyd~oDy1Oo>k^@jgO+aZFc8M?Y1j8QN0@^J-v zFhOl(47}W|z>2g_ZDf%?3|)LwKBN2V=KbO}^7A-L+*u<3UEu{yM5jaK|5k4FLIZz@ zHA6w*mH))Mam5s3Ge#)>pt@9w?7aweyaGV&f`iW)07YDs_z#9%O93|#2eP8(Jic67e-l!Eji7|a}nFuWSl`s6$ zJr%HXHcC~l9_hLt?+adcb@}H=kPCb{kaTFN?*R8d(?X_u!9&Id^b9Ne!Q+F!2>-XA zn4)>6kACUzpu4diQfnO9O(HqP5Zz zgi5Ln(J~E4X~p*=yepm0{N{L3<5Y=Dlvz5i?-ZB*WS55PqCvEc=~`t)*X zCA7L^_EMMDmC~IKdPARdt|D-z@!iq%QdlZWB$5;G;W_vH%Y-oCTB$992PWlQCj+`A z+%+P^McOc+-S&PiMQe#YtA>VKFwDj-Pb7>m$-}`HW=Ak+)AIFNTDFKTC! zt3G$7bBS_G8JPjQf}0H3fTt4GN3W5YM1I44^qLL#L%6$V+T_>V?fnFD@}I&Cc#oTD zlGtpUyvLn7P+fYepSv^FYtWR+iCSmdZvt8_SIjaP4Esr$qUzQTaZ3CU*MDoTHo?)G zz&RF`_KI3gFiTuEH>B-1^m1fvFPFd|?dT<(#kJPU57=_ikGofU(Yw3j+gJlJ^hsn$ zD<|}FoZfNC^)BR6oll@`#(b;I_87D`9XTC~il#7T=ULQOftuD9p+4K%LT}?W_v-Tj z!a4flxlTpfPW!=_6MEwlV6Td&y^J4H46jSGiKWJ*uQmUXJJA zB8iX+jufcncy))O&GXnaL+b1Be&D9SLqxkOs$HWPP^o8)Kk#$L6@Fq|=BE;FE%^4I z`x(QFet2{ES)tX>3CH~c+W2z>Cw&%KyY{AVFtaUuCA!uLXSH;#txG&6xZ6&I7nvtmUzHly0or^7&P)PMk71wTfEMwpW4+l^7HRSZQYc{ z2O(u8-NWphDe>}%!t4c=1C9_!$I<#cysQ~CI8HU?d17Ia$?@FraE_F`7S=6TC@hjD zP)#PSjbJp$d%unF6jYy2`6lRotKvcXlEnQjlx_r-S1VqvI^tm_U8*q38YU*KvVzE; zDSg|B0iG~R`s(vr9aW9?D_+=06smpk`z~S)!q%()n1$MAfohU(V(a1M-wg_q9#(x; zq2pmh#z30Mr_>4wyMIZ$pe<(RQQwA;PaUzt-49PRX*g z9=t3OLXg;?|1wMxZ;U2{mBG)^O0G!|^N z^S=1oTg4r%OhLepRhf4U<>~xW9Gc%uroJ!n;xi9@@Q~`^@)kWH+jjLI!hx&*FjQ1v zHpisq58G^29j0vYK%j%`uF@A69v%&rC_Po>Ri?FZ1u3qIO4C{aK4vGB%~sI0$Aq=; z@G-2FC$PfWeJf=Xeg1Qquy#3>{DGr&&Gl=by*-|eHQ!{P>`Ma&lmcm6XVVro20F-z z%V{YFSBGhmI1*&Sg2V+n;IookB1k8d%?7t=IjlN^+&{8j&KlZlHRY%`GI?Z!NdC5h;xgV`_-+t7)+i@3HuNNhkBLumwD{RDen$}wwuz(DHl@!m{Jhw`?;dp`${oY*$( zROOff*O)zy@{5rfedgOUnzp*6W%=qmTFxl1pw^*~4%iKvwy!zH>gEN2B{J>VBb|{P zpN4+3suR6qUZc-uc*`|bvAc!Us@)pr$CtU=h};y)6>~(sIGVpDMD^vQ&BiB@H*O`` zkJQ%YRPnhZ#?IZVlUJt{tX$o=>YS$oHG)5Xts_#WY8SJ+2ero28s`vsOQ>SCNsKL~ zUr$}u&9Ok|@_a}GX`1$R4kSTpU$6o{Z2h_&YODJ}C3K7_d+n>&sJxzQbsKYFchy68 zLUKyIFDSKE?kHm^#p=bkl@5?~;Bp)c6BJ5 zb*%gsP`b1JNn(%Ress6Q$yUaiE%=CqJ=dYUqziabP_y2fGC($_wlUyyH>1Vfl1@C? z?@rmQxRLHk+^p0=9{q6el(LynEBL0-4nOkgdLz{MH7bj(c|mC)Bf*oy#6(j`5t(cx z*a-TZkF`-3=ZG&xa_oavQQs0xw}UgzZ{1?0xWKU{RosnsEFNyn{z?<<9D51{Q7^)Z zZ5)iW5QV7Wp&JmTPt&(iK2X=ZOF3dq6>~j0^sP6ngSLy6N8qoz!*He&7H~Ns@fGDM zE8|TNQdZLZr?Ed%#gFjqAl`SWHJv&kZsln}tPbslgMSSl!}~qzl+I&HjbW!cv6I%= zF-qU2snztYHC@d{-tLA}s%xcfeC4I^kzh(&*$YhpF%_)YtZaaFF{#cyHHGR8VP(AG z2a23!ub^&=Bn+HgNBwUtSg##rha`$Y54ocHzsL^Lr91Zme**%N(uzicr!oE=h7{x* z$EBdm3nUzT3O1=dxIcmWOGFDz&7(-Y3SKBWXG>9r?#2Y@+D<92TRW5kk#BS_mEaq_ zlgPJMtbn^RV!KqpF10o@Pd*0=RKXgOUF4%Avr=4l3nyxJ+w3**knJ=KTS7vNX|dE;rfYo{ zKKr`n_RDPYd`Y`dD;exI_^xZPm-TJ&g0?MHNP*WZBriN?2-p3D;fX_9D!H4g3l-p2 zn=}p{HJtQ`=FX0an!8PZuZh1U)53vMV27Bi#$xoq5O2_gxRe#riLxB20ygiJQk8VZ z^%%!>=2QX;N-5VfV@S4y61?u|<-1^GCqZ*!pDCFSK( zd`X;?W{Y#?!WJFpQd(Et0)HUmNN~+y1vuv}O-mc83R; z{N@9JbWUx_I@{I6nBue2i+KwlVz1`4k*WODhWqsedMDRMbdDN220p|kovg{nES5;G zE&asC$agagq@2dGdT4o0KwCmJ-gleFc@G4NINrjdR@QXJe;{xld|p&%OY=`Q!F$@I z5k7>Ro+ADs(w8d?)hoz_Nejueq|#D3L;JGWB*yfqfg8yIlX#%!2Q|!XDsY(Ekm}mg zla@&%!R!%(`1CSe-k!o#B_Vz!c+ZgT*3YR2-*cpm*0%wd+#D~o_p?(CB~=ce{>=Rg zsW(C$ndZI)c;eZ|-l8_dXCaSIx;LZXB|Cc_9C@y$JCm8HsN1Pzm+51&2EO}Y6XiIT zWu$o%i4=WHSI$!f{nfAURNT$R2Gp7 zzQy?v6K1uV@>13)ydHDZWMpA|Sk8&H%cZu){gS?r&O!CDf|`tJXidc}REJarpGmKX z)$h6@-%!d#S9OVlDLJz=nji0sv?kWcpr-UneIaS1^+0|QnM!zyc$}47IoIMSCxWxQ zqSjD*vcFwrXz7;723P+{uHuQ0;1g0(x2Le8_QA+=ek=7-YnNh0w}+FCDG%t#PNVn> zi4RQXUM-|{Bw>RC_()h!b>eGfo?M4cN^a(B3y!9UtC;bnpD(+WAK&pNmvV1W+XC7B z;H|b?hoiU7!N{eILv}9#zH{^}a@3x13vwwp$ua*4u9g^Lin)M}Wdxs+QMB78INnz> z^5s^eD2N?c4-%)f5v4y2w{BZ^^A1Jdo_cR-@4|_#%PjoFjze6MGuoB~JL>DUdba~Z zM%z37Z|#vPzF7<~sR61cg;V;z|4n7aM zJ-?Q%{YYKfYfoO-rgg?Rw`fudAe{}6^|VtG~A4LytP!bQZe)AtsP*^FizXk_i1raIXD5_&iPRO;CN-bZtH5Pcw{8hsop0 z)fdRE+2UnCcWu`?SXpy5mM?r!%|9^&z#FuCT5j0H5Vb++EGB7rDt!KYj{pl_J5te_ zXntz*qcRn(2bO6$w*{6~10&x)2yVxt2VEKo9)q8P4l-Ufotv9@F>xEtsgpY67D8K+ z-=&G~>`?fnD#HT6-&9Bur_f$F_?3eD((6qT4!@-9~`}{o($@eawl2l--^@REZiy5b5$1+Fn z`;NF`BD-vyWA`GVb_KJ1sa@vn%TWi7<*0Z>4^xrB|ZU+N{kS>1liI#MJFRl9kcbZPuggQ;N zv4)Ao*PH&mC&NL{h)|nc!WvgF261m$w4}R&mNeCNqD?lSV;Iv`8*Q8R;{&`42k#40 z_xmi`4S^8g0-!e`nj$KFp&~V?BynjPqKii7$OIeJey zm|G{_t8H`i7Od-Aw4j!+Rmq%c6~oMET&DFUV+`7*U#ji{mjRpy?og234sJG})Uiv~ zxQOD|bdC$)-8Dwo1o{bjm-RpXMT)`3STkJL{5smFv3^lqk_-OuN5j0SVgrTjiuF_r z5e~lh9x)|h$NZyBX-=rrV2?e}5?5=*deWUiR??mEP-J&0t^Ez@El%tc8|Qpt_Lgf6 zzq4!4RMak0t2$tNH%5I3e)n!g?Hg%p`=3oAGb)~lz0lKe$gVlB_vJ=3>vWgdu*;0K zlbj{Y>7{)cyPBH%8WUsBO(lv~dj0Gz{SD&_-e@{xpHuhx*^1ib>eo8n8e13r*!a_&tXSRLE^WKvyZ8+p zx}-Km)^d}5sg=(1J6q@zuRd{^Pl|zsgX=Dr6An%u-J?8dRR>Oy2o%Z-Im7K4w>97$?63HC z*DTEp0dE_Sy5JiReQ$U+F^(^yF{03BCnGA$9A`qjn;F;!QKQ6c8W>#(Y-6^Wgss9r zHDnT=6E?Ae0I!bQhHb#+nxb$p6ar5N51>QP8&LQ*B#|sPE(-4j$&@cizK0k8({76| zrh5(W>%d-2SyDEP`e@#WUN*AB=!$9q50JY~L=(o$%B zl9J%Zw!D_c{sAgPmc;kM)@E*g$0rN=d{$|`?z${18Pg*foSj%)(`Z&jcZHcg{;>RhnD^ca; z1LJ``!qBVF?LMYVtUjhp(j8OM4T(d~jlQ5vXxBDPXnHpgpE&Jo;#IA7sWM$AZRIwi zO`lJ+kK(>=?4D#N+V75CKfwKIT!VKlNhzE49vYkj)rNju##VUSjF+k?hkx zSbkF4`)%aqAK7{x#Py@`-Qam3seEwuBy97EYS_Tp(%yP*VVf(L@+?BZ3d)Oe6+eP6 z@{hn>M&{$>h{yl%kAC~3>wenv-*%FmU;AiltYxB)%-lFoaTv7{wfXMr4;*gqYbOcd z#oPpSTCq0O2JHG<;X4%$zA^GVte6`IoQD~dDmu)GEBpBrVZH31wxL?H@!HdeNzTTB zn#0k$lTr6wzG%&J&)&S=KaZaFuQ<-k~ke7qPaZ6^>pegeEYE>Wp8=kqt55P*caUlFAgK-bP`Q8_%4U6zK_$F;} z;LT`@@|!o{a%7O0Hx68R)3`O|>@)7r%fO^syoT4LT8$!{Hzkhul-S#7^XuxX#z2-aOv+yC!BA$+5}P>+lXaca-c$ ze1uI-t|QZv&uuGVjN9*_Skx@uz@o#!TSqQQ1`i9r%2-dfxTDahitVf~{$m8QrdQI4 zGGg3VG#pGDxu{;&`IK|=BPv)3TLS9D#phK6a&l9|+WE7(riiuk0PgOY3w$5+$Brj6 z=6gR?+Uqi=sY5Z({#D6)l)w(Uy6$JnoiD!wnban)toy5Cee`Lpq0H&f&*gQt8HYqo zU^00Xx=CAH=FqkPvojpLKJ@FpIN*}chJFSd!kY5MM?giNMf&Lo{e5~pv-h`<#z2!t zG6XIZ(?GHKTI8WPyv&(lCvs(7ICyS&%xC1MXEjWxPD*mE&>Chh^^;q~d-^r=aYjIC zZ{eh63TMDd<+HtQhc3Co^ko{7tsdgnV-R( zra|u*75trkKU4(?f%3h2nN8%ptdLVeYtYNu#5iwNWYh-u^H7ZW{SmETihO-Ss|hfg z-}`j_MWO(z@v1`WG$5*S6ZbOqF>M7jZ0JKoUr@;R`Z5e86f3LxNbEWEC-&M)Pt9)G zr>Ly7Pg`+s^V9uLjOGGnM>yzK=r?8$ogM0bN^^vR*9KqrU(k@w=!|^!1?9UajiR)P z(kY^I6H22#RsL89t#Qn!%Bh!Mg-05*|E%V}I;#-pS)6`a(dC2dkQmbnCAOL!in%)5 z&hDa`9XFS0n+VwEcISK9{XZPqay7#^t(Q~(fJ)|z5aTT|f@_vjiN)-aoO>hlTV@#- znVIFG7lChY%;~tV=QL--PDnosi`MopNItXya+V(Rkw9?=BUdx?dlQl%ap`l`A6kEh zhV9e}wDu4<_W2ldI5;z;i@eEKCvSoYikU;tD)S@XUQG`N zpB-riq`$s7lx9>8(3Lpb-*`A-i*pCu%AF)dG(7)_h^l(z<5CW(}OP#jz_GP zwyRl5hn~A?1I3&ao?iT-Y6ELh{Ehs^YiHhwD*@J$sdVC=MueyYO*wcfL4z*~MR~h~dmw8_+2RV+8kK|oJ?G2{D?mL*^@w8{)<6$A*J1A!QUz;&5aDNr|S8@L%?thGf2Hgb?4}4!L zt~^{Bxb$Y&3=q9_R;k*s3eZ-yo{s!RpXuEGv_yf$AUY~cz(12dhkyo|9>5Q?q1jk!_Oh2bKo&*YaR~%esFU!D{>Q)R!w-RrJ1~-|>-KE?$Ut^&qHX(IDNmz8rM@$vP z6b8;BZkR*7HuY=HYy06sxA4Pz8sXDKVXeo-8A8G4QK1r1j9tuKL7!0Rz+M;1zvuk! zLQ~~wVA`mxO{Ru|FON1>rBY9V+{Oy{FDimG+u)GfIRUj{zLrq_w#PLZ+zq`2c>pJi zXEnPe>0ONLxxJ_hOo{AX||hIogfyWgScGj`i$ z-&CBr5H@5LXV6^JBe@Dl7IG~_uIb1XzYV!2I#Y}Gl~dST?pjuvR$`Pl&NmKhU~tVh z%3%hPfX3zJ<4g9H*O~TVtbZSc{%r7Z>e*ro1@DcV2@?0Zmc-+VeKUsK{|0zf>^U3m zAA*OaFh=zi-Bcc<7jShquGrxtz`*eY+D(xwqEP{h6&5kk@CI$GL0N4I$$~BvKK}5X zdz-ZV>vMX`zdu)xJu4Ak-U+ZwE>~26Os-t|-6ZW)0hEWCMo;!>4Cpl8bf!R;f9f(b zkjO zwnw9wvFm36i~KecaX|e)iTq&;Y$k{+&Oj`|LJvGj<#U6~o*O>0R6{!)d>B5n@rVi< z4zh@w1N>4CKY3K);7i$mKIk`yy^%OG7JfEyEhE7*Z&w#a{bp36R*Fa4;}v^`s*g%ZM!V)CM= zUBEatBkeDlJ{PjY9IqxYQ8iUgR2{a@JWIWpW`vtDFSAcmDzGN3hJ|Kx<*>&jHA=s; zXP>z!?RLd^E=uQIg0wU}(H#GYP*6U}wdfw#RM(AhSjFY8aBxnzLefS~EuwQlYtDkN zuhKdd8Um|09nTBH?_#z;_GgHH!AT~Rv-}mcE_>jaY77O35${0b)wIo_;6q`pC)J9b zQ#9<4$G(B4(iI196D|AOxM`!iNe`*`5+aWH7#P@Qb!I ziFN7m4c?35Hjmp=j~LN3Db_`E!~h>V@y+6)9<;mdLp~zM0k$|qchhogi`_*`X)e83 zT^I`+++vS2QZsljc6{3;smR5+SXcBr?VD3_xMC3#9_^pr6@snCfgW?Nlosm$SY1f{ zC94a)@Rgk166eZoDS>U2dPi0lrnrLs<+$>j9e`++q%HYm;^!fDmLA@mnv!-s+T`X3 zU>%g@QG+WQ2SWa|Z{FSZL}J6G0WZMpB)f=wdJv~G=nfQyf=l2F3(26AJDuFbx~ayS zdezc%VgCI+eCmRQ;RzT4@TE2AH+zhT>V`J1iTY+n%g~tY{;^mN#Mp%Y8OxEG{VVt& zP`dyp#X0u1ap+yN%)frw_HSS4Y|&ZG%>G3ik^Tq_#6S;3`$l;hD{R2;;%p1UWHOD& zCZza486ooINa`h|^a{?ZDw_(;IDzl774c2YN`ZC1M$^fFkHJ|y%5A*{wYg0#&Ol6x zTKp36K@MOboGM`XPS=r0-aFtG`--v}Q2vj~V|GmhhaFe0R9055N}~{KdE_PgG~aFM zvqhsQVfX1kf5)ABQ4yhkU?FFS;MiXu<)u}2+Tt&j&-{GBZE1-fa_i^kt171z^pzj8 zcX<0MmuK{rrz(skts2(dtV{m2vX=jgU)ww!6eCej)VnSmeC|CheBT%o{9%lFsCfpZ zk#i6^704%_!=I}#m&kV_(rPm~r8JZw3LR-L(j8?{FS}dcrk*%?*5M$$(%>&(nAM?V zEc!3RN7xAE-T1(E+)v?tcFZ&Ey*3(8rJVoxXdNvJg4|fyGAWmlBM0k{VVhgm0dSR?P5bHur1~IKVrdy{l z3vrH%lfas9OJnkZTSUB@M=T*9bRJ@w$mAx~knAC!E{%FYu?4*7oU+5N^`>%rN(mr%+%$x#RBx3<1!XMOLN8^wU1 znXS#u%(;Xo@KB2```zFH+AFIIsqQZJ9>kxw#4e1zH?H(kWxD$qdd&zH7u8^aBFsB( zzjns4p#SuqLfFfI|1xm)AH4{ekI3CftyXWstNUkkh2*$Vx*j-l;BC6sb=Y6p<`R!n z+6oUM72;R7xl%mZ%HiNONZ{0umI$Q-U5~NFEY6CdyvOD@iM9q8;)g{6K6T8_t}2{m zvzM5IUi!SEibm|}Yqv%q*ukkCkXyT zYpCqAA3fm%X(SYUdsJAX#xB`kMZf-VXzS2c)X`H@(L!#09}(;v`IDbaqj3-$)nDO1 zmYkqz(guBLu(V#%z;eXw!ii}IVgu7-io{Uxr=$Foxm^UO3^H-d{+Hn2z7N_5l9TI= zZ$U|(%2?l~tmhP$;q)W1o-*ibqOul!!x+oNU6nfu-%)PWy@Ocdn5N{Woxm>i+xSN& zdx)tFH0ssDBJ7P>fTxH@@K0$@T0++p(^O|SdZ9zm0dnq7ZhB{Mwr(e#RnzZ~=bRF6 zNFM0ksPe{|HNIromZ)zVXJGPF3KRFTf1G*HmptI!sBeokz}Iy8LEk&@zhCaXQ%aR> z{4#nDLxY=2ittsSya4r8p#3r;zJi_u@a=x*M*4kYl>d2rte2i4;PTUXYifxNWRR^2 zdn6RRI1)Kqz|40=XY}rY(!2W@!yGPx~b2d zDxlZeuwrkG@KcOkeKo`~*LN#?IVQ+q_3b$2!%D~a+&52}usj)Vs%o*UF@wqjihz%( zr-ltHPz_xy-EH*S{>V4W8t&W*$qdN4;_rGS&O=icKp?(X?kS|@Zms@1?KA&3{7>Y& za9T|Q_+p$X1WEAw@RZn&c$0&W%Jdxdo@sPB!Sxy{VP6|&aP9|t-hdsL7dmXe>wkoBsl&GhHtafl`3EhmA8VFA*tD_35^5fZ)Xex|jbHigVzmArA;ZR<)FfybWMp=H8;jDppD-+}L9E>v4ka_r zb*u6)mJP+k6GDu@JrC`IsbuHAVloxq?pE6o8_C1YMjD4@bcfTi5IxZ}Zx&#^nCeelPAC z++!o2!9VTZQ>Y6}N<8l+W+MN}{aiO7z3$uo>ZYIcJRgOf*z-Nln|_iG`msOlPmxn? zEZ{Awx=lanMvh~Hv#q2lIZdWJ<|g$V++H!Zp4|D0?FT`T&-o8-ci|nd1xo(?Ka~3? z9H`GVZeNLVw0&k?tAFM817DX;P8*=*Z{iO#2UawVujhH;SscDrlH2Io;CX!!XXW+aB%dC{H3{W?QblEOoG}c(Yh8*~*DAArrIaXp!gOzA$ zn8I}iq>?3wDx(mN__;`GI#R{pxTg>Xz6A7~2YVZZDOCj5>%kv~f^|be4P#N`dZ!;n z0>2J_>~~bAV6?0^wqPeDWXdPjW3KrNaW$NU^QPfqW(EAQc(1{Q$oZ+fI8$7?{mrHu z_(A9UCyekuVGSAM&i(;zjcSv^!6olSdIL;H%$K~4SoN15NpCW(`SAY5RXYkBBlL=% zFtE?wxS5>)?Pg}qU;GL^p=SOE&y!n@0J3@Tly8eS_{m6Zm7DkI+nV0A8^Di( zs){S{mN7lAaAaJ7W9UeK8h+F67C-m)JkQ+z3x(6AH?6E{Yx3P^X=3K|JVSR)lt=CG zQ}~2ul$SB#t&Tz|F`w~H#3QhniY>!dGv+&esxpDrtL{h;G7MM z)7md5&UPU0m;UO)x<~4_Z(7X^)%Vv`?X~NU#ro>EBbScFo1>w?024~ZoYjLmwqH)l zM8X!+*)7C|QNI_~h?3{mHEzVXzco^*OeNJV%w3H&zp$&$otwf#>B!M0``MJsLa?9Tj4gYM8q;r(M!$ zuom976jnmPmbVX+>S-0y*=5!O-FFbDIy51mOT6x*Z$^WUjC>B>PbsCR6*Y(x#mOQ# ze>r8O4m;;FoF(*~E^5PEB<_Vp@9nnOfQI={x6Qsyj5*KDD#AMMgvNq9NBN(pN6p>m z5E~hbsH;yDzMcB1E^WKte!pTdl=g0e=N6y5TQV?bT3`!t^L-!DT!tk}xq=_Mkg~2o z>X%=qio^@9P;e38g32^!#4bORr<<*ve!&+PU}9-+NY;`CSI@@d3vgpmLKrT&ClQz zE+YTeunM#D9mx8rU1a*Wu0u7)P0&vR~=xB3=IvPzs6dZt-SaWVPcy)wGycwDVb3e`z zBxaoABRuF5>iYaVV4cdrTSj7wxGfA$xPzXlj#3Z@W&$zu5iNq&HX8Ioi@?=Uojfgr z^D3Y<(2J1wEjcYDJ;OR0ylYqw4q#?ZKXe2*J%VHIgbrtBatri<)mQy9bB4UoDOd)e z$Khc8`dj#hj(_`MqD_tHDkK}>P6H4R5d&I0fAN`@8ZC~(ZHh&;;u7$>a~c_HR~ z&N=2+7cO)6(Gw|eQ@9$pm@l4z4*FQQ2-0U9uim5ej0Qi4q@s=BpSwI&5_Eg#xV&eC`uXNuQwBF+Y|&hpI6R(vTU zGka3a%n+7Z?j5ZHzdzq=aZPoar3{IynQ6JpN2c8_ zE^IN0Ye83X$`N1Be{h+7LJz3p0}~ks)zkbBW_Bj^fKT+rdS>QKgl6{rFjsTj)3b%z zaXCw>w^5oVlB~FH6TY+F7Z#|_T>OM&(K=1y8GnUziSJ&V1*mKTM$vYNBlt-ph(URA@2TG{RQSVsw0mb#c54l%>F%+4QtM* zDD}C^O9Y$^W}VwzjQ;b^X_sVeXL+$CEZXrKj4DUdWRv`q`?B2*Sh(=;sM_9Z&zLh??Z-vc={iW%Jx{2qaD%RfRRBD`;rJz&`FfVAdJ@KKGn19+oCt2)KuF1>&3jMBD{FQoN@s__3@{F{O zsPOd|gZ`nNv^aKntMCT5H4m-&JwlpRpj{@P+8D7w!SP4Wii=M{3dDr9lU5O;TF%92 z=j0yPwUNu&h1kS?;(TLeLZ70Ih!0}+_O$Nr(h{E6##UuCWZpIM`b+z&o+fS@p^)yX z3Y?*x7UcX6>kc2?7>m&r;}t3&@q7Xf=r-pn&oE$d4e_>O&l3lf7JARFA{y^20t#G3 z!gMB6*lYG~#@k|P3%tVv${5h!mE0cgxwvNCcAPXGQa&Hw44Hvi%xcGHXZd@8_ID5H z$-v1Q)ylto6XtLP`)EjOLMK~+k@qUi3Y}N6m8iux<0LHFhn-@^Jo}rDaOkP9vfhbV z-q97+)-y0CbiQeoiO$?6W&MsO27G9F_CJw!PA$x{Q!YD-P6MY?gH)r@nszUpF~9I* zZR_&m{U}7jR2w0FBkz14-#Y|nau#Um#i)e_CBKI~9}aE8Sk<=TTvX5M6x+{0M=2aC z#;Ke?#qSA+?m+L7e&x{p*EA~L01aX^z2TOh$M?jZ!SPKrES*JwJ1;yVYw*zxm|RftE)5gvuy8WEA8bqYYoQB&_?Z z9oDwjk@kA8At^q~k=P#sW~b5UdefOuneAznpCzd~rF?IjGpcEHWpooT_*^7o^cFOs z-UPjK+eR*X8%ES68PB7o-|JTal}%&(&QIuUqOlEq$oY8VX}<_xFt+#=rhj>rrV~Du z@wk6OBBMPrT0lt5uEt}|FVC`D+Xw1B)Mu(3y>yqyfYT@FN;0kBwSF_&Jrr64uERTI zxrvw1k1V-ABz9c{&+9zVvI>;;O?x+DKf}_CeO}<#*a#PJ?qI%p-%hLcl&Nz2QWI8# z$3(q7n&#q$>2{KjsV|yfZz>c|Pq%}j-MYr{liyUyy+JY5f8tnwD>vn$f2Z|e^V`li zdyAx=8xGCu9pc$p7~@08^%3rj@Vtqc_9pt}-d;B8l$S>9?0$R^a_<9@441BLwmE6^ zya(#mV|Z&Z_QAT1LYs~IPA`euw_quBT;HH^D2|QB+BL?(y-26>9bHbxkm3){@``Xs zhqe=yON-TN3;4%#JzOp9Njdg7>oMxN{_inHZv)mYedo^lb@&z^b>8j-pQ4$tW+8Ld zBaV#%XBhkmjLV(POPqD6cOB{-Eo-6D>M+-1!4uu#9rzCo;0pDJZa6@?BB1veTgOYzf(0n5L>r_7Brx-o)&b{64fJFliHco0Xo&$FOBu7lw>P7_+9C|{d z`+7oeLgtxvJ?+5q?Mi_jql`-49opXg+vj0ZO@gTT(gcj?p(i5e-R{sIyJ;S9ni+LP~Bp=g)9o^g|nKELNA+acS4Ibca@=7esJgDxpcq<~|La#iu16IO5%*4xmC& zJdFs_%eqbMl2@oJm=U3Z7#aI%n%C+a2R+p(gNW(BLVx^9T2$+_Uuigr-E)8FbQj@5 z(C+dtk}en>BifZdS;q#erA$}f@C0bDshE#9ci{=h+g)eh)vo4itxq-|Nnm=5jqEeg z6FtR^{edSCQjU7#fY z_UXPm)CeB=g@zp-ew`L*H`zM0UXpc2u+z>)zwYY)dJ`c53mi!Wbcc>MQ>=_Uc{qai z^FL!!^6Ql8Q9esYIBAD;r+!V6Tl$@zCGq$4gzkKo&Xv~zWAsuH@l7_{WgPI|z!z3R zr=bUOl4c8W61dtO9&S%}=!b3&^q=lfZTA>Y0q8LsfWoAFs2dbNqW1$yOx|OFwz!DS zaXH|7h-U0iG-Gc(c@1!0kGwQ0v3ShvLEiWI9#&51W6fbBq-)}5)4A?zth7qV4P^CE z=;rP%(w#bH9GA9h(XbXerT$ZLdvMReGXL)V_C8RAmM?W2@hj15J)vv*=t~);gtRmC zS1!nNmiXz!SEu*-{e4V51^NIP&J1AWvA}IzoSw#R46bkLA{tbsz4VIK^)|*9M!ALi zBNw>8mjmwREUOA>W_JDHSHho$I(~z(6;I~^>{X3$H^My)NBf_`c>P+n=Pe-2=N;y9 zdqbagUGeiJBtb+{Li_=e5u#JD8~ewhc0&{C=}V=3A)$FVq+xdV$G7ppYXtBgqwgqW z9S!cCLA9bUWb40GQorzNp|(Xleh0p;7R-}ZrCj)Z^0%E%uD9acrfAoIIL>j@_mv5! zRK?CY&1}LglE!sZr2@_O=4Q1M=wP-5g)6@}V0{yJ)W_?s^N#OoXVHQ^r)hzmXy-3m zdycn`K4kZu<*i#BTF)oWZyfd3Ker1C%gHF`@q`jvl*8oEI&A?+!#PkEBc6YJ!6&$) z8jb2#1l8gKoP46%RqPb@BF{O7d5GWji6hqNzl0N(IxhMHuxq7m> zw1Y1xDwLJ^gviP*zX6zUSWGQ0y13UUnoXtlAb+-<IYNU{9ppcn5}9hFpM zx7lZA%xO6oG{s!+jfJm|neIIpG{(&Iz7aGFtqmGeX-k{p#%8`poo5TUMZQNhMb&mN zm>FY2I&)0Bk47cG9jDYc`8uk@zkF{53nACNswE2CDqAPJnfT0c;H|15m8eu73@(nr zIu|6J8!pS%>9&2`z>+q!*#f+13y5Ni-v%nn3HuG7 zoI)xVylVqWU9%f^mc?j%yA;LEsO6%;9NC&bA;yUq$Imfr4VC3y^dw?jF?@3}%B4GO zO^yGJ;9|7)nUe>D73lvxRZ)Sjg!v{*;Nz-K?Jt%rki_l8B~v$VwNoDy+vA$^?Rc+Q zEO4OLZLk0OVDO%pb)A3sYm^=N*yrrwhlP(`OU#~2Qs=c9pt-}55b#|db7 zF5T*VMOE-+oNRFs?@?14&}(7?+L!__l@!-38i5{$U9ds*TDzdqe0jiba_Yg$t1mhb zrm9wGy7PGQM+gyti+^g+sjiz0#j0dlTX2F&U&;_D=Zdv)T*LIJZe@zi&a z-){UX)VI*P8S#N?avFQ$UB&QX0robCXTZ$f+gYPrhO^aa_YQ z728z4eTkFhc4n!+^?UJc{0QzJaO_ApjQn+}_N=tA&6K|p*eg%N zr{}02P0kr-_{qezq#WyuJ}NXh4X5Hd+1>OuM5g;Ng!_a1X;+S5QKPg2F4z^D}G z6b|v(ZTo)UW)6<;qQc$nD&>`ypZxEPlJMn9wU5Hc1$Sc7k6v!(5174+V#H2;1&>vv zGG?uB-(~%Z3Lnil%r?!Zc2Jdd3m|EawcvJ^mKM-ylt9*=g;05WJ~s~a9)&rq^isbG zzPZ5mgIylC`mHFSr(lkDiKD-3pcLE|%x-sDfQzyfj>GEb?%40Pb?A7kdzUolc<4dSf7Thq_U}@Ow zrxuU-triEAnuEcz7;0l7*8Ua3sRm7YQH#b@2+cPkaAS%MzY#XujZzfN>|7 z;Tu0zweqjLNzhGpHymlW>`xAi6r+sex~t{BQpkP9Q(y5JUiDi`{QUOOYi~70`FP;F z@pT2x1gB~$v&&|$gI*%arFuLou(LQoJ78E z7{lMIfnZ{@Tm44+C-&R$e~Uk%(_PB>fFIY!=d?E5?a%K}@(Jg7nG1RedC&?#s~&Jo z@Qs74SnJ>_LT@7p>tbZaQ$9K$H~BsL&cd|Qd)h^|qwoM|UrO7YL)`Wp+gSUW?|0Z| zpgeZBGRP}U&ba0>!&-SBeMhAV3Fm~Eue=G+pHc=nIo@Q@8<6ka@y(frbEpfIMC(R< z(LekZV~2t&Ft2+<$7!sk!y&a_U-a={eW%wKUH`q=9z*;7XG!)27*-D@Vuul9Pi!{g zTSRks1S}JLx7G}7)+BoY_WK`pY0~%Gr^%@_r_I^B3nA}hTHUS|&L1aP2WbPXX`FXT zcF=!Y_D_&Rd4Ds>dg(6K&L-MqT!7gUn>`mT(OhyP{(~2F-NSr_b6>Agn9THe3`R;jVS#zAC6t ze~s;4}9JyZ`XCz|4&s!E=K2on6=i9mxP$QRoYO)18LBqX3HIg>D7* z?R_B$5-b{=vxo+C#JRL`bV42Q5n~~{n`ne9{_g7rcpUxonmp`Qj6FK*fmy%|*qiUg!bH9I!wf_)Fqx z?9_mHPAAu>jBX!EFfUMDktL=3LaRZE4xG9`T-Jh!pkya6#oIPhV(Tmww5@%33Q>aVxh-MY_?D20wOI zmBf;6PpFoP^x$a2@*+t;(^!3_s}1@oILQHT><(G!N`tv=nhw4pBeOZ`%{rl zkMwHrbN%5RLA_9BEz4IQUX3}y{e`70(uYH>#I0@Ru2n)ZRm{BXgY2W;=m5HmjHRQw zkw$6GS{^ia&{BGGP&b8-PzFbxi~$yv5M&j= zj)uhJu;V;X&H2C+sP6+|KJXl_Z^6342R@Oto5-HQCU9~Y^ai$+zxL1IY419$l>p?q$Q*B`C+p2zX zX#?R8;jgP^>bK!8z^!dM z#Tkjp!|Tzr!0x+M;sS@mWuS%rlk|!X$@du#-8sA$^De8Qg*cLgjfC_Tp$_lFGJSUJ z+SsO!e}MYzf>{ zCFc74*{EB&+y@U-jezASOJG%%X%tF?JPPYrRt4>kNC9R}itR1y2p{#5T9_ltU;+;w+&ObUMo2wNJbX?8tO->tWs=>}MstgKm^>fyFej$N z(fm)o2DVZL#yZQq&bKmgidXsk)3atf-*0-#jx(?xbhDug)bC<#Re3iA?km{PnI~-M z6bd#3^a7U$X^iYSIO70;V4dHGUQ8lg3oiQ+iLZ?r>mfpsj)_=6% zJ?~NeDIDtTqxR~AFMq(kHlPhFYmY*IO0h>#7Y-c<_ZQR%H?`v!u36xyTTu^ccX)7= zoajsZIrSkqb%UJxZ8`N@NWETV3G8vJF(Uu$<^t1xe)51^u0^Q-fpY(&oPG;ZwDb?= z{hFM@Ej%HosFqV~a4TPr({r$7s{oZ>QLDg6t?Ns((};bR(nITeg`9pF(l7PulV;4i zCPlfYH}p^Bi&p&+y5$4uAC%Lx)wlgXE9dn{Kfm?w4P!Iswor}cAY9@t?eszpx2k^w zQPwQ-Cj7;msV15o$mWe+P#-j6rPKYz8$@HZ+|3xWq(=W%+A`sU`)r-n2wC- znSJkmADOjd`vRWTi9>ue=9PPRLnMAu-y*%dLobD1(qWouqlMAnG-m;moeNwC>{M7j z>wnz(t@k+22g7rI$$2<9v_jpp-$(ZM$rxilV*f|`@w%>%cbH^7rel1H7`u7! zGvxJLoTCSZJFYSuv-EmQbGkp{??Fo4&QQlhTyv9r4cI&=klP z)1FZeEw2L-mwFKt0u_*tC=V)w${VD|_l300bbo9Ktli43sM!m9xILq1Dbepy*um!Q zi=Rb3BzBwkaRCLeJKe|CRA+e@Ea=aCbZbp&2NWZncdiV0Q%`>fv@WgebKiB z{H#>e!q9D&`TZ`m`p2fy&aZP7H-G{JzXf|m>H})O8TC-Y2NzUsf9X~2r#MZCsu3K7 zRB&hI_Hlt(Xq_mxE<%B&p6K#ZT9VJR$7597uPNOR9ZBghmt?T#p;x!`;~6hEgV9$! zH$bb={oV320=OUIDz&}Ns%wn(f)lc;4w_%3S2+0NeNyNUH0DJ6I9PG*4P7%JEfC+v z!H!jjKU)6c&soc5D7<`z+PetSEhE4Kp5=6}Wr5DVul*&kOhf#SW#A!`wX=Bf6r>~z zme&DAmYKAmbK}r~oe_5E_^127XF}>0+4c_6t_AR|heWhGK%f4*oAirkcj1KLNNvi2 zHfjdsf=FVPIQ4F4Epm-8yok{!z zZdx_2@}0m=b?K8{UU`R$C2ez^awV+1W96xpzvKj($dWvBqoMRNkB0=ISw)o1e@VJwX+S=HfrUfW;SVHTm3H#G)=NMz ze&JX7ykP$AT8qK`YM@NJo@k2jtkHIqHdupWQoV~AE2?)v3oTGZdJ@|1d`Opk5Bz7s zKb{??w-|YYtvI(4zm3}Ew(q>R#Az|S;GlYc*^gSo*5Mz#7VMgjI#NNE-XgW=#ySOK ze!$J`EkZk)8B!a=MdG-HLo33I+o~O064hgibQ&r7pHtQ&r?cK_=om+0+vHfv13Ip$ zr@i9k#~%Legt1Q<}2A?luOv$ZiaU^$sQy1E=zq@d7}2o`TKTJ0VL)8c;imNDhhkh9s}?jQ`mhrrx)isYh%fKB)*DCN;DvDW8 zXF9G&gD+fPL}yRx(@Xi0(Mr$B{1KO6YeGBW8I~;(s+-t z4_oU6hRm>lLwj>gi?m~IZOy-G9`VgztDHs}A^(syLWEE9udA5-1=5kFOc7PjK(Gg8n6>+4nS??WUDKy4OPMoa)L_HINls zTBU4L2aj>7$YXUcOZ7u1Hc*x3ti_6Xxd(EpX_mk~)BlIRDs7Sc1T#7Q z%M-WaiJLJt5?#mr?||cWlW*Qy{Zt|S22fi0KpdYrV`o~?z!L@VAJ?n&ChTqxNKfjw zx$C8;^xIZG;WwmR>r+k4p>+CM>m*+R^zJ`G+HEy^kZ$`!HPTb&7QzBI9q=-JeNiKx zNF2yD-X}tTkYZ~jw*|a1FQ>nNcx?)E^73Fsv5h=qemvVDUEq{XE8L)(hZxem@Iq=j09w97J{9Plj?jsfwV zrL1UU=`7&K9DCdx>)0l@m?Shw2?-1S!a{%%tZ|B_H`5?ilFqUwhr4uoI!EqYy;UKwRjZp%*kCZmjm2yMZ>sR(J z4bb({Ku>V1RSjJ)19ZJK4GR+9lkvfq`VG%~k664@b7sS=(H;Lo9y_7u70HA2ymmsD z`7dS1U#b~*I@BF~YYS2>=evbkx^{_>~({PWYZMt91qAM~#pEfKpZ z#$RjK-tMVI&%{Eb-wmJSMh8(U5!OjSv>-bZRp_ntIw8O-s$th9=y}*v=%GH-+kfe` zV)PpI8Dp(W+% ziZaIrm&a(mo0^0w%w7(9sL+rAO`jP!z)k4bU)QQykScr?`7NfSrb~yp{*Cu8W(*@vUb&GXiY`dgjairOGXyTKWKUp zk}LF;j&Leoed?7ZlN&bQWxe?o(ywxmHPq*=uT&EXJrj0Sb6Fqw@vUb)p;};p{vI~2 zEp~1yed)QRHzlRxQ%UFAB#C5KTR$B7>n!y}?`Qsek7fBU`c9k|`-x`STMw}h^zm=( z9%)B$rJ*O3O68cj9NH7p-mwvVZ)}QC_<*(7?2>K45&i7hy~#<$r%~)-h7csxfyAj6 zLDLa{AJ7>@ROwzfPb)TJ8zy8_Ts3(C81L^rZ?6RU2N>46!VUhD@LB|>s>Eazz z++h!e{@pVqsMA(U>s;^r7{g-z9{GRaM}fU>96S3l_|?)AX0=fV3BqcuQl*_ES7Y|> zsCXQEE?m{rR#aH8v{h6~LhZNJ;^oDwcP$)Na_nq;u6Wrpe}lAk{ZVNR5NIE@PP1!g zvw+k^=egd{qumk9%PhGk6xH(=|D86HHH*Q?V-NNadOEkl4TCd7cK$JE^lY8skJ38q z;YpJ5L>K+9hs2otOmH`oU>AubF2CzmU>8Nt(cWE5HDUE-fy7iHc|03&1Etv7&%nbS zWxseQm*aEs+4a_uF6lH&Ej?!uTAF!deWGAI(oo^jyOeE$QPh{XG)A>+lj|dw>#*X6 zGk!W_DsDJQGoD>WU7ti*N8lcXtAb<2uA=Smxl~=_a4(-a&g(p+GAfdzU2|OXDvMVx z46NgybO}kHxGYIgE2EO0T&Zmvj6Yskv+_w7KM==~X0IeGF@v$2D?f5Yo~9=$mP`5y z-)UJ|I-e}r63yocH{R~}zBmHxI>ACe$SZDbgI(QYKPQgqs9sK2j}Zv5Uwr z2Pv`d2COm11H^T={mTn`f6z!QcOpR8M^E71r1b@#)}BMrX%dv zdnQ*-gd6MGi}^d`l3rECaJZ;;cyZ*#%=7ptlJ{I&TZ}u zeTY5fFPbf1$eJyrvvqMm=D!EH1%opG(4O8eIICd`M0EnTp`ksq{eRV-iInjCe<|TV zf1?E9suGC**Bk1Dd*Lkw;cFkU|2UhHiTrIapxh0}s#oM5XVe1XO z+_%H3YK2aNwF0kwsd_>)F}u{D|A^b_9N<`?g)L#HXK$C*lIwYYqcx!8 z->)Lj~W}$F2x4%XH7R z9-|WyN*QlJ!xu8f4my2doh^6_)>Y%E^^ z__ZuBS1R+^3I)*Hb-t~ILy==#H`3=)J2EGI;ag;76Oa2y4+!IUgV>|U<$l7wYRe8Nt@5m#M) zSXb_JS6qf~gdg+|>PDUPW0 z2WGIEee55)|G`Gp+uZB7Na9lV$KKG5-QrkfD-iiH-$-{HD-EcXJ&*<&T<2(a<+6}8 zEa|6G+duZ`n$#{CfejR)%ixD~wTiIxODoiHX@^ta^vy;dsEk57s4=tXu1X>~^AQXq zrTJ}qKWSal;(PsGcllUTJoF=>SDFf}s=ULbQ+mb!NYkn&mi8{*2KH|GIP*8N)I`ub zSw4+l*k5jXJE+#)cUJr-OVhM6Q$i~XtdPz~VjI>wBgynytR(BjOrsIA@T!=|{dv}k z_5#6G6!F1-{ckCLi7U7&Zt%JJO|wzINUcz#tVpe%|D{%e)T^GNo_l}u%NL@T=AXX? zk}S~+CR|i5edpo_OAlPMm+Zb+_(<=?4<8wMQI~Md#o8!ZTmO2AxtaV6%oy3pt! zQM5k;DUcg{Pg=LwD^E5+n|_{$>*g=LAJlWO{}t4B^S$}7y1T_vdM>fppnbPTx-zc& zsgSy7tXo=;1=?8PiA`3`NwP)! zlbel)-XExIk^B3)H(X&8XZto;`7hRkC)nk#PAEq`IQ>g@mf7Y-+8fXK`KIuHQoC5X zC9v7Ovt7%fB}HgMKQ~^l#mDQCswZ}s6@@tW*=}A#(?IWH zq~wh}zR4PQlE1#(_Hly!9JA;7Cz3QPum!*U0lLmVloY;xys4d6FKX8gXi3pd)rEfmHmktJPUn0E$f)3!LnVV81m3$BkqhNIK-- zxZe!96w*s2o6Up`R|h=S7@*a&WGm1|fkKc>*Yi|8Cm7B$IysaS*fTGwQ-?5g^ zBXYOXE#E=SQ4hu-OwousJ76Igb>|$B{1+ailF#D|M=`}$#aIurK<`1=Z8ic2dWfqi z2D}>B#x%>^o3TSpq|2viF@W|(TnZL=2H@<6C_&B{bMbX1@%A8{! z&hHR}ZNL<6clqK=sLNp9ghRUFlDbA$)Q^2!TN1qu7f`cnX5`*b(CGq# zdCiRMlAPIJNbWr0^14{z@*n1J=j$9&==!dS$aR|hp9ig|E1?36u#EezU~ipX@`Bas z!@eAM^SZ`kuaU9%N+_o*r5Fg7Jqmj={Jb6`_|`*xDSIF9DVVEa{jReN`Eym~j>Ab>{e1vFaq zfpwO$a+^ir;U4pPwrwv0~3nl9ri03t*T0NQ0%*jrl=Z?($q| zeyRayc{njOvJ;7Ip`J~WgiH;jP#DuTCj*m>8Rp|;JE}lYG73E%3%XFAtjp8mKac*Q z{sdpxj?ssGWjJ&aawk_pTYCuK8QN6PYJ%36s`txN_*a||X5Zo9gEiR&utMo7GIIA8 zs$suqD-fDBE!<@`3`or<6~$G~=d3l53mB}Y1AV#%PQQN$>|hQ9ZzJnXpWD*+(b2yu(0r_ghNlKv$EnClt^c zz7jeL)HYGpE`AlN!%IM2%md$bxY!MvWjOQ~q$)$Iy+}ppPskntBQ+Gd^{RBhlAcNH zR@8BJ+087FI;{%}m2T&E39Q|w(+%_&rBXKzIZo1Yp#KN;JhzrJhtpsQH)p*S(wlbD zksksLbEz>V6*=7_LIT=u|DBA?yae^Q61opkAhYCJ)Bu-@m+a>*U zLeRKfN`x=MkB6^@9|vCxUk6_YUkg7Dz8Zc!d=Y-4c`zT!`LllYp$ex48XPpjj;y!_ zCo&#=NO6Dd#|}7$CB@01J&;$Rd$7EMvu!AJy^O~vJ*y7t)r6cODlXEg`RDYt{n^gj zP}6PJ9N#KjCE{wLuK`!_xJvVN;3^JR$-eB$+fd_e)^Wa7xYFV(!PkH*HLgbZI&dZ8 zO6RL^>Ze3%8RgSY{$1gRzN^bC>)$8Wf++i<;%)p7VSl0Z-=HY*N!m=lvu$B4tXpbl zQ2YC_c8aW9k(w07I+qCxiHbSYz7TNDQo(J#1mv3vNZi=s@oj^QB?A(=K1tn3I{B(z zJtSn9j5RxEwjNfJbd5JVU$CZlzg)5l?ct26z!d>a^3r-SwrTpI5hdP*JAmBJ7+HkJvnL$% zCpuX2ML*SR8C=}#yhf_QO-_Y#t2M#vTe1m#Mm0d`EXsg-B*T8Hu*E6_c>(g4bCq5d zWM!z#KZf<53k5Ro#|X_U+*ymM%$h0h^`lvG`KtRKn38$lB=~nb%U3PBr~Lk9YbI7O zD<|UkqGckS4sIA+5}Xn4PPo-@Yv3G6msPK3X1FnMiEs&cs+@6bAzTIABBUurZcE_b z1>cGIRdAVbGZCJp71&)x%Phnux%*<$_8<*S!6VE+#MNbelU znFGG!D&K-IC0R2N|L8z?*?_-r#fmk{R+KMVyz1`z$}5+%e3#3*s&e_gx42m4s+E)A z?!JHd;AnRs$9Ja-7$Unisj|^ExsN#VN7FyJn4Wh4ERb!T+l~*OwUCRgtY_ykO3d#uZ)RsYB(*N4lWKZ9xf41&zDVFwD^HZYt}q8e=Q5+v0wk> zHV@wPWI>MB3|nQBn7S2i1YCP2>_5QG!2L0BcTL2%aNuXawGVNvaAyYG*(pqYdmd9i z2dBA?sdvJE8;%~?int3?nffP$&%$k;0UZQ{SHeEpE%z1 zWEeyK*Cai>u{*ILKObh?W2bpXL{I+|qWkcaJ%?uU;Uw%)^?_aj;sR>(@9J|F=gMKTuh* zc&a{S(JznBzrUhl@#@w0pnD$DuNo+pGWw0j2THD7eh*t-zMQ2}pQd5#%X&Il1rfcS zUMpj@V~@S_0es8%FPJyOXRmBYfWete*K0{Qy8cXZ^#XNx~OEc?~}enR%W!{^IB z-mUDjB|lmy9jnlv{RenT68NXzU z?6KP;e$7$Yum1O+@+0lcFSus8qOtKno&9px%(Fsi-VNDf%w5F~uD@e?^XheHN=Mv3 zw=CB>=Ygz=S=UZ9-#a<$y2;r&*JfqIWIQs?h>S*BHOxO>;_ap^V&SeQnc4t1>}ia# zjZ7V?ft)?ub8x%h{tR~)KEA9`Eb1tZNy^alF7y`nh)V%^6wOn(6oREmYXd=HGln zPWH^mFA^x8vLN@-YwyBxc%JG(XCfZ|nBaTIPu1+j;$ZpF2D$@9Cf+!d1_D+f%QOxi zP5~50>kq|EB%kpXJ;lXG;w-qNxM}47{NpSEJV(hW&h+zr`9jWfFfQY&ICm;k$>6Z? zfIz_5qqru=zz&>_@FTb;$9Pf9L-=7_lVcpu=OR1<*W|c?`0H^^jvILX0bG;g2hu-; zYjXTR`jU7xBPR@mm$ir2$@N6u{}(@A9~1eeA}#+TFlPQQo{^LEz9o-|-%c+?#tW^_ zg_L^e1QnahEE!K}ST-E}tQaNq%OCI~A^iVRpLy~;AvR4W{``ALbx*jJNz8r%6<%UL77b24j=Au)*J` zu_MbEZy5|S!#L);I-I6g)?6LVGU#?(9lmbn$OBi0`C_KSdtrmWs9DO?tHZ-*>nvA? z6G}#wT^&xE!(3N~({EPRTpiB7MYrSX@YGvJ9=Iwj?*-Jn1v`D(T$CLH?qV;-1 + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The px4_fmu-v6X board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 + +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The PX4 FMUV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +// GPIO_UART5_RTS no remap /* PC8 */ +#undef GPIO_UART5_CTS +#define GPIO_UART5_CTS ((GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9) | GPIO_PULLDOWN) /* PC9 */ + + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is FRAM + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */ +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* The STM32 H7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 H7 BOARD DP83848TSQ/NOPB + * GPIO SIGNAL PIN NAME + * -------- ------------ ------------- + * PA7 ETH_CRS_DV CRS_DV + * PC1 ETH_MDC MDC + * PA2 ETH_MDIO MDIO + * PA1 ETH_REF_CL X1 + * PC4 ETH_RXD0 RX_D0 + * PC5 ETH_RXD1 RX_D1 + * PB11 ETH_TX_EN TX_EN + * PG13 ETH_TXD0 TX_D0 + * PG12 ETH_TXD1 TX_D1 + * + * The PHY address is 1, since COL/PHYAD0 features a pull up. + */ + +#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */ +#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */ +#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/newbeedrone/pixnova/nuttx-config/include/board_dma_map.h b/boards/newbeedrone/pixnova/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..1f45efc569d1 --- /dev/null +++ b/boards/newbeedrone/pixnova/nuttx-config/include/board_dma_map.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ + +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */ +//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ + +//#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA1:81 GPS2 */ +//#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA1:82 GPS2 */ + +// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned +// V + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ diff --git a/boards/newbeedrone/pixnova/nuttx-config/nsh/defconfig b/boards/newbeedrone/pixnova/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..3c6064c790ed --- /dev/null +++ b/boards/newbeedrone/pixnova/nuttx-config/nsh/defconfig @@ -0,0 +1,332 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/newbeedrone/pixnova/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="newbeedrone" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0035 +CONFIG_CDCACM_PRODUCTSTR="PixNova FMU v6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="NewBeeDrone" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DEV_URANDOM=y +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_NACTIVESOCKETS=16 +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_TELNET=y +CONFIG_NSH_TELNET_LOGIN=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_MUTEX_TYPES=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_ETHMAC=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PHYSR=31 +CONFIG_STM32H7_PHYSR_100MBPS=0x8 +CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10 +CONFIG_STM32H7_PHYSR_MODE=0x10 +CONFIG_STM32H7_PHYSR_SPEED=0x8 +CONFIG_STM32H7_PHY_POLLING=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_DHCPC_RENEW=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=10000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART7_TXDMA=y +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/newbeedrone/pixnova/nuttx-config/scripts/bootloader_script.ld b/boards/newbeedrone/pixnova/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..2e6eba3607bd --- /dev/null +++ b/boards/newbeedrone/pixnova/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The PX4 FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/newbeedrone/pixnova/nuttx-config/scripts/script.ld b/boards/newbeedrone/pixnova/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..b6b341d4e84b --- /dev/null +++ b/boards/newbeedrone/pixnova/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The PX4 FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +EXTERN(board_get_manifest) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/newbeedrone/pixnova/src/CMakeLists.txt b/boards/newbeedrone/pixnova/src/CMakeLists.txt new file mode 100644 index 000000000000..605cf16ac948 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/CMakeLists.txt @@ -0,0 +1,75 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.cpp + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.cpp + led.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) +endif() diff --git a/boards/newbeedrone/pixnova/src/board_config.h b/boards/newbeedrone/pixnova/src/board_config.h new file mode 100644 index 000000000000..02acf72f8cc1 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/board_config.h @@ -0,0 +1,518 @@ +/**************************************************************************** + * + * Copyright (c) 2016-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * PixNova V6X internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* PX4IO connection configuration */ + +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS5" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks +#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid +#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage +#define BOARD_HAS_NBAT_I 2d // 2 Digital Current + +/* PX4FMU GPIOs ***********************************************************************************/ + +/* Trace Clock and D0-D3 are available on the trace connector + * + * TRACECLK PE2 - Dedicated - Trace Connector Pin 1 + * TRACED0 PE3 - nLED_RED - Trace Connector Pin 3 + * TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5 + * TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7 + * TRACED3 PE6 - nARMED - Trace Connector Pin 8 + + */ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +#if !defined(TRACE_PINS) +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +#else + +# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) +# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) +//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + +# undef BOARD_HAS_CONTROL_STATUS_LEDS +# undef BOARD_OVERLOAD_LED +# undef BOARD_ARMED_STATE_LED + +# define GPIO_nLED_RED GPIO_TRACED0 +# define GPIO_nLED_GREEN GPIO_TRACED1 +# define GPIO_nLED_BLUE GPIO_TRACED2 +# define GPIO_nARMED GPIO_TRACED3 +# define GPIO_nARMED_INIT GPIO_TRACED3 +#endif + + +/* SPI */ + +#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) +#define GPIO_SYNC /* PE9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_100MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/ + +#define PX4_I2C_OBDEV_SE050 0x48 + +#define GPIO_I2C2_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. + * ADC3_6V6 and ADC3_3V3 are mapped back to ADC1 + * To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3 + * respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO + * PA0SO of 0. + * + * 0 Analog switch closed (pads are connected through the analog switch) + * + * So ADC3_INP0 is GPIO_ADC123_INP12 + * ADC3_INP1 is GPIO_ADC12_INP13 + */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16) +#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* PB0 */ ADC1_CH(9) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_ADC3_6V6_CHANNEL /* PC2 */ ADC3_CH(12) +#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13) +#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* PF12 */ ADC1_CH(6) +#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15) + +#define ADC_CHANNELS \ + ((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_ADC3_6V6_CHANNEL) | \ + (1 << ADC_ADC3_3V3_CHANNEL)) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* HW Version and Revision drive signals Default to 1 to detect */ +#define BOARD_HAS_HW_SPLIT_VERSIONING + +#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15 +#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 +#define HW_INFO_INIT_PREFIX "PixNovaV6X" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 +// Base/FMUM +#define PixNovaV6X000 HW_FMUM_ID(0x0) // PixNova V6X, Sensor Set RevA +#define PixNovaV6X001 HW_FMUM_ID(0x1) // reserved + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT +#define HEATER_NUM 1 +#define GPIO_HEATER1_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define HEATER1_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER1_OUTPUT, (on_true)) + +/* PE6 is nARMED + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#if !defined(TRACE_PINS) +#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6) +#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) +#endif + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 9 + + +/* Power supply control and monitoring GPIOs */ + +#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) +#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */ +#define BOARD_NUMBER_BRICKS 2 +#define BOARD_NUMBER_DIGITAL_BRICKS 2 +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */ + +#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SENSORS_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8) +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +/* Spare GPIO */ + +#define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) +#define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) +#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true)) + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 14 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2 + +/* Some RC protocols are bi-directional, therefore we need a half-duplex UART */ +#define RC_SERIAL_SINGLEWIRE +/* The STM32 UART by default wires half-duplex mode to the TX pin, but our + * signal in routed to the RX pin, so we need to swap the pins */ +#define RC_SERIAL_SWAP_RXTX + +/* Input Capture Channels. */ +#define INPUT_CAP1_TIMER 1 +#define INPUT_CAP1_CHANNEL /* T1C2 */ 2 +#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT + +#define GPIO_SAFETY_SWITCH_IN /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * FMUv6X has a separate RC_IN + * + * GPIO PPM_IN on PI5 T8CH1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7 + * Inversion is possible in the UART and can drive GPIO PPM_IN as an output + */ + +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) + +/* FMUv6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#if !defined(BOARD_HAS_LTC44XX_VALIDS) || BOARD_HAS_LTC44XX_VALIDS == 0 +# define BOARD_ADC_BRICK1_VALID (1) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 1 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 2 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 3 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 4 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +# define BOARD_ADC_BRICK4_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK4_VALID)) +#else +# error Unsupported BOARD_HAS_LTC44XX_VALIDS value +#endif + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_HEATER1_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_nPOWER_IN_C, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS_EN, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_PD15, \ + GPIO_SYNC, \ + SPI6_nRESET_EXTERNAL1, \ + GPIO_ETH_POWER_EN, \ + GPIO_NFC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_PG6, \ + GPIO_nARMED_INIT \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_I2C_BUS_MTD 4,5 + + +#define BOARD_NUM_IO_TIMERS 5 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/newbeedrone/pixnova/src/bootloader_main.c b/boards/newbeedrone/pixnova/src/bootloader_main.c new file mode 100644 index 000000000000..77df9e78bcef --- /dev/null +++ b/boards/newbeedrone/pixnova/src/bootloader_main.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2019-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/newbeedrone/pixnova/src/can.c b/boards/newbeedrone/pixnova/src/can.c new file mode 100644 index 000000000000..cdebe7a3ad61 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/newbeedrone/pixnova/src/hw_config.h b/boards/newbeedrone/pixnova/src/hw_config.h new file mode 100644 index 000000000000..4ad1049fed94 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/hw_config.h @@ -0,0 +1,128 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 53 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/newbeedrone/pixnova/src/i2c.cpp b/boards/newbeedrone/pixnova/src/i2c.cpp new file mode 100644 index 000000000000..8a557078e0fd --- /dev/null +++ b/boards/newbeedrone/pixnova/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusExternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/newbeedrone/pixnova/src/init.cpp b/boards/newbeedrone/pixnova/src/init.cpp new file mode 100644 index 000000000000..71d10f100e20 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/init.cpp @@ -0,0 +1,291 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.cpp + * + * PX4FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + VDD_3V3_SENSORS_EN(false); + + bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); + /* Keep Spektum on to discharge rail*/ + VDD_3V3_SPEKTRUM_POWER_EN(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + VDD_3V3_SPEKTRUM_POWER_EN(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_3V3_SENSORS_EN(true); + VDD_5V_PERIPH_EN(true); + +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +extern "C" __EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); + + VDD_3V3_ETH_POWER_EN(true); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ +#if !defined(BOOTLOADER) + + /* Power on Interfaces */ + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS_EN(true); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + // Use the default HW_VER_REV(0x0,0x0) for Ramtron + + stm32_spiinitialize(); + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + if (OK == board_determine_hw_info()) { + syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), + board_get_hw_type_name()); + + } else { + syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); + } + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +# if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +# endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +# ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +# endif /* CONFIG_MMCSD */ + +#endif /* !defined(BOOTLOADER) */ + + return OK; +} diff --git a/boards/newbeedrone/pixnova/src/led.c b/boards/newbeedrone/pixnova/src/led.c new file mode 100644 index 000000000000..1e33dd1299b3 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/led.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/newbeedrone/pixnova/src/mtd.cpp b/boards/newbeedrone/pixnova/src/mtd.cpp new file mode 100644 index 000000000000..8e57555eacad --- /dev/null +++ b/boards/newbeedrone/pixnova/src/mtd.cpp @@ -0,0 +1,136 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(3, 0x51) +}; +static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(4, 0x50) +}; + + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi5, + .npart = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = (32768 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) + } + }, +}; + +static const px4_mtd_entry_t base_eeprom = { + .device = &i2c3, + .npart = 2, + .partd = { + { + .type = MTD_MFT_VER, + .path = "/fs/mtd_mft_ver", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + + } + }, +}; + +static const px4_mtd_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 3, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 240 + }, + { + .type = MTD_MFT_REV, + .path = "/fs/mtd_mft_rev", + .nblocks = 8 + }, + { + .type = MTD_ID, + .path = "/fs/mtd_id", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 3, + .entries = { + &fmum_fram, + &base_eeprom, + &imu_eeprom + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_entry_s mft_mft = { + .type = MFT, + .pmft = (void *) system_query_manifest, +}; + +static const px4_mft_s mft = { + .nmft = 2, + .mfts = { + &mtd_mft, + &mft_mft, + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/newbeedrone/pixnova/src/sdio.c b/boards/newbeedrone/pixnova/src/sdio.c new file mode 100644 index 000000000000..869d757756a0 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/newbeedrone/pixnova/src/spi.cpp b/boards/newbeedrone/pixnova/src/spi.cpp new file mode 100644 index 000000000000..d33dc6a74739 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/spi.cpp @@ -0,0 +1,89 @@ +/**************************************************************************** + * + * Copyright (C) 2020, 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { + initSPIFmumID(PixNovaV6X000, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + + initSPIFmumID(PixNovaV6X001, { // reserved + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw); diff --git a/boards/newbeedrone/pixnova/src/timer_config.cpp b/boards/newbeedrone/pixnova/src/timer_config.cpp new file mode 100644 index 000000000000..928f4916f0b8 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/timer_config.cpp @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH2 T FMU_CAP1 < Capture + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + * TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer1), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/newbeedrone/pixnova/src/usb.c b/boards/newbeedrone/pixnova/src/usb.c new file mode 100644 index 000000000000..70eebc6fe0e1 --- /dev/null +++ b/boards/newbeedrone/pixnova/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} From 019acbe1f5f831e1974dfd5e078b79c7917b9938 Mon Sep 17 00:00:00 2001 From: LiuYongNan <844550332@qq.com> Date: Fri, 3 Apr 2026 21:41:13 +0800 Subject: [PATCH 2/4] fix(boards): rename pixnova bootloader binary to standard board naming Use the expected __bootloader.bin filename so ROMFS handling treats the PixNova bootloader asset correctly during packaging and constrained flash builds. Made-with: Cursor --- ...oader.bin => newbeedrone_pixnova_bootloader.bin} | Bin 1 file changed, 0 insertions(+), 0 deletions(-) rename boards/newbeedrone/pixnova/extras/{px4_pixnova_bootloader.bin => newbeedrone_pixnova_bootloader.bin} (100%) diff --git a/boards/newbeedrone/pixnova/extras/px4_pixnova_bootloader.bin b/boards/newbeedrone/pixnova/extras/newbeedrone_pixnova_bootloader.bin similarity index 100% rename from boards/newbeedrone/pixnova/extras/px4_pixnova_bootloader.bin rename to boards/newbeedrone/pixnova/extras/newbeedrone_pixnova_bootloader.bin From e910373ef389445c3a6dca900db98c678798841c Mon Sep 17 00:00:00 2001 From: LiuYongNan <844550332@qq.com> Date: Fri, 3 Apr 2026 21:41:13 +0800 Subject: [PATCH 3/4] Add NewBeeDrone PixNova board Made-with: Cursor --- boards/newbeedrone/pixnova/default.px4board | 14 ++++--- .../extras/newbeedrone_pixnova_bootloader.bin | Bin 46764 -> 46876 bytes .../pixnova/extras/px4_io-v2_default.bin | Bin 40160 -> 39796 bytes .../newbeedrone/pixnova/init/rc.board_sensors | 21 +++++------ .../pixnova/nuttx-config/bootloader/defconfig | 2 +- .../pixnova/nuttx-config/nsh/defconfig | 6 +-- boards/newbeedrone/pixnova/src/CMakeLists.txt | 1 + boards/newbeedrone/pixnova/src/board_config.h | 35 +++++++++++------- boards/newbeedrone/pixnova/src/init.cpp | 8 ++++ boards/newbeedrone/pixnova/src/spi.cpp | 6 +-- 10 files changed, 54 insertions(+), 39 deletions(-) mode change 100644 => 100755 boards/newbeedrone/pixnova/extras/newbeedrone_pixnova_bootloader.bin diff --git a/boards/newbeedrone/pixnova/default.px4board b/boards/newbeedrone/pixnova/default.px4board index f5bc995d2cfe..ba42e02a9d94 100644 --- a/boards/newbeedrone/pixnova/default.px4board +++ b/boards/newbeedrone/pixnova/default.px4board @@ -7,11 +7,11 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" -CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y +CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_DRIVERS_CDCACM_AUTOSTART=y @@ -19,11 +19,14 @@ CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPIO_MCP23009=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y @@ -34,10 +37,10 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y -CONFIG_DRIVERS_PWM_INPUT=y +CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y -CONFIG_COMMON_RC=y +CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_UAVCAN=y @@ -54,12 +57,10 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_MODE_MANAGER=y -CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y -CONFIG_MODULES_HARDFAULT_STREAM=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y @@ -67,6 +68,7 @@ CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y diff --git a/boards/newbeedrone/pixnova/extras/newbeedrone_pixnova_bootloader.bin b/boards/newbeedrone/pixnova/extras/newbeedrone_pixnova_bootloader.bin old mode 100644 new mode 100755 index ecad9c2da1b48cd4236116e9b50905951e3b6946..7d45f20838940a844b798de938dbd817301ca263 GIT binary patch delta 27893 zcmZs@3w#q*_Bej;%p{qng{BYalQzk;&^84^3sOKNP1@-rU<>%*p-Z5sQ&6cQS`|qu zpgd$nMt70A3ZgEG0x8s`U=0eo>aJ@7bhosyR8hyaq7z!k^pWI$Zi?UC-}n1(KR0t{ z=H7GfJ@?#m&OPVcdH*W)+AkE|;Kmmyyk6|2Y`9s>q*F$TLrBgZK=SfIBtIjT(v$B_ z3nDoM?xqKkXJ<0X+DoIXEszjGSuY<&?7GTlkDOJ|RIcB}+4^0DpF;i-I~H*xGSQdF zn?{;xBX`V2>PTG~Zp5>Gl?1VszBBEP%F{|t7Wp-2Erj2qEb2NcIIUQ+=8F><1Gb4( zOfH@wKFLf>Dy%db;vDA`U6xVSP*$0yPD4INY-QF=z9aJNv~ow*IY>si2;PzWqAX*- z1>h}$d^J3`EI19G|eX8|JIM5|}R686=_T-9l3d)JzLiM}W)w^+FV^g$io%?TY z#CiIvUi`jkQ(xSc({4s@{s_s{$CtYCtgBM=7G(Ox%i68|u18NpZOr{7p@~0ujc`xf z$&<^H`J=ir0vEi?rWiqpvTwMLRIJ-;&^n>Y9@ub#dHWb5VLp3_PP@f^-g~ z*R?LoXD%kst&TjuCOP45?A*G@U9a>?e#XUwxjQ3w-%Ig!rYPDGos-yp`6nc+qhb4_oH2z(xa`vObFD1C)K9^WKY5G&CN)DUdHo{b` z_)yo1JTB-M5GjkkM_q5JQC5@|u@|Bco6zjy@O!m9!-oU&#C=f-;tNrUKxF%(O4Du` zs6L3;uO7yEY%}Yn^0eO6mh(n-4U!Ea)@CyIKBM~Vs9u{x-ERSC)sWa`EYAsH=n^g<=e zOuKiN;i*jiui~sxg;m;NEdPEuDnH;u6PeDH`qrO{ELgtqaZxMVOlCD4_$i!aP?bl? z67Y#p3O3N?tv|6)X4yx`llTDwOfd-QVU?F-xmIi)Mb_};Q7O)OgVQSX{A~_K7L`If zeplcNZ%=nnoT(1WJ3r0NVs9l6>Du>5prSSl2jq9zG>jsO)|G$`vW z80gheh&=%J>*2m0QVFDTNOK|Gn~vCV;}Lr)gHRjFV&sxr2UT{x<(#@hM=EU#m%wPqkikzRq?Y}!=i%FMrdTTeR?y)j}u@r3y~4OOY5^33=FIeX8UdNPjQ7%#}_xjIW5FEV6ap5yskB=vZy&x__Z%?GcvjizxL^#ee}Zy zK;5%_x-DI9YD;_*%A>YW{%}Ej6XjB0LL9de>900zhB8I1h|{lB8T5S3CM@4SbZo$g zP|mMji}e?YpuHE+PWqz*^y-1Jd>N+44SIF?t-9uL;B=VDP_i@n6T*Qa@s0RmJVE?6KFvu$CBa;g=XChN2gy844t;N9EcoTDmT({{tmo+? z=2m&u2VXeQ1N`c81bs!#8-GKH zegq*df)LS}pvk+{ZG3W@HOfc(^|;(k%ZGv^sL=C8t$IF7_(fu2+FlLzN#c=&419<9 zO~RCvH%=nYM=>bt7^I?R6_2w>cW8O6n3Bk0Mx32Eaop9Q!)+4u{FVDw3*7yP+rJXa zVz20Myrk00=SuHuyDT5vzmMg5*U*dba_}>n!0w|Ho@&3h7#bNmo68gaO28hG|%h zE~l39-w}mHper*aGXA-=N(4&X2$S;sqaSXAZaoiFdQ8c1CHJF8mkn-Im|a>g=`Jn* zID{K%2h~`!Npl3c^`dGwEvF8vd6e^u_q**CycKGEw~>}F4xLv@jx-DQ9+m38m89-k zLG6#h%pUX8&fR6u+!neK8r(S2;6`YW7AyEG+s!<|4cCv>UfEdl;JucOJ<;?y%jTYF z07J{)3=vS_Kwpq7*k_0LOB1`p#VUTMehWXA&xA214l;ZfC{uf(`?-7pPm3{)lo;KJ zMQtMzXF;uLMnwfn1c+MxWgv%V$T%AG{0}gV>j!SY3X4|ti492!X@3hdz%?_QHLp=G zt6%%N8%<5%wLE1A2R;@LC#5*UKTquLD|^nlg;((}@l&ArOG?gOP_71;jG3J|yjrH! zNX{B$GGaQPcQ4>)0Ci&dd3dXWw@5w#xrC0p-6a3(fT62^pC2i4NMSO5={UF=nf%@< zktZnwKTFY#6}+|*%Kib#`=P{l`p%d=#qb)*Z^3P61mx!fgw?}3P5{3?JRng(t=d$2~Y3 z&&ahbR18N>`cdp8pG`4{my^>z^WsTvB`DEi` zW?J4cY~i0*UI1a?8s^jIoy_N{sYSfHcN50)Qbo;I^=yhl_vDm#QE!y?T|XOjlxJq2 zQqW!tboqf{hIf|~^LT1C+?5R9QS!IaG#}DeDoo5tVQKB}93um#shnS0oIx3o|sRNbAL`spIhbVsu(D2%C9nQ(|+%BO)N#zyJj_ zh&$4_X_vwbe+q=sj3HG90|ZXVXTmvrT`S|yN5?=NG7XaX_-qgxk%94R5z40JpTr;1 zN=H$VH-CX&O5P?;PtV3z#e35yPJ8b}4qvT|o^{0$4!ku8iW~|D_73JisfFQgkSVV5 zXadn~ZyBt4IIX4iCk6P9Mf9XUsUq`LBF-LXOJ5fvLTUy`5lX%sLV6Hyp5HW>$k0I{ z5dSi+7B3YI8A%BOnP?DX9uQ=zh#-p>?HLbIu_5t9hPkFFq~gon$nVhPugl?+r%eH< zpN0=x13rhIl5;~0zlgk5Q4^AGpRi8PCr>3M+~N13gat|@-z;HKp$WR%C#(fw9VxLl z{PxWf8gX7`Qp$^w8cOSV5H5d*bOus{--^#@Dta;E?iGZK9i7 zf6z*U%=?Sz%S;;G5bkQxfy%10Q1a6rv2Ib4zWnoU46E5bU3F)4|)eB zM}?DH0KxK~2d;s5S~buw)s?C2y5@8c?qedNxqe_oJY*av1jIJ0?P)^ic94HG29bmG zp}@5uhTpe>Bkx^8j+v5ohEdLW57J{j3))FkrLH+%DYQ_%r|~8$Gu2mKf69hr4AKS{ zMw|RVy#pYlhJmJ=^c*WG{$5;P3V@GazawqBK7@J znh^dsfq^(suMI?7Oy(K+sDd~nuQp&kBY$u+PeK0Au%*p|GWS9ALGlH4Q?Nz+O>q=ZAGL>W{DZaM*V#mD z2BZewLxIvowgp7tBHMyRJl;jg`-Z7TH9u0$b5qeLSSGt6ja|hrRHle0v&T5!7#@_4 z!1_|zDW|S^p;Dk@fOy^;hKzBII*S~C4 zpIsuH>P7|IS{6B2ho&nHcv_`EJB%$h$0ywgVIT;rL+2<5YtMkBb1ZTU0y_!+%-GY! zyT`{pFc)@tr~2pw))dvQu3VsS`aF<6u?TZ>_A>tXvsWkNNYh~zdG>bJn+ja47LjwU1dFRr84EpTmyt821FJ}Q1QK6})guEhSj zsxy7`ZHZn^#1qCkPqBlvGJ25i%kN=hY&|iwZGKe`A479(3Ubl8^k7V1P7lql>7fyZ zysd|&O^$jm({CvRz;o7l_g_av?S4etdRclYYExodqz>v~SyHyw@i8bp2|i9!CC5hD zJ@5Egx{$Auvqo3R`q7QZ`8!4Bih|~$5&CvTWyb#SZ6Et_ti2tYsDZJpDfhxi)|5d* zF5$O^+7vd@3@HgsAzKfk!EAyKI?$k6UM&=~C-x)fWG`*QxvL%V-YY6y8zaXsAEH>0 z*+)v$a*X=C!cKKNEq}3aJ($k4ol)4w&Ne*@WJLIgvXL?@lxV|z2^p%uhK5EzCLwO8 zgt_0t)gw_{t3-1rB@PITwm&gR2Y61!23I7a}6i@SP-spC=Vm_#0i-1!S>l&`5 zV6f5FM30UqR+mxahg4*n8TkouM^4&|;vo$etLK&zRvHSdI38Z0L9IEY1T8NfqUF0G z-8nSMo-8D{#DLgI6V|pMy+(df{5B_Zx%1L1R$Stjz>H@SUohPgXIp*VcxrVne|}bS ziT;65V2;>knm!eI$V$~UKl?DlNArU%X_fK9v(|K9>Rf{m2U?rXl3cdWe;$3>ojT>b zQSS%_u7||i@+aX-;zRjq5#tUS^w;7``LiPC0=e1tFfcLK|FvzLQ+Ddd2-z~mDj74x zhQ0~X3w4jORBsv8G<4(I%DmzWxFEY96)#{7P!4KT=R%pC)jf{!m0F9aY|!D{89rhzN z82T-bjCY??UUQ6g7x%j!dDmgIK`ryCrc?*9JIJk{_E}X%IhHDhuEaC(F?qHYiOOX? z(9DWYrK8Xd_w}wda4)+SoCYoy>JI;EdszHxVjeb#*C*b|-5Aof5QVzre?(+mb19%0 zjeqV)oAMSya;NyvBtzPvp+Y{7XDUXXH4mwe)B%IGFmdPy@!d(&@n-ScNeRxaLmDu$ z5O}Ger;**Y8Ie-zeN$3%iblSFH~|tn#|AH#iO6HF7cn^$1MBFDo1L zC)^7&mROe*FQlr#JMc0fDZ%!#(xA8XG$h!1K3!{*&Gbgcd1aH1l3NCl{#z-5@0ALi zM@4~_&6GLM;6o;=WV!6mB@R3 z4{TnNTSjg^f{kQRtJ_S7Hj%eJybJmt--5D;WsQEg5maqt*j*NoF#PsK8ac1L5BNqy zV!3%d?h)6R=i^VrPt0SmOZ=C4&El^H&jVp52%J2MPJqF`4Eq=tm?(C`bv;~PLo8_V zPeAT~d7*m**ga5(0F57nHLbjFKCkSJydx8PJG>)TMtoz+xVtNS0NtG8ussYEroYX; z2NowFKmOM8V4wj?lGg5oD`{;$Tt`})3%Q-T93G~~Tq!KI8vCDFK=-4C2{t?QaHoEf z7*}AxcZ!7t+0J_azi%OUid>+!vgTl5I@CUZlEL0|`v7Sj)WdhP3Zb6}i|3W&VA#=f zDlyjnbvHc?$wx>TWC2BpHJ?$ARR;q}gBa96wqj(Ahky_W`5_P32`oRAP>bk~!D_3* zr~xLy$u>t<2w=PTM!Zyz;&cH$gMOXw_c1`pjlf#!K@1SZK-X*)it7`E%v?^+q+jsF zWU*NZjyc??^~LoudeK5xV&GzE2pbm&`>S=WA7R2uPjyrA#R5B*74%k%j43q`V2me` zi{TQ$2?feb<^*V4=B z7Ta>f*_YRB5bJKaC+^mx3H(Z&SoOo=Nz9n@hv<0m(k;0Qs12B7D_|lDd`fz`XyI(1 zDCtFVtAXeEHVH+u7Nqor!4YSXn|CV7rxI_k>Y1DL(c)|->HK~=Zl1NL!G`53T<$56 zT`RLKCYyNA^hsD2w@)|V7sU^zPjGTFOWPhN$_*@rC;$jRvFxPfW{`NBkinG=YJ0<@ zAChfp1E}rKCkNMyZnbH2J2t#($+gUI{~k0(OsAfIjmL!=liD}p(}hlV^7s@QJ7pJYg?)Deu=)mYpo*QT{MFV|19n-x@U}`Mc16H z$KWpqF6mANCJ+p~C*m14>=#RC*s|^m^-5Q^#NWOoBd)}_!9CRHUx4klor{s|u+TPJ z&nGr*h4}sqvsgWIEZ!tOFw=n7id$z+qnMC*YGx6hEe_0_j0?ovSscz2=gpdtmJX^H zQ)B}}>}PN#`83T?n{k6yKUUl~D`DQHAh#i|k}@pCdj8dFY#b@=sv)Hf8`@x6bW^rj z*2oWGu7{#OgL`0tVPZ;el?Yy0f?Jp+KkX&zOpfeqxnEzujy6-)7w zMOGQDSW;cH;l93S>6*ut*4`~?E%psI*+SbN&)eF&Wsj9Tw|qmnT6G@G<%SUx)Zag9 zOkJ@7nZOHAt$3We^y8M-t?`#Kc*BNtdnG=%=vsPX)6w2HW8*qfDlvCfnaXYlEPbj> zH5UCt`q`KF2nY6igmB1yZ^?#unWa*E<7z9H&udw- z;dD0>H($fHA^ix!6tym?oxgnX@*7eLe@;!cfyFZ{gHh*S!K$0;jLj`j=pwUkuM~vyB z@wQv2?x48jwp6M!C_a8$bz;%51&B;j9u9?wbKhODw?o;Vy6`&b_ZN{+`O8s zh<);AYJlsXAWeq%B=tekuP@UuZB!oR%T%Mb@nEB~!N9r4CU(&vqOhsVOPON4$aKwz za%JDCK9q0@s_lEilGtNIjwi-+k+rWjU1>kvdz#jY-IfW?9U*Rgr)F&1%SydDhkty8 zO8Zg#l4>#z8;oodTmf-VZltkrpeBU4x0K(RmDc;8c;|@=66w}~Hk9{{k931FCHc@K zXa6IIp*5t=nRDa8!>4*rq0#E99v7PHahL(0b$TGb=|lQjK z^DFw81nx0eny|iJg2Pz4takQKI;^!h`%Q=P-| zoPOistV%Ei6>jSMJK;WjXtd4g>>oaaVJriOzJQly@Us6w=PKxu7KLiXn8z z+HZN(Xo;~H6{w^cvV~-kTC#Jqs67@*_lWPKv{I9$2rxV&PE000dsLYsD8rGCWJGC6N-yu(^CVknaqBr(WFFU>~Y7~Y`>anp22CvXURK&0(#NZZqMrMwGW8JzR+MKN{-E5t?*wQT7I|&MKNa&M zPs4P{v<^DDy1_E>Ag}R{LkB!nvL!lmaJwJB1iss$w|mvmuxi_f#KaQ4^RK~ljvk8I zvKy8xCo}XGxZY(?w<7t;24FD5H;t_?0vZH@nz5E!Vn+K$kTS0_Ed~K;EIfQkgWGgM zoMS1gFSssURsc;C4gkB5HI}v#dsRJo+4!OY}f5F8gYSj=d{#@Y5tr$Xyjtw)nf ze3UFxj=Th4n=;j~>f|fRY{LV6&r+M=O7ihCgH>RL-!!~x{qjCd{Hn)r;~ov&Mj7+% zl>h@brfH(vR;?#c^uQRhfypfivc~Ml+s9drA8S~DI{Tq-_{SN%9^QVS5V+2a3ewCz zSc;@6h+7!^t3<&LlFIvsuU*mUs^s+O;+E(k&C*7AzZ}YLhwCYcJh6aq3J10-Hfm+BR&s zpy+ZgC{q_z^^~XKLAK9ir9{D=Ot!4lQiXPmwTuO3M~kz(R3kQK_s}Yb{Yxls2Q2JS z;`GOX9PW-_vpP@bTU4@RMP7 zv&;27LFfOLEPW9Uz}pj>rlo_oo93{$9yU-H=IAD67B42ra$abEX*5Mzh> zxoi5g6j2WVMlPTr2aE;~naAXG2*%9*x&>goSkU1(@q-KI@W1DC8r+LQSw<8yfWg2X z4(t|REX&0vv88Nc6nGyEWE_I{YuSu3c4eJDhR=O;IIstD1_;s`4m60f%kNd4fM~)4 z;v3~Dc)QqAp61+KZkZ4aTnuf3?dFBZ?>|EuZwF!vZ-f}1{zr+yX*lqg0apdZ(_lse zGL5k+jx?(yWc>6oY8^7h3{l1Dg}+;wejoPNt6ox`)D_D*TwCXB!UY?Zdvwcz4Qlc> zD&@M`dSZd9t=q3u)?M)-&SL1erwJFHQnHq(n>D6WN@B4~(HmS!jA5@bI!^W>9P{=&t_VbtyW*hrLxB?^t`>rFI`Qm)kE@Lc&gFNDpHw8| zz7yKNI#CaNyl{U_DA25MLV?~UpQ1Ua&&g<^O?KI?I6{DwV8wiA2m;4Kfq#Zc+|e0D zwI^XGiS{!}`l4h(Ux;$v2bWfr%vx-UKE|f#?y)J!>7rHkW!sT4 ztk14UC#CYCR2Gyffl_m!R6dl7*$$$RwS!_|*{QZ8Gn&1-Re6OHa%GoH_dxW%?Sss`vsA?eMu&9f`$Wc z5bKSb7&nIk40zLuTEjoH%|n4Y@tND}r|?L~aZ^I7gKAmgKpYL;2(19^2@Bli?n_COvB&~x6nN%Fq7XkHAkh(f%Z36= z#n!4-Q;f8*&5~f-LD+d}k4uP+B3nP(Kch zM=}RF#$Sz)oDs>r2DudFyz*0ZHrV>WkOGlnb*;@xiMdfjpEvUp1vT#nI}{1SP(d8- z^^WV3n*Uk+YxRU#A1OcAuCDz)RnIG}rd6+5$NO$cE8q>hAYgeEEQe7YuP8j|ixj;X zt{`PXjIh#5AiW{x&MzD{AK;NC!-5vSrsB!*~#Fg?%69US+$2&ualP!3u54Nn}rqn(6=!e7?`W$RmNw>-)!CC*e)6*lJ z{%wf=dvMPGjE;(gk*$zk1#RGL3pPgi)6rIi0`5N;B#~Vxhv_8mP~M#W>cc4C*?;%p zk$WfHuaRlycG&tl(N7X7{of50!SiZn4*Y7FTOle;F5U>Ha+N=swJe-ry4$b~k=kUmFfA8^#d6NL|#|4hL-F-FJ_h zcu!E1QPznjR(To!N(ylc6lNKkIMtV0$oTb9B?{+YdNgO$PWc5uHh=i{5wn)X;TJZr(+j_Gl>;XrWkO8rT9shq4L)CErRuo?m( z7}IHxudvV8tX*ya66hH$BJ6zQIzc5fDlf$U_j!Mm)`H0V)jQ6yZu!q-&}AD17r4#F z^7q_QTMm9Q&V8l+pc^oz%7%^X{sEM8!v`IXP;1YyDkHV?Ny<_|%w zL6%6gnHvVQQMRz$!(a5dk{e+ewSdZrebacZ>%ZY?0iO1}H8T9?X9raoy3Qznc*aiv zx<3LM`?Q8%B`ZJDz~fNjMu)o;pM9q{O10vJ{V$AQH40X!cxrKC8cf^ZYZ7r<5u|`z zV;O!lZ-Hr8CO)#b7>^Z?F6MB)_^-tc&W~@#L*>Ip=lIQhGUS^Ek+BG-FkMZ|CkNrq z4C^r*c;{xB3@EdA5E+Vqwd@!|1~Xi@4sn335q2`-d;CjlKClzQo-wGIlSBLKXF<>c zKt=oOh=FGK-oVBd9fa;OJOc$XLp3)Gq@tRU0)e&gz7B$CNAqL&duq9d(`utnet3O{ zQ`hm~^=-~m*F3Iwu5VkbGNEfHT$g`Jkk_Nv(Q){H4;@3|q@}5GuXgP&)A>_kFL+T7 z2p88&;^L*#@jCIPrKj(+gl{wvqud`Q>owgYWJaF^A+gg-%FpQ+4%1y|B1NK3QC;hP z0htCm-gY#QqZx(!9nZjOOGd;U^}03M`yn`^euiNFpS&jFiUY!Jm-h-a%U1)TUKU&K zneH4Ltf}YRj6W6KS2rAZNZDU+`X5XT2kuiw`cW4_1u~?Xk$h(ufiO-75nLT6Vp$J4 zdnA_+IX=wzGY|%opU#5hIUa%{6(ET5Cxh@B3jAS^tH&nw1w4zZ17Su5rizc;n~A>{ zU%Gdi^NC1M+S}o;L5A7D2Au#dc-pHidC7_)W=IzqDsw5io;K0mR7iM=U()KYNgBN@ z)itARhM&a$hwkEh|H(5x?qLMWfDro!O;_DS39GY&1Gj(tA4wvK#lJIX-r0nw{X?n~ zYk!wJfqVFtrbAXe&@XTxerYY7lrZj4Xf(=CV=^f(gb!I={P*HterK3+PD)#aOr2hA zJT_3E(}VQ@VzazS&{8;XDMfa9Gy1Q=W+Cn1Qc z2jgNWaN45)-EXePvo&WOLMZSY_((=n=D!_3jOxbM2m%44%Eqv5P zJcVqqc0p(%-H`)jw}kS#I{b*z${I!xh_hpn=MHPNlB28Y*`me0Ox!kMu;mj4?abj< z3Ak~A;?(M?UM7B_V-<)sk$j_{skXwW24^# zhs%=EzKg7%!lW~Ep))O=s|Br}(c(Q-J%3{sDq1t_D|fCINNx!%C31aZjI%PXG?$JJ$+5I^v`;L)4JbO!unB%yt}v zHOzQW_8OUGWvu0VtG-ohW})=fV180NokY z@ttlp1Vm_{p9CnAutz9pA;`P}GtWZ6m)x4lKg`pxZP5vA0Z7X9sr(5meP%p=!>5CJ zPv!>$<00^2DDYKKfQF_Id=IN|bd;p9Bda3CM1qMZNg@M}~)Rxm*u_*=wDBVDKl?_IE2IBHn5p_BgXczyr z!hlP~ffduKviHS;ntWU-F009fu-C0M3!PLw&119HJvnc{mkeGUs(y0bptr6}X$C!* zPlY?yn^&1=&Z~gP?NANKVBX6)a_lJrCy=*RAIhG@7q@8nHNaPl%g=P9DQCK=`;^v& zN3lN%Ez8g;_!|(XlZmTO?Ryql8tttF4j;!~k&Ji4E#-Z=^v1c~3&=n~X!(m$G7!tr zFzj6F7rDRMN=zU$bYq(^3bq8_NvV7a{{{S#g!G@mTt=h6!tWS#2K*9b?<2PPp!nX( z4A{$kxpKC1dh;0YvMdIDCmb*X!)H44U}u7N0|yC{!ycsKU}RQ$ZpPt;0&fog=X?u^ zd{<{|;S(Y1{oYRS&C7-%2tb>Za&a#Amax`VRG41E__HG6;rBagmUAoKQc7HBy4B#- z-K6kNGuR{nNe~7}!ZV-8?~>S_pJ960PTaU#*y}C^!q}vkL3fE!p~*d7#LaR@(p){n zKJ5$zIw8tGr-g*-%P>Z)x++Ear-D{97|@4Qu(tKUh*}1}lP)OwDRy_dqniIx(H9Q| zx`)UcCUl2e`cg?R?vrkHd;|bk)z`pI`ieE6B<$qJL02+Cm5=Yl?-lb!aJK>OqM&0a zt79uMbXmbm4epxzIvT=(d{{t{K{SYt`}x}fEqGQMn1A;-$d`y@3I~Q-b*-njQXpbt zQKC1YcD4H}uz>CnR=DG23PpQ6VMWGxV4Mi)#UJl4kKG670#Z7uH|9s$J|)h6ASGo! zsBR1&*MYbq{-7fq*b!Fm7Tlr0khtan+qeq@5{yE{kl6Au%y%H682-5V z7@{kNnGC9fIsm$@IP^d!o-TrNh^L8jge2!3UPIo33#Ydd>pg9X_R+Ok2+Uj>+4ER| zi5Ov_t#w$s-W5>ptzLsMd5R+))@Tqy4eJgHskN)zosqhDmfEC&1D>=zj!DZja4AR~ zDX~Y;wt&vk0>=RA!h!R{?+Z1;LC1DDS|r1^CY%*$gTTxv4#HPC3BuEUfbg^{l8XCQ z(r}lhJzH_Xo`!BQC}bAue5Ts8)iwwOA&m2bkQwGOeE?3dg8w%M#2~|8llBTElH(1S zlu%&wK({!**0y+GDSZ*;_jNwz@JpszGO0N?hX>ZCslQ4LxMlZQPk25M68Uz8tquq7 z8Xo1|R~ideUAFEEcrwO)a4Rl62-CfK7)@^X5~8?0bY8q#TWUHqAUH;qf8I^0$VQp4 zeYrITgyUYYs8qZ0PB?1kI3VnXNmGgUt}>(z4lx;8Fs_6HEiftjJgWo|V2c1dR(y3; zX58ZAx>gEw_uT?==bP)w){9@R%FO+95CRtT+!NX^HJqv#3cL}dI50POX`}H8qmU4Z z`6SV4bzvjXmhC%|};eLZseN^VY=hx7?^squNhq!L;n%@j_!MMZZi zZv6|TF&E|wr@N71e#=4!){lLHHkur%Po(m*cu9&EdZcK_LI-8ME-i$x;*kSrb>d5_ zlWrlcVo)TA!<^*VW)+-!90FJ0P~ar^4p~bm&A~DI$G`=0tY!BMet$1Z?X+(5oJvJ{O9_(i6~BFOHLeinJ(Lt3K@CAq^Jo!oOKQCRIzKRFoqbdVg#F^}jG8w-W~E6L`m0Ji)L0^Z7I zRKnrNBp7{{EBUfge=4oA*pKipLor~IX%BO7q%x_JYbO$rP>)JxAzUc3?^N~ zW#;Z*8P`tM&;`ZihGz~m@pJE$hfEIc;nj{$BsCynC~!-VuokVF@L5`Y6=VrP; zr!{Jb8NS2gQ_v}BCZ?ujY3bwVj+GvSr|j9+O7A?ozc+>^vVEcNAV0qAb?eaC#Iu7z%ARM-hw) zhsf`Z;Ju}D`qv#k09NB%ei1(q_-6Pa5+tm3OMCbl{*Yt@=4>q?)^{Ut2r_nJrbw`T zITNxUNh3fL0O-FY0`MO}BBg?XyFwe`ti+uD^25120X`7eKb#wRb2T_yOnbzJ-xQZU zl8t-C&5uklmuKLd7eM5VL2KmAV5W^dme9-`TnM`oEK>5JA-u=HSHlL-79^5YXA%GX zNQO;r-f<)mW?I8j2ke`--UGy?fG6__JfF zUDv#5!fpI<{3BPVQ6+0Bt*2aevDA=eIyI!e1r8IK{tQo?E;fVzowZ!v!hR^7@J|AN@Z%dv6^s1z zMrf-3AUu64HWqsRSZoaZt^x%$r{5)H!nw@ye!b8L?;nhfhVddWA4124|GY)@FTh(N z^47KHx3{Q%q^?VNMmpj2*TpsfK>baCs9q~yrWb-6`b@(G{!RO0g*iwt#CrDdq+8W| zB1Auf5`!4W!!YIHY)SR_L(VLTH76$cV!x8?u zZ%_E|k9GF1IIQKNqvf%NXunev9h=J@Fv*&z98avF(aukL0 zioD4(6-#51$Gqwc?gv(}KzGc2&s}wO_$v zG->}TkzG9Y>Suh}M96Y?*+Tv&>2%Za>#iy+rk+jZ*>_ci(IxoR6gLpnICE~UH_gw) znmWbO+>Vn_myDJIjkU2ft0Nlx*|_m?TI}GKJ_s72#ScBEp5C=84i}PsBB1_1yPrx= zC^>39=IKjCT(TSm@rM~aoX2_Ch@wzG_B zGzw_a4d1vD0#W5_;>)`-`2URsf-%3-OM`87Q3rJ4si&<6d$kmRXw>?{GnrTSSa0#L z2h9`CB~yM(6?v9DxjKDYDGf_=JfK?#c8wGM@EqDVDS~YJPv=UtzCS71=4qy!b`|8Z z%n4A6^-P(7r*Q)K?g4YtdFnfSn>kX0gHAdX-<>6`5_zfGwY!V}RPE9D4yF^Js$Hb9 z-DRph^q-DNQzmpuF0kG`4?<`oBxnlEEmLwcJfta3*3mo2m4t>)=7d?7M!JQK)U;iZ zL!X?0r_C?b`muJ4r>KA|?_D0V)3B-}UP(ybU3Pcr0=~BcmeDdY$1$G!45bjyOlFVi z%#4htQ=QiKH$RG=Xc(aav*DyaDmLNb$Q=V?jP{%H3y~?oK0K{mB3+<>;Lb@V!}k)N za?r1h{<7(c#QMWUPz&C|>Fcu6z`1E9JpXnttJ3yrSalZxNJw#anc9tS`?U0iZ+1xy ztmKukY`?yS0<_o0KJ7btUB9Nr7wy+X!|I8?z;`N)Zn45f!}?!}a!s->THRr>+Tm__ zZ!v}_lA$zMz>GJur5X;ZAo(j7EK{de%PjzLd;7rNUM*TS=u$|buNB6HWvYdUJEDY}QEba}MTB*&4^l)+S(VvqRQM>0+WWfI()YQmFO}|PHO{`KrD<@eedzVB3&3EI6WB&{RZrI=uMrNu z=2b5|TNCZE^qralDGoJRnqHL1$jANvja*iPR9+NI##-im&%cK5Xo||KY>zUPM>az9 zCzQcoa#>jsKz$_I&qQ@P6*ySsMTT!BXs%|EG*^RtuBPkKsiuEPIr3Om%K^KLppNz? z5!6wWyoA54l&HqE`nyb8A4GG2z_JOcf@T+nsS5{wKm1CU9VQ?RaD%-t1$G^GX@oA| z?i9oUFl*Z+GR@9x10j$R-n6^ysVJ5vWP#KmTpVC#v&my4d)E+wahBp-$uF8+0Sfa;d&>NugvSiOhgCr5&@Egca zO9L1G3|dxM>2VL@#+490$@p;NxRTL7;%VmyofnRNPtPwH+<1+AxquVm!KJ^utVhCg zMml~cS*;3i>A&$*BlA6xb#waPexFD?Xa9@uzwvzzA4_Z!FCq^)vj%4$o=oS-S)^nS z*N+|>16K&|jjHPTzTON+`i;B|&fR?>Zhoqey7w9J_)}*5k=XrI_QW@?TAn`kOIfu4 z7u_IrsYGU&E7BWRXRki?%jc12iRWimuv~05)=#-gi9=7PIe$Gnw(E_nQ&t!L=lRq6 zUo-&a^QQ?ERT~6=d^egJ#GF) z6aB{345<6pNNY@I(=W`^c$y2IYy3>~Wuq`mWh)PZ=I6keI2P14^2reL0TDf@X_p3bK}Ex0jkq$X0!ADR^uwWYaxSK* z`7{{uOTcUXGMsu!%!%KEeG2T?LuxyG=*XeATbJ7$D*HwV zD>&6nPl+a9D)O9OkJwir8N}}OX;bhskb^|*+Sq_Y3~&{ zCV9nC)EW%DAx?WHa~A7K;D3W!S4P5A&wvfM^@lV5FO;yaS---WHhA_Qz)rL zT4M)M{@IRyOKsh1OIE5rANw*VbL}5lA#%cVD-iFWdl^;<^aOir->cTpcKA&^3P7Dr#gh`y~ z7Fp-$3DGbDV!{gs-X7?Z$aNnaPq`$4vVNRcwuoIT9Qax+c5?jEVQhx6nv)@rr&qGp z7PyZ@@J9i*VLNb~%sG_{J{@`aNgTO;a*}vHki0Qsnm}^+B!t)>a9ZLDl2O(aNV;Zr zuERmee-Q_qX=*(@NlzA2T`Q=9WO0LQyx|jtl6OD|*19ky{}J*_fut$f8;Q2jStvNo z_?c_QvO5L}xcv?|yy77c%#bL1yQ2e~?8ERGE%FQ|zUr|3#Um(N&0khdJv*+Be&w?A z#hYMr0w|M|(eAGlXvocLTwc|J8 z*a}2Q|LIx89)&ap(z1sCq}dxs@||#fWfNjgL!vi>Rs$&;(n3hzLR$O3>isv2|C4wA zR|Di_8URPxlpaF&AbtqG680?JNWLpTgKi&ez#Q3-Q+gN#92k2Q5JxGC0C5TM@gS7* zfG_d}QSxgFAi%uedS5%}iCH!XGld!!S_A}G=*D|1M<6EDvmPfJpU|?zo>rewS9~p= zrVQ!>A1KKX9P@3+A(3u;0)}lQpK72R$$pj=FT)4so&po(8( z!Q`N8?=_I`)6vnR;}Q{LD1qR@lOa-@qAyE~p}71;x^{m<^L3XKU0cy`S$XZqV*Wk&Xu=mzV^O5LcQ<6U80^!4E($Us zsw!KiRoNx)TgUiFUs-xvWSsE98gMA*g_xbpZj^KC+Uy2qH+~g~Z)`L=yKZUJ`!P*BZ z%?!P~t6Jaxt6tyV=+Mg=K!IvNk=fdGsIB@Ok_Nn264G`@!3p)#*EGHlKVe&eg zsuj+>u_p}z@R@03<_}uGYzJ%}_*zLm0wKsjG9(>68mtX)2$NGCP>JEd-@uh)kw0~j z32cQt(HvE~u}uBXJp3d0uOELa4PQ!t(g!1@--(oVz755n)mY?xE*54THraB~|5SBH znzYbuKN9f2k5t$JCH@uqZIbs!O1S7VkrK~9iS=IfyNP-%{|&xQ!WdLLRX_?mg2eU! zVVI;e#Gro=DSbbbzHfzBZ=6{%DqDSEIB*8Q!l+&WhH|sQBasSd?JGa7gboxzg?XKy zHDye!Y$qM!;l9*c)$fI`*)@RGrKdk7Xr z!d*X(kbOo_c0Vm%*_@j&16)LKz70Ocf@N#ydFvH#yO{ahIA=PT)V9M$C;aoLyU6DU z5nRFZW(VI}4(lNfsGUQjD)bI$ZxDjB+{r{b6-3Xo8IpxOM<~z=oLkkIy|R8jT3!I?jlR-pzWOa{H7=x8z=1;cPa(|i=m32-vX2Er*6xC^4z5<27O z)$%6j>8wGj5n}FmuK)O2a`u%HhXdaPSAo+k2VhSbH1jN|dv(y;pIfT>zn!X@*9pt# z+o|m!?@8ZDzs=C+M!4$0Wgh9cUHssA1HMcA=K0#YvwTY6O97XQSHvxeKBg0`ms+j+_>gKs+9uWakNoV(VI6!cJwqIl)bY-VZIH0vTL@ z-mVr!^m8duUgc%SF;G*kiiWKZf!X}UtsERWKDxCGFBgZl&ceSJr*GSjbz^Hj*JL6@IhT@6t!t6 zQn^^ht84T!b8kXL>1EVjQKGFv3bZ**pt;{p%Ajja*4o);KhJ;mdF}oG-~XKnQdsU{ z3M+vXmX3U)p#HM+LP(phg0l4a7mzlPYAvhjFwf(|PPAuGU_e2;VFq}&!ucJ9at6uL zGm+n6$Odr7p!im-vUixj6xFeR0lNcryrte1Sl;v7gs)rDY}5dWseTh(K|MGj(t($a z;=I!XqLY6R5HxPFyurtM%@Iqt!2!6sRg~CwHFk^A(_e0T-o2zzK3A4YuJ!|W13D15 zX>NVxi4k^6w(G=*WJ*5%8EB$DvFGFT*54o_YE}n2C27ho6Fl})#%*p80dmRq7fo1E zNT4|Flk<5Em+g&~u$V+20fXO@P4YpE3!_IT&)pz;4@FTo=O9IHz$G@v=xwtPbkjrN zgI7Fuq+9HHmNxM@F4@X(E)Rp8W;;zYxi7#|`7^GqoOLlX+RAO4;A#7`n>Ou-U)FO_ zZosJ_NVwykrkpiy+JxlR|E9?!Xz`Fc*Aj1adwQV)U5+u}=1OvxV7beBr?N9l`*W&j z3qwbF1>zSu1(%0c)G_fTZZCvr;r2HC!K2BU>sAz&*d{9$yD8O1lu3<;eJ86YO-G?V%qXG z7YjG{4PK5sj{ir=V|bB7HMvA}2f5GkpWDvZ>2N2)UL*YYN+zQdqIa%~f92)}rj+v( z)#(U^VR;9Hmv@%R7LFhBoDt6LEU?W8x!5~h|K}Qk@^3C#b?2=im9aD{ta#7OC+jvYq|w)*rh}E zcr{O-cmf)1R>KE$qhQ9))i-=;jg91NVV{dx<^>on!ywbFSjOvR^iXB^O*k@ zF1BiHmjE212%lyiP}F8h*aIgk?Qa=#Tw=TZged3Cxg~vOEor?V9<$n<&s+4AXL390 zZV9vNYyo_gXikdS)30=&6f?Og{+1hY-SjRX`<$k<^C(f%{4fGn=Dr}BZ5+|m@U2ho zS~$&7gU4=b;4%O9@$In3UG9AymnWt13FCXv(0oDEbF;czYfZ~&Hz&ul%?x-wUo*Xf zl;j_n_e!v3V5Xn)M2#FH0bldYed6<64giVF+#T3rw3qEgD{~tFndIUC2`2hG_PEY? z7C4OSO)brn;6?_|%1uISTMm;h%xg5=3J#ULZ`IuuzqH>o{G5tdr!pu-ysZoF0X(#OJq`6kzM<(XM+u9 zq05l!7n2jT5 zjwIkJIF85fZKOf0^0{-(t@|DuK8e;ZXpbqa8m0W1Ks zD6Hjku{Hue_=eEdp2@Tbz3nN?Ea6;x9uUL)>wz{$Ll@T@aiG(9X4ft!Rn>eC z4%f8Cf&#{sR}hDJJR?x&1*RRO?fGIs!4!Ab2wAKg2>90ewIMwPR%wGI>u1k6m}-~x zf}8Q4}k{u)BzUv5W5J5O$N%SWtxB6eWdrgGI&>s>hIl z9W&sY;U}5X(El^edmRilq2+&QlJ-fU=c9_MnP%-Ex$_4hV{cm4VzI_iRxZK1QSIJS z9)q?@KjxRkRJwwqv+h+UQs@>|?oFsCIe&)}!3c0NEVKzK%i&&KqaiQTUDvoeRRU{N zO`g=P*1U=7S(?c87V}E2n$I^|PqD>nEr_u65pG)lI_igOUvaa=zj&I{6Z3`!utx(R z(b^w`ulGK(VmW5SqB|RHnMGJwo*;em!%P1Kl(3Z2HD>WSjrmZgx*c#41osPtXy-H* zA!kk~Czj^80DrO;@r91rX31cjW2%MZf9H0#?yF*$xx%*{cQD5UU&ow+gBD%y#Yr5` z&u%GL=7?7zQUiVh`2n}om$;4SHKxM-`mRv>`fTdi^ZKi}wDR7lv&BH3DLlzrH``6maz{46C*lROdxhs>5!t73CO+e zrpSTRVTlB9rrCCHLQ}iRcr~txol{qqlHA$t3`}@q0_vG%Ly|HQkdGY-)s{*L&ZXT; zY)ywy{ic0Y8Czl;VvL%_Ag-cRNjN z|7I+jN9|jZR}V{AhP#8O^!TW`5P*VQqgSx+hd~~KFNEL|jK&%8jVS`t3_1{pk!ptD!HGT;QWf~*?z^fvY{9$@iQU>!6;6>&l&Je(2*p8^qKeBh9p#y z@jd0NpScSp_UBWz4v*}>t6h|ccbfcF{+#P2B^iYNmQ9R@Qj z6mATIH&7%swha0rt`{(?;IGFX>9P&>==}5c>@EMUi`5^}x?}h{05KD9 z)vrqU4~bWPl74;wA0LPYzyWXvELAz9)Vi=VJqENiQa<9mCIk+r==B#+e>K*S0LY#q zBj|0E0RHg9$!3MjeLI~2Dw%@^5^}Va-kxNOw({d^QSvxd#xMZ#U!IKDRoKSI4kM&~1!3^p%a4>_b_uGMsQ2>-c$3gVf z_R1R$4ihl4nKXC)cs48m`SoMI z+2dIi#JdQy%S^<4KnGn$j62I4WVN7Fihw&xdV%~rPToe6U0Zt8RMMBvN8rTX#5Bg- z`zVykV_+^F^Tm%xSH@;9%Et;h8QrSjY8wyN*e7qYnmEM21IV0Y-URIRrtcf!WanM- z^LQ){9~H(rxx1$JF&d?Yg>!b2S*jWHT{^LX>MI7xAVsV*6=S}y@eHSFP}*yx70RA5 z-xosVTS>OR{xhEq)$5x~TYD(}i)0=(kqg#S^os~ehv?fTGR31Fr9SEWl=~JBkyK`w z#8p50rX&7YRRzKK5AtJT0+MT|Yf2msiYmf6mRjaHPInux+c|3cpmP)J!bG0hB)D#( z?CK^pN~u2lXpcWn2Z0kM1re3FGKs1$6COT9vsBD7$QDJF#$!zIQh{S7eN_cKDs(`M zq=tb8L)pW+sn&1+p#L%7pYY*@?}V9$vTQ6LSUDwpk=}lhXUV9Y7?~g*4AcL7w=MXy*fT|s zyw&iK9^(0xfX0FD1wD?z-GJzqg!Z}}-Va1y4Mk|sw=gKx&E@IgtPc)b7K775rMZ}_ z=Tlh8^}#xDegy5Ia$2_*a)6H)n8U`C@WI9)(DV|Z^uq1*HY6)Um6n7={??y)k_vEV zkT~U|K?AuOR0n-r@H2;0C%q?n(MXMSCNmv4jAFqgx=FsOZ}D|v*x;4I^#cFW0lf6X z|Iwh5rTJGqQo<67n4{Lr1oS-)vlUgIer(6NH6Ko&9uu@9!{~k6&hgyrpzpsX47x0D zMwCjE%=ea!o>2kY%i%@rD19<)WkIZ9ogeh+)*^HPc5yC179Gy9> zvd3tll;RxpkR;@_nZAevbBelWnWe)NgQjSBr9NVkc=eL_veVZ#ODlVe9aLF` zN2=~Bmi*W885-B)Z^FSFj@;^G_uqP9KhK@!-unbIBg!Qi(Mze!xMJ{FUTnj}5g6kj z^!^o;ix%K^#BT+^@}!!-@KE6_2>8fDCB$H5mWOaRB)bNlcnMl~MvL8($jk>#pw41r zy?TZ&iQq0#t#B#yGWUu^x+5XTIesY(=>@cxu;vf?p1}tNKn#d}Uq}(O?<5O}M`vaf zt*U>f=&7fEzqFD3+q(L7B$QtN^xCx~YhzK?Mj`l~yRy2b*i`k*^up=03a9^$a3DeSO)#Z&+VXs@F6=u;H1NoT-XiKC7m%k(i!d`y>(Gb=)J& zf2Y%C1{oF$(nu1@(@o3Glj)ktc>ekg>sPL;zlT7HOv^PIqGTsy$z&`? zfeiTyq-m@~T7o!ovOIzza0Et1)MN&*@u74yjfEpe?-Vr7c;U*?XxqSaSi2C?3|JW= z++ReLxecK=k!utqKP`8fm3^&Mvwvz7h zF~k^`sZ}}@(hMgmGCPPe=OrBL%Q&X(Q0*h{3PK!1SezE)*6D)@48yPz29D79DY_J0 zEdB}JD%o=*x`dYQU9H`z(X(-iN)YBC%oUQlGh))Pm5z{sK!`A_n-dD1YGHYInoxvz zV|S8}?^H9HLYlKk{Uha}4*%F6V?ctTaq5-r?}g-~i3DN4bG`(82nW?Yj4f%p{p~q3Hrm_axIo+Y|`2NCAFVAx_ zXU?2?&-R{oKl8?~)WI7RUhBjcC|oCYQda!Fm_a8+uL~e4r5{Q63?ONxSWJ&EQwNb0 z4R={Vc_#J&u%DnPZa(3oi_&0_B3p1%(XyPf^oLMPOWAxY}KFH+Y$>K(4Y~sXngFe=F zR@P)1Bo$?mXzCQ?M~mMv%f-2hQSsE_x)RdzUV6r@iHGoBJS|78Q9P=6UJm)Y#j}c+ z9~f1USbkPUg|VCHKF8DbPCOyj5x41S=NC@Ixq2&K`MGI*Z|tTMPDW??3`ut%o8!b& zZg^4dZ*CaLN>w?Gr4V!1ylCtdH;iv36)x%Wnm(&55!;kg@n6J%@tn{tL)<_%X z=mDlL!G?6HT{H67_S9LX!qlRua5<7RwwvCE^O$z+tg3Knuh$NDBWKlx@2-1a&7&?< zN+FY`HFnmvaM>lVrh>_iw9%eQSdw_#8LuLnf;`HXlf24s*1`39W3n%MR28Io7`03M zJFAUin=7R*PFF_Yi4vQj-eL)ONRd{IRww4fmk)P(iPa)ADIz@6R3L+0=v&pd$GZ)^Hbb-DlOv_oLhK7YM$ARv))pD++=i9Q#qMhMCWQRJfJG> zR`8=-2^k5zRc2}pJl(@YiT{Yot3KF6so1GsT|h{9QIidQ;A?z#j^H{@tlIiZj+>DP!>BHH2yDPzqeJbUct8zNX7qx)i|D!5|~OG{A7`Qu4+>#Lq{>+gA(?dh>-v zs0q;XFrZJB3T6HshWkx4V)w(n4ekX(C4D$KW^ zw=B`4oeXqw`k;=d4r^MG>sljXwFigmDJo!pJTmlqogz{vGF-_w0XDNaP zUNws?z1?J%Cz(;tm&jt<03-yazIC}Y5(S{2--sW^OjiHVvv0&}F?yz8DF2{1LZh|w zKwDo6>UkvP%M7n^VqM5TdWhmNpABV?2X#D_P7jio>zWZ4#s69OT$ti~S%?rmv1mMv zEibjSU8D0E=n|5?kQrYTTu;h6zV&LInUc2Twkg$s0~lA3Gk~#5u7gIeVMp*CXRC&u?BVRSf#PWB_El&xdPab4*1PpC;77 z+8+=6R$;I=*^6mL3iq?KdElExFB>U%g}jdcsX>V9Yw8EZ>Fbv;nuK zRnr{ue;H!Zl^shgv@{?dh)cm!#joOK;v7*OpJFH7)mE6A(}Wifhx|-v=~A*9cMSb( zWz6)>%$ATpBBbLLhfS^Yek9e&)>O=E+;|(kpOzYi@NQB&o=l|^r;+?}SP>+RlWCZ? zUpygy4-lyz0X0ZFh0W`P-+E(TL0Mm)*rMvje?H9{AjJfJ%+f(C0I%ggwc2OQSm@RnL0M8Ynfk4OVMI5 z!H7?ZIU~8rzYKLl|0JMbDM?IBStsNDRBj^dI@sWIOS0`tXA? z(-ZRdo?I?bD0~+H+FZHuFat9(Vvx2Am6Aiv_+~|5k@3xE0f|hM2#d0gejAo#<5Qn* zhOTYw)oi-7g?|0Vrno-zRD^pYl+n^}0lb&CQG2V`s}4hlU#a31J7Agz6?@1OTzCJp zMX_UMA6oI#x|z_}rNBA4=y0=8(XCKCx`aSjDJXsRD6H6HTD_};G|B8yK+^;dNTX|^ zQD(`@i`|g`gqHplQ0(n&S_id5{_8=q71s^!^VT(Q zIIQ5e=|=G1Ut=cHQqlm!yPZh?w{`UPsNK}|$lZ8*#O{mm49(x3125&vigZN>$R$!= ze>Sf?T-U1Oe}Toc_xoWhMJoEd8O_Q!(2fWIhzk&x1RLu65CbGJqgnL^wNv@V_t#KC zJRiYR`jEd({5~K*%5$-*KOltJVw%fxa|ys{I;KvdRVB9$n~c9qIS%@!F@lYQv+$H0^E_F9nC@v9 zal(gU#(VxDBQc;&DWO0XTAEZx~3^2>ol z*b}s*4lo?|Y{-uW7w~i#mGC5N`b1oml%eXEzlQ$p6dRHf?Z`!#n;8;eZiLBcj=m`~ zX1o)yydvaZ;wq>Zd(B^oauQsd`Q5yVN0}q}GG1#~Wum3sgQfgNc`NXSt%H2(>=SuB zRZz$)d)8wh)UuMV>|W2J>>@YnVI%hYSoR3dOmCCXzEbGn%0Y%dY%eO~aX}T_mJZG@ zYA;UlAYHl4L>(9A*4%3w?zs6T)`Cz2gxKw-r3Hi7w7OPV^p<7R8C+0Q?DH&_l<1nb zLS`!Ok(msZ$J=SCc(8%TyLG(Uht;%{JUFY!4On+SI!|y9o$*!xSJpKD)+_Ez9);t? z1IgA&f0MCkljS!L*2!MNFKOxF0r_`&e`*WErzl3Ao7&FZE7U)Rd`^3YL`kR}h1 zwfc4d8<3vyMIe+#OV`CSZY{tyg7p$Ujy5cj|KrvbM9td(x~)j}8&; zH3fJMC0!muI^cR?EO6C`k69HSW619Uey0fY zyHR3w`jb>BD4t0-W!yQW;7gszXH(@poy}_}O@Jo;7CL0{du%#N8Y}8E5+7_1y$|Kyt;tA@!o%GME<7+HHQ7K8e+JH+Lw^2 zhe`ZQd`A}_Z46bl0Nq!RMadFB*JVwP3uU+HKoX&(=#aJrrd#^3|0XcFCH;Ngx)KHS zAyo+ZW5R6x`F_%akY9VuCZ_2VAG;C6x*`9*AVDs+8PLx}Nw0-a_Bj{QVI2zs3tJv1 z=W7~(xl=u-=mqs{RwQ8r!g_wB(Ff>US27>4y|DR3;eJp|lSysVU`YzsR`{~f1Hxx5 zI}#F;AWMcjJ3L&J8Q(D~pXhV`cyMGEugOsEQ;R1G2WL`JyZ3Q7k>xTQI;0s|!-v%-Of(>i{N;(P1xO8zL z$hwgr>uQ>dYIOXN|0E#l@TxrbS?D@ZgQECR{4U@ED0_+<^36KVE|^g z?x|1L_Qs0#g$nT_L-Nw!f_YsgKA%U1-NIZgKA$8^XnEI?@I#W2)AC+&eA#ucmXG8m z?!Fx;dKkRhcEh76BkTKJ@Sts&kRwp5 zqz2K%W#Ufp9&RB%CLZDvE$;?zhWC!on<9k%=LbMj#HpG=BHxDfTAq6sC_pJawpg+)^&eI@@Pu&VS(S~lPZTo$(_Yeie8 z(w-V52ul^a&l*D6H#}FoQ}_i?Yubn}@+{1~AB1Md|p20uV4bO4=}p_C%EJwBWsco?)=$4Me1-O~dbO zf*i|#9_9r{#q(L*m;-|Y-gZzF6%~|S(>za}s9^vZJ{?5BbIH7uXJGLWGe##`jyO}- z?6fG)+%G%=+7+6(z{c9*yHbEakvom86wESFUBmeWHrZP)pj@8^?(;vth7i_iTE)82 z+Q)SOvaOenXN?i<%JR7~r<(|jB?e(G$w`9&ZQJ6y5{;?fdoa8&Wh>N8WO#Nwy6JJ$ zRLqmdRH3n;K08pKnS=L~M{c3 ztrPWQM%laA0a}h4pnJ!4vm>nCBWUZK%5I*exom;Xp$FJrT{n%Eche&<@>k-fZD~;%;X|46D?K6;ZG#*Y>DaEKOTz~PgbUvS{)9Lo2 zDp}E{hW7HHrghG|(sZ0%(GCEs0o3wR0BBxb;%>aIE;-z3#=jSG{1|^HN-^m*!4*Ie_^0@CN@mJo9Z$ zA%BJ|bbWZGMzphJrA+gj$u+}kMOI20TEx?EZH0qTeoNPI*5DmR~fDVPmp6U!oHG{CD_#>We{HJ?sfcQ{j0 zG3bzif39UpT8kyyHHFtpDmp1yRiT$?tS@@W!g!)4xANOsagomp_Qh%9Y2zL7=Gt?H z9Dbkg9Nkr`Ez&(c_g$$+I{i9)v25nJsDbokL$- zOODss&KZ*UpdW|CXY$5nT^r(-)4p?5vQ1geEk7l%*EtN_^80Pv@}K`>ws=+iCU064 znOdpYx(ukzdQmfWq+Jss7=Uq85>~KamtGHPYuySK_mp5~;I?l`&ddvV0%&dKGFAum z&dS?#8mO~P=dp?M3!1EQoI`aZs?cNUYkNeL?MR(Xx!LSVo_CH|`W$nirY3^aN22Vo z%@p)~<~bvrpiIu087{p?lpAafq=UMp;8+qth(O}E9!b_%~o04sWtw^n(_gW~u z6obvs6*Z%dinX?QsT|e?jXZM7djz`Tyw$ZF?j^_E(_;VFe4HhY9e0m|)y z89}suIiLbl34t^TBqpLKn?PQAY51*i1iRJ=57vOz5Wm~9beY2KywzaObuX8+2qdrE zO7~9r1rvP)8^LzHBFY6;xs`~EwC9J3zj$$f(c+2Iy8|4dR~l}xl~J14K# zP|`p8LA&!N@t3`pBceb{CTz;#Jjh6OoRi6$ zvCcFa2gTP-a}v)D9hILqB`cNZkIMC?6eV?@>}*jCnU*g+GjI-&D_-EFXgVGSz7tf9 z=fUEz3$D+=^$o;=Y`p?<`+>p@1785|kVZxfz%G^#n$F4l!q3R+mcui0MdDWz((Wns z0CZE5&AN=B@brp3usvZ#;--}b{hOgCX>B1~No)7Ob-1-E$ZgY+wVEezeSey#c3S(; zym_{4o|KOjr%lx3yTu15W~D8JiG2@2DRO{p$(n+GGrYSWX~Be4A-+8^#Xh3q`)l+h z;DP<5mKmr3YdS3-tqS^e1DFF#EMOfO%K=zyf^neIo39p83+R)fe5Al=AxyiyIkHRu zE5pSQ;?%QKdC)*prZ^u;HRTKZ%d#34cn@GW$iI0$4+FUE22%e6q`H!j?YgGfBFwCh z7cz1;d@$?o+wj;@fPyn*}bE#bj-IKwG4(pnH(UT2BK#Wdd~U zsro|bYq{{@f(vFW&A=G=bYs;zA=3GUu&adVlQXiT-TQo{G?Qbb04!xV>)q#@Pg6!k zdu8FNrrTa@P;uXY+!xRPE!>&wSiDj&(U1cc>eUN11-nWTE)JaqAiL$bdhz=PZoY{BJH%$#dmlmcbyJO054;>$+#{q?5r?ASou)eKnNByG$ z)#IVgG;K%4GMIC9_?F|T#X?n;mX}&_{u$us{h-*ADIramnv3eA^l|0DCutm@4cmpq zPO*NrK=+&j4%XSU2NjFGlg8P}S{$|3r)I*eP;>>%SU$0s>=m>nYXD5$(W3g)(Evn2 z&r${yML!Gg@pYfs!q4C>1DVTtR$P8|!Ek*j(-TNk1qMhdHCm7h2pnLQJg#B*9A`xh zy_jyXE=F9%;_4T~eRn(%TXZCzUxG(g{<3f!GxFRgbi5cnIp<#b1*B7#(LN1@IggxL zDw;X#=W=SH)T-w>{v3=IMY3ij_lCf8X6|aYF6=5@} z`U$+bDGxB^}1%!G;)+Ue@Z6)O?+;O6+bSvPDupu@N;Wq8Io*f+A4NUF^Q+A z%@?mv*Nd@JN8$zIn5lYPB9={^MEyM|I;IxlyTq2M<8i)tZ7PS2V)V2rRN8DYeTEh% zii@Yko1H=Kg}8D`zX{C7s#)g;7%cUnV*Gco+B>&_KEd!d@W~wsF^1|jkMyeIt5*?`Bji7M5*cEFQ~c_Zn@7~B z_$dCNmdF=OWsC6r3oH_PGa7ar?fOIJT5xAtyIX{mU@Dw*kuXC`jGwdo@Zd$#(8 zg-XRauyN~$?Lr@YR{g@q$;*2;#G|p*&qQ3jyy<{Nwd@D2C;z!l6@9)s{Cf2>`WKQa z%JG>6J*hjIntB>zB05HuWA2Pxz;1!5`$8@#{K}ig_jvO+=kgQ40gzM#6gx!TW}qwF z3tY?UH3|b6$m&%SH}`HDS@dz!0n4O@gYDHX+%K+}9&b;sp!mAxHerhmQ0GNJoy=j> zA&5XwXWk3(5=*Cf5^5?I-`PU$808n&m{>LFl5|&9&CJDGe$L`yjkvBgUeYkJJPnHL zqahRD3wD-6LBdpH5OG5zv^i8zj&xv00QWvqIB^yy&bUiWjTsWl@46#BZD^PLoJr|B zjlv5h&7yUaQ}5UWWniEg65qP3D&dYnGvJr1G~^EifHaka{0CY^Y6g!3V%dz^s@TC{ zzdxX!|9nXH5`%?x4e<>~w9aUj);iFw9ZxTpcuctd(jdt(J{z#P$AUZM=@ZDlS`XKq z&?d=?app{WSzt=nQ8}^hsGOuZDyQgT1~v}ult;C(O{1DV^F_ssZjZUivJ2!q3Aq-V z5t}j-u`A%Z^7m`31+n-1o*snjYDoPvhSPIUPq&6wG3TjV%9E}{=M#@`YpfEcxmDbn zPSvRMJCz_DWb<3akU6O$JM_oHkpBzNc;AyBG7-}U4Ll4RbKR6N%8iWYJSgXkr>z&o zxAmIQJI|WCt;qK5$S$A|z-zv2KLw_$81WnP82hQ9)BE_dA3S^8OFHqvd6fIUhrptY zi5@iG-dBAH-a*Rj8Mhxg)Yj96Mkp)09cY%zW`cRF(*d%L3lKxX$HAAuYGLoIIE3M? z(nB==NG}u5t&+T>*VL)(w^koQx%R&LL&LD+0QPhbKpqdEr?mgy0snpIjCauqJf8OO zl14dt)puTMyx2Z-D$qWfZiLAho}?b{1b{!`Q16uvrM++Lp{i~rZSTuDWFJ4{_UJ>^ zYiKD3Ml+*NcgRrw)1SZwQ^@rVRa?7pJc$5FuQ0q6Zzh7w+Lhc|ySEcyL>~J7ihfNc zKvf?4AGoIvJp?+ny)X0$hA|AlhJ2}Bbj0RbB%z3CRbOJF;H{TIumJT}LzA&WU zRh|+BkvYqV@^RHE$m9-1b%Bk5S%^x-49Vpi<}x^mq=l3k67GQX_R>Lr za`2LJ;rZt)(w&ts zb7aQA79ZXo^4}hKzb6v*@y`QdLXpmXB$&$40rjR`;Z41k-UQdGic|}dY8pcRj=|rp zp|7;7@Oh08Yg@$XCNA)zG5qXa)y(sjipuViq=hoAgB2;Hx@lGm5hoeo9GzC4D1{=* zWXe>##sXVKqHV@_&w05(fB%VBp^Zm?1-vLvw@)B9Kq|2UjNX48s9m!dNO0{ctwhDp zZi>q-Cm^&E8x!fS4G&HSUJXK%?hCSdKygCf!$NMx@$r^q{;Z9;_{0TYaJ?+#CKl`%RzH}?l#1-ksltVaK5 zR&&>ESH_;7Rl2;lIPSn2x6EkmFeM`hp}i`m^Eg zMF#%qCGcMF|3dWeN%q(K_osyX8~Ueg-czc zQ*hmXC22ORSNKK(3a{>ewSS}u8QIQeIR#Y8+BG=L!E0B&dZl&^Wstp%jQ!Txk0Z;0 zoK4~SLe(4yv_#whk~W2GUyy!QexZlVSy0sK=2`pN=AE@2|Aj0gSwaUSvYg_kl61AQ zAA?;x|JuL4 zjN)m&Qc8`o$hH*BTWmvyFIG`cBSTbxN=VIrXi3tejIUk+Y}i}`62;QGb4_^SI{5+f z63Nb}a@WbF=B4$^does|l*{Wbdk~j8#%#~(Xlj!)7q`i#*i@54*6AH`lwK8}<8b~C zdHPJ1k-V}Na{J^FbFO-jp}Op8-JrjH0A)}}r?%~;uU{5Dgdf7(n0{-S9 zt_H$nI`MSBhpP#5p2hc8+%wBia|Q?qo;Kit$hfT7fd8GL#@YlO%zu7kHF%ChUs)0s z#mMqG1;ocRBYiFNo*DeGz5<}NHJ8SPor|D z;37@o>1#L}C2zs>0>;v;;_RdQ}zIC1rNe_cTh_sHR zxyP_ChJN?fyH63Qb?;ZQ=ZW7}K4A}QQnV0h z-Q%L+MdH(`E6K=t8>~)5$D)NT|Hl)=(czwCJYO|t+6no3O-;>`WF0TJ8lQN>GTL)T%0ynz3j&rjfcViJugbj1DpA0< zc%c6WhZtdrg}{4DoIEE#jhBZv2MbEj#*-}Ag|Pvg?D_(zJ67B{X9`XcKc6$r-ZXd_ z3|%BRYtVluyfe_LX&v;ZoP?-NJ;8ZwU`@EeY76-F+@We_7aN ziE}eP7D9#w{Yf&NuIdQ+6NhMlG2U`-HTJp}S&S{1`^AR4xR-D~x3&&KrpVhLi+`G% z2+qG(=W>&2Uemn88BxT72O68Uf!`S!bbNB1x=SPDSrF1$fxseUPR50RGdz?{L&kvT zw)o@R#0M(Uw^>+syo@stM3$l)zb7s^;Qs_neMFlb0Rge5=Cjw({H+$X=gYXT2#9g`s)wKn z>62D)ER(5{BE|RTjhS%^1QZq;L|kQG=TlS}1+kwgEy%V06U5d-iibgS%OL)0duJ^~ zo9;&0emA*aR7)aaG@^RG9ekjh=a;7Li}2;COZkBRl_4g5N+-$$?@T1#`vy40_J}v; zb08_$bZ4H3a8~i#N`|#KQiAnW{EnJ!CCBA)n&Yxbr*4XC+HO&K$g`18q&bnH3Vad! zOG;s#Ccx~3y%w*Kn&b^lle($FqIZK7qJepMAg<|n|3uApOS=mhK7u+Oa+EHvugk7* zN7%Dfo;b-Iqjg2=aDhU`k?(k;v->@9eGa?U6`||%qP%xK$H6amzxz%hK{7K7J)o#= za&VxgZg}cb5-YU<)Kt34Ucv6Zkz1PXC;Wo8i?Ti{8Cs8OA|Nak!z&pNu4U%5EoUmUF7dbEGEE~N?Q z?;#VmD=U!nuJ$!UWc>1a^7b zoo0J_G1ve|+(5}X!2!Xlqxc7FO2HS#IeY34IAO+^EKo}uL1Vh@QTTKbRnVn#gG_pI zXHPvXh47XmRRHzFfooof7orjp?5Z9mTT-kXwnJ?yfSwTxrLiUvwre{WPNH)Zo@ABc z91&mk1+RG{a{4{-QYJ{<(P5G1wP1u^@W%Fw#GrPC;>t2U;S4j(~9N1I9 zb6x)pF9P62oU?>Q#Z6R@5km`7CKK?_2ATBR9nNBW<}W>J=83HbV1mgcs@=wADYcQ# zY<^dXaT%e_dtsB3apa407AE2{v1Z{+tP~F{r8O}_^r<$?5f@b|nH@_!jX zhC*1bR3$Mzy$yFJ*mWf6h{S9#zI3Rwa{%cJfrPvmKzb8g8v-13b(n0x)XYTE(bo5X zWQ6G?MDvXsYOJ5;L>xdxjdjGhHF%$YWebU=3gB@UWI7oz0J+<9u)HyCC9ze zwW~zqON#lyjk1ySwqs+LxNp%YaoHjrt`%Qdbm~!S=ynq^#J%pd+|;ZfqUf5Tx)yLn zjipHRDC+k%3dq>s@xE;XIDjwQcxv}2(pNSasFOY}(G0aksJ{h#^ z1tBucsla{bg$PI1LGJEwE)Q~LA+iJ*EP5IUl{}^%kgBjQ>zVhHC`}5&Iu=hjXd#yF`u;nOsMA3E&hB%!%*el4$T#T%zjkG%% z5}x4mMnJg=lH3fg0e(FH$ktDq8h^()jpvcAf8-etw+w+qPjK#6=def?^3OX-*aKk} zDEq3rajQ-&c_>Zw!FoLDA6{9keJDqK?V)tlE1^#;4*nPM#6$Z0b6!~HCy=qjjSWYE zdg}n2QTADPBESp*Jv;`RMd_Z&lOW+ghsUB6qaQ9&tgT+VHC9~saK*GYT8U8}ye-$k z!Cs*a+Y9yzVS53IogxQ~U_6@U1fB(~Mi8q;xGW3)+}Fj652x8rhE%-Ze81iSF<74l zOXMt6*Mg@v*1u^{bQD5t(i>pD8-*ge?t>>o{#S!=gkw^(#e4Q~+h6LCPKHRPM2KV} zJ7vg!0?f7y|6)C!t~z5AhWsypvtw9PZaH=c)s3ze+83INGFb6T6D}`>20{kuWh?A#BF><=?fROJrLh!>h=wt{c zn=A**+zzur5`@e$eO{^gMTpx*(vyPW>0+ySn3&rWPU{Z@>c3&-S)_od365U|^iiYI3T*y7nMs|OG1LqM8of^&S1?1|^`#H9N1IRkE@vdGOekdx&4 z@wu#fOnHK7Oc|28hiZYd&U71XSryqrszBF|H%|AU(UbXEEe3u$(2?B55FEyQd5wBT z3zN?H60tQsR>uDXnRYz!+r@Yyoa1v7!7TN8h+bBI!g+Z!F=Eih1b3q_nn#(DT?VK? zxpx*T&R)8JG6_%vf7V+qjNwyxFvIfSLqgoQu!@nx0XXzG-mQla+YW3dAs+m1%^RTO zFE|ToQk_eLDCfQs1~36houX&SbbCf~6pwc-bkZM&`~{#2Fr9dho~L(#Vh|2NCp3Q` zyiDEyS*EuJ|Mx%%2}D<>Z{`yq4DrFvxE3Vk1Rw%zoc1FAkObRA3_-kaC*HeDFtS@oSvP?`l4`5szmjz`1K@igPf~^$UnWgL!5_0#FXkS3PcGVa`kIo9f{+8= zM4C--qbz9F4AF`pmP;GIl2d2S_`y3XlL;tS6&CzR_JQIMnMcJzZ!x%W$c|9)BY?`_ z9fT7z>2aO(M|gK3jO$Nur|zW1nU9TRjj-(r`ir*5cypiyPb0@_8XKgGgcX5rq*c>; zYI8g+YmA$&S?&B5j1+r>r<}2HXd>F(3EU+CB3NMtP+bWqzdt`#8uK0m=qGhjZ_nXL zTP|_h<4H;LK`dkV*bc-M@&{}o|JIOlm*6D0|K#IV>=vDmr{H$+`^WW>r696V9n}7i z|9-Lm@eDjpOcFSpCr%dDoLIU3|vsEGgT+vmN6#e)h z8sFh2lU_dbFY%X}V&lGk!4_Tmw`-IldwAp#|E2vyz|HLDbNY zKLO%Qz)|olMD}Fe3I|w8&GEC5E`Am@I#-~_a6(E8XREeJt#Lw=QPd*?yK?(nH9(g7x{GH8Xv0}jco zhVW_-97qfo2C;%f@sT{+tbjv@0e?y`;6DJ)LDmeL8qQAjXFIYPW%n-Kfz07xOND6jV-zLRi@vtsPhMEwdF8v|B@8i*u8RWHNwgqLMXhs6Q^ zO^BHu@UIZd;3V`9;;Tz@@O;s=Gzs4$URYY2HenF!uYyDrDbo;+%54SFZ#@a|56AL} zi=WK6s~Id;H=6c2DSH$|hECKB`G1g!o1Sp1i2%8A=%+2@U=@wY!M_3jDHnN4jyu)0 zwjU5rKA8-WcNd;avp;Z>h*neJgh+3RijU@Z@TuhV*(Nf&VHYk5s3b02B{+ry;6E^# ziFS;)?Q`P&1O6)m7__GW|F(fNrxjv|*Fg-i^0@&}K!^$p!Q)|)HBD$-LL{7gQ05sE z5IlAI-4_z!jE%kRt)$e_v~n<}(KCGrUk{+gB;wo^;^4@mww#DOKf#_+f`x8Eklf85 z*eO4tL0m>o&19ZTAR-oPb@i@_ZOp^O^$bbtRmQU44U913+=tYa{ z#VgJpvmAgT_RKEJ+%t_mD3a#$TNd#|S$*3QIMbPOg7;jbEIVyc&ToZFwq2I@duWCE zLWFQ8xuPh-X0$~KMH1M{ZO|B~E*NR8-$IUbDQQUIW0^(#S!YC#3Uxq;({@{|lh|m! zwdD$LTat_Hxi;g4K=Oy$168>~xvfM{Nmw<_YPFHq2ZH4Px8PCB4)=#XmYM)q)$jj& za0?0DjXdZz3hEx3ss(F02q(5$(g8TVgW(hvbinkv*BZ7sBwH=E4ljZ9Eu5hx*ST=~ z1ZB_Y6An#?;|bt?|LcPj;E~mfG9MJV6;}L~`1pz}d{KOP#TYxDLgf^=mP;@GZd8pq z3TNC7fJ~SIXOcuX>ky##RGGk3CQS`0!p8_9Cah${QM#G_2n;DH;24z@VCw;$rH6(m zb@I(!;=%9ZePy?G2^LW%A79N!a={*q2205i% zU>k9`PAq;(Z->JYqc6&~Z6ch$B6|r*zpXp&%Zh>Xk@=Kp6v9X0?)VNEPS#JNjQ8zH zB~PgxJ~zxD8(}Eni})FNv)YgQj4^k);VpQGrTCS+LGRU}bNk;E|V-Xaj<&%?ilIpaNg z3)x%F9``*TlM5YN6*C6@pNP?WGW#4$?C&)d_34(hd5`;YLHz7eEQI)9>O9wdx&Bj# z8u-9PdYr*OY$=j9F&{&%aWNfG3;7;g2hFZ}4@#ECs6CB}QWtb{2?0qUqE)ZM69Jys z{__N_B2OGkUV~DyWex&DtPx+gM@Ax+> z7Rk(BVgO=YyLmDTrF?>GCJ!S01SB0Bbnv@=I_`Tc#@_eBp$HxtFN)EteJXWK4!b`` zQblIFV)Q4jQ;~3BHt;6-2!N!faIVGuuF87Oo**$X5bO%h(n?9Ej+dfhtZvd&f{WoG zklhm1p;vv-L#x#1j=`rUbYL*rRdURSS=n<}5gJ2kGGNgt17QN+v8#lDXJENjltW-n z%!-OA*EW!Z|I)*%)jh0I3wE%Y79xh2rDJRFD!RZ^_PwXCR7&90gAHj^yS!0O-IQ;d zi~?!q7w@U2i?VJX7Ht)HPpTyabP)DKCO@(W?@n?8wj`Ny^4!TjCT3jcj^exyf;nXL z6bRURinBW+pqqGaV-L%6sVld;d!>TI`J~$j5d4_Wj$#tstPfN1MJFsrU7=(& zCP7liq$9SF!$4h&?9D#B@#wckzN08Z*s-S@u|B?zVdb{@i~0Q-@K%G3efR$uTg)- zizj^Ki-`E9$>aSF_6%mD!5|GgYTC=P&SW>JV$K6@GP8=KJ$%uTD|p5qSYA^6UXMz7 zyZtxsXGt<}ifld!@E0_L@mJk=#ueDbOJbNlT{Q*dq$Z}`bL5t8d9{aZJlJ&V?|3j@ zXcozAB+!I~C?`kKsFfXNOBviP?wN@*pyNrfmF-G5nL6521*c8m;|dP;UDeiHZd)p>JibYN4rX5}~=CuFYm?fq9xNkuW8D%l> zf#q~ZlRCGgU2QCGCpOr-vx?w1vZ%;@$2$tOkBPh>!;z-*NPo!-^lkBvZi8aJ%hA-< zbjzD5jbb9WjDhvx=~9Geiz2f{<+<5|Pk5=lDfRanBRtez!mzADvY^_5VX;E~ErVx% zDT8TGf;qu%nD{acXjhk&_w{$(Z3PcC}Rvfnj|H$hza z-)Qj$T5bAO75Vm!T+y>S(XL>Bl=s0Y`hADzT-QWWQbqrA2qfLiqivljeu1F?9ujRLZHW&YUkDxcJb-$`sLtn%F zXFAaUJ$U%nlE_Dk@U-DRUiUQGy`k{$H#jAOIogzci4;<2^K(B5n*QKokx7WjLa(2E~AUJflsh ztw~81;fPW^kBq5@F`f!7wv{xd^8f_QXIYD8CP`0OVf^Jrg_s{VKlV*dmQKAf>8 zWx@@T`xEp56i}>3H9>!S3sD=Qd3_D>nOi_pq}`VVoPXI?*c$Y|BbNOsW4abvTW3QY zeBfn5T?t(wg94HSP+}nwXb{t|E$9a?kZI8G1F=^FpSlS8H;@D9hc#m3pT_1VfN_-h z0i+Q)$xM`-h`a$0@!Ky_-41*IgZ`CZtdTly5M#A9>}eD63-NY&T~jzlKzT0c&zIE@ zf9M3f!P7{65qfpD>9q6rTs$qK+cE(sFT6z~VXIgw2 zF$otcc~uv2Qw9Aap}Tz@-vbSp3c(1Z8+XC?N51T2irxcGamq`$cfVWDm-7+;QZX`E zReNhHih39S3bsK8K5YZKS?KoxnKZ4|nqFtnzo%dK#3MD^EO5xMW~W@D5u@x0#%LG~ zvE>E*@Ah|j$@MKbRdNwd9(Q`-M9i_e@cNAcYWAI2V(0K|vDTh8`rTt>jj0^)$Vj#m zIDBn8QCC8o^lQWB1tblf5D(kUv1y=7X2SQ=G|lWRn~j3c=U_*QG8;;C@uI=;2$dEu zZg7m&pO7hOBZN#n6QZQ;kiQ2ImXf{=$IXy~?_0$09aHR8{S&!Ha+1VFAfy6ps-oT2 z0Uq!{_%0PGBLSlaD_%K_vQ#{Tjjm0rqhAG+5T?8lI9KwADHVq+l9fOG+p7vBBv_x}I#_W!Q11zx70 zmkO}D!>7R3(tC*(NsEiSD*K)X+uvm{)3)7|8%UjAuq7kuW`mH~c)Ezw{sH%liQFh>+zN(Yk*XN~TKZ(X&97J%jEA0#&EM7SJL()}_l zjj7S1ZwDzflf>mieKRe>vY78IkFSq!nNg8aA73}~W*klFmHX{z%*V18f@}5OuMpCm zkjS>kOhlP~pfVae#j_%HvRnDu%Vp)l7cE>x#jl-o|hkt4-^g&6Xm0WS?Ge-5&|ry-A|Qx3&0FuaA} z?Jx?Q52pU7_K9%qrf}_#!?h1O?227$Rc2|wg9U_p-+`rR|9SOTxM4HB>k0w?YWRhn zP@{e558xk!YdGkQ;Tr41HP$(lA13H9d}vJpu6V^Z1>m6=%;5<>zC!9lT<7v|{iRU9 z_7S(vFug1>OSym0{|^8R<9ZdsM}L3e+3*W!<$YI{Ko{vF#H;&Uk{H!1>LoJe;9#xQ_Ig>cOS3<6?5OD6>V{}h`y=qK+E z({eyr6N&g!SLke7VbDJr;vu5J^{RuIwqr8R{uLA-6`VLB?-Mw8iqRYO`J)3VWlBJU z2#^a3k7&zCSD69R5iBX-XFnJ{K;DZ z-~7-DNLmVpL=8AqwM>Wj`lj(#CCDIqK}jU`s4pEPma@Db8!c&QObiI-o>$LGYvEidBj;+tEHc(wS=mN9sa=-ZMq=>c&1k(if#CBXi|zG-l8 zF@N^HvI((Ab|7}-PGYuYAdrORlfk}@IQV9rICJYrd+$urF9r;)Tfps#fFy@a(BQ|| zJA}sFcH?oS5Xr~*PSfOsYAlb*CJreestxXSlpgQh3E`f@r&j+4=2$|u4Z z)i+Sce;ms7Q2vH#H2958svqT2#~ZeP$(q>DHFA`LR3e8OKu71{+o@aA?1zEk!gnl( z4uTnaq~b$ZW-mzJ!FYUHX@X?}JMTho+)?Qz=(uXA=RyKj>m>qqsPG z3y(8_B3(GrX|@R&RX^IR0bZq@A|@S_aZlE$d$j%M851gbYKWNJP&IpM(ktsRL+3-))q;-C_TO;Z5q`-I0fPKI7iVR-&)rP=3oeArOvbaWF8PAFk!K;PY2^Rp zBAHg;xctztBR#?**!+^oPq^dmn)Ky?A|#{iS49@1$RZcSCDu#s4OPq$wz}x18yp`K+Z zdjWZO+iH&>mMuGA?!JVYyQ^O8S$Dgnj44#4OI?ce zI~Wbd!>Xg>&cjriq^<+YDDk*4-(E6DmmQP0nnim9Zc(iAfTI@VvIyCcauu@=w(0@a zP(V07q-lS(e^(h@W?Z?jtYYQmvIe>Coq8dxK?C{*c|!!Xvd6w9 zU{+5}>R*Z&k}?O|0|xc9`n~pOfTv*LU49whDX|h|xYoYQwnI*sHeZ2dzInGM>Wc#G zf&yK`Mui1@gBUp>_K>^*LC-J)1^8yztWm|_Ph!qa!>I3k3{WJSD!l(Ytve}tk!K|!=Nr1^5njrJ3=+FX{A-&tlP;urEU>$CDi?bY29Nfg@ zeBxI2A0s}g9tManaF0O0!A#zSD<=6JSzUHfjmYsIvN za4ftN8qyh)_{WAs=J(}2v#$WzG~qj9pa0xCfGJWJr+ppKSX5d>M+%a{?kk8F(Z-53h0K?l!3`iJP9U6 zN*alsM{_g{6UfuX3O62Qa$Q#T{ziVZRsM>Y=J#3@U7f74F+pKG(^_HWtm+ukV&+(EClqOmh@&%@Qgks|A?J@6S*M0=EzH6=MK zPic&*lo8gs)`wOWRW0+_*sWGY@~2iya#&SZ^42PS&%N|ZD{HH^TG>zS;2Q3_?%iHFw*A*OoC^6t1FZW_Arp|BbcwXRylU09b{hiEe~oDn7t; za~da<{9NL-UzPaBzbT;zz5nUEoXRJLq}$NpV_$?*_&Csx4oTs6#p8`Bpl`j>7|%Q? zN{tz||G|mTizSR9k~^r_&x2Y&sASe33lj(gBUMmJu}6lbi-RNH4r^i|Ah|2OJfsV# zwy)VXJw;_>@k5Rm}Y9+Ab`Cx3ZcDAc+ zGvR?ijGo3giE)ZGTTnYDm9?GRGnX0rJCJXxufPl(&k4tce@)6WV$$9Rvi4PS9p7$Y zVc(+|cip7~fg15>WU6A1CEw#0_a1&-bOP$}bN*P|ymu1wjd*(RtITWS!Z#{xN?|+1 zW%FEH`37NScdK{9PY*d5FMI1O7;Qn=(XaQiLo>iY)nJ+5n^0uXf8>(~lDyj_t#9;q zh%Zq4H2qC{Sa(97LZR;Wo9&*YnkL@zQ$h_py`peQ+@aPspA3%ih}^ZbcEsF5J*;!6M294HAt2H|DZQU##ubO?ECxl z3~pr>Zeo~8vvGO=OKxd=(UF#3W=1$zplW$7?uKEg&WgQMi)t_03j`hR1UWq#UqobK zFH;!qBg2Ph(wu=i$zd-Y22S9VT`L^w3s+it6_(fCpY(H@HcPTsGc>nXq367s+l*Iz zE1_VJj^%8EYlqD@D06z+7oBfRpbJ`GIJ&@k)jy30bVJ+kpKSNk+G{aNo9##XS#5b? zurq_8BMo$B2JwXtZx3{aVKA(Dt1oSzxvHDZFE6z8YAySGY{UM(aArS$K{zZdzP!-6 z)X~a@q30!Wc z@MkwWrM&Qdw^`7+>HOir`$#$|mO7$c$LZ$E(yLf6NX1Oik*cUxouE0I#P>KWe*!yq+tkHfmI^pTp4~5(_Gzm0r#L|N%<^{3lU=p)N+ERAlkt`L3V%Z|G=b&JlJ~$qc zQv%=lK>7?w1sLDVH3QOvgX4-{=Xn>UDglK3(B;_uktk6A(7Y|KPzmKK#tV2}4$xYCAY7Gp?HI?kx zGNoZa`u4=5RHV^EdMGTNDH@Qv@fM(Ak_`KTB5nHs5W`E}9BVuGuXr46k?&L}Yz4vG zNHhq9(iQ7z`mY08hYVA0Chv}0YZ}uva`yaQlECzl=+fuxj=1N-iq7_(WlI2{E^;i8 z^~CI00wTIIt(Mz%Oa=-wrjr7~i&pHi;FPAoTOe16?xHuJEGx2f5D^lh?@WO`4lyj0 zQ_W)wRK;U47SY(1=AWk07@zx^LmYp2jH(I$V(`CW@!?dP7Q`Y=l{LJsi@8H0Yj{<+ zs;H)NCtnK!zI&~fVKmmmamPjqmdZ#71Wbhh;4B%C#+?8>FQ4$B6sYME1{wj zgvYul#CR3T4M=MsLYo~ZRSQc6Vwx4O0-xho8Yc_1<7@nVmGf^~m+1}P#hHY7R&l$h z!Y?iJ+XLyewMWsKUs?%yvH6rjP~vuJcmWV}!Ey+#l;#97EeLe%Td)2U?Z7zyj}G-6 zGJ$4K@t<%U<$*xYi~;;fN$6@p(e_H^w|KkL@7zk|L?(AkCzD61SVoeYG@e`w*fmf+ zWGrd{h2D!tOgT}0JMP5ddE3qj+$6|XhRw!QPtpjzAx`K(wx5RE3VESLV2yg9^yr_l ze0k&%<})#;IX>zAVa$YFk{lCAIRg0<*k6Xh@qoRTBuy8eY))e8#k%HoVEFMhPl?Y0 zZ;)y(%_YH*#suliEk9da0o6yLxZv$*n`VeJX`#2JhLDMKIM9+rv@fcBolkXsvFae7 z;$n;@0I6}ZxV1qU-7)o4Y_W6Mz624X6fPpkb-M#v>T&U|-K&7raw_^wO4`!r{t_&m zba&{N+5`3`#0V`Abk-`U2+rV1DBvIQ_q!7wFC!^8+=bYot%i%4liyCeu%J>^*~G^= zU90LKD5qUO^CZlGj--IHO3}b8`dI~3Cnaj9#-zlpL;UOK9M=m1=V2odEr_WG!9MAv zb#D;oy%R6Symx34#kn$s5DFDl{ld2(j38MbN`F2SULEwsC*H|>Z0g!|Ys=THm`-Q~ zIs=p@Azu;l)kwI`L5qVh^|c81!4C_i>ky{pMufupkUx_8;)0{U)n_kX@l5vm_0KM> zCVuf_N3>XXbfnFZ1Er4{R5sZ}dj&2Qt}hD~=5W&xp9r^fJXV&_$AD`W(yqXL9dcJE z5$z-SM7tAC_W;rEhyNZNEz*Rv>ywH0Cc;z5Z3?SiF5``IE$@=Am0cmF`N<-ZSJcmENpD>z#2 zFCjnmsqECJPa^o6+2#`V2M#FOv1+UzZ3nD~;?JbvyoIpcFCj5j|q zG3SAa_vcQ?xgYFxgousrCQS1WZY5d+T;wZgZVS;$wa}Kq?SwlB_a@v@NK3nS1e?-9 z@JPE<0ADn;#Z2>y!H8yLOd*1U(gXC{`8uO?9pVKFBx zn{y@*hGAF*BmVu}>9K*K(zIw=SfXhmMB9=!S=S=Av?hpO!D-v>6DPJMiWO}T3%AxY ztHoE^vLm=r!TE@uus?$1SlroW(hh-F4-qNoSF9L$Y^nm8#FF-ygljDJMRatOtc6}j z&^uVfmfps-Skt~ktZz>=N9Gc3P9F5^@Mpq34M+3Q&%aAUld0l@WBxG=txn5YSem_* zEjf%;eG}ZPN?TrWcY-3%voQYupI1w3Vry%u)tp6*)^?&QdH{R>||2JxN7m}zk zB+ZbKG;;(=+hx67UvnWl)o?P`EYZ|&t!+MJMkXZP64lyu|F05tEt1$MlDb_Hr4$^+ zl4%tAj_Hu`7=?^o5D-Gf_YWX7GN+r0>`xuJ;4n0;YHDw~(3HtnN*HH4R`U6^*s{uz z$(y9DkC=wtGc!qg*lo&mtb+K-lvR#)hk-W_yUo^NcbUOqsKdK)J1Uy;Id1oQR`X^_ zqFk#TkQjEX7?1nc#bX$ORl*cWQ<9Eiio$^j=G9H@8?3`ytyXCf1%N>Mg!w`fb;P;Y z!0)EdoyF~V{{MuAVGRp85__g%vV8 zpjMyK(2|a}4J6QqEVcnPUGBIi{OhZvt}?(eS?5SwWbFA?+ET4ZK6gp3Ie{dd;!SkB ztm{`wI^~}%(+5;4m&Y>CRxRuFX!t~>=bF3WasVqEV1ny?`m*#gJ^!i&+fp2T;wEVV z>J#^NAhjAsf+QER3>z)6&`Um>GU=?!4r5Afl+8v|2(4+IFWsbv)lWuSEIXGu7n63R zp896JQc~8=V;8%{l4ec!VIwlaG?CyVm1%pgj0#pLBj--Zj2d!Fu|?gLQCEFE0X6ch zw2*Fe#6l}$bwe5y3*8n=h5Gse^YE`$oPxMl)B|IswtWe2sXaYNHpL^n3+ zd-PqfNL$AjDHaliP0Tdx7xppp7Uu+P!zY?|%j-}=0p(X0P=N%GZP?wIvguQYe$#Hb zxfE|$W2J{tqiNW(Tx+A7QlVdV*s_`QOBJepP`mkGLY87Sep*PPy zQY+X^cQqm7k0J|smSH#K7f16Ue@NVYbdTIry3?~dx6#^IxteMic5mJzH|q^H>p*L& zRVt;Pax^`Rq%R`>5)E8XJmc97JEN2?brnwtq(WuJpE`_OIv>Sib}MwXg+F!GowgN* zili?ij{6F@SZFMIB92CfMSa)S2lvQ4LXs+i%p{e<^?a+hV5$5#LKR)x9#qyAaW6tX zmWsj*m(fkqKyo5RuA=ATiAY`1mCgZ>j|qBJMi!F3k74#*`EFy1Qg!ZKd95*3NuM)v zNIEFkRQXsIHmHglj`{RG74YJ`I(CzS6RZpT)HSD-#IIfZ8N`Y}!!Rn#tszwF?<0;) zv5<4D6aF6>Gi`#oDAmB45dPKOD6cm%U%j;cLN>PbsS&Wj5s0ckW)5 zni2D+UY-RgSs)O-4l)uBM$+?b1*~|b@V#oLD{ExDuWx0TVa`gKZZ=I z8h~?533Cw(y)tHuFHS6E@*$rQBjYY0&Ip35E44PY1}OQMzBUEo$zw^-&Jp9eWT5Z2 zg;5@66PMgBGg-BsPg>@8-<{2KrRC4b3HdOngt2lC&!S6y3@}HWu<=O82Vm!SK{x^7 z+usQvB$TZp+2mbmT@05PRN@49gJn!pLIo0yvCzLp`@ONy#nB#Fsi&c2D!@u+dAvI- zF94}XrUgf`nQrMo?G_uq>1qN^C~~T>T$431*~ARe`dn<|U%QKxcMQ*Vw7?)oRMVKCo*4)@dyW8bi3X%r+Vx%ZAWDaqmtsjT{HU3L zvjl~fowtVBbTuh;jV{f$(^1-U;tG{o$+z(qphIq@@+>OW`82GKC8a>);!jCzNQ{Lx z3ioQK6q*~Pel~^cm3JkcxT-SlvQnR)lK12|7oU>%PCF%c=HRkZ^2<3xqVSQn1RoNv zX(zjqztC4yrO<<0X*%ez(bt-6S_ftUZXm@ljShWJlAWp0ICMpfW1ILJ*q$Mr7=y^;cqp6f6Bw%=;eo>-$kZ0Sj`<^j)W9x9OC;)s#_}Q42J6 zT7ye+156nJT{Z;cv^D%igcqa*6Oyw6C{J%UbNX7XG24Np+hb-fsg^b(X;}<9G@p^P z7qODdW|R7DA3$1)AAjrqsPCzinc~mkWCfi68uhPakg+lcsdFHtb-CFM96rdv0=32} zy1%$0Oiawhn}pekbLW_1>D`De;fozcj$jyRsO}=L_sS*HdgX#eK)|<*6YzIT7!cSX zf7&6unK+BV(v_I-uf$SZCnP6L!k-9JlX6zm991P)QNX#FmT}gIXw6NL@d8T5x1!<^ z$Sv(c`8s>=6=dCEP4K^JRr&Gk$OVW0cz z*-US$cZW6C|J4Jye8t*#M~d`W-rrjLe28VYHS=l1{Vs)HQ=|%{NtWacU!qwl<6=Df zl9*UD5=a|%yE1$l^RS4f&Hem69u?o_pU0<27To9xz|8F20S8X=gGR1n!`{VTJdo@DTki?)j8p`gA6)Z*)??)ME^dAhn>sd-)PL$w{+-bFZ4t9fFdgl8BFP#hIjG>Z z3uv0!w@IQE@P?m2 zU`E0}*4J>Gn~?Npp*O{(IyFWhJt#y{vKDy9?(!6Jgk-eGl>NAzDLx%Q>?SE$wYiDF z_S#ql8PAr-c!k6$&WM{gpyDBaj^nYWABE+q^HS7ftsE*C2q=OXnq^Rby3mojXreay znW!m*Rg?0PX@8=L9H=-d{E(VWQBgscX2d~ZTH4giw6Q%RL3Egr#VDAeW;hF%1igGH zJd`$f;aj5$uK7Vi=Py36cQKkKUWj?0fq6}8K-2yyqg_cC2!ws3WX7du8is!XOE-6H z0l$ARffoAHZdpDwih->Mq(rgMcQ?{{NPjbm%uFyBlljqj5Kis2Y2 zUlDDNmp4Os>W%U>!iVXL5}$Mb@mi~ES^!N$((^*{gdBZV|K7#=U}m!4j|wjN)BA;m z6N)HjkHAkj=t2c=`bpU~|9){cAV#rcKflp&nICkt$GMcfz@;!8GNr;)+mUc5UGmuzBH>P?o}UZiuigxLA1}FJPVI`SA$w zx!FC))cl~yIlgs@`87)BEX;Qk!J9jU{Syn9^hHVfP^?#U0%2je>D;=V`*)6S!j!;& z(hO|In=AT`_Zn=ialg*p85!Sgt6f!5}SHHRCZ=$m&)b-)BM@EWDr+M*g zhC4*4MLwEB>RyB$SK9qY??mV$7HW&qN2H#q&ykWf8*cUDxArbRY#k7uo0Nq=7v7qb z$N z(M7e;94^&(W&j1u;HVZ{KBFk?cP^H@XrAE=Ei;PL{-V0#+H^R`*F~FQZ*qRtQDD#H zS)P%D{Lk%@Gn;XW5LV7iaSXb!ck^n9|Nf@!1yj6`k+k4#?y!=1@} z1pg!;{AZCOdj{k%j#phqI6f~#_Vc+l7x{ajpX1>y$ayhh zfd9dW!n~h1Jc`VdU3Pp@cXXcok=P-n~#e_k8I(yS3IeKSHy z^&lNq~;-R0jiR&Kt?@;ui^Py z2xZ^F-y3DXWicdCks(Q8k zy4NPpw$Otg0uxEjD%ii@xc?qU=SsEN|LYRD3P)qll%lksx$U`i!$L5Hrx0^3egWLVdSv|GyA8@KdJt<|uK-kO-ioFBsjFY|LpapAv@tICedjF3IC>K*q1cJbp0V+ZWIq0@z9G z523XJTHh-Kb0%P&pvs*L|5J140{eAOZVrA%_*HIkO4CRI$HeK1k^47~q~$_)?mXA= z5hi#3#R8xuDPe#?qLsRf&v;gF^SA;IORIoRDdMFMK)tjJcX~+8QzNGSGHyB4K+R~IWGN7s&|m*DAQyvKHeEiMAkGst(X z6sf0O2{kZq$=`KCa3kXd87=FRQE5dTo}I$CSraen`4h022IX0G z3OM+!f$<}m?D9GNc-k=^&QIa-yh2N(Y&!BD=y#?EY_iD`^ZwiM3G_vdZx`;^Czl#w zH_yAg^SXE4RZO#zgTB0l306_7INCVnXZQUKNuL9(TjlH{SW1vV90yq`qZUiQ3^PCt zVj)FzB}bEiJdbDNQV+2FNSDGV+iOt@sL=pqL=B#K^!>qg$;?G8ZIwTQm;XjwCYK}s5Oy9@_(!QcH@N{Qk*zuc&-`ki&+89b}LIvCg_Dbcs0 z9r!|!P$#Q7`~sGuV{Q)r*2t-YSRD-s(Wu%XW?Iq0)VaW$5|Cv*c+N3BqhbZ z7M?K8oU|m0OFOM_W*KD>!`{GBWJDIzg_EYNLb4MXPTj@WzxHPE$ZUe4+CiCtq_t5} zrtiuy0ka|P7Zm2|)$2x((c!qcA2YZt{)))dU?7D<@m&)Xv-sG*wyJ<;bSb&@MkGBK zW4K+g@25l*xy%L9@6TcdAoMUnBYGF8aWAYjmcAGjUN@JylHxD6kB~wv9gP=#JW3kb zVuNBu7j05-T6i7VklFw?Vd+6&MJR~*I4fRZLDI-^`~{X?i*Ax8g1U*w?MV9ZI55n0 zOs!Qe*W>af#o<6SbmaYP7#<;oG}#TUK!k+b*%^vBZV21ixy9uDvCtDS^8RyCAY&jA z-K5rX*CcMDUC9x$77H1LL3TEtAei#9Ok~pLc1^OA{9xq42gxSRk9=)oEO<{|cPtbV z?#j!={}3L}V^w_-Y`g>u@oL_LqJgPB{^va~*Uv&A8W)^r0xE!|?ZV9boO}KeTh`44Z&MHe{2+l6vH0|r z6fz9y;mG%(<=GgKU{YaqgZg-_o>)P5#w;@2W3h~GQtxNsArSfZ$A;r_Od^-i!f+#= zD&Rou!aMn01lBoYYMV( zi|}~CjI<*_E6LYmK=)| z$T1m!Ai|iLL#)z-jaYha41o$yX`&$g%ouF=o>C9pmc^{~!Ggf4;9N|&2VXezuD|0r}9&TRHa6kLr51s$rA#|pTaT*ho9)sG#vh5`;)+LIB6Tj`;uW-Nso zim8toNsU=ZS}^uD)UZH}Bk>w&Y6{e_D5h>EHS|!UXzYy}HC_>x6iu3!8E+x?ybZ|y zI)s-Y++4o@R(R8Z9Q4>tr8M%rE$k~Q#`}ejizX-BdEB`esJ(5r5G-O{ogRE37E+E8 zk{AnpFq-4BfvmL!WG&?rL^dR=Q_97O_Lg#f|N3q?;mZ8yWd=>IJ1?XDOLEJJlat&T zl|h7mi0Ck4v+A&PAqFz28gnd{QD=cw+5xMiG$E;K!~$=rjUaXpDDU^LpX@43=_BiW z$C%p#Sq?PqFaFC96+766H#$y=$~fj0jfg;3HA)HoX(jC0IKOqPH5s8#+80nC+BTQ_pnbMveJQAXd1k_q9>2PCL*K<9xRKud6Hl+J~4WvyXV_-y+sEP zo8SM>k)eX;jicjp2c!U2=U`av0X%q2-$R(Z*M-`WEGlbMxSp3+`-|f@mjQN8r4Ecl zdpW`;)c8>m=SPKA7op=DOoojoOtdFFx%Od4691vBbK_aL-GnmzJCY{^O43}q&r|rq z?zGyk4d01+PQyuJ8&6k_r(WP+vhE+m^y`B(^XedjUvOvw1st)|eH?k)F}`c!2Bp?Q zj;=$}>B!aiX>?5_ClSm}Jqsg8`C!$V-|k@fG*1WUl+YLBGF~9U@>yw~cD|L@RJA*7 ze6`~QzjyJVC_FhWWAz?5K-67W`qL=Lc|BwvK~0x;RyHm|=5d`MvYm#f>g&G7WMgv^ zQyUEpMpZ1^lnf>=y=5%)fe$Z2#83pRJ%|c11R6Xfi7_EO%^W{|$@HZzQF6)LIT^Wu z--^tG$3p)jY?)E6dO1Rl87%b7U~#(e<%~4yy6|G@G-^+W@R!o* zxLdeZO7^H}W|rnA1g}~IZe~$#PjnpTHNc}_js^r>E>j@e5sR4aW#QK|r>}je8~NUa zg_dC(OoW+3(n|SIrUFD>CLd2Rf;q2=?+mI{M7Mb%E2Zl66+Fo(tJl8DtLHCu8)c@% zFxe~# z=sV$^Swe!+XLqDYTLXC&n1g;lW%Pr#t|PAK}!Tau)~>3C|qSw`aDX zLL_Z^D!)+Ur-N7vq9BiUgG#DBA&3(uaZCFJ8F$h_N_#w*pZudA+Nn9Nn!9ycL*MaW zadM?U8DeAdt^VUdHrWdQMag#uzEyxycER#@UK^VDgsWq%x4Y;OX-W=gkn#h z#xwzR>Zv{)aj7eCL^-Egax0FBsQCB3T#lsgwpL4Rio@dZ;PhmR^m*%`0tLTntp+>h z8<6*lW6cqrk2 zDnXAy8y7Tv5{jJ3uHpYVoDW@)j?iNo=@Q*oJU1|jd(?iX%*1C&?Q7=<-08kb4!GBu z%K(+`4!gO{(7rkO-%uB7E&!{(`Z-xwni$k+?h}o$Ay^>ac+r7sxz|(m)}SI`I(L^i zo4XDhljU6ou#mtiPrr5ej>GttM(ApNvSQfSOu^VTBtIHBdd;}$uE6+0OyXAXcgkul zjH(e8v67xvT(DTd1m3uA&`Nc9zfdU79fReh0+bC7BRBny#$3oD0ZFwZmMqlqq4$CU zy=V#k+09B=bD(;1c!w)&xq94PHKfOx7JVUbtV48wl~U-*;Vof;wviDaDFKaF$w_&6mceLT1_xx?Gw zKN#FZ-4lLl^nEapHS{GEEdiSxCEYor9)4N%^|wwKMvv%uD#)m?ADO-sVWFDCe#mXc z0k`*>c*6TnG38~X{t(1cjX7VMs5k`k#kk@Vh6C7E<|iw*JU(4V<<3D3x?k*&k@1eA zgaGghuq6#VwHt$U5epfjJHD~O^nanm;5Xp5>CNZGfq43atznpX^h|th^G$mfF9&9h zh=rRnu8{qY2sGll3<6S9M4k>BF0G)j6aO2^t zH_!(I9l&uqK!JJTqW7qE=%Ru1THp4eDStGOWn%rMHxP~Vml7Z};{)zsb>Zg+1{L&y z>SJK&q6ZVy)$gH>y;W1bIl#>n4a4Xjoz~Z4T4@@GP&l?A&rVtnh&OxF1Y`3*6Y-+& zz2it==!aZRy`+Pu@Db@DF5Hx`qq>Fz1^ZP9;oQSlL`~6iq=ACu5T_ z2T3M~$L#~z@f5KNOp@>2m>=gE7RaR_iWhJ1P|;^gIVCrZ9}+PbaFC<`AD3$vu8B$x zm`*qY^j+8tl-yKMIu<%FbT7JbLf!fvn!kK+EVL;cid!a(a5CNl?ZX%K zJ<(7nsMt^ORT~uC*M>dT0$)0ZN;F@f4Q4K*YAoavvKCF9qO{}rv_omPHrX5s`xXac zPh6pAYMn$=+*ps)`4Bwy!UKy8x)vU88ST$*fz>RL0~rQ=58Z@n=E)I&vfNyvgytzmqX54oV2uZgX zTqVTOD?aRWP7N#;Sl~bnL5`%+Q2C$7LW&-_YYWK2JFQ6^d*)LVD>nC8`0X&cL!&B= z_q@^KHpW7K8CfjnBWL&i7QE}3WneUNo_2&8f3UzFD~cEF?7tQ399hHmXGy2 ztZiJv=fKs?jD>c`Tud%~p&(wlsQ*F`Q52j?Jg<>d%u3&F)@5>mzG0wEg9n+E9elX^ zB-rO3;Bm(aSz|2Vs6i&R(eVIJo=EyP|CRoSV=Pn}V+KEBjN^jU^L^YuMLbJgf`fY8 z7dY4g`Yr8hS2dirOc3Bv2Pqs2)d9?Zy10?o1Q|`EtSQCqr{I+v`G$c{8S=c^v5_b7 zD>veQIXXqT3$a><0=R0B2O~;O_MmCTi(6W{22UktUlLW5;O{sHJN z`Qo9Lh5=FiCwK*65Me9;{MS&Th|lKR!gk9v*Nf5gfjp+dw-Br@q_2Ka>LPjvB<%^4 z1=Q%Ei zJ-?h+m(iz>Tc>cLfF95&190~5pdK3wt&H+OZD&{Jxbi{w{oxf<{^1p>oVXy&;vxV= zB9MS>N7{})!@G_?aD^iU z0uK*{c7ivg?zNGxM8eVfVjDT;Z39Pt@|v~4vB8nXDZq{Jx;k(sK6JnE&q|Y82a~Kr z$hg~DhF=xRty43p5mdl%DHjl1!5wlSY43<~FYk$lyuxN{Vc|YdM{SZ6%op%Kf%y@P zkl=s=yynwKi0#wFm2*WL1(N;i!bxjdl@g|(xl70t5KI=Tn8#b)-T-;8B*nt-)ij{DH(%@d8$j&uV@$z%?7u|?ds$SmUyAM9aalVU z9|`Xp1Yl0{o&4D==w3A_S}%am9}QiLtB}shL`wNl_|ay{&kiSgI;+zI|CH749>)aF zAuw|uY8?xeh2tEIpXe(7Ak40s47vpwhW8AwGbTan4~3?xG^`LFtD50jdNH+|xOpi! zYI@@5@9^cgq&%nUVaFTLCz`P+jxKT2>N6m{z6FjiV@$64BJSABcX}!T9X3ZxJ+Rgc znlS(_3=15hs5hRI)w`mhpGOs3K{qJq7^3RH%=cnKumGG4#zI-6yCb?%t-bs5 z_KQmGIoPDaJJngZN%*)rCvB()+`15v_V)6~V=M)umoQR2)uri&%>zmblT5L2n)+$8 z`EfYSA16*=M9L+SJdvvyZcR6B#`!dFc-+Vl1;Q&aK%mD7xG4XcNb2glv^@3X8c+6< zd#uVctN9aGP}z>|l@7H-)t?2Yb{$VU%-uG}$twt9(BWAf`ep|a-$q2eW2GYuyBoax zrlc-OtuF$5aauR)Xm&_FllkKwLDrv0dGgt6-TCGGsVm5|yt~mc@o{XV&BYGG;|6X4 zCyJ^3fT(peIwjEFLnEy39iMn74f>nSP?fHI=hmH zzJA-d^=d41Y3zG1!*zNnm(EV!84dMDiMbE~e^v(Xe@Omv=eXkmmS{W{5_?GLCW%7M z9s&_jfLCW2ThyMn!Go%z2hV~de&o7H*)<&Iz$7A3$B1@e+7;Q=paOrVB+k@LoI>S> zXy|-T83_2UF(MpVNZ#{QFbynR$=cP`!+pBR(NOl-9GQ9f(`rp0b7nPX0w)wCdF2WK ztbFVU_q8}jrm`6@CmolmQWJPLHyJLd>}~aM`pl9OmR(dq%BXHr02@kIxz<#>dJk9+ z!GrS5Uh7?FvJ9x;uD}tlxPPBDa^?`XCM$3SmwYBOMuR6Ht519YVXu{_&6b?kv~_sT z80=LYUX7b|YuYL};z+*E4KFrQkV>;11Q4PjX_N^vYGTbZ`qyw5uHaM+2!qQVDV_^1 zS#8|mFt>rMGP~32d4JwKpTeX{v@sm;V?;GW+ zZyk0Xo(aaaw}K2c8hSd+6Dywf_hJV}bFYhR+qyOa8UcxQ|388Hqd4B{3~>5&|3f5Q zzBF11QyC2z#@wKCymigu}ljUFmYkDdw|DIBJw#xONx z9Y{)g+0rnOz4*_OP;hei+3TuE$`2rsOJ*IES$A1A=d%YX3I}7ixTU1lT~^DGww0Q< zt}4~wjfB7}8IJUb^7`xEssXC%&3J8wK|xon%q@+$--PPd-RrBU3d;btAk*tvIiAlg z@w47W48c3Cit~vcIQcO$skv+7(eRcaDzpZUTB+WrtZ3*5_g2GwgEWPWFM+1v-+rjM z^ea#kSfpp&Z3b+bqq{j_Ilrq z$k0hz6|jTXEdvZp-#9RIFjmR~F!!CO7Obzb0VuC$bw;Rf-nDM#j&Lh_8~k^9x?xt< z52_g^tO}U{n8~)!EHFDiL#9R%7THBs8J&!;tY>_JQu4yU3Rp^Ql#W1c9l%zAIQW8< z3Dd&~Kh4+lGcQ<6&J!TlRjnXv90ZIoyS1Up@rk(91xO-XxPXHRoa3a`G1{INR|difQb~yYi8#rW8e&EPtolpBgcI$liG=UX9a5{pmVs)73m8AC^E=2{7)JRAz)_7n z?}O)AVFan2keU(3rpoJkAXNnGr5pveYYa&(5ay354}h&~B%%G1ywWRpmBtrq4}pJ# z>ymuiZfyrG?TC;Dl+-UXFH+Kb;PgXo9fiigsvUjKZpmsIRO2mHpmX%j%FHuZ`UsdD z0%{u<38}-X8^F>4>|y{`?QgXcU^81DlNd`R!L#K+O^Rlwm_n(;!Xn zvMSo!D|Kgd2NW;BEvJzlxvEt0TQWZI-Ee*)Gx~TBcyfFW$xL;OtZn!w@Exu+TO;@_ ztc$_}`;>KOWj&1Tg|SHJm7l&ZYLpW-P5S_pLV>cpRa^KQ|wb zgu*Hi>9D53_NT~D2+uuUy~l@4WQoY@){j6tI#!;-2CN zt8WAS!nRCsErq;HP?8NpTnzDNuxobtX>=CiJ_yEFRfz1Qk030AHhzfJ_d#U_0){}g zVKp=)`u19gLI1H>!L@OdI6%9EOY(!ASxbo!hb2kw_b3JsO{|!jz){a$Yq~$Zt`|1A z4e+GbO^%2Cp5wAwZ{)Vau-+G9EAm~GeV=>3taMLq{g+69CVH& z!9Dv%wbfJF?Az<N|)$loe!IkD^8lip+GDh zxGH6!Q>8kaE~)4YFwS?N`nojtIgw(+Vy&H#T+He=O0rPtw$*JblvW>kGQ!hZ_bIW` z-tRr%X4t+RXg%Cbi5?frV6)(U46b{*n}cE|xOir7rKF!n9u!h;PXn;t z45lF@HG>mMlAV<&T2_e(KVj-O-=OKP;pKRm5uI_dxPQf}d6hDXM_RlR??^pGe z6*L24uLs1Al>%?S<)MO+z|5K-M8=4uePO_%&3moczMAWwHLkRk)MxunTumV_tSmw%zrnHOHB4 z2PZa^>s;tKafbNhA)r$n4SA&t_>Qavjz5W{8$BGT+EJ8uNv_yM6b53HsL~2$N*fCF ziJ5uYntzJgnwKE#5huZuA5zbQ6T#OoBV?AyY&{C05`qPS7s6-;2u1%refqAtp$RA) z>JV!0oV@VG2<}I0nqz+(+|t-I$!_qkX{#PuhT*VDCNq-Z%j8n)$sx<~nUx>gR%e5u z7@Hm8(CVo0`kipu5#FIo7+)PV#9I4r+fs(zkI(_Kp5f5!KMOzHnX4ex7$Ifl&ZmQfFlZfr*D?5I!TJ zPe%&i|0B5JW^F`50bj*x>a?|ykT8N+O|5|=rEkD3v~)1GTH<}sM@oD4LjNyASPp@y zLN3e4_aimD&MbAEfvU(vUibl|EOnI)>72gh4!DtZE4?p!+mYo?YOq@IqE*%RYpd38 z0cB4N?hssdruC=F_|w(_9e!f%kKm4Vg0d9N3Y0DRvZaXYYyoHJv1LcytOD%OL?;Wb zc`b$D`*tg)W)>{D(~j0TnZZijYPI&QbM7)vsYknwys0i9Mlu6NV&sW)b|h3eLVzS7 z+9Y=zK%&osPIYI+TMKggzHI4ip$^dpW1$&D? z2bWp%usPLkaDJ*(p3~cNTBdoB*#NHJ6Jx}FtgAQjF5rP>f3OM-`!)8g78<6JDnBx4 zOa89c2y64D4C+0T5!B(cWB(SH!Ar^75J2=@N@FCnTh6c(Jjie;;Ay8k5xfPeuTy|p z4~^Ch(GYKdOCYBKkkhgrLONi~IF9I9UF~UE?V2^mI2!uBJO`RT1s5C%8d-<30Tpz! z#@!iC{u%kmXvvGO@#Kbxxn5&DE30RLoe%1%XJKihOrAAHVzD33Sr^a2kfXklvnrmG zrJ~Le5~J@SE!G?1&|z*=s3jE`J@~2q5YX5O0Ccdg5#R=VR?o5xqj0Q zf!ki@oIN{2~4lJvgW%6EGz9Y`5ADj6YV_P*PP`WjApd z4i(^PMN|osPs9O2SqL2_cPQI{F8>_p@m7d|lK>md`%gW0Dp^jd73 zx-#5U|65B-c}hAQJ5Wo(Wi18R_uy!Wy#Y@Pq8Qu?C@C1Fq)-efZIuQ1WhR2It~VV8 zM+UoXUtOs~uo3XtYlOMg(~R#$I74kiYU;Smlp3rS>GsxC z7yCjT7IxQY4}m3@*BqjPI=E)=n^-H?=h2(M1_6efGx9#Uq!gTpr1I7>b8{P6<$Yil zAwC7At%Rd$c9RjUQQ@<{vK!q0(O6+=z5HaHkKPOOODWa8Xvzu06ZWP-3WSB94`S@f z=>56<@!G7m$Lmsy3w)_8>qhL9HjvTJ=s*%zw;~pq(JjCOO!+Ht;1Aog+Ah1teR6N{ zFs6-g5O0y2+gOPPAjr7Vq;%RMIa{BTvrAK1M$jIjg~VVkO$nMqSh%B3b?BZNGStLi z4h@6N#*~y3QGxU2J~_wO+=hz4gTqab^3FP~F!Sy#S8nOPkzC{Y;)FgjMixrQ`F;S> zz@h`N)*-dx9XYR*ygbJO&YEtx$ir3+snzeuQ{uT91GE}R>2Oa5sV95Xrg;E#uAJ{_ z7*?Ye)p~2gq>vqx!n`GNdvtf zNrz&e04h?Zyc$r0gVPKP+l|lijQw-xjw-)$5)bsvD8|HG56TQ{ZB3$9L3px5D<;5a$92wodC z$apJ!XrTb&=@8zB{1S*|hzb68LVdCy$j2C#*AUNwW_P|jk@${+TCv^N+_oOv%P`&H z{p1@Ku&KlQw{Kvs5(3}Mlqr`Mmz!lOc@T;iC@KWzXFdI#Jh@cUp+1-PNA{H zg4dMVR|C!(gbOAhv{!%GOBU_c;piWF058Z|v+fj_?5x;6nFY+N^N=|h-%a0t^8v^- z>$P8stP3!^16&LU@>Fw+xvSsAC+>OV3&WKD83I`jGS!6HgRQq^{D#S{x{Ka3SEy?8 z0gBrO6!ax|)^1&(8<2D#+{(ws9iV#G#Ehox0KyN^oPH!d6YYdes-V@q+w2I)pdv2M zFC_x~>P>rDxK#Zw?AG7COX_G zGuoY2EBuduy@Zqs#-?-^NdQN+S>@l@wo0`W_zWA}o1 zT;5HU82x)?G!an10xGkOakA(NP$e0Gnz|(dUN?b7d4_(V?$u9=IPW)N6z(~mg{j90 z{UR=r0@>h6JWq%8{1|#0EtZosXB1SQFtj{(~W`Aoil<>Y|T7p zG?W;fUaK%hL$jk$r?|}DEi|p0>`Fh!g1nKzPpSo$+lHkl-b2M-!qpezDyxOIi8Z%C z+v{V7+Fr4^?V>8-+@yGY?Tz}Ej^n%zk+AE?M|K$5k*#pr5Og5o^btS}A{7uGm`Di6 z;kg^aF$i~1Xi{8sAk6W5kn#MDV`|^a!o=nWT;b50V+EWUY&7td0C^*ijI4v*z?8F1 z6+O!zg?E55ED2=q(a^4#)AI&@nLlJ@`o?YcqoISo0=V{bWN~p@PE}Bp!D7<;9`RQI z$9ZDa56Tv3=e>1r9rsPV}f@J&+4F(6}eNI;;#$g{$1ybli)e(WNk% zo+%@F11bj3`ASqz{~nO*lBfcMFMEZuM~ z1PoXOG^c-8+gFm;Y*W`?URmz34(T`l)~f8&zYjJGxIZBL&-x_O=dXeKPolcX1rGxE z8}c~ZugZ$}8f_QeSzqibVOQGVD%na@oDSWO`{<4TBOmF(*+qeUX8=ApG3lbNW|?f( zujJyhliU9~P$s`YAClvoZF} z48zJ#dAjy!BzP4s5Y{;p7L%6{rHEj;*Q`7cvvjNM!UOkaSAPTzRR#L4^gdl3#?&Cv z+kUaxQ<6vjVtmv#Pa}-n2Ckep0oVU@jczUUN&3|Zf4g@oP86=)%PPPD^ovd*=e~Ou zy1KILS=-YFkaD^o<>hmr4XUE|5bq^@%n9x`aKOcsuolcAdT<+6!ZzFVwRrZYE3L9_ zp>X29QkN6>q-Oym$twt6D51$0z?72@@|1Gr^2BAaP$776q5>}Py%$Zhk-PA1&q}$-S4M0b*T*kLN2{(+ZdOenT$kQg0zRqA$CK=fHXw5W*Cj&&Ky~9)Y{AgDr)Wk##7*_yfxWRCNHZlka1=u z@Xh7D>ptZ(e_DIYHZ}o5_uS~ijLf^y98dHS`b{3=4Guszb@`vfG&cFLq>9QSy1XP;;yZPZQXW+IG4mikHZpKq-}2P3^eo< zsC87*2BikRp`moc?;(`OPwC{8{WuRzSzrejlQa;D2s^li62_N~7&={1yvv1V+~X(L z0%M^a(Jipb%L2d|cNT+Y9xQNa0@%staWznSHD0Xapxn@_& z`9?Zl^MD)e_HMJ72Ncv+iy10t)@l3E6r6X2+b^QLmMOmxaYq_>pu|FJqx)pFk=))~ z34S7g1JA?iYl(Zt1no8P=6)fwMO-xY9hn3!WDlD0fpF*%Fzr;Sb<@z$pJ2`uQhK^e zWk^rY=z?E{0ih{(+RNn$dX;CM1&(S(RkF(YJ2?Sa<+V@ZskowHz^ze*HIWtagHJMHO?dHuR%M0s z3YmX$@qk8U6((=YcWw1(rzQ1Su0Ki*SkA!NLJyvzvk%f$6ntFaU!ViD$tz1ROT#-& z12iT#3X_8Rq!iElL3Q$5WIx`x@PP6whf*@|+olbxj%pt;^XvdcujAq4JnKH^2fW*G z0Iq44mfJu{U#gvLf)BprF`wPIn2C%zH`f4-hy-VEt^n~@NrLrC1Bd9n@s+C>(-!E- zKKRm-A5g`WOJqmBCIrz`)ljJO7ElECKm(^A5xBZR+hdTU3?3t)CvL=7!S*^{@7h~Z--bYG+{-fA7hGvN8|2+;|RgjPem58^u@-U;yv7gU%4iKUUs>+e8Z2i-pp zF$eiNh^>*DAqB*@K+HfqAM&#xo&)s_5SM}Rh!}lFLcf6=5*I=ZHN^Q)(lC5t*+^(d zWIWD}*TqoQ3Ux`G7IBg08IWv&ED~$tl`$i-3*(H-;y zz3YQe0T;gh8B4Nf^Yuf^%1;sNo?@-%>=i1ntkgyBJngc+TB$kHZhgBFodL(Lx(;ue zo2mOiu2@*nLxa1u8|0n;fj~NScBO!S%mR=93RT&Ag)NfW{CCveQKRMCt@VC})i`Je z+a0lG^1mYs6)h@QOI(>pLp@>0TeE)ye9Yl~t*0M8gmLx?qhAh| zoc?(27phyJHq-l1hJ6shXCEloweXduidaCT;no#ia76qJXouGEj>r@pIzPR31)5$n z5?U6Eg)T%(;%b{t(ez8IFvCw5Ci-#VzQ9Kdj)L}I+qb_hzqZ$~&aHL7<_56D@%)kV zh@DW!ZccM-7n|Geb6*uUIVZW&YE57Oq1m5_xLgg=(b!cKWXdSaHsPFxIPOk zIY?*(8J>i-`5G{c2*+n3_Cp|u;@FSWDUN`PR%Eh)XFYN!pima>}wr1&4CCLc~C1Aqf<@fTOr z_ba$Bu4vlR;o@5s`C=WF`8Rkh0M1W+e+}GMgY$54EcAl#>LY0`4ctppp+^4XRV^m= zt42rl(CsUf@X?9->z`RyI)3XgIO?t+G#eb?9%W?uLFI3;48>+D!H@V$pDh=>k-PA` zkG-+NG`~8}Z3ZWmdpNHJo$#XR$9!(+djgoHNQ@UY46LA}fCyhyL5P6rYWS^-ThOB9 zc7W9b#Q0?j(A>nG5w$4>bLs8Cz6`oCv3_btF@3NB!P+2e(Vfpu!GnhDa3BFHG{ULZFxkPfl= z33^Tz&Ijdr=M%O8eYzer=cBb?2mRmha`@jC!O~74xH;?2!g%hnc5J#yAJ5H&+&m%YXPK@EaB^-3JbMJbHQEO8#~*!k%b|k@Z*dP` zquN|KWWux;6?ges2W+$j?FBO(@k=82S)~T&(rrg*p&T62cXLUv^vDZ$Q7@>9i(rk@ zBsF|=s1f}fy@{@)wIzR^&1ZoF}i-we)lw*WYg%6}5)K{*Yt9S}iB=q_yl4aBlvX7)K} zK;2UwxK6bTbKQVMvCt~vxyQ0t0a_Q;Q1i};`9HN}%wmaY#qqk%DD92n$-g1Fy6idyiYu+ z_jh3H9{x7;DFOmcF|xgmeu!#dd5hg$KRZ{-Rw z-)v8t^tI1BaT-;`h&3!76?2QK!)AC_me?OXi!8IsTGehwx|TPV(6gL_xq1mE_YST@$al|iHnHKk!GIg|$j{0GN8TZr4TY6>EfETv<9 zRVetW^tf|=f(Hd30qqBoVP+Z3Jl04}&J@?~&Su;vx#m#t(6~xuS%t(*Ea@ClXf_OS zie>gWHPz+YpgNa$0s9}XH6_5*OmRez7N8Vj*>*|_3v=}ir<9`xrb= z#PiCMI5{;{y+m2Y%c+`cfcWabiq}rffqprE&ULOR6#SPSItOSzfx%{ssDrdUu}3Z5xAWzlaXIR?boa&W zSnByTesGKh%|TQ?TU8s~s>cT~V>(*z&44icKSE~id;YUvpgj!L=6y2XOGsc^-&OhA zpx)(7lLgy8nHw~X$Bb%j3c@~F=%t%(Vi~tsu)xxfzYZ0dLU|#$pPx-(u&sec5Ad)W zWK|o(V1lLwQ^BN64s|gGOzAX}&1a*P}w|;tss}@5y7ZZqkd#!fm+uk&JGO zQ)`*;b8$JV0=#vi-{KT38b3BABi<@5TO!n0li4w zMVL)Aw~k>z(LAGxPV+1lYFD*5Th<}WAeX_GS+c*A7`0KqPcnKi?0TXkoW!SIieO1I(Sqr4ach74}QpxQD7 zDDE>EYD;8a@2HB!)&ik26k`trG#25w$`1zr?YmohM@uq}^=KCB77LKdeI3wRe2Dqm zrH~5?K4BRQby%x#1{ocX9GR(6H%P36{>T&R#Fe^f=7M z)G7}hAgW$>cvhymJq`+oUH6^fDcKBIp%xs|Phvm2HOS?-#cuJJ;=Ttuz?9!3t5}Du zVXi%L4C``!<5Xpo-xRXUgsCe;k3{f%xXU z9bh9D5C7Hui%K;rnlGo=NIsTgBTnl8k3F$CPFAL>vG6EYsA1kXTXG1ptU)U6p-^6; z%Lnj?BcWhJxUjd~&sFBj3E_eg!UcVfg5qRFDp`shEvCX0D^89?X(LDY$anlChK%(e#08gLOVo>L#Ias?GO98{Qa)-pr11~cwgz( zEcy@_EYpcBtCq|p%IoJA|BBLNn(T^u=QQpv&AzsFYB{y4A7`0DYC0S-5yPp7V71J|gbYye`QPE4glxC#&t>O+|3yAJ-aPBIuY9jvia z4%)`qf^=-#v>(3*p3WDGYeYG?i(s8HY5O*Xw{PBs-TU1M=rUAI1+PyOC<1 zQv$e|G&IIBJ5uoiGl-dN?Vm6R6$TJDr+M@;H^y%H@JjLbQV~7$AGhfKScU1Z-kWHhMMVDPXs!#E)(8i!$4HRwqW;uAWn_MnK4tBw`rm&bk!+N^p+t(O{`S+N7;?U3V(_dpfUgI&ub3k+FnqetR| z<(SQ}eDO_?pf{rrUzOw0PVswjc2YfBp5~wDEhUCqmB(AM8r>3e3~bjmg+4<{*u zgu|U)RJZEg%qW%q*wwe3`bM0#-|IuqB!GKtOjal5rgTPd5WWbYWWxcO4X#a1vuktdIVbajpZB|B z+At%fd5*Py8r?oe5mN!Ri7jG}J1}>tL0v8PRDp7h*=Zm;-@D zO^dv$gWy5ca{0QYufs?Plhxn}&~&A#7H&28Y3j|kCI)jwedj@JML2nrt=cW=-JQ$h ze-MhKq0&IRH}2%&%+l?hEs48f&KNmh#p1|$Lcu?V%|qp&aZ+mEbwBrG>H4m8U}8no z7x8(Ml31U~eJDL&zu5RrjR|IhWCbeZehu6r0lW4VnQ)yF*mb<%+9Bz5eYXC6bgA}z zfXN?)hJb^^Y7{R8>vQs*6IR@GYoN;am>dN~MDo>7j0J2bH0b(Gu;COa#bv-Z z5iFCXhZ+od%kKg;Hg}lN{F&eos)X;%>T4@H4v;xLnZA(~>qPJ;(whwy^#)l8>sbO! zNAfomMB8LO4;H|<*Z_-6ifzoQNQF_q>WXTC%765q*GENt&S5W|2=0es2X_g}BS2e7 zQ&I)4+-qAx!KTy9SbRGnHWb`>8uC_PI&mTyu@6hG#uQhQOdn;1sPbSa0=c3sWQZ3n zM)?SSV6H5r2?JkZ?tWQScuG+)<^zoB_rBu{amjkP*Jr;&1KA?Lc2=i&%{5Oz)>?S# zPOu8~3i{18^qU4k4c37{p=Lb*ay%7KU(4?yl%oY$(WdP-&9K^>wMy(A{ba4{-nqG) zm~a^Y+@g9wy)v;xDU~$o6S)F5%u4R~ONL)r0}glYm>(BvS$V2!W7AoIAB&cj?O8g% zx^B};_vCF_1otO3)pbulTfJ@Liwl3svbHYD+A6L8O{V72P0ws%)@L_vu71%fefFED zq#x{ECVjL|-}UExS-fiz!zq;ms{jspC-IvK=M$OoUHrU61L#ZwQ|}LO2^AHrW2QBGUXij?N4uf z#_&k>*5_wSfJ@e_99**2jQE~Q7@G((0#l`Uc_zH#h0QNiZ+hlFW`1GY#*G%XW;Ih1 zQPPstEIsV;u4T$w4>M&oh$8d|mxujb=H@ugaAhk~ZhMg_e*xMK+5y@H+63AHlCJIT zl$!U>m!eyAQpeuZu={U&(tM}-8tOVJvA!GlkRBnVuXq(HJx~$uM#WY3>5B^-s~lNuRZ~^-^p;u&qY&~3Clxx17gad2_~KDlal@!&fGdqDbXAoKP5bEX#9{d~i)N7ir2WVz`;dQ=*1q%AuWawQ~7DvjDibPu-Y zIXV_1r;kC{LZ?(-6m2?@NjZ6m%DOIKvLi8Fwp=RK(u$jWRopHPhZxNZA*CFRBJ0nW zGXCgdw_M6_e<>les^{dTcgxbJ{TV5ua)}*MD&JSpqK38&rO?MLwjm|`8ML}J`o~K( zJqwxq)8sj%@BLof!pYK4JI_l^ClS2m8)%uN8I+3}`ClwmLkh*4mTPQQNn=5yC#~Mg zuC@ySO5O%oY4vHVv#OQ+s}{Q9&=0SUoC(9_TEe){td@7esUvIYsvpK!cBT@P9pECXM#h-=MVTCY#ts(Q+Fgl(bOxlIhaIAX#Lf zIw6h8E5ahi%h!>|a&1djYkRfbFhg4>W+)Nc`dW&QAuaWpe>`X9^`^gy`@(4UFnkjR6PCy5bX8Lub$eHECEX8hxF1PUS zUvlZTO6@SEqcO+rrCcH$j=vRzdwMZRLoWrj-COV6EAa@4xiMrUr3|k3d#weF*PlSB zuKVFT<;~^X<4}*q)+oc}^pG+Vvtn{RSJ#`8E&Nq(%*Uce!t9&Uuk;ym#pyStRr*Xh zeOk{U@neBjl;F5frZ7$ZmrvV^40YWyZtIVLUO^-cSaEVf#fo4d+PvrwuRj&;{@wmKXtjo zO7iC}-wU}c0C=n^Y(hZv+ashuE%cWNr;Zyp0%o;3nEBr?Pf1dOZnbe^DM!YCXH%cU zn52pcl3czz5mv;F8wkV-dNj0P^t{GsHwAhA4h z8d_ksoTHkNsEX*heqh{PtI5(e3uWF zBe3<|kn|Yoo!yzunN3JsIIeBZfZR5o2G6~k;JI|@-VsH`m`z=DJ?s(9o=-aG_WY`V z=ghT_NGU)smE*M>ol5K)UmQ@K8$4Eo3}0mad!OQbTf_ z0wc^GS5;7fRDB}s9~<;0!k>@zN^&g?ccuWW)KQ>wgPo0m<-6{5zrd%Ged7QE}WzoBr6ox0QR6qfHkhzz37#+B_+;KU$`$sgm57I$M zPeIxXN#NBL_;ulNb&*qhPFvTIK@V@G>5#)lUtVofJ1~pHBErZ;t%E?HYG+DeTLg-C z)#{*2St&)Rzg7y$lO-2>DVSbL2N*kf_QznGm@r=e$|{DTw1a4{t{ZABw3B(^75m{lh*tU(*=5R+Txnm^a|)=P}(YZ%n^Z!}l{11ljREmERy(BKLN>0c>C z%FU2;-7a<=hhJr2GMx$G4UG}sB?L6H=T;}OdJtQ|n;d$MkR*9X*)6x{^CSWH-!j4d zUpLS|>{Fx)7@!o=_XmV)Q)e)gsE~x;q?&U%X);SY2oAzQ3_TzbNy=_4eku4;3zu1^ zWJq`(CE*3g6bZn*8qM8l_P&egx?R?kz=x~10ExPQOQplUvl*~&?tKL&_1)D5E)>Ky zMdfrzNeAH?=3?ph@Ve+}VOE+E$Ap{G{)7WUD6PyHZrj4kxjre&mC7kY#VJi3-h)I> zoS8CZ02Q~1E*0$9YTWgdHLnj|>tUDiA=rfar3U@7^(v2r+r98d@55JXEF3oMS+{#( z6YyGpT+h)*LCARYxKye?E=|>Hy(!+!R)fD^s?g#Z<*MV6a&4y5`nqkf6e zXO0d!WqwtuB9JLs(sO*NdYJ^n&v+-8S{eytj=G#VK9znnh$@Z;ygVvz@Xz40LbK4+n}qhLAOL5Rfe(<$hvV- zgGzl@etTr2NHY%v$u;Q$8!Rx~?uB>3F1Carzba;Z5X8CqE&MI(WFf860{BP)jOGqh zb>dl*#e{siA6JF!fISQ?k-5@dc2R-flbNoDu&UVOQ_vqK*S1562 z6n7yL^`(9t60ZmeZQ=Bn#uZbp9YB?KKVq3sD+R*LN>o`FV1~C)x?1?9nNUv3Ki4*K zn^q(7gkaAw+~ON2bMxZ(*Spw9GQIiU{ni}cCccR)@X;W=6xxvZ#(1Hpj3dlze}cgM z;&>f!bZHB&WlX*RVmFHEicPCS!TWfb$jD9wH?2daA%CIczSTkDQ zLOH4>@O*`!%bY(WJpNfwRTc^8#Nu??pK2hx|BvG;gBU!_XG=K0UqPQvEmH;Z6sj+* z9J%|`xUe--kIxA&WKP5B!snUU_hGdMF` zeRQ?mWN7!^7zha*CH@oC8#CmmBo@Gf!Rp&a2kybJb?xmzKIv()D>6X-iSU~Eq0V_8 zG9_8)P-zE|Uyyjm+e9d2I0hOli??5Gkcrx_-oH_ppEW<#?fUcO%}#9qRU&bRuq~@l z+tIskp*ED8?)Rh8^Zsy9cr&Y<`gc$m%zD+iGdL6I#N;@{Z*W}ThaJx(r6?CjQ4EI+ znXqqu6Cx;T(HEZ8FBq~5@q@yG?EGcruxU^9fW%eD zJAfGn$I|T#cQaqe?Y3t6rvP~%@ues#Rh&(P8)JxPN-z6&m0t2&taUw@z0+aZOb;S` z-gaD*x0!4U!pqrHQa^$RWM_N7SHi1K5&E(X_(|b%_H63t^Fmcl1#T5q=9J-j;o+R+ zPMXW@%;EAlTwCp#UM2;!9Nmd)rkkSvj)hV;4fB)NIlWxzpVm^^oCN|xM|=aUzk0vP zQDQIU3wXM7x@mp@O`XlP_87U1u%onaz(>|;1!;7+7IXk>%hP{-V(LB$A#dYJgcAhJAP%M6>wgZa~ zM$TPC7>oDB7`CdFb+9}(HJ;P+Ah3#mh?Rpn$nrABD^5LZzF)--^HZ7z_*~wgNeN4^_m10uZ>{w zN`w+0iZE3 z{!+T*8R6;tJdA{%{Q0&nuWlG>$=nJ8m^G<00b@+<`mRACu(&qSwt-QMSk#5?o2N#r`%L1QIqMVT(WaWuU|VM zOVsruR=-vTe4>3T7Vnqdj2ICr6=9YAl;m;4LDDDTb7a*A5_DnIPxxyh{Aq%jB8Rov zC9SnGNwG>R{9MphTM>mGId&};L(;?;NdI-Pm>*8|cMjf7lk71O{t$YQK@ZmpcNb2= zX~MR`BKUo&a5g?AoG&cIUBY;wDdWCKDaRyvjh_3KN8*jboGEjhCnL<1xdWxZBeJ6a zhe*pc1KT{yxH+(8U~z*4JtyyWKs(*p8$G1u#}UI|4Yw3pAn|z^`=_&qHy~5UU!ANO zPy7&UhLXBV)q zT}H8;QrWI}53O$IzTQIXnNR~Y_1@d>MdCStdaG2h8;g^rL^uliSavfOcSaeb@%}`Z ziZ@-AAn{CWem$t;)0$TzodX%wJOGa9;l54Y;r4W90E>I2k0j(=vNyOyG9opPYv@qo z+V}aiA)0QKSo9rCFj;GZkjPpiYp&W(aD>XTd^@=PoQqq+O@c}KO`I!ee5-<^X2^%P zVj^6$C0;^uf)76$R-~Mi(C#JBZcUtlNo(Tb;Un>5pqwffv^F@I`Li3|YMc^4`eupI z^h-+f0RJn;gcOX5!8DV7y#zaNsoxJPD&8;6Fk`d4;c4sSQ+USPRxz+ql%rtKE-`JO z2Nx+h{1_Ii;tz57Nj;|uVO2c*K>WIf&w*xdMt$(BMt*oPC-8=(!AW)1;)KLJVOU?A zJui;U2dzH`uwDvcSSnadiGmG42ypqZ#FrX$lNQDF@P>SRVmaj)KyVO`2oD$<@!f*Y zkZoNV8A&dXP%xiQe6>{pETvn{t<@v3E5UHPVTqT4q?d;hrJxBhAw7B%7_AIM z0xUA)LXNSm(W z27N{N*f?EAru+wC+&J6hgYgsL2NGob3vu9BuuuQOh^6jqZn9ktT(*!;gbRdQ*_rb* z08**fz^}j4IE1O6gGT;Gf)wTlz&%0S?CxwkY5imD&O6B}o)-JY##r#)V&Kh}gaDh1 zzZHgAcI6i_tUsURTy-F6{g)Ra{Zs4i^%x)6VU-8yP!2Ztz|4!K5;Lghig{4v#EPpt zix|1UXz;t0J@E9^$yR{~`jxP*xWswQJFme6Jr9XkwQ#WkxCCHO()ZvQ`igJ>l*}2V zhdLr3hFWC=)^8I_dYI64$@2L`T@SRW`QTy(!3pfGKZ3z%V@!k@B2Q?Otv*YX_T)f6 zNc>wOr-!urO>_hd4TrK4qe-PFl}qVlxQM3##FLeRp~O(wA~`%JUe8^)Z3EBVj@UzM zK{OppZc$So7j7+?@9a$Idu*^J-wSrCe!q#gIX3WH97z-F)^NDd(+U*CM@uo8X*gv9Wod*m=3^E<=NJ;ZK_Xk= z-vr}$`G*{rg#4+~CWV0H@&TFB*wx;qCc;OB8>bqa%g1hwx+OQ+Ql~5Z_$*952*^ax zge53H7i66>)0F@N+ZDhF8ztEyf0>HL*@PF1Z4V!1fLFX21BE(;<^knOEWoyArUX#k zXj*_b+Oi!+2=2T!x+R)DitbnWi8dP#@0uUOU9^MhYTqg&4E|Ai9}?e<6PEOo|LdLg zoOKl4^Ys=aZi#;(H5~2c?L#uzZEMNHbGc2tP&2J+vNJxx%M)QXPDI$!C`cwqxOZAP zo-8~w&4dpMpH9oiTZQ1X>AHUcS4N^bX~3eBYo$RbD=kS~KgMuo4^gM$;Rl74rA0S3 zyj^TggtxqnSh5#Wp#J0l#l1Cd1aVMqzJuFcVN0>i5>}V9 z&Z8duaw5!(6ULhepB$_7P#kFJ3rvpXps&dvNQA!_BfF)UOYRR_YWYKJ$%b0%M}{*J zW1i9kTI}G-ob%FyC+mkV-2Fo=4TJTrg%TMF)LA9wST4K80yDJ(W=al*<<^J=Mgpyb z-7BqfY7ea~D$DFAv%O~A?SU!>s{E_}I%ySv&<-G+49c%k?03M?ix@)pe(G3}*pZxIijim*rs}JZz;wWhjB6>w1g%%Ro(95d89an)ARGd6)g;3F_YZ$_0KpoROiy=2+^f_va{zyIG{ZmJM4 zl{mMa_@xc8uxPl++&+$oD>eQd$57ey0T}D5uw&zi@cu@$sQK59H2yv4m0>M$B%(hP6p)hdF(aE#A-|W*ft~I#J-u<%JOzk35TYF zKWpxOP*8N9E*_cCxsF}})If~o^F90d&Ah5%zr)6Jj+6Ypg~PDPB%fah0uSKVNju&T z>A~+v6sZ}o3ld}D`7ux@dJ$4~Yg*FvI$qs8Ve>>boul!JZ**&3xV@v{z0lBP2qw zpSeiRrE{kxd?eO*95Fzp(Rd(7=3Ua9urw%j^^` zRxVPvj>Ob5X(Sqi*Q=(}NR$ibt7;YR#K`VfB;-zKC;##USU5Jwxl}HTV?CRl!m{c2R8F?% z@NJ_{Z#sDS>5dOBrlIzBLbjkt_$(W8xr1O<8{D967`(mJh{WFuKToe@2-<}y<|;3*O;q{)CMB(9KN z&6S0+X{H2EB?jEp{GpIiVHClXk&hcbxQMe^NxAA-URk%;#ey`cEn+2V)u6*DF{^Tm zYQYovHD7DfbIV;qM|A}Q%EP#DuzD8m75-Ii$aw@dI1Ok9@$e0>8R7w~9|?|!N5%zh zO%C3EtgNOCUtlbcDP_HDSj3~v3dUbH&IM`$6&onf*j9pb1L9o&GD!FP;(-f+7hHs;{b=TXK|%*l0OLpEA09dpDoI!Q=@3>gg>8f7(H<~~?Z-2-xt|6F2_K|Gl$x~p z+21B2rOLo@?{Yn%1?fxrPlQbAR(}@c`gDu`M2Jnd`Ckp0=>czw>AL=0u$yQ4a7+I`JAk&$wcKP8 zdtBL^&wiuCB-<%{`#I8amam=zxv_c)Aofz!#cddD7O9kG2xT}OY!;O%r{Gtc@{eH8 zW#sJcI}!SAdL@i{Z@RM_vi0f3fwEE8x}xazNb{(E-P^$vq4IQXfOHJohvQ%PF52Vim(@qH`=6uu`?mOD};;@q5>&xSi@%<2@-9E%l zYM9cX8dj!!(&$VHG&UUNi22eYZrMDuVJ^3li+o4A$ODr&%zV`kethi^0Jb(gWmMlz z1HRTl+ik96m-QRh2POaue^0SQ%Ljv4CMttBUVcvqQLLz?Q_hmQX6u?^D+MhwA);V; zm-nnpahin_Z9^CCA+YZzGrjQ< zKh$ni`*OKlF2&pI{Un>*dnicoQSiU;aU!%Ly-bwTUEXD|5;jt|Mjsk`JCu^Xyg#LU zY5)1}DW`aI^%D5gFIi$GgK2px#3(2~F=l=hB*R6n4u?UuRdJ`hO5Yx@2pjU_pm9F} zNo6b(C&K_|Wb!0RX@XIVZB_mWY_14)Nl1S~xhjD6sbNvu_&lE3gFzKags+S{l|dWK zQokHSbcV~OH4X%G0e#qS8$D@j8)fe43ldr=G3;A7!40UH`xgH6oznQX;Je%mFbnPH zn&6iU=8d}AZ~#}ML8|&=Z(Fc_L{8@o(di3DTaH}1N|ZEk5*j$k(%g@|9_#3U$NHMx zho=4}kIb0SZ@x;oq^pbop7|d4Nn`1kFAt~C?>2q}R9o0UWYehu)K%E<(sv(m=V4HE zYnE??q0_+f)J);CxyAGF%;DfK9jQWzxt|BgLLfv$$U)B;d7Y#w*uC)M|11<`C{cI! zccom4FmGP{YW*=Z6@tkmY|s~i^%e37=LImPqz4Cqndr6+B}u_yu4D#lgK2x0LU9^{ z1sRD-Y1WWlUh0!`mHZDuIrmeLs2AF9Yy^&PC^e6V4+`h!d#i0t-Inz2Lm(wsF{)13| z%`^&hDE^uPRplb2Otb<`EE4{BO`h{ExO@Z>8K35;2EmHJcT2;Xjs$5i?q_u3T2vMd zX!AN2QXD|ou*0h3a3Cj7+gkwUepGQK0CpNgL@ZUSk+=4!7O57i+s;cBu5OUKG0TDg zCvFBK(Y&{;m-}pumrm_l7z!Q-0i*a;q*lU@l6bR=Ulpdz&vTj~s%`=oS)39?FK{5j z-c0tnvG73ecsTI3)V&3C_MO%=jy?4$N|=oO7JfTIV5CuSyyt~Zmp&1GF0xQ6K^;AZ zI`RAiR@qtNH*-gbIYu>jBiu=ZH%G)Ep4n{;_TAxlu>*u1Fh6Ibm@`Op#p{;X{-1bwZg0obBdDG4zscO7y%ve)$mEbV{Yrq;!1P4E1;c{Wc1|ii z=;pGyLJo9a@&4FmZai!Ro$=a%r5xF}j{8(01%6VZ%pYraT6c0OUp8^L8vOQ;K_mKX z6Ers@N(avZBPQW!pk$p?i3(Af2@heZnl4%FXXj3}q(eiD5`-Vi;07=XjR*)j;N#fwT>lFfe3@9#mO0u%)wm z`2FzKV={pRHqS90J_L}GIZ-lKh{nf+ z;aAB_SZ#EO3wLB^OX02W6S@{uI)4?< z8Y*V$eAjRnl6?&Z#cpEhKp=m~pjBNQm1Yf~iqwI_oo_-=$vVW> zf=V_Xo&$zGaEm}NCCmMq0~e&ChRfk^;+3`Zdv94MbK!s%h=?%G8ZZgMOvZT*2@5TS zw@m@lJ~+8*!O2xiVlifLF@Pc!h~(j;u4CKy`;Vj0{6iQ#>qmPf)S{_~4? zHezXE-ntE*5uVhJKR?CeY>8Ew*d{V~Y~zItSc86K68T|yOT;9iKVAzbb*9?$qDh#~fnpsj(w z1dBn&ZR0iiH0b0NVY5w#DdBP3bZ7HGW)BjVMPwXRHR&9vqOT;ve;Q||fPyMYS=}7hdSC`&1yEI|CFSmtb6R~oyf!Z5>W-y^N+EnQ@r;KTN5FJGaA-TOJp`ED03M~fUKtQC*>=Xm3xHHru<*vi z6!?;!^{wXxXemI;8-Os09hl)hf?iAzI2IdtGomr8?L8N^56IQ0$HR@n=MDLIws5hb zQ1{PXEtm!nOTEk89_?3xa*k zG39ERFP{0CMKK*$N0trHdGJ;bg^G*}EGoy-mg z0=kz=HCke?)xw*y_XGZX>2;j%Wwxhlv86Tki^4p z#z}}3;eRy%RlW4AldO#n3vsZGhkJU--DHow1kMg1jWn)t$|MOp)3u&W`Ck$Nq<1WQ zPP!bV>?#feYXxh|abl4mJF5#UBI%r=heX>-ZSnA5dNX_C;akSD2dR*b2J3|S=0-H~ z7guUgJUl)&TVkI2v{BQ~oVpp*T(V$alPmyM*7!A`w34lGwnP=khEr50BqwDyKy387 zyt4|syA=e^nNo^lKmjGa(k%z^l5SYpcz@qf>tQG>Pwlg=ICW?kscEjZXC-$HS3LN% zHFoM4*Oec*h^^N-G@c#&bB=x17lvsWcShyz@}A1GH*|SbE|W{;ws0h9f4%F3MCmCg z>1?k$VH=J^Olt`>V>V8E3GgJ%>+ zsgVN~6jP3s+a_rmhj8O-jZD-@kEQ^`fC@m|qpsH)EhD>JRNefB7lt)5fIE~H%UA^_ zoygEP+;r-> zM()fjAu45U!}G%`2D%^!Yyjw^uLB?qJf%#w2Eb=lLTl3*s%~wAWhljRFh*@B&$KrF zm0QH+_D%Nx%5!WujaoY_W0n-)zkg`E-@#q(Zv2-AnG z8^MRG_7iuT%di>PCUy^aw|i9<$|ZcVsMM()V>=P6Xkj}h;+4pTZnn@zI~HCCTGUBk zm}8LMhD0`CEUrjUx%Hq?P|dJ~v1F(C2<{P&Uqb)nQ7qb{L~eb$DIP9KP$Fzw#-~~j zEV>RfH^z|pa;89wp4e+vin|=x*Sf`f!TAtkDUERpEj(c-=1)ohZ%z|2?@(e`lI!<0 z(;_>D4Yn)Kpjh~;NbATE$VWirX&tG8(vK0#P$R;njGwf58frd^plN?tbb>q1y#oF@ z+m!=Q_g)0hdu1n-dL!6Se`PO}j>8$Q$zx84KaPX{W*lskST_-G`(ORn$onq2Ao zGrI1B;UTC{%p0S`pCr|vDDgvZ5mZY^RK$sM{{4JLSUs$wWdQcMiws`h0_(;1kTv%d z7C(q90LUX~2Nw(P{|~^AUj`Vo$UtU_4EnQF)bfTkgU6tLWjNmHFRmhes=2?0uEou^CZD4EV{MrO`k0jgrgXXE5Lm40z!;H?Z%0^3 z2>HWYr0fSm{S3r~F}U{?QjCBr-f>fAnVhX1b8DgIfdJnXa{U=xh-PfTONW zg6sR>uKzZih73CvPc;3q-`#lDUn6B8t>>mvZGVxg!;Pz5UJIz$9WJVNI9Ma;&_Rg( zHb9PRj|LA~cliojIj$kNlYx{yIWB7Orc%0piVIg$weP_F%V!E)Qt;CpXTo$>TgPIz z@7+*B`5f#6L~nZ@EYmgVb0n%Q4@yoj0sq-`B80)v+v}n#)qc8?2}Io6y@nx%8FS&8 zKYEGf@87|<+&S{_7jL^R2Papek(XTOzn6&`W6j*A7jA#yg&ThL!V53lwdwbdJ@yd% zp)8S3*Z8p0fRY?58on-(1=5)!kOh;)1lE91$*^Enple-!4{mZZqLZNktp&DC?v-+@ zZxhIJdboPtd#~%AV8~sweYWYd8um_IO?1 zpMuwT$lc_t zZ~gNAn$o-d&RM0K!26Uiw+!A@8V$^`I|dnW<3Ae(THmzKTHv#eyw<+Lc3v8F75GkG zN;khOX^;$B?7rHf$Y;6ojctW(;$9m15SFu&)eWAPUUpevuOt%jA7Z4>`=c*Im>+re z9w<@CmU<@`KMUc1q#5B6?ytHaJ>1+~gybcJu zLCQ~(n#z}PFk~r@hm`4M5~aQzfWZ%*4r=TsM=$)wAn6>r?B_u>r)Qwd3!>U&f5H z$AfD+b{kV$(H=dogtP6j@IeXO&3qm>qGI7UB?ws)UGOf%V2FI=l?f_tf_yGnVUQEF z)OF{={>{{8ifQTjyuv@Z8BUP{4}*hnhAew-N1xm&Kb>hW?5qSOCl6kwBmv8|H@#I4 znBFJ(Lk(!uud(NM(ts|i_UN!J{f9ns&nD zpHG9+&}q$M;X9;Rq@xICO%Cfw0ZjeG!PtMigM8#o$-rb#f&owrk_4fIJhG0&sphw; z^ehj)M0gGYaED3WX^`~17J}+S z0i`{qCC@>H`j_4807@K1a35?fjuno5j&A@H%3^HMKpOb-U8n+bFn8DxdtO?*8V*zyq^CF~MUQZmPevtqwj-5Kh>e zDG+kyV2+?fG0_B9TjCg$CQ6)>04kAy*EU#yGuJsBwzY<%u}hciHVb^DVW00&1W>GD!*Bx@^P&Zen*4t?zKijT3z1WAPa+cd40q}5*o1K7q!ZQiV7r>Vpu2aFMC?MSqbq>f8i;SOvsQ;op-+jTQo{|G$APQk3 zz)R6J&%+p=g{{6tYIl>9!tJhOfW<7@BAPcpB2}0(Sw=`dOuWHWG$o`R#=;XV>cdYo z5nQH*DrqWIsKJytKjz|cjvbIH_3ds{4mNogq4YntqzfOf%6C?o4@9c;YfXxN6AZ%8 zM1C;29s-0S);gk8ybgin$J|Ahd;Mq{V(Ukgve%_qP*Z4u!%8kRl}Ko`Uun1-HpAh> zG*26x2K_aZzfDYqGFrL;%I6cT``3#yOd1yv0$NQH^XVS1eseZAK^Ne$J)EN8N*p&Al!0RU9v)X*#%i_@cc76G79#Ig$@t1TFvd88L6iJ)Ht z?-&p369=SPN4vYqLkM_c<*@LwH0`Y7+FetE08R$qRjY!~cP%e~SbBs~?2Yd+`UG1F%Zo zf``1;yZa8gSIF-^eaQW!{MSN;W0DgVVag%*J&Qm9+LYtl;J$ltj_>_T7P_`0DHLsz z`!@iaTMTRKko$f3PQ?0_^=&%1x0@qR6!=K3MK`bGFjxatdU`;$PzGu{YdweD`7-#n zgTVnXbjCNh0iL^`k}q$nIvo#p#M>YasTMZN#O7xkBpdBHPt**xM#HiTTP$Wi36x=wjajCE5T`j#93f^VVmZ3 z#KYLO>#Y1VEe*2RU{%{dVKxa}=m>;)t9fFkR3!PPt3 zm5FF`5;=kSkx~zu-3V?&K1V>^aza*ilfJ-G~ z%kn6zWPt6du%nThse{U>JUq>s0(O`aUZ8vNLX^B`L8N#{(Zb+a-vzZ0E1(32f_6|@ zk>OWHnecS0%8yuV$b(LhI6qo41paV1lYFfW&p?&K0kRS&0{E#?n$y0i?k^DTZl7k@ zP0%Bb!pTp061+cM1y7JKRA|+AZEnp7d&exO)p@X z-?rP7tru3!&w)4o1PBF1rHcY^Ha@*2d6a*` z8P+BiD3vjpG<7lNx@)&6CB z!CJUltAJ0ipf%tKaYDhhOn~nq0CTY3ytcqd#bmc|{=PxzyW7n;ORkYB(zOjeR?DzGIPmkKW_bytI{ zu~yQWH5@iMv7a$r55eIOi4w19nY?|uJKJ4rqlXYybDFoRhZG3Dk~0lWtC6x%txZ3K zkr7I|&DBG4I^AEOZ?qNJZ@%fKTo8k6`__EQ7d9V@g)ZTF!WzsjU#;h+4o>vJOhr>c zyhjr~OhyIz8{CbyTBmKfD;+vmkxM!RwhPDTfE}Y8kN`uMJh9PGjt@@D)q?AwI>#rh z39KP8A`{0($=m%hbtv<<$uj}u)ZAtej>$=PRN5GjSK7c-03QRGS8JU&ZyrL^@YLhP zpSi_l#KJ?DoEh#WX#ATv+I`!xGLDoVg2QvWdum!BNOm|yyIWEoY#U0+UjlbR@yZs4 zM7MP5dPqwlen4WD5clRUUy~?l!BgR>Of>D3#JE0%ZIPdLl>1w9LcUM_UJOnMJQgkz z-Z_@*Y`M8%kCbwtk5R@VpH+i`M_KGEm7Y9Q~Sc-I`+=>sj6~MB{b{OxCUO^Z(`v z1w6}RTfk9ZTn`^VX(!8w*g!TPA?(tx7z zbg@wlB?8dXut=vIsiI=^Jq6QlwLJ~O*-et71J_xlRS#}M>Zl^ROuF;Ig+nUUHe{9V zd<~pHQNgvY>b845xRUbY{Zx5MKRx_DJ>^xpfr1ZOdCI=_1MmjGmP@DViZTN=pfz^*Z%0^Ogwj6aKOO zJ}1*Gv#WRtJ_M(;sU5ycZI8x-8aN`spr}mSO`I%|aC(fmAtGV*)qFenVkhowjah~o z5H8jDh$DhHU;wkxmgG~TkWYteF-itl+e;I8Z zc@*+~xS@gki)hn`401o@4CJ3deLmzLLHj(&KZs8Faw6ff81d;ufN`~qC?Wp~+-Vy< zxg-)Uh)v{gB->)Rr-Qa6e<4}p%z>f`s!0A+vMLu!7-~o^Bx~eQl3-Ah??~1tp!74; zkbHBpMhm6ypoZj~$(jr(or4;ZZ-iGP82k}F;x&P}@1uY@jGbk&06Bm`&=(2+^#nN7 z;Itkvlg$(Rfd=d+8Zb`nwrZLbXZ#mYW7cKYti}*hKorRxc@9$Zsh5bj2Xmkn6KhN{ zu;%Z9k@Z88;GEgN60IXkYPRM82~(-|`e90z&u{YdU8GoT$XO!?Z=T{A5M!UPs!kn- z{5dN+mBlgk=e-3k#$Mo%Ai^vh9E8q(f>Z~cOWhe@H=F12gLDnuG#-JcUW7OpH5f~# z#K0h6Nrd0`J;lNC88Xb(`&Uk35-eeHaJXeGtbGglNS^>91H#ml{}B)Z-GbAJ@~fab zwJ>m3iIX%WaU1LG>)T*p*E;(Ye#DmNu#8ab6zeqq?Jbi*4%YFvwQd0=Sm#&^=Tj}> z6E4dYFzvWs_a4sc@@}#I=FEBN`F9WT@CiY^V7>h757*L6?dy8vXGgxZ$xTYR{0jco8Af#TrC=t#| zRKTZ&Ag-|D0sj~95>EnNc3U^~ku2vU5e2hXJ(uLsGe4ONa;f{f{$;Bb_|!L)zH ztCMz?13@qke2S~VJn(5KX!spfmgA?(QvJAWZ{VYO$H1CD#&29+d zS|#X{_Z~@W(XEGXU95QkPM`L`0b>#pLx}JPm^LlsdPoJJ!_9y^3-TODgqHRK_Yxr| z)5}90F+&g&1kv}1S%R36azOHT<}{o1U`1+(h8xBW9Ede*CN)LERpWB7B4)KrYRYnu zk7qs!v!`p;IA}+MgVrk@+4@~;+zw)~`p7}Pl;d7)($`CxYjlnXd~JuUx`q)qth&9& z2>{rMl;mS_3;>BB!G}tcfWrpoTnGyMb{Ti>qUyIv( z$y3SCWBMQlcaS{CK(dS^s^xlTB7Dwgn*wroH=gscH&LeZD~+yV2x_^N^IFhJFRD83 zbHN}b;Nc=Up4&Eb9U}&U!4BXj@CFN=i=X6bI~CjxZa3E}6)%yQ(m{x!MOu}a&sJYw zY7u{MVThF@>eKb`u`&ui?SVlyM{G1`b(Y5Zk+H+RucO1B*Fm$P;9d5+TKYS55ZA5i zVAzYn_04>Xy3?Pt2Wkeqc&=dmTZg*itALCh2)5f-x8`V zJK$JOC4r=zyYN7%FULrrnP34At{_k;4@|(cYxj-X6T*>uiZW)7kzPND*2C}bpzqCO z#Ehb3?HkG3+n{!Xpx%`0)CG3~+3$c4#6AZ3#~*!k?crBny;cb(E(7Hnf_TAE)Ydj+ z0a12|1NVXL_ZEgY;tx(^Qya9r!>^Xfe7Q9fVki zH_>~jy=`u1rl%eJ1^UR#6&7*NW?TXb&u(yX1s%8A3nAqs6MPLS@hkhxjvUvo>;)b3 zI@O@Zcm8`7Jjg^M!Of-Ek4y9Wm)Tc!EVEbi6m(qIqU&TEbREjUe9-H|{wz zkv0}>!SM-hm(_NU?uDhG)wg;3Rv7QoF+HC+W!$Y#ao1n+DALsm; zJ2Usro%!E;|M%Yi;}?Gx1dXY(7@B-y=y9hBOG;?dTXanHH>r>pl=meRwdg` zy9$>wfkJgC^dufgyBNi)nHwm4$(=5w2~Xk`E=w1@dAQG^!nTf{njb=EmD|vx0gqWVuJlKKCREq2r+n4 zg>=ii4=s2Y^Z|q%ZP6C&2t}M90__JK1bvEoeW38;gr5mo0on;V1^N=S+OnopZF33{ zw$)2-N)0Z!nPegE-BBkkGVATG=PYS}M_P#rb<%Rn0jWrtaEwb-(_B+>|}%)trRLo#_wDt7*# zjD`hfYQ(VPJRIKb*rv^<7FTMQwqHO+Eua%18Z}ykK#~Oybnr~1fK>=`?Vx%hzY#vX zfq}ofwE>?03fz5nbdQinm6ExiCC#&J!ZI%j@Rz|A-MXs^?1D%nG}T4Vy;98Q)bDy5W^8|P)C+<3uVIYV&9pR}g%i*WtQ8g(zeGq$lX6;Q)|`~7a5 zr8gFGZkU&<8VkSk=xqwU+1KS@wCR<&7jqP$P6+}t$L(db$n)w^guZ|41x|QpRf<|K zlR`VqgC9DyHU*%@Dq#s_Ot6D$Z>?46sKY5qd!^*dB>TICxq^AH)$!?C#J9m~^#`wZ zXPjYS7n8<}azo63GA7YXbhq8@c=+!N=XA@{iRJ|hX<)}fbN5MXCxtkRcB^cwOZQ1k z@0zvR(deOl64xt-8>DyP}$pOQhlU4$MI;hmCl2lM2>DfPQl$?&#*EN=B<_0_W0HNWoDMO=Vw) zRb^9Q{tw%J_lSwuNIJvub$5IunoNCgNTrah1g^+*#K)G!wp9cY!qt0e4XV)|jQv}e3^fQ0M5!tj;i z%dTR0{xJzdk%Mnu7*?e}4O$TRs|xJ&^e#K>;N`S~VdDpT%vK}JD#amUgeB~hOiXG1 z+rQXa3&y&0BA$+hS`w6KkG&Lqq1O8c1MWKqD|55*I&w9vrELt*@30aFW6A00=^VPO zjWj6Xo}ldN9Eu>3Ky-8YW9_AIgoHz6(u5MJ`$&!XH4as;+`yhkRHxoNI9}B`RG>Z6 zAvY;a>|F=>+N&@?fvxAR`?Zl+Ghzp;8HY66ksqH=Ix7|tZK4oaCNEKy%gX}fc4#HH!-6WeC6_8B{Q91A>`~+eD5AORREWPY zs)6*s=BG{zEq=Zo2K_*#W8O1pj=YakEm7Do+lgWJ4Ov!hz!`~)P$lLN0>H{VCr z1U70Q9bR2=J#xv%-96D+QG?t8Puap4hs*Pq}XiaT|%0SP}gSQ>4CUGb)c=rhothtGJ z3{e(nB7Q~Lily{*RgN@ZG{C87LgUigt*|EzsfrBc%}SFWgblWdsr z^}j%_Z63Maeh^?Oa6Rg|(ZRbFO%}3mX;PdKCGoN3L@U9|Uvq zH>It;Pf2WZJ94h8&od^pNaQk4(3?o6eDo+>z;Oi1-NX z!zYGE9wY?hfzj^e+Yv9MVP?hY-UqH7^(EF|JX2E#9pgtoB>ay20|CiK1rZfabRPIM zuG8^Pg%lNDR8UdjMdbmNCsdfp+jT%GW9G!oaKPYK=OvkkG4&An8SjG9aA$oX-;>vF zm+3>gGhKO*{t@Z(EG}qN)<5X!vulU?Is@b38*Ej98wQ{Br^o1wt;5Ke`2a0XekCO+ z{fKxBJ3$)#!-*5*h!t=^#Si>_k#LoKa4z%|`ab$S4}g?Ao_l>vdeneMF7NlqQzY59 z82=nQ%GrmC?nZMeog91S-Y&NJNa0sk8QnBDtJAn++F32_R;Wl5YvKA?6?8H`yC|tO zNj1UIV83_%+=l~^-1CLc7ck9?Cbcr0vh`;>`cMut1^!b+xDLuC${EU0Dk&+4sjQI+ z_Iga6M6>AWVjzgI{anP#Vzb+1RU5)#Z#I=Lz%JB+-)cy8Lu$?Od6mE+3ts$SdeC^G(Vo}z+JSC@8VK9|565HF=9ovlA zLe$$WtAu2yvdKUE7LdG5y)jq`WLRPXD*+2F_aL@INC+alpfidwfbxAQR4+Sv;Xz-^T zxft<&oi6f4i3_-J;uir#-CL$8=v-$YvJ0Ck;+rnM{8pwtm4+Pm&@B@+kQpyVWRH4I zZ(kEO96&`F8_og{(7^S7dn2GGeCJiHlrE8UL}0}Lw(SyK?a*Mra;ty%d)V?WbsXPL z9Z!x|0j3QBlkq}bE26A@YKeY>9){N>e+cS`(&a%(9VLXhv+TGXFL6`38@I83zg?bp zQD(a59`kY*uAH;fmJ{t|EV4+)>BA2{F9LYV$=2|t3))A9ua0Qiv#e$p2V^O(H_NI< zY7GE`4lkw=u0KK8q!H6`FmyGG2ChzqUUm-sX}Nttf`JjDqI&>}E+}tAmZ%FD@i%X) z)DFX#hxk5|_=`YU@R5Rho&w*_X9v7(SKj_J$10=6gY^i@#Gj@Cq+x&rswVuADTMzf zf$)C<4aE~a6*LdD0Yo#?zt@qj0l6m0gK|-z$ID&By;ni&@VsED|6i`6Dq-_$^JZ+G zSy8olowcHB{Yw?wHf_y$k%;TxlV0>_-~l(C@UKt9?^~n?pYnMI;TzKkpIJRKvznBy z-?TxqqM~}^!wLwEFlFc&B2z;iJHl+Gp{EqwmfnxU5eM;3ea4c7TYkQ!V)KTl$jZ$d zHWU3zn|@xgRZp_EY}>R+M+%-MJSAi%vnG#?D+vFO<%BN<(d+kdoDocm>OC*CjWxtD z;%j^6YCKz!X&d2}f}RDf1g!!UfQmt4&%RVKTuc$?h|@&lzB5XOuz2$b5=U~$dUA&o zWA>`rI`(9;Vx`#0p(=6Ke!aMQ|BsoOZLa;COuozIw+FtL5Jqg=pA@ShYA*PxgqX<% z^crzsUmV{GpGp*`Ckf(HP1tnOJB|CN#+r%ku>yHW2MX9wfOd;OfpbS@i7orp@bJJh z)sw6YJpW;K`g|}pn0@LIJtK)PH`$YpBJLy`HKE|6Kl-|@zZTi%)p0awo(n~s0!06C F{vV?Y+z #include #include +#include /**************************************************************************** * Pre-Processor Definitions @@ -285,6 +286,13 @@ __EXPORT int board_app_initialize(uintptr_t arg) # endif /* CONFIG_MMCSD */ + ret = mcp23009_register_gpios(3, 0x25); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + #endif /* !defined(BOOTLOADER) */ return OK; diff --git a/boards/newbeedrone/pixnova/src/spi.cpp b/boards/newbeedrone/pixnova/src/spi.cpp index d33dc6a74739..5a0637785d8f 100644 --- a/boards/newbeedrone/pixnova/src/spi.cpp +++ b/boards/newbeedrone/pixnova/src/spi.cpp @@ -59,8 +59,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), }), }), - - initSPIFmumID(PixNovaV6X001, { // reserved + initSPIFmumID(PixNovaV6X001, { initSPIBus(SPI::Bus::SPI1, { initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), }, {GPIO::PortI, GPIO::Pin11}), @@ -69,7 +68,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION }, {GPIO::PortF, GPIO::Pin4}), initSPIBus(SPI::Bus::SPI3, { initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), - initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), }, {GPIO::PortE, GPIO::Pin7}), // initSPIBus(SPI::Bus::SPI4, { // // no devices @@ -83,7 +82,6 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), }), }), - }; static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw); From 7d172cf2785d7a791cd1c7148ccb1301b6758288 Mon Sep 17 00:00:00 2001 From: LiuYongNan <844550332@qq.com> Date: Fri, 3 Apr 2026 21:47:12 +0800 Subject: [PATCH 4/4] style(boards): fix astyle indentation in PixNova board_config.h Align PX4_GPIO_INIT_LIST continuation lines with PX4 astyle rules (CI check_format). Made-with: Cursor --- boards/newbeedrone/pixnova/src/board_config.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/boards/newbeedrone/pixnova/src/board_config.h b/boards/newbeedrone/pixnova/src/board_config.h index cb29fffca66d..a7506096a329 100644 --- a/boards/newbeedrone/pixnova/src/board_config.h +++ b/boards/newbeedrone/pixnova/src/board_config.h @@ -443,14 +443,14 @@ #define PX4_GPIO_INIT_LIST { \ GPIO_TRACE, \ PX4_ADC_GPIO, \ - GPIO_HW_VER_REV_DRIVE, \ - GPIO_CAN1_TX, \ - GPIO_CAN1_RX, \ - GPIO_CAN2_TX, \ - GPIO_CAN2_RX, \ - GPIO_HEATER_OUTPUT, \ - GPIO_nPOWER_IN_A, \ - GPIO_nPOWER_IN_B, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ GPIO_nPOWER_IN_C, \ GPIO_VDD_5V_PERIPH_nEN, \ GPIO_VDD_5V_PERIPH_nOC, \