From b47fa81633bc393b3a96489402e01fa5591c56cd Mon Sep 17 00:00:00 2001 From: comla-x <48378896+comla-x@users.noreply.github.com> Date: Tue, 29 Aug 2023 23:31:33 +0800 Subject: [PATCH] boards: added SIYI N7 flight controller config --- .ci/Jenkinsfile-compile | 3 +- .github/workflows/compile_nuttx.yml | 3 +- boards/siyi/n7/bootloader.px4board | 3 + boards/siyi/n7/default.px4board | 86 ++++ boards/siyi/n7/extras/px4_io-v2_default.bin | Bin 0 -> 40140 bytes boards/siyi/n7/extras/siyi_n7_bootloader.bin | Bin 0 -> 45412 bytes boards/siyi/n7/firmware.prototype | 13 + boards/siyi/n7/init/rc.board_defaults | 14 + boards/siyi/n7/init/rc.board_sensors | 21 + boards/siyi/n7/nuttx-config/Kconfig | 17 + .../siyi/n7/nuttx-config/bootloader/defconfig | 93 +++++ boards/siyi/n7/nuttx-config/include/board.h | 381 ++++++++++++++++++ .../n7/nuttx-config/include/board_dma_map.h | 45 +++ boards/siyi/n7/nuttx-config/nsh/defconfig | 250 ++++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 ++++++++++ boards/siyi/n7/nuttx-config/scripts/script.ld | 229 +++++++++++ boards/siyi/n7/src/CMakeLists.txt | 70 ++++ boards/siyi/n7/src/board_config.h | 310 ++++++++++++++ boards/siyi/n7/src/bootloader_main.c | 75 ++++ boards/siyi/n7/src/can.c | 128 ++++++ boards/siyi/n7/src/hw_config.h | 128 ++++++ boards/siyi/n7/src/i2c.cpp | 41 ++ boards/siyi/n7/src/init.c | 269 +++++++++++++ boards/siyi/n7/src/led.c | 235 +++++++++++ boards/siyi/n7/src/manifest.c | 132 ++++++ boards/siyi/n7/src/sdio.c | 177 ++++++++ boards/siyi/n7/src/spi.cpp | 53 +++ boards/siyi/n7/src/timer_config.cpp | 50 +++ boards/siyi/n7/src/usb.c | 105 +++++ 29 files changed, 3144 insertions(+), 2 deletions(-) create mode 100644 boards/siyi/n7/bootloader.px4board create mode 100644 boards/siyi/n7/default.px4board create mode 100755 boards/siyi/n7/extras/px4_io-v2_default.bin create mode 100755 boards/siyi/n7/extras/siyi_n7_bootloader.bin create mode 100644 boards/siyi/n7/firmware.prototype create mode 100644 boards/siyi/n7/init/rc.board_defaults create mode 100644 boards/siyi/n7/init/rc.board_sensors create mode 100644 boards/siyi/n7/nuttx-config/Kconfig create mode 100644 boards/siyi/n7/nuttx-config/bootloader/defconfig create mode 100644 boards/siyi/n7/nuttx-config/include/board.h create mode 100644 boards/siyi/n7/nuttx-config/include/board_dma_map.h create mode 100644 boards/siyi/n7/nuttx-config/nsh/defconfig create mode 100644 boards/siyi/n7/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/siyi/n7/nuttx-config/scripts/script.ld create mode 100644 boards/siyi/n7/src/CMakeLists.txt create mode 100644 boards/siyi/n7/src/board_config.h create mode 100644 boards/siyi/n7/src/bootloader_main.c create mode 100644 boards/siyi/n7/src/can.c create mode 100644 boards/siyi/n7/src/hw_config.h create mode 100644 boards/siyi/n7/src/i2c.cpp create mode 100644 boards/siyi/n7/src/init.c create mode 100644 boards/siyi/n7/src/led.c create mode 100644 boards/siyi/n7/src/manifest.c create mode 100644 boards/siyi/n7/src/sdio.c create mode 100644 boards/siyi/n7/src/spi.cpp create mode 100644 boards/siyi/n7/src/timer_config.cpp create mode 100644 boards/siyi/n7/src/usb.c diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index ef0cd5c77c..a6628c8b6d 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -117,7 +117,8 @@ pipeline { "spracing_h7extreme_default", "thepeach_k1_default", "thepeach_r1_default", - "uvify_core_default" + "uvify_core_default", + "siyi_n7_default" ], image: docker_images.nuttx, archive: true diff --git a/.github/workflows/compile_nuttx.yml b/.github/workflows/compile_nuttx.yml index 062b6a0891..de5a0b7c72 100644 --- a/.github/workflows/compile_nuttx.yml +++ b/.github/workflows/compile_nuttx.yml @@ -73,7 +73,8 @@ jobs: raspberrypi_pico, sky-drones_smartap-airlink, spracing_h7extreme, - uvify_core + uvify_core, + siyi_n7 ] steps: - uses: actions/checkout@v1 diff --git a/boards/siyi/n7/bootloader.px4board b/boards/siyi/n7/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/siyi/n7/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/siyi/n7/default.px4board b/boards/siyi/n7/default.px4board new file mode 100644 index 0000000000..cb42f3530c --- /dev/null +++ b/boards/siyi/n7/default.px4board @@ -0,0 +1,86 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS2" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_COMMON_BAROMETERS=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +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_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=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_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=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_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=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_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/siyi/n7/extras/px4_io-v2_default.bin b/boards/siyi/n7/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000000000000000000000000000000000..957f0f13a12e8eb8a7979955f29ad98d82433933 GIT binary patch literal 40140 zcmeFZi+@w~{XhObmt2|_nqGk3fF!42+5i>`TE$D6w5OL;isCi|wjC(CQ;JYUXWiVF zU{QnMhSY6Hy`a?%MJEZ=4^?YW=H_K?3735e73oBcv^r1PLQb1D`99xCQNH{99^c>Z z5BS03^qidc?e%`WU+>rbeTE7GLX_XC#GL9% zt8H@_j?;Tu&31?WI8n|=waQ)NjIwFWsq*>XhHg>$R6M1A8zTP0EHRx(BPK$KDd%OP z_u_Y?lN8Q#UAd${S|w!*^Q!07Tv=Nx@lu+UCC|OdsW4oYG{-elzTQ4vnj+6qw%$8y z*u7{9eI9ntnj%fd{edadrNW!$NZE4Xu)DBg*u5}YGS@LrEEJii$=unWFnfI7JlUcs zY@USsuyjlE-nS-kS2)(8Fo`l&Nn`oq(clz8kT}^nyw&McuID%@70*Y6REayFbWf3A zB1*bunObP%bhr8Ei919l%%{B=)@#WyaeOm^nwPPn)S55+t zq>Qoixb&SOXa z@SKYGeGLL2OqBv=y(>3S!#PZrIe|@DL*Gr;%7`(t={UHIo&3hV>MG-BGBX_5WEl?J zo#i|yu^SnMVU{)0zH*&6uQqlYJF#Y4lWP`_d>;SYw-u}Kf4(pGvKx=fw={C-i3O&! zoT+YNjz>PetoDQJmu<-2xLkjH!@uN%QDta(3a8BEn9_eqEA`HPl4ac3Dw&55EZe27 zHZny8LC|Q!E_Dq_v9bZZl?|qNox|>B85=*6GB)l~8%S!SFl=9@$6K;2b#>-Oz&vc< zv0bZ+ybh?VO0Mxb6%!MW zJn|jP!tl{Eo`#OR?jGbH8pHSU|DE}Bep?XS=giWN?krp_i?l8@?1y*rkhBf$!@MqOy!c}7I zCZ@4aStlp9%iarHHvhQMD891(hJg3N?#%VX}z` zSu{T2~GbxE(_{R{%#1pCvOyow1g+677-Cr5) zjPipw2r27)XuY&zAb_q~>lS#rDYN$m^j zPfBu69s-4Xv{O!+L`F$d8Q~CCKSQgd?@gIn4)2NbL7Wl5{{qC;7bK>#?kr_8SKwbJ z6Cspedn?Ms<3Pm{EV+VDJQ6#Ufin6vK!~>;bNR2|6)$rqmI$2`l!@I5F$0 zh%TFe-He>}N<@yMNi;1zOxCoU61Oq)A1Yci{eQZ;U@$-vz?J{j#^j>}>?dY48? zAtOw>=?BmeYP=t|T-)`N0$D66eN0UO#m^lt6`6(HoNt5tf#&XHzY8G)%5l}fC2FQ(G3en$V+RJ|ZHFk;jQrIY5S)IH%DXe8u0L|6ohB<6-k|`bujP-%{d_2~z zYKgjiqkW7lH;CHtmtukI@8tdw7o3l)ZcMXHd^tIOru)eiZ% zR4#Mvk0$188IC(v@)o6;U742U+%A=LA34uvmdhU54vFQ~>P`?_jz3M%`wifE+o@c} z@5#c&P&{(G-zoRVlwW@@GdNl3XBdN%mCpI7UIKVXNoR^Hr8*a!BTv-VrQGz+kk0(1 zgAMASFO_t2l0{-li=_*po!^kY-MIGRdJ5MQxV|0IxMwJQIve_4K+Oz15}iDGY(i?>1t1n+T|W&tJ*WGwhlsT$HIp4`GvDBa2hc^7T_ zO$h5>at?c_5U?8iNMBherHI_x+`24jnUw3wt?jtTFFUI8bL$oNf}?8oT#Iy6Ets1x zXV);Ly@Xjj?HHMr=_(d8Yf??qC8EgjV$oQ`nTXO57qCW~AzS*Kf}|w$!!@s$b(gEW z?K6z&{uk*hz_@x`#7OkybJDk*C#ILC6a5xkS)Fd7QDk1`K}(zCWnE{^llkd${@b4? z=Sq({^CU|BS)l4mb?*F+I);fl6o1W~hMTmaO->V2y9&f2sRVrv#Y@B@nJDw)*01XppTJ|p(#VEZ33U0=$BP=Dg*4yR7%Jw_^r=FJ@Kd zMq(R5IkA*Joa{Gai86|Ul%pzX&h>wf=9X)R$AkrE)LhV7Ph`M$Y6R^{Bcw|0M}{-!GoR)?LH@yMgtC&`*Q!G`r)RptO= z?p>`Rc#?P41OA0SR#k4==$UBaaA97nBL|;8>h3S@c2CrS*S@n(Y zp@}zkkumRT+*wtP-5rRTMD75roZlQ)t)|23Y@^Ya;@jdd2YS>wMrMJ2)!~t1W2WzM zI(y4L)ag-qQ|55rW=+6g)de#ZdwPz4l1Za7sm#K+LzAo{!OUUz<{ZDlG#nyx4hMZQ zDXs`Cl(Q8(?+jkT3Wdxp?rNlv(NXE>DLy(*+*cU99B%qd;r*XA*#O1Y){sYK59q_$ zz-Lh`fkCVP;xAqU4*B~-^mnocJ4V}Cbtf>ol&60U{5s%ODQ}g3+^7i~^>$z*1^CSE zo!7!#HC2gguM9BrYzc^yJ8hsP?rZ95T5lEeWvt)~-D%o8Z8sNK1P-^*vi3w-(|Yc- zRa}YZuR|->rFyMc^QQHT8Rd<;t7yA<&Hn-v)A&zAkP+4ar{q?{vfreL8s1Ed9t{waf--?rzYm`$8p_^ z8+yrHSAYmS_&Dshm1J&NkRNDevr6%oA|6E%wZdy&0H^v*b9~zlq%J(s)d*~Vq z&u`E4?QvLx)#$M>g(&`UN+*99|7?fwSf(!@WjX#$al;wtaKa(d(tl$-V{b}0eoX)^hZ8NCpuzlY$RQ@%pFxd_ zr@fWTu|Eu?@awkk2VN=m_&|~lD0CF^^zkP`l($nnkZ_Kk7wzI?ygxdonK7rA?w2I> zQQpHCz&BFXZ10%pD+7EBTxIViu0mJpk7F8ewo5#P%nhAR@|DRhGWSVwrabvHU856Y zR!Xst)DQonnJA^>r+~TM{DThdG0GKJCb*&!I1dWlq&Xj2n}o0YqZW;rCfd9o$xf{O zN0LU^E>S%T6h-2Z&&HC^g?RpC;@ODje~u9g;MQe`Wx(7&62G#w86uT-?@!d5ihA#k z!HyAG<)847mEe9%6@Y6%SzbTfdp85^_lYjz|NI%M!}8!^@yME3N6TU_rSojk(M)YP zqWtVF>M!6$9_6>h8Yap!Ny9|>k5Jy+d1==)tj}*;_NIMMSNe=&Zs7F`j?MX}U%&9^ z=6hk`PRV-40o%k)ZCq;a(qA6;>#&85K{A&pkGgGggVZEpYY5D8%=wO0@)BDfu(1hcQ^nT$XW-i~;u-znfw8kU1#xMFF28^$U z9D~NY=zf1Owmq~6+{z|($W78Yc|dv=6f=dmVaxK6YniY~K95rRpxpUvlu1wuQBEhG z3i0k_6nu*?=H%M_{Y|AI-U!q~K@n8iXf{oN8xX!_=c_2%aGMk+~d z@NV%ZK*y^oM5|($%R|YzP)hCv2R_%5-<6kF6hvRPgMf^7nQe!0IM-i=mFvJqc8b%1wS1MIk=a|0 z{l~maln3xD1zH2setO%{^Ze}=B|YKCJ-r3CENrCYctlxs7`BuW8cTQa;tF}XxYLmt zn1Njj9y3a;y3_GUWt7Og^+I5WbtqtWlyxz}ddaqh>m#PTZOnqaEmUtc!B>`%D=E2aF#iIdenYQ7OzLVObpT?=rllJ%23q&u0 zhY^8F{48mz$hLS6kmAa~$LAT2+4u2zuJq&c8d%WbDq1EdA1C*y-MX; z+`!#&Z#;4+Ufs1(N#(V>^7ImF z;ap(RcXdc%iFD?>8WHRnBY%?a9R8mnPRwn|5%WZ*biVh>A~k3fxfW)@mA279bCuf3 zVRz)UTv@CSTv2PS$p%iEV@;5!frwXX0Ln;be0}8c&{v;7K}&UiE}M)de3d+pnY?;?7(cXLnei( zeHN6nfhQ_8$3Hto3TdAf@pz~~zCtVzKMJwp$GC{_A!d-u{f*9p`yfPdPM%HToly>T zvG7APu>PR&`>8x(gllfPW=U&jGvtR=ENy0$-6Nb}yKj-}s`~e^7FuDTb)m~DF05HB zF-qfjsY@28ORT`WRNBla4~)R>Vi@J_C@;*b6C^=qY?WtBGW;;g!_i`_yC7?%mo}SV z8+{txFVCp%m4AwUJ{--*nk0w+X+J%Q_M{2s&g6|VWEM1KwHymt+OjY$gagLRIzX5K}f-~np~yh=&G z%KV=aeKq>1vo^!$mnLTSe9ygeyW)}8REwyq(^p^g+0{jMGVmU8NR(?+zDap=6fjMi zL-Yk0zs{=fOzTOhy+ti4S?Og5jVaMSjB>Ytdf zL9a41*l(Yx%K(=K)~U^_sm+u#yYhB`3v8uUB>X{WPxTzwgXn*c*NA$pUFc&%)ANm( zN{B7x6L^8Q8c?>ZE2;BQ{{geO-IukM*e(RW4Ka#iBn)^i^*4+@dDIuYIr4!~w_;Ce zu43qj7_Y1|-IXRzmz%MgRnfiPf$bbTPpnNBcv)_h_c%C6>NKM3vx?3pL27Mkkd8JH zQ-@RrOfeKwi9WJwv#Gs($)@tM9>~sO*29M53#gT>IYUgQwMofR)=dP{S`93^hOLZp zpL%G-LWorXclTsaAC{emCdI_fcPNa?Fj&qwv9V9x81(H!UN!$)BXT3glH@VSTG(QV^OvWbK?$ zz$OZ786~VHTN2Y}p+b2e0ofVgG!65mu)GIYG=Sv?mta|F5~T-yvP6?A6y2^MUB#5F5>cR~2%5 z({d-XQwEYmwxzZ& z5ScbZJ84^t_A^usFi5@c_l{UaKEanw;ukVeel&8C@+QqtXlAGODY6S(e<2YJVlHL_ zyi+s2Yx|hFhyBbf@Z`ld`^~DblNo58 zOzotS;NMkZkNdumK0<#9d%FFz?N6&E#)j35!ZA#{MQLCS&WpZ|)ivU0t(=JuSFp41 zx#J$9oB_;R)qLUUM|q3ozIcR_Wt1n>_c8htp{1&Yq{_?!E*!t%s64r!<0@5wdqv9UXEiM(OV1<4j6ALQeoFlRewF6rjYWdX1|486-v5EmQpi4QTlATLY zZ%vHHidBoT$ZN5K@S*E(tgGO!zq;bh${C2$)Tn$~kE$=}m46~7y(N@CGt+*cVqaMU z0q~?)kGimgDbZFu|fY&fe$|$^j*xwpgj$Gp9Hgh&6cm#gtjS36@UXq{k zqP~-NeeTPV3E~?>xd{<3_)cTAov|~=49!M)EoSm|$h|TLOT`F2nF>Bx27dNEhf=&w z`J5M}fU?)y;Ybe(a=v$u{G4p4*ds0X8bA|wjS!P0UE-NJu=~%4_-aO3IWh=LOd;V= zz8wE_s}7u`Q!B1D5v4uOi#x%`tx?Sk9=n_<55}$VjPi(M9)e`oK%Zw6ew@r2qPWy3 zp}=`|K_2YW6?ZpRArb}6X`#2_7mSUEHPLW45%z=6(|(MJS-M7OPmJ;fsFqO_Xm&)o zIX*xmpk|Gj3fP9Qms5j`nNgm`SS;>O#;AQ-W`~FI4dx7^9FJ{Orh*sKmMeQjl8+z_IENN(Ppu}hT@{udPqgf4%7WcOeK}O> z+#jdU=VCPenA}ISPqlNJIMt;Eho3ITBL!pW-lp}7r59-Ltw|`^c^Lt2UN*d9*}-+| z&9cEs3fHaeO^iU44D9#}U`_2d%j?!#`Wg1ykVXE6t|tFA=$g{d)t%E^wD)hK>*1e4 zPE7Q3CvRt-D1_cJgjJw1IA$MFeylnRc+nVOL}njWL^UTkXQs-FC0=GaZRvrXLUU@U zSL_RDt|y|5>Fk8OZoN!e6Vp?T_joP$KkCp1xo{3s(uIAfSXI8yBo@l>C@XU&WFd|1 z!shtp%FA>T1AGpjez*Hro0fV5C-fD*MhP*tpUms&f$yr(k?!HYvTDVq6Dys7X0~q23-~Cwcj8HxiP9F_7({n z6Se*pw|3>AAENvthLBarSTf==}w`sO5X=>S)aJ=G^ab z=!3@+zKT+BvAjZBC-0HI#BNnWm7u+kycN(^TjHiJC+_#a?&%5GWGB2NtrB{g&|%;& zVrYaTx&Qxqx&HyJZkzBk5bM8!M(q6GjT38U0QoJOPGPS97%ghqD--3VQLR{V&@Sg3 zBuXc&$QuKjFpf`tP#Tik;SpejqL%IOp|(mk`6$NcR)3EP_(d^(7`r$hE3A$sH5W2F z9yu_ITAt)?5;kjX`rvCYSdTi0}OoiQ{btf7CN|&_Do3Ftg&4T^3VV= zLujg0=eNmgPb`#~D7?o%L4t%z~TyzYRyFY6sN^9(dT5+IL zcJ*sCx38sbuN61RCBM{$)0o{==>HMg|2eck{D0HA)`s;Z;*agE{i)n^`$PSyXoDQ3 zSW;hzM}!!)`mLj|XP_rVoaxY!i1n&~LoRUbaV)sZ0y(R$g)RqgqMImF5pyGE87*%c zF@{sqc@gv%Owd>1MAV`6H(ur?x)=7ws0WhS-7%nNcRF_XkK_^4HKNCFuOQ0S7;W=K zf|Gm}ihr;}Q2sxmg%Bk*5$)v?9IqmFZacCA z8qT#QeS@&=P@3Gib%*JWEd!mc8{;W|fjt_FJTM9_D^WXu$~R-@pRrG{^K0W&Rzm7RPi8=woSWK2RL;@( zSUfVA(6?ier$;Ar|AfAcRhr=I9B4`#WY(u9bbRDH3EbKwXQz@4^|nrM=*^nql%QsP zv4??WQtT#{@~tdZa%41VOMzn$c)JR%uA(JJ&yxzPOES^>6|TSFFMXQrqJN3HI3l!%46P3aCVx;0iiWLOk+eyv)w*1Sg0b@G|@25q_L%S@Fn`vAJGW zM9k$zo3so*QSJSZO=DDxE)f%&V{570v6kxDr2%3-rSc^+szLdEM{>@p4;(2UICt0A z(a8*A`n9aWtFYVjj3|iHYVDxDM?rmBGyGE{c8mnyoA3lOjyl%PEXwSm`*Y2>$BQ=- znfsT(t?DX3&;SUIgtQa9=u7M%gZ5ke<+PBqPr*!&;RSK1RW;g={o%W z`B-voAhAFXheqKq6S#Yg-IO0*T35*1U;U@NojuVGxpn^+dAs$EOMOs}UK(t~-3gww zAn@oxQgr2IaTBLZeK>y_omsO%nk>Jkrn#AgGrB0x2}kGjm52+lV;`4S<}fEST|5a10Gng%8qiY-IHNp9 zZI*oaOs^i}ouB)z^BUj_3mW@t!3TLrVhu~0pw7r z)B+C$KTBkm42HCI`cC1p917(5jR|rO@(fv(j>(7wmKHfna|NhHlq^Y` zMdS*VbsFks$&B)kXo(lNl`Y=>J1mKrARkiJOw5DY2J;j1pmU(I!rf%@p4;BbGbf2+ z9yzz2W;>i~MaJCu$)ybqG-s~0>Er3VI7`uKe(7~K?RQK*b+oA%o^XP_uZ?r!XHCTw zpEay$x+Q;2Lk{*O5u)%K8${NW3%HX|)7%nREp@X2;oDKFi_ZKG&cO*dn*pbG0?uam z-_LyKQ$rM{iE_SdQSffrOs)QSp$-2X_J69Iy=^KXG@yJN>}} zG-D`BB(L4ybIPRM@EX!_REmd*PX8;Dt0aP%Z;sjo;psEAB;9yRXSu(RW83vKW6A zJJ+9Y-~68jm~~6J!n}=3%cIYgepwTUNk3=e~Q- zT4Q(l9q(+YvuwG8*6zDwJklCFw;@^g+y+geE*dM$|iOd5v*dv9r4JUv1B^~>~cn=c|JF*mtq?Cz)x@pGLLmJBJ6eLFNcZ$ z^50VsE4}>phKb)Qc>GivqfnNsFXw8)(>Q(>Gn?kytd={%dL4}h1@f7SKc8o&395e8 zbF#i{iCcgN#5hw>*;Rd#MderJ&MZZy_h)jc((84D+&cOyMU`co{vtsr0;WU!A;8Dl&HC#B2y9oYC^LVVH z1sX#G_Hfz2(5pF*-fk`U>`H4gypC_20I`P-m_Tbhp-u# zUdA*S8jlQ)bKtN;pF~0?u|J`Yv*1OkU9rfv?&hi_Z_$W)PZ~y^s-_9cov^pq;tEYg zQ={O`^<;QW9*;xQbE^cLEa1FPK`+chZif;&fJ`afF)jrV*hmlj&Lu1LBcW92c1d69 z{g6B_#^ofxOl0JoRQH;CeHQ6Gb+0{vKN3UPOMlG*R9=ycOQKFV9}Iikxrar``EESFNeyJe4r z`f0fyred2f*S*w3;L~QDH@kCTo5mv#0kbsUDIRI@tMIX;Q-8#SrB5sYz}M?L0%$3e zWR5dPuDmgz3ukF&;l#yjj%%QCAP+R&2@G6!jP`ebJWb%DM5<`aK4|eY$S*q<9DiP3 z1|1~T`#fw!i)UGWs%`SAeZF?z>fDB9mWpb(X#y(Fxy()bTO4oj@C#{f0mTJoV|0UIY}b-i;Q{JLs+0;0fqvS2}1s#Mxli+&JOEJdEI6bY@s1#kJ?JK;M| zmEb++*lMSfm?$(5u9lC@_RJ&TNdZj=dga;kHWpZW^_XUX>eqXf7zQLN7_dfHFq_rXb+iQXn3;ySsP zp;PD6oHq@!y&#tdxC6~q3Nqp+iH{x7iR?aF))=*jhzsn4w_epe!(2t_!eA@p`!VVqliq9UGPJL76|n2i8usoT?IaOGHcs`%sp)?+4~0c zcA`A|;2Yst>4pGKOr+intzVGIE@TnzVHQmj|J~Q7GJCl&n@a0^8^EgT4Q5e%N9+pU zn7*{AGUqb=OcZBkqS~u!;2qHQy%C<9 zJ`XiZ())uo3X_trGW#hU{|p+Gvs_2Gl3|N}b?S|910Z|Ez077;y4=%5zw1XTpQxwz z?-6Og+5U17bDh5wGaMRqi%oqs3Y$`cvs5QTHHtpv82%bl{t@cBKsI+Ceh^tl-I zp7dh;U6)=MEE;w<&K%t~QZsC7d@J-uxH#Pyr2S%D7PA4N|6GeVL~MWb&k!lxKXKG3 zo|Jv4H!r;>QO~aQZ>bq}-~SBWtxr$IJAy31nqkuTeb40n-=I`Zl)5)wDkb+P$8|Tl zQQDl&`ilTV@*TPVm(b~S`v0DOg`(4)RrSy7ug+EU=`({~F}-h^2rMi{-jx0^HM?X| zINP9vOyDL0bZVNr^?qgK_<_nl4CuKh{COg=91RoBgB-Xi6*DRf1NxK?D^r4%6$eC` zjbT?>w=Al-R$M8Ld`WxALmnAcecsmr=7xU2wKhFv*wnxQTaBpui2L9L)5dkdBwUfN zSb@fE5VOuCMVRlhyTgPP6eE{{JOh$h<5)A`U{NEJYOd|R(;D4LIwl{arSP*V|8yHH zTpMPPQX>-he5yyd_PqlsDL=)EoYs7dD26@!7dNDc;hoBvqmPcd2j6v93>w)yyRjHn zYM2WON``@!(iO}V>-*2$O(EY&S9#-O0leLq>d!@NEyY*k`*0d9doV*E2R5=l9er@@t#C^EvYwRUn|scF#VRZ2FU3F8(xnbMmQiNI zyp9dfT!T+TbhMF)(HMAO4B|1L-oMMIK-by=-ROQ?21}7L75$&mXcPG4C_Wj+IWLgJ zKFG}s@)3qW?KVmCYGJel9cBrN=k95-6FVS=v)ZkXiJu_+h2> zlYIjz+&h);gI=dsP>;gwAZedo@y9RU7tdl$^3!bpa&wDWkl95vPwMmU#yuOzQ`q!u zzs+niqsO1-_~)V)vuGf6X&gg1e(lF0x^QA#n17CB2zE7)1}!FM}IAC8yZ^`%uz zNq8cgAxHFL<}kUdz|WX1@IxMo4qjlRQ=BQb+2R~g^GQjm&q0v;J$S0QJH>l-X(aTc z(hDKl&UBE>#_3poqZwo1b$Ft&>#6GPO|ueq-?eH9qCU25?K<5_2ALy7 z(W_VWo3vKHR-7w;9n#{I7~~xMYK#TE+iWcvkL*>ceKoC=W*rF)!dl_>q#w{)5{ujz zBZ6>8-<<@RMVx%@_ITunqY-%gXoNl%S%6%i(OzSBEV3!#Cp;oIH5TMO0qZ7PBy$XB zY>gH%r(!(vFme_LWOwv`*|EV84^aFbz4 zYW-Ptj=K}y9!3xnwm4#zi{EryIPR<*I<~ti96AhJ!-%uT^rGh?5_cu-Ftv|!EJx75y7L@KsBCX2$ck4W5R>9Nb( zu+GYuPL#bbwzy64$nzsr>MYXS)zQLS|FlDMnr4rBMref1(Dx&h#3Nfq5QACN=?ESF zne>Nd#IWG6od$m`wHL-Bd!X0y;zMYyJ0>COv<`k@*LTDK`+2#4m1C7^Gu8KRXV?Kg zvrRTJ$GhHDi5oRc{J=;2vgKUGPbKObT#2V=zI!?&(LN)HTF_Gl$Hm?d;?#5KiK$P5 z6bf)K!?H?f9J~TZQo}6h&IMSydTC$v{U7qn)Z&t($&pIvb8-~=lpKXVospiS8IkZV zXJ9gBM7v=(OwrlR*ZwMuG?!51n>A z@{?G0e<5GyzfL@tfT1s>bkYb6fljPJc^OWJWcQLelX~~J9Kwhxr<>%@5;NnmUSxpJ z?vP92F&vLvgZM6zx1co&;s)f$8+8j{d*3GOOSyO7bW9Z^K_e)S`hgc9GK}?)$ry!E zzW|qe81d)-m3uKgWyDJ4Yh0dsCI z`z*~pP3AaF>dk?MfH^-*a}tdK_)DK8${6@8FJ_!3LYcT9?RJf5cgx;bWM|ya7fs|N zGPd;K;>LWegm!mX7eNFmnR!W1R`i8pkzXPP3h4MV_&bIFHdKPWKS_M#08ZIN&0;aE z0(!cWpOMyk250dQncq#?H0|+-0aV4FrloTc7uO+1aJjt^kMzdBw>Ksqn%1eAutacT z61{0ok44@c|K1*=K7ON}+9vu=?}hTsM`aB%IB%23BCUu4>9HSjz@L)dfxpP4=$gQ! z;;T;`ke42uWI;wNBheF!@azlC2j#rR1>W9?x#tJj#JfGRp)0>JwTs8E@yL~XA5kzQR*8VQYV|5AU~QUG>FiyT9SKr`}{m2xdkKv~|bkpC(_=jiq?mb1mDdvJ=4dU)@YnT4N+7@Y8? zt5hKmf!AonN8~iqWQ_O{vT$0wI_a>y7c_7uBt1N`QAy&fK`T5_)Pkj>KD0lakpZ%xQsE9=&P2hf=0c;rUx9s~H_c!Wjv*>nDNavN&4 zq2>>CXbYbr4}M@J23E=Nq|!KXdu__u^C$&Bd5QX93PP8ZyEL(YV;n#?EEx0waz28!=CcC*r4N z3^XUI(^1@9iZe8g&^SXZa{dkCzaII($YDjCf%5S+aT-IR(X8Lb3-LzS!JC;|yGkrka);k%n~9+(o~`pw`DC|J9ud@9dAqr}eSnEb2>6T~SE} z|I0mTW-Ky3cD2es^-*P74}WY0ygii1yrS9xRrdIG(AlYObhXMBXa-UYZ$K-eU)5;L zJFRnh>R?eVQd6W}9iB{jj~4b5SFy74zT*cR`|+$lw%f7%SjPZK<;2pimEv_`Vc#>3 z=&^%hdw%dd-vvCH?2qu4$7)E@@Yw6FXA zbc@aNQjW{*^lVRe^eq-yCp+-Hqu=?S%y}XIsauw~XSmx}P(N>z`ka|i`+={46?|eO9=SZ0z9y*2g(^@%SVa*vXbQc zTO17oPOiBsc_+%1|D(qDW#-GuF11_MRSWo%P*ERV5~>Z~Lj`Z<<bd)9f?6#PW$9*(MHX1COv>@lPpC#8w}C zERQkQ_h&AdIr^a58I6riju!ktA5Bv%X^wtP@#RB%&J_i{*?|wp@n}>SJ z?0w3Y3mf3hjY_zVg?KvJ-CJP$idOp zFe!2c_dD3*52Eib_tw1I2RM!~JtLBNF9%R_$sa?{+JQGVNHMjFTr7kB{He&c?n(muGu&6ZtX@!~+522h75M>AHz&pYy4 zUuAz<ut~SwZW+~$)%9~}vqp8p_5B4) z4n<=lGe>s-hTIC%sBS1FsvmvKKHX_cbN2HU&sVae%pe(MhEh%y4DdXBIVIJ{p05;7 zy%c6s)>gbQVBpaM#a;zqAAJ>Y&{q0HZNR-~E^6COv1My3?ENYBy-{`>ZBtkI7x5-B z_xRMnPrL^QCbMe?G(115i&!wyOy}R|%HBh8nooITKJ1&c&<=6nOQRV7(pmZCvBLxG z)Ylt*jYD?W*MR3mv&Ba zt$eiIx7(5NNm^Z6^{f`{e$5_}nG94KnKn+*jtMP9(A5gf$x};Irz=V5^|wOrJOa5j zhU+a{RF7hmC2=;l9F{&?1HD6_^8J03VIS7VO-~+R6z3?l44+p5YuZ)A zDY;{e*?I9<5{-O1QaAV-?t{>I>jvlH>6;OIedH;!DU? zb6$KJ@7^6Dc-oGq?h(dZe(?!B9Ug(NZHy?RhOcGw^|ANN@KPAlC$^s-&(^K{X>^ zU*z#?C9OPj-V^@$;$OlyFg4Cal z(@kbqaf{Bx4LCAqfqI z-R*$?qxLxXh!dxvkGm-s>+rsz>WwCGn~zccpqjix6Qx7QBGb?54brywrWWFICqi$i zTI2Z;=X%=Rp=#YTw|p9+c%`_$+Df5#5dMhW;=;h4))|4TtTMC|(Dpsg)-VH=%vU)_ zd^#)Bv%AtBWRxq$+gm^I4fO-OfSA~V^lMbMJ`Ycu5q)~y{YIEUjH%nr&P@$) zbNS$iXPeL5&+}t$X3;l38d>;P=uJ&i3eDTgrzk2-f2l0<&D;&O0#F$BfkB#E2dN#C6T`(If$p_a!?q_ zvz~JNI#^tdZySz18v64Pm%+p9#wz!ZwPLmcqD=XGej4BRrl-)GSjC1n-9N|o^V|)C zh&3(T$|^ge8~z{0G>b2Wahgu~LEP9iTb*KG6^c&KY1IA05ShDq_}14xcT#Bq&72vH zyccsNGU0l@B>q~^DCG^5R{w_U6I_&Lb$f|^@52nyC1{s=Y^UI~udYXDO+#!BCloSM z@4YW|(aNi>zX)i17Fh2BO>aWHJ6=-Tcc*nUc#TWy<4r_)ZWL6$X}6=m?-+cgVY&0H zI_xg+9~nw7*{7xv4QlM1s4>%TzxcUxxieWdnY@R6t{1ZU&Z_&|c1TZZtvnp1ecm^^ z59h^b+q?0^CTf}xx0vpl(LCKXvssXzb#xsgCY#I+RB<-REPs%1rcsSY&Z?_+(!QoZ z5=+Rx$G4Ia7UYQ-e9Zd8VSRd$%BEfjV(h&qLuoFX)Q!JUTv<}C@Np;=_i4fhA%iQ7 zi+-Dx;;aT&HLe}FrUGwY}^sNYA(+r`xt7CMY1=ZG~r-PIqFZr*iNIH)kQ5o8#xq$blSwx%_N`H!Vfx z5`{4h_f*%Do{VAlU0jgT$!O$Yce^J`F`*4HYh1iPA(NThW=LiRXH)!iKDVMBzOe*9 zw9cigrCN$Ep`}org$RuD`?2KrmdbyYq@|Mom-?G0>YqXV>aQ4LMEy;jS#?=UkSBYS zpd8@@DHA@BQvA<=?<5-e*@zW?*N)T=JC-4X1-|jL+6o~WnTu}_rq<-)O*B$IBH()^ zcC=;jRlMv9V&`!^g}#yLZr_Xh4{-fUCi)w3HkIa-+;9`lRK8=AA38wCv`NO6AGHwW zM(&w{o157IQTscG_Ee_I3~cG2%oM1M@nYyV4o$!gt1~WiG@omp)Q6L!#BQA)oLl>^ zmc1?UNNmjLb)%g0nVPBp2IuQq3ac6AMuwd~Yl(}jY35-+ZgE_3%BV8G{Ds}ON)7dN z(YEYabG?Pc4!CrwyglfbqKE$ki+Fts_#{A?ThOlI}n&=wq{vzz}Ox&%o~ zI2>BjywftNj_fkYdVFg*nuvv(J6JLNyl^AojE4TT$R(mqjHN9mnth+qSZ&n;Ur8~XO1nlot z1K|oX9Kgx6778z0dSJkr{`GNM=2797H=E#nbi@QawH9&=crR$Q*X*aRx=Aay%4P(%y28a8mn*@;53s=(i=e zf``n0j_5tOQ=6xL$>Rq~Ju7tcPHGUx-5XCz0A8FOsI4!PS)8P-sbQ6e;bVulT=_aK z;@9RFgJ>PTbQR~6#VRC0g&lIEOp=^yabA3A$mP5N-^||aKNuYzx~}#Kf0jGLy}0hW z`UY?*Bggx%uFY~g2lecmo;=5jV5YFJmT6m5oxY#65qa`{>VaaE{qYCI!(OAg3_Lcd zKCNDdFAiKASYT=JP&_`ZmKjM=S%7MP4enCUN*!~;;>vS>?-^y373x{_i6fuDmN+oL z=^;Nj*b^xQwJz8Zj>;p7eoLM!zdGNOUz=(3_%j8;O$4*&Nyq$CX|^i^B`TZGlv?n2 zIMm=-YoYYi?t3>RV8nLcpQ$I$@K>xq<;kyr7XSUg<{LL=a*KziXvhKlrZ}g3m*V+G zd>{K(12N6PbqC%_xD$a`{sx<*!ReNUhZGa#aW|#!?X~Go8s!XWi$m*A&Wd7`&a1)wv^uZk>5+M+wKiQ(DMscws^yfr zHv_jsa181-uj1_Vo1W?R4FNKX2<3x%?W^ilcr(Ke{lQJHpjsps(3>|vYF~)Y@(&9zmq5B@QnI!_1>ca0C#^+&!dkp!ul!)bj?Fyg94ug5Xni!!nrm?PqZh_Z z^SK%@qq=Ir9Yel+Mj|hU2-jnMd93gH&`YpE*8cCtz67qxBmIBgHzy=OAfVw;0}~-ED2V+ko1FN2Rqj z6?!Cy<|Qcke<#5n``_+w^Z88Xc;}s&_nG^d=lPCgFKDgL3TgG<{X93UR?hj5AQe+R zUN1dJK>J~g-yyWKZXXBZgUwiDmYoq`Y)l&8we&q`;iJW_>00z&nq@CHO!*rv6Tv4i zPYyGm0wtq8`4@SGX`RnYA@P>^H9p9Dy-YL`yrMJ|RL$Z4>mu4!l46CCx?(H>k_*Ncol&-`) z*hYqo1HT~+?Rf@mn|^3b{J(N`3P!c0T3VJkl=W zZJ8ixI%L@cBxOeV0?v#g+{(!3L4D#5$9(%d%oeOuul*GDA51(jm)E;nYh{>7UBuIb=*BQ1>@!H2CiZj?N*= z%6zQCDiw_-mM01njUU}s^U_U+=*p~8Xf44gHxa$;kmV!bPMh-Nc(O(3jep3pD9;mL zE;sGpyj8cmzOarNDsD=zN~=3$2^RnnI&vP$zqz->g7RT?rxeW039|M=kASEQxwG<8 zuoh*~#0eNNBwQ046VwLo()>4UOw3`Nc(3nehWa!m=%(iu{9DX)%(QMndczKk_0%PA z*aB=P1omiy-vs6diXztISca${B+$;*Z1T5=C%p2&)^xwBzUHF zgsuW7faQG_t{as_nQgf;#q18b3#%QGcKR1%#@ z)5EWaUth$td9S<)pwKMTv7?|NB%Ef{!y*A8w(MC{+ekIX_KRH2Tzt zN+PE6P5$6)+;c8-o9f;)-Y_20@LN1*VCs9$&5g0ZDXGm)und5{4Tm$yODE97AhSVh z+X?9yx|h1mkr*l=%hv|iiH8ax6%vD4nTEu)iCseH5TKkgk;m)NgY7q5^h7?QdvLpm z&y2ijlR;_aDhDt7Um!!*8Dto$RxkOr}jb49m9HV8P44{L$AlGM>eM-;EN zG#ks)$&N@`A_kXe#rZd8q}2gcu5zbF*djYg?DbR|K3Rs7p(XZ6;zIqcruAm;0w$Tz zQ~p=_%3sY1Jd!jUdlI!uwF&xD0^R0%&D)Y7`m!1PgZK{AS~ zL6Mq(oJlA~uNCQuVuAnOBF$qUHAZCGRh4xSD*h@j?X-1;pr00!IuE|*K?*qkeVvHu zH~GZwYGn0koXqpJq;WIaH=|mo1|n77?)p^p-B9RfG0DEM9Qavodg||qL+LI3-RUsB zmw`8sxwc;eNmR)A3++DoFiTWBVZ+R6T(DB6RdJBrRC-q(CVYwa8)$x%SMGM616?K8 z7?m(@zdDtZ$s*f%Ocd-ui$p6o)3qgyOYwgq^x+%j?L?SjC4(b|L<9SV$-K@P%)FPV zj8&N1)IjZ6cQV?jsE6OlKQsmBs=SU3JS`_p1j-Ds&~H%$guZhFeDNWS?%^qQ`Q=P< zCQd1NvH3-J`tS_Ah(R=ON-u9uaXW3;dCh4`1`=5s7h-@eJakM*?1UyD#0KQiwEK{F z3hWVLagTtDnaJpb;CJpa&M>;15w1so8xxfmVW`&3G3+s1HAEEeDY{xTr({pb)sl!( z_)0}U#wW!%w}fq;QVq0Y%m$iSr4dnVk6>PKZl_U{RNv$1qSM-bwXy`%r$Hst9;iHw@^M(5xgxuYqNU_hHl zmg<-U#>!8a2K_7GTK6XA_1joz>2FEX^4bX_(MeCFw2KJtSr|fwq;ma9npWA)kSMt1 zYg5{VyZ~#2GD|y1KWpa9P_&-33&o!q2jm{^aolFotBV;`VUbc7)8}8gzgH@cxWYnjYp&paWq&OcYr0J8swYbUDDi0H!of$x;-J)x}N4R1(OG zXGZ(SgL)%Dt2{c*6b)!CIIa{Wl*DE=36r$oTLFPKJx!CIo=(URCgvDz*U))lswwtn z4&pxEOSY69j?+>1(~w5m(vX@5jgk%@*%nS*Q_$`cJ_%18y-9g|Diyg~-aunk_wMER zlc)^D12pC6JSGNj1(6}m9N&z&DaJUYR`)S_bO`?k&;Ko(cU7y_bvvu?h33u5+{XEw ziHHLA#B7hRDsL#R-b_< zB#Nh$I;7GJE>XFQNEU2S@5X5u;k~R*)9$X96u*Nu@L(*Udo+sW^=fT@NJv*i@ebU_ zSvpAyZY;2~bXOx5CX&vh;JEVbd_Lr__>YmbF*JNSMv!0`88!`L1d(Evkf;V-slU$U ze{-G7+{#o3)|~_oE$4Urf<(Wiy@%@F0OjAXjZy#2mf@1#z9P!HG&o8E7cIv=^vr?pu|2$H z5kux`_hB7AlM|Vk(Hd^f>Su|>C2~#SDpqH=`}#ghG+f2o0#AsMhKMwraWy+cSM$jK^iwF4(3#3mm&fRBXSu1Z4n}AtUCCm}!Lh4q=t}4{BPkuJz z%SlvzbP4JUvt{3y4@BmZBV(__UCy(%2yU`^JXiUwi`Guxw@`NSoV9i?ZK-OkV+dXCra4C%A0A=Tl1@Pk>j@FU#Ug~-FL^>laCM^;)ZXL?k-=q0 z2(_Q~gapE6LkP83;>#%goVcOJOSeuJ=!O$efd`X_(yrTSJ&ySls-e6p>3EIe8)U8%RxktnwuYHpdntosTu`B8Oj$Nj5*^6jIk{+9PmoMa_4tW zN?otO7{L1JGdfs7xUsVC0%T!ij#MGe!9}lPfAzA)xA_q4*EOU$SjX4DQ6FLE>mv*t zq@10$Hl+14%xI*|0TVLZm|h3OuK7qM>pi^nS4jOyz_*L-0k2B!c7D{j2hxWLG?%{T zcbgf^bDY|sWAg4f!%mP!nkHQn_ty>l-HHXN;>4D<`XaTEo@=*+&;{YE#JhoNT;#L+ z9HfwM6uF(J`p}55PWGfj<Ayu5yNzh*4UUk46{ z+)xTsE4BS)v-&QWkd}Aq4~6ZnU#EGz^*Z;)hx?7VeN0)cdDJ>5cTSEk*7*fiiGi=; z8NjD8Fe+7Lw7F8GcI+}gq91Dsw@k}z4kM~<^>pt?rBT+Ir{n^kPsyZa;2#vn{R2cY zae~_!>`ug;0Fb0lTxq?CZ`=v0ZP8R-pjhnpoHZ_lZQNgu?>i)^YXhqAMV!S?f_%g` zp4i?R5?oMp5MFKv!y;ZPT}_Q~H`!R|!!l!8!#g&5Cz`L}EgL`KZ>_00so;PJpd`j0aSAIh&dhU8udD>h5aubWxb zvo>#dcPr3w@>G>_gBhH#GIIwgw*OAfvidvkEpfEGZj{Hr+BiAlHA6^lBo~y-Q!TX7 zeejyD9QD9?=YCMX|`@;()MX!GPIcrbBX&WZOUamy1a4$0|uj=nDhr#m<=Bq!KFZ`|97 znv>^B4Ln1pfu|H3`YSgVTMU%T`iTLjA0|stf--}XJ|s7EJ2@an$kdsg7WBt`$7udP z{e_6>9ZGzZk-#WmXt^o>m5U`>DgfAAWU-8C_4k3^3oZZe% zrwPfsdob$3{dgpqs3kxr5#dI+4{u8tdIk*SkIrdR=#4O988*Yp z4g+qOnG93g514CKGWNswrUQ#m)5F-=`_d%vDjKCx;2Mw{E5&;)X!(!>L62KKlZAHX zb#C};1?|P+>@2>6#}_#G0^SAeiBbBUwvv^+QQ=H9wDN0KYTIQp#{SH`$&fGz>B+_a z=SaW#9=S8ggc#DcmC+n4-M=!N<#m}#6j~rSd*ZrXH17L|d$KPsEB(YqOKG^5gi`+E z0*=%@MG`Gvyza)z*hWPZEu(itSUrQ5RlL_*(#>0@%Z~qA&O^;5D}5b2-#?ac#66nd zIadb$pG2-}|4Ru6dE&n7iCc!a3x6%)XEwfawN0R0Wn-09Hl9*$+k(FIoRlcH!ao1W zCl4Pwc<^B{c)F3SxgGM@U8JC(U5!=!BsG(6uD?rffT8WCV9~^9Yx&h_&8#h%n97 z4}ej4485Q1G5rXW!u*&%!jxVm0iUbtn>l!o-`#Cn8_QUk*zlGq`Z=a4`ox9^)6_h9 zl`2zi61Rm{kp!o;U;@tlEpF$l?pTanX(k}tA^fT}QkS1|6)iT+^rdaxz<~+fEg5LD z8F+fAPBQ`L7brRCHROtW*d#?JmlAIOVcM845-?n zTNP?G4a*CvI$L+0JF|t+HK4ZL&be;XE;(LR9&x^Yu)eNC6A)g7x|jK0B?;S+Vtfue z=8`S?*VOn?sV0(Ou|^}G7rFJeQ2ja_AoW8D((1y17ZPSs<^=ho&beTON$Lcuoi?HB z6tIy7G*5vGu?hWv@;c>p6A-H(C)h=O zK~*Gvm9?@i7hzJ4hG^@u_1QV0Rm>QsqiNX`^i#r7-Xk<`(>B5`Rmn{YtH$K-cdTU# zHH8^LyP#3N6+GQ4{;oo3+HT<38th7Z4^_#{2Um8Wud}KvvUGF&s)eh(?kCOhD;M^K zpD-U>)zKF|gcFWGR8^QYvXz#DqQ4f_MLk*aWR4E+MV^;|_Z~PI9J6C?8p;m$rUtI( z_#3te{RU14I)qh$4mse8y8D9)I%Rm(8mhmH69IFR_v__&`idJ`gl!~Yn>8@!X>g-x zD;0TmLp&wrqtW`I^+oH7*3VC%zYbXKQ($PlJq?@InF984m<2GjF89JtKFS~Hr`uRN z_)0m-`n@|S*NENgz#ew@0-d(2rjmeX2`K>kHFpwl^a{Fm;FbvBH}>LGFqb+~e(JffQTht3NW+XoM~0k_ogH5Xsin7aLSyra-MKGBkIb?*N5y(YIC24#u!$ss%P4uhvM{S|t?l5lw)uPv{VU0WJK$kaAfB*da z^YL!yU!eEoEWk)6zcX;xJQ;7$P(WCxfuNDipJnG+C4Wz$LIf}AhIUeKiK)Sb2FvvZ&+k6Rq>+EjlD zPI#z=iDX>7+l)gN7^)_5H>?dv`vc90R%sMbKBgyI*dAf(HjX_*Z!++=%ByDOZsVA? z*>hAb|J&O*UYis$(^8lJJxG8PvYVgEr126+_4kmntL12q)4FHk-vw-c(k_I+(kg1{f?aFk}l>{eT zu9NOdUSGN1Z})zVY`O6iW-gWoPKN(3xk=E5dy9G9R{z~$CPo#o3v`Q=!v#rT)YDw7 zZ+B_N-(B(EuM~_L+ebl4KV3siRlrcTNe&vh1HpHZ>TGPht2L&IH#E!|{wqx>^?&)@ zdt~Uh*8cG~5l=o8(tElDT0_Wrk4}QqW=2Y)qHL6Mj8&A^4>&_2eW+QsI~=xbSGZAb z@L(3cNc$x1n+MSL=(s`q=O-8sHo;ABJc9XKyS-Kl2{F-Ip;0?P&#U)p9mFT@8u~34 zlGluW`HwL4L3&y)!uq(_d;TVF4!~|So=S}vXxqZx6epO=lQ9}*395bdqJ#YEh~3aC zU8hGMxAcb4acmv&j$^+o6D?2eotHgwcrTk$V@EfpDp@^l{{zxTB zp!cZCTF%_|B@z>K0WgX|&bb%z%)K(W?!eXKR+{B)(ge01$Pn@B&U?$w+|E$F-6&0y zrLpa1@~tf(0VgH#yvuHt1glr3<1x5jr2s0FB28>6}9MX;N5KArR{LV!Z2VxYa<7?#o zg062;=tw*hI-F!M9gS6<(U^|K{qKvg=Z4;tTj&{ifpH5>KXI+B5BVmRrVT?>$wx!+ zHi`B@nfr_xw#mm+-m|Eaz_s4{Ig_zRrsd<)_h7^@XHW<9zEc%WA$XVR$Zd2fG2&lv zQ~916x3~e)FP=PmY;U73MjsuZ_rs2!Bn-d8k4?oo4|sCE^3b7#>JN-o(=X+mrsI?! zLtP79UU{9#;0irQsGD;-p$Gi7Cirp{PAWI`62yECF&}YJ|GHlKCiPErF~d7-^ls}L zw$Z0(-i+!~F#~;Zicqv}js$mRGfG+ubRD{}7N-oVQ+YxiZMEkfv|2$!o_970&>hP+ z+g~u#?^NSHD0=%I<9kGZoojnKyy`kf4nNN+lHcJ%)$}%*cenv+$Sc>7s2v_@q{B0jFY8LdqjyBj03H%H9UW4mh$lxF8jng3} z5gq_00wl+Hy9sttFPPK05O4(&@Gm~dc3ctwWq@T=)#?yVoG8}{IPpU{xUsb#>*ol8 z_Wau3wz|E@%bldaDX9o)t;UR60X%a{UMd%oOyyESlEsI39hZ1iqn~jJ?%-~M2tO?k zcyFRav4a)w_Q+C91I`FZFg87zC$}(ZyX*ZEpI+p zh?87(I}dHt7kplZ|2)?ZlvO0F?ZUO|eB}w$ukO5Ip4oTD%rV zsd-Z;(9+7yk-&k1JRVT&s3oy1q10c)Uf*nmzn^Cu zNVbU^poytuQi9|5VGN==0!s8_I#$xYZF!T3pBlg2GoI1$hmJ{f?B9fN+VAPuM8_;T zKG89YjstWYp<|e|Ar2Vm%!uG5GtQGY*husaD%&J|+m@c|W7(t;Ume}Rj~BE?*Nw)A z?;ABrUk7eZ>HVuW*QjpaJmcvJ-(yz{1aat@OzfdEbR7D`u=}WWvX|>8b3=1pbbxGi zJ41WPP9t<;v+lcZN+9Wc|6Sohw0g97F)#psXzIGjMEN+Qta8=TG-t?HP@P%xItDnPH7EnU{$n5As=Osp4Y+3AqhAC6sJ&zt@ZYUHC^@Z zzUh$g9@RXW0q(eRfXRo_bpBH}@g8Oe{8KdgMoJ?}7fMe$K2rM9F$Tydm@A1gb7B^- zz}XI-@3btnHO;6`%P&I-QT`d_vn2ZEuu*w7pUKfp*!?)b7+h4c<}!q`|B21wyk& zs#D^IXNqg~8pj(La?O8NtWItU*cGYkXE?>>KyQRp3AV|0@wW-{u$I`CinYW;ZXwO{ zS#O@N_vOI>rGuhI^f!{B!>wuMg$-}s$yn+Wmx9@eu}39)e*R$tXXC~#hjpyZd&A$4 zRt|EWqw2;21D47eQz?x*kb_e5x^W8>_;4lg(OYdx9JbpVy?1Mgp~Fk%AUHMfdgB$5@KS!AsyrRY!q~^3RAf`^4zDbQ7_t=0X-9g}ZUaV9 zvgawq;9j?}OGN$Me}k(of~>~UVX_xtp(d(x*TT`u4& zQTYmrpTRk!{*Vj3A;C{~zE0L42BHskdPX;7{%}Vxa1gxr2CU|4j7s1fcqvH{mwA{e zmvT1GDH>$u8l``w_iHdfZB9Na%-;m<^W;qq{JQ?Bz9Kp@z zR4PD^9h6Ihv0KU+(0uAul;9@-voIlu74@_t*aF0vdqxpPc1&w2xUp&P&x<(#kf;3j|s zJH30J{D%2-<`yr-l%4U47xRhAwn%Bc^%MODpJFyA(Gko*s47R|kYELhB1CSA>C#%>atya+U7sy|;PzCc2sqt(q-zda$}6 ze+`6I$K{`GzTm7shg2-5Nfb1Sk@LFKbX`ud0Su_|UvOrBx^e$1Dpk0D8L;y`blp%( z@pKfp55%a8hjhhYw*a*Fi}TV|1S}b155X9~yYhgp{Io7B(2@TQL+h0t59sOZ!L;z1 zklxVkyxOg7h&8I~c)+;kwZ(cct!4vlbVoMD+L!?hg=Emsi;EHKk&huB+=er^KQ3I8 z-YSR|WIf@Jh8UY1eW+pTvFf$S|6k?tDlsTaXc%kPw@hM<*LA$)GDZ~Dk z$qt*_y@r5h(uj8Jl!1*A?M;Q-uwJN!Sz-;#1m9GuW)+Qd+cP2uQbfrTZTlpdwtaG7 zO%IbIwG(yS9TMPzp!*RQMWUs*s+GaA3vbwu!9t+JI+oLH!2}HV9MTNCjodP zU)-3>=C@B$s@o?k*Ni>e*z9og)a_>{L6g0Upe%&PjD7TK5biI%+K7^>P1$FGSeQW~ zU996Q^q`50y*IZ#g{U2b6t?F>BSqPM)nv-vhV&6XpKVkV@OlH7vE5d>^R7lXcGw8d zC4n?Nz1vFpATQdaeP0Wi4t%e#H5suKjVbtVX~LIdO-ysAW3wVdoukfBA8VYg357g2Mp)!aQ&ig5s1>-UED-*TE;N1nnhfAo zYG_L1t*<*6HUm5$S%;K->&G^0)CU4 z#5Sruv=4HSWe+uyJCu&}E405-73mfC!`n!)gwbhOA*H5@rljsNBQ|YE;6*lqYS2nm zYv#5SsTfq$+F#Z(Iy@y2Z8(u+X&8;`i?|Q`pe*R6_TVbaMGs&b*JEse+=Tsot+;W& z!(6!k4&j}2ZSEA0-QRJxPI<^gYm@1-%7aG!qoMdCcNhd^ZWNs;n`A{xk&HN-YZ(R=J`6Br>(A|i`m&p>3F zX)PjQXG@@qLVRHx;E}*S6GX7IBg7m{h#zd4fj_m8U;wqhLB2BBXBom$dp(cvsEvg9 zu&Mm6fcifb6Ct%hd=YHAe-TsvOM%1(w&4cw0%4oi4u+7 zIv-G4Jg_0~qNHAWuOfXO44e8_RF*B9Te-Yw*>Y08Z0RtVxhoczRhi04mY0>5S1tqj zA6mR*anYi(hsm@>Ws6Asyox17%i~Gx;uRGYaU^3R5mQ6cO6jw=P9@?m3W+!uhKApP zoz&;{oit;3ZoyckC(H81^L@#LtO;Y4^OlvBDWg{;Dl3YX%`dB54!19fuJk3PW209n zE5{{QMOP_{yw*IgwP;-Q3Q}3NTv=LHykfrR1$-=v7NJJAV!+#?+C~085#d20qsNa- z8LWy=GClE^l@$w%%W?{I8B+^qJ=$jb`PMyPgSK4%vgzDMpZ;^pEBkhC-t_c_1MmIy zwIhd*pZfUB`F~xxda2pXIqu&0?x*$-Y8y@;di%}SU$m@!ruwD5yM`#^hNeF>B6W}= zupf`_=R1AU%*XWkS(+urqIs3epIWu?g=fv%x9#3j_kQECcMk4|Nh&KA3yxZ z7oS|aeBmMpU|6y2$<>n|nLA@bo;EXdV1Jo_l}ICFhQ*E>n>Ku6t~z_lv^ldMUs|)t+`Xaxs%gEBV1s?0rW2Bf&H9(0=>zz0YXhrO%Rnd*X4? zaGEBy9~j!dshg%p4SnuOdj=deG=OD?Qwx5E`dL1IG%N-D3iuhGSo{$Dq40-NKVJqQ zGK>%K3*l$`-WS0yqW-@3W$??WzwiA(_yeiG?|qB}Xl=eE7^6}t`GKb_oHikIZf2IY zATw)j;na+&S#zgNESxz}o0X}=cJcpznq4q;ZcbK4X4aIkO0?}ijpIq{zemZ>n&^oT z8(kXr=LuzIOwE`bUHT}E`lq?kNXn!n<-GF6<&{Rb{xqg`iZ*5B>=aLON~Lmkbk(E( zN8Hr^DK03LGk0oMe%6GnsZ(bD*TSL*v;Uare=EW0xio1Hq56u8*hoT|q%6==vSlw> zu6(?xqP)~oTgpjAB@4@z|9g1OZ{bsBcnM#MAi> z3dS$GR7q*%&2wH+c?ELCnL66E$TLndyg_JH<2}PRE5sZ_+<+QneEG~8w6y>_l@S3y z0CU?KPZto1@FsCHV#4zgv*R(h4WiQ?@ezoKFLBeZgZa&kxy_rt6zTi*rSFII{gHkE z(horTvcB|XNI$SI{XnE2g!JV|Uyk&H`_d0a`XPPkBa71i{Z~?4Tx6L0*rRi1L%MqU zBh#i9PMKUVae_WCH(Qsf$rwK_eaxugsl$@uhp3bh3b~)>lj&#t*Wa+dr!Oaqo=7b6 z|M~c2pPixS7KvW$T3{OSX34Gn+e`PQTCVuNaqQ~KfwwNTSz4Q4NyvZS=hW)Dzlf5K z*|rX7+)^t0U_hs`c0tb4hTC6foL>Lb#miwG-(6cY`RK*2k2hRc_sEV4`I!R?OILLl z-~aJ^*>eSRnBdk5VM)oj0M{Kq@$;W37pFfaE6@Kf!*FTY()q79eaCw!`yyX|e}iB1 z!lS-#x(*y2QL&?5^X2&ySJd4n-@Z}NlDcBf^{g-azPvhfT+^YqlUrlPlCLM5Cx7)x zzanen(XJzrs&j`Q*}47r7XfdcI=1f^8!NU5=GM1L|1tQMr0&_(ONIsJ8)qCEQ1s!r zqFMVJ z?);;*wrtX^4}#i{o!+$C(s1wkfNRCMNtZ)zufDLkEdOH9jH3Dp|C)Ss>~eB)|F_8} zE@r%WJ@2dSE#nrQYkH%n>&puZZk22AwJsj6v&?_TddzUSGKru0{QzFt+rls*^dHN5&=(ZBq=zkY1T`PR6o9oE_-2fq5a z|G2|5*ZLh9nm*^$2k%rIKcifC?5Fn+H|~;t`#x`1bKUYW*_Ybid!l)7NX!-fx_(zH zgCr$4)~A=g^zed3eg|ePSS9(w|GT|zpXwp+65qOgqNg&e1MJQF#m^c$nSs4$h2@V< zFLr)5zs$UJWJRb=xNz~~;TL<`5-x0Gmt1e??*8TU3)<5k^uP2%t>K6L zUw-+Q>ZaGuooyLCrSp1$WB!Sz`O{DS^_uYLc>T!woXZJ*E&1WT@7>MgjWn#{XMFUF z;rg`e^AG&;!s3*br^|Jl4;OtFwr<|Zn&u_ZBfm9H+5Uv|b6&ROL_YEe|0wH3+vHM`&ttRy!-X++Ows*V>(NI+_Qhd3g7BQ>{~*g zJ>y6EcWjt1S|*=P1W)HRZVz5{?Avz}>Yf}O{=Rhg3(ed7PG9=|gI}($j=X+Fa&%N@*;)nAVG`)Lu z)|ajGB-hpU^p;VD@1A_?@B2=Cz2=Mh>|5@m$q}8WPCa+__@~L$hYSC@|Hxp$NbB)x z;aC5RoBs9G#`&$Pp{wQ{K9*N>jtw_H`clG@_)(`NM_zkD`ce3G!K~+hVUu>$xz~8s zBbegaVbSl|2aKREVhuw^Gio2K4SZ|*)+IE& z?*}*#(EI${vM2jLImKMsdyvc)>@6CxY(ApG}s4)LbE|9$>m}G-21T~1(&F*q?*Dh=3K9 zh7CcDVp}BCa;kG z{HKvrXWI92t|=vQ{V(+xjbh)7HP{Hx+V^>6Ef07>n{hC6AT zh}ec6k*w{6zKPGV$!fF^pMzfJ*aoaNv=&KkKkbUE8mW@eeukmx$4Xwg#*dd{JwHft*C&}Ol6A*;(9^q*4hz__goYy$*+ zy90e&M4#83k zC|8-qHq{i<+1kV1c6sJOW)CwbH$d8mm0eWwrhz0`tz-_%X{NIb(;&1Fq9+Tq-kfrx zXN(>A$}Th93B*~>&}RQe~GplgkCFc|;ts?evl3BTPgb)1gwlg|=ke}5;){qcB9;-$h`&Jm1>yn3 z1GBWP(f$)Rng8=|#(D_}Ghv2kYl_1cEr)?~TZqYR{H9-9zxMUbz@qwoZ3A81*Ep{& z!~7Q}HgE&(2R3+^8Hw(sh6g-vdx(kVf6=@JrH^@dz2yxe&pR^T!_59FK=QuvVU@4b zlwqA0GNuawGVPoXV_nBa-t+`4Z`2f1cv4(N>zmQKA=-M~)z&qoetb*6c?&Ty@Xl2C zsb-4d;n1HWb3wngc(3+7JNosbSHI>YQ!m4uZH~3GF8Yn7b#oIj&b_p3S<~f*H^p@k zqxH)3%!-^uq+)Y)_$SBctTWr0JzH(;CwnhHTyr6SnJ-`(F9)J;nNL;}etGrXmB_n~ z&CDmUh5z`sca!jrDg57W-;L7R$a=p@mx9&H+f^{#fxSst|ddv zburtBd|Anrn4Ls!7*1&+rhLil(u-V^1#|gA1a2wycA4ku`%@aCRB9F|6UE6{Xrlpb z)BvX%rqQ|+ar&wEe7;LpUKx4YAJ~MaN#!+>r;CB#=Ch|OTrH%iL^au#?2wH@!uMqd(otKVEUrJk8 zDsgfGw>))8AGg&u?58DkrNFbv6|#EfHib`b zL}{&)7`3Hw`ZO1jUmqgIiKU#L$etn8Vmzs2+-j0H+3j+V{cWUW6J0mUUl&^4=o9F; zK)xV76z&&dh|q$N>~))%m#aly42LSh`j&+JPcD!d>?f%%wn^KXCK-DfHqE63lD*{H za&vy5T&z9KH5jNVj*j<~l0WT~l5;EF2g&zv@>K&-ddd9l8< zmJXw^hR6nm=!MqUHJp>y8M`LYRklU}jA_5e_g&qm4WE9b{^%DQPsN`)z4>%fK2gOc zq@+$U<&d_6{h$zD<}i_Yg?WRtMxXgSS2vNliOc%yCqC>vb$+5u-;akxg_%PTo)0qY ze@aigAZO;}X}UeGq) zSP%p+BOe@QfGJoLdcjL%qR@ZvOL=ymR%Q}7akh`SnNyf_Ca>_c>@DhLvj3oYwb|@r zZ#F6HQZ7$-`cBQnnY%M!5Me7s$P516?m@~5u!(I z5JX0fJIc%Z+QJu^5=Q>PZ6yh~s5+$JIm!~3KuCEe29E=Im{Bpp~B97@A~8s4jn zX={lw6FAGERwB168o5EqaK?FvJaaf5u}0oEmKJ$-hZ*_VK}LRfSS6nt;!QCn^oz7% zRpiUriaHV>R2ccXk&!@ww3IXh|C@mS0<1i!;!Hs_YDM#?ecg2(~P%M_E9=5NYT_Ei&Ry)%q1eefCj4J1qK$=Luq2Eh&kqCVoKf;i&6_)qP!B(Yg?H)dzzEC5c6gKHvvX|bto7ZueTEQ z*LWXmQi)ILCyF0k;Ae8ObC?%>9%6X6o_jie7yESFF6QajU7sM2Je?~Nxj<1(QJn#2 zAWt365!FpKt$OiGiO3HQh5~EkIMqNP)2n`#Y>!2K%q(I`#cKa3%wrBSy_#p)9qMO4 zxRVzAhx)>F#;0BAFMe!OgQyap7H5c=;wMVZUV^pAPr11p z?aG{*$X$4f?|$5~K%6b+00&>_Zfv$5`C9KEX)msWre>p^59On|Lfp5~lnArVwkm`AgRasF9Xu_FQTH zy<*WX7CHUY^>o*{cReV{?6X@^0!vSM? zlj*^5$TzkKd>%&j8|DVa@>(EKs*p+i1ZOEpbfrn?H(~ouu6?6#c>>?f$>yQ=(E5%* zrIJtLgG_vy^p?cj9BZAc7)b!@pW^o|2o%35p3ibpNRix>wkO10qDCZHlf+U{XRNVs za?DtX__)$w<>Zl3F=O7be36}1D60FmFpT`@pc?zu7J=kAe56l^-5(T$Ln41`JGSEz z^#1H9FE%+!MP^ndo{o&(;pm#1?kD;(g^xcfos@p!ijK*8iP8O7foPoL^KtTfqm1Q| zm1@TyY}cG*W;x~t{cB`3xe#zFe8rCyJ`S!6kpD6Ax4u>8aVJr={Z~Tm22{2fRoLoJuMDUguiBa%=(abpwq7Ha> zU|5fp|7(TfwAQOL@OTO+de1(oTjIcJYeCK8K+S5rfak!kYdCqyATMqMtv@uZn!-mg zxo9v)tZC(gS>&)wEgu?1KeIWxc%(mq(Q?3dft{J=VvI}H))W_dw@4~+mZ$1r#>}5) z=2WdErUR}*Pyr(EL0_DWcvvH*ADgth`jR{k)JshzDP`b8DDBs3bahY zpUp%5aL9U;(oIS)3%$IkJJc>Ud4N?^Qu~gq74Ib3=@K)Cv&NMW$*PztqjK85mB}6o ziJxLO2!~z?(^fmdpB7^87~gXg@3ms8Q;nTrvJ?(EMiV?MSIu#C(3a|nF+x)}uYH}$ zgqtCevezg2xa(7V%=Ib$`&JpGSUbtOZ$)=RDkO3uq~`*RP-!(t_pPGb_csBf^c5gB ziN6Rup!1<~TD+5`N1MW-iKDAlQF<~k@`atZayzoH1Et_=733>!Kapz`dj=zFeatp) zKPUfXh}lI;gBFPv4>Osj_h4K^zFy&=yZI6jyF9|^KfT&cp|@Vb7#_tK^pH$32KUu5 z5dE{&>pjMYp0ug`Tu{eYS_HsFHN^Mm#Vjcp01gg))lB7By;#_)^>UBYNB5WStZK+E z@(16pYt|g^M|(dY#j8qt1C04Af9rWIuzJ!F(&mdNS??hfVn=4O43V`g4e48$S^E4C zB&zT%+A^JW5-eBImHzr*WeXp?Ba&_!ENnrUnI|qJ(wUTB8v(B<9~hAX(J!=-QokR} zY0;q`PTo1FYoX;f4_^v|L%$0T1i&X3O%P)?@M7*E2WU>-5R;=3Yia)}XYieInl@c& zR-2Rjxf}Rk2`F^(kjrD1^y1ljR!XLOiD};oBHtN~@Cj27_t5wSDR%?vqAQic9vTe_ zd#cgcSDoz9J=9 zCw*qg?pi6;yCO6Cy&m$I#jlz{Ee7eV9Si*MIIQ4nI5}}J($kzyzgEx6KM9kZeLl$G z>plW(-Wkr_uov{>FT-l=K>0qaRC0*OCx=On)3**iXqGm+`lUT;z9V-7W7=v>w%5DN z(sA^RTlT|k^1*V3w)(na#QyS6IE6!h9L5(7KLl;HS@3@szORhkJ=CBy&@ZM7KIRNC zN^KFbKh=SfssA@%+N3gbeja=@k&}i@n>6Nc{N@dU`J$h`d3W%9fbvY^>+T&L5j0-r zX(F#3%<(Y0xTc>ed|x=!|K=K*C6T9LtdWYxn|Q3B+Z7JGpF0L)iDeqG3WdXiMhn}B z{?~JV#QZ+K_Vp*wv&S*NpKs-U_i1wyw1crex*K!ybcNZ&x!65bTQrgVv{F=Ur**1! zQy5?LeYRD#y=Z{k|5<$z+A=B~ilfOZIeS&AdsfgI)=BDMJfqred1PlXZIR!tLdz7N zX`7TL@!N~U&$n7cBU=5ue)*~&TQ~Q{v6HNi_Qs(OPG%L=o+yO^Z#8NGJSGkAg|r{O zr~(g}0jl@@Py}v+6hp(IlSe6?61=RF(WfJ~Y%u!lmh`}t9SX_mXoIE^Qa&*WWl5me zb)Y0{-*IlyhITuV8OS(HL7X{=ovNnTihZ%r`>3=8`noh)n$+1+Bc)YAJ-JhQBSKrg zzYb_Fb~M?kQ2ieG-5y%!Kl}l@x*z?1c}~t%{z?iC+x zvH;50D=VdSp6MHymx%ErC4O5WbSYZE#-LZ*zZ_>KA@5vp~P{KeP#o8w{U3h=-I9I0aA6gUJDuuN+#=(OCe0; z{YNO}D+K=i0UQgcIqU+g{Hrk0U&O8%-J7-E6QD6vBOCpSl{d6zS%`ekQDV|~S&`Ys z7^lJIlG3a@As|_sDFOCs?bR~x`a+Djb`~FT4Tc(v<9%7!@9RoRo zxjD^R364$Yd0X0T(_xN3jO=TWX7z&s%D2%ylhWA#Faw+TIh+}qO?fG#LJe@SY73Ez zuI?p;ts2-qE)9nQ|A|W?a?8j#mt^s94e3170m|g2au1chYKpbqaOhGP{QQ{}Hdfv| z#=D|>g|-zv`T-3t2dbd5pF^jvOcbzwYY)yGYY#R^C6N z5=%TJ=+fjrkR$4Dm?5(A%&~*Ekl%%w-!;OEi)gNjz3$rEuX{i*>SoarhOs}PgcT(k zu9mQ>$aUJ=uUn@VwUH9qZ%aJ*Z3*@|;a^IGM`;~OYZLa^BM9vXvj zbsT9VbPva@ZoN9I`Vv;&F-rFEVw4hAdT31=$Vb(q_qf(c`&@^lv#vh|DgpPu4yTmz zVta%GL@iH5Yk2~cmINzVy_hl!(yED-%SXxX*wP&~X3u~>S}SdzQ0m+e{iXpaL3}I1 zqf>Yi(@oyZ5<_>6N53nr@2JjiiPA4-C)KbU9%A;ha@%N@bP0UT1n79Jp0UtCIIB9v zW7>GY#`(uWqu^)@TeGCgf$+s7(DHQ2?n%T*Ge>(`v?Y|*uyQKJjUV93G$nMtVw&f$ zJ5aZ0pDn>}lF~i9rRStr$8OgmPi!eGzdl0rE>{$0g{?X7S=iG5JXf3UEXm7g0K3Y>smO66oXX}t@TnOYv0 z_{s=@EKG5M=4rig61(w`Cu8FdoBHGuX?aWg1u}DyOK>Ikq+^cglh#!N=_-S)MJFzz%LpX&teSi{amtOj_p!IYh}{UguItP7*nc;gWY)BGSFAcV8Dg%r(IC&D0?k03e(9Y zzq{JGP`R#>Oe6A#ZZcrSKAE6CbeT*i@~iGcm#v5oAa+l;$}hRw`w4V7AA}j`*M5it zW^=9bPIt;cO~r|R?v@mvUQ;0_2+p=Y2L-M`%+l-idq}0C>Jf%GC4PwOzrI(PXz!iK z+2>dEiUMcKk+@uLNa)x1a%4>}H<3Zw-b*;MYmJW|uoj>nx2^J_celm2v3jEKlgN-D zPweG5o&CJ)4d_g?eiLmo=6h|n$DqA@l(f$;nZo2ayHH;hYFbl*`mAe;efuuESA85L zoV_oe>r{kx+7BjYVsHG!3Ym$gy^J4Hj~oC$T+p>wHKWts8_zMhD_zOHv#P{SUXJHq zCkX~V*yK>l@#+pmnB}o*hSXPJDdeWWnkuY_N(DsUdS0n#4L=KThNS^wSRA0*m)Zc) z|1QAje;a`1Gr*c!1Dxqtz=Ssb8d>jOMCPu&IULG_&N({Q6T1XD*OrBzwCd<=)4A5# zQrdK4M4yPgm9)`07reau)hI9bAzT=p;M7UFmUyhAbZK1+(QD*o;Rtp6p6oFeXgx1j zHS+wnsEvp6iXrF~66Y~bPnXnk+c2{WJPzpfEn^dCeIB*^{;=MDqIs4l7TVH0&(OVj z(#h4(JU7X$W=RuVMNY4d>@MJxUOYnUqdG}SlOWTsjED9wQQXr4&6^xj_E+s++2mnT z&sP~_4HJ`AT}9--Dt%jt9@gK5ef5Q{_Lci=7kxzju|hR`0srTKW!Q2l5K}IAO;keu z0X?i*_KldNuGIv*Gi{#{89nimPa!1?!`@ZaZW2nFIn<^%>{my0;^HWg7mQFyFtW9c z`d)nV=Bxjxn@)M(*z#<^p<>wL5ink(r}tiCWW0r~CP@_;ZR`0$jCDq2taO}|Uv#h3 zd(Lj{=9x}benf%x4&#B|&UE6!#Dc0Ssz=hys9(v87`N&XkA39<+r-nySLTTXT;W(~ z-SFotIWf=idDZfj3(}WY>99`_({O;JI#zwEI6j*2MXD8#E1wEJ-#toosKuEFE*W**4jqR&J7#Tj(Au6z>amkhd?SChJ`t##BK6 zkAo(O3wFTvnp9?zjw@UAZsQX0s_wP44Q*@Dy&cB4R@dG89KNIddVKKg>S%d&8Eu!A zr!Ajd{l&L>`Nh}KwKM^`L)rAF)ltiE)oQ&Ml?uNv4-r$2SamPvV=St7lF|PNC-6O; z7JQ4eu@bzC2rDxx0Uj}15T2^JUts!*8PD*Q;ELR$)65LWm)252k8=1zuSJ<{dcUht zsnuqeF}Z9nVGI4Xf%fH%$|e$%!}^4r8~o25f+x&^NDH()X;j>_Ye(`|5h-FuY9ct7%=kme;^a7fp9nxA(Urhhm#` z^?r+5{t`NII-|Uteyqkj7xPV~KGxK!yg)!ZNB+E`6E!d|(dQg^W$atYHkwwc8a2+3 zE^s#z`SaldF;C=6qvbCQQ#%OcP(G1N%7q=%n!>{z}Ex~05}zK%${9g%ib+nL6*Xj!1G-T(?YT(!z5 zs!M6^i3{2r%;3fk3~M4j8slwiy^hr#N)tx$`f!JG#L^Dgy51J=%QSZ=Z|Hq@aFDw?@_x(2~3g-wvhL!X0AF6_~5| zwu%9=4!nkahvL?1MXKAk8i;{D*Jj6j)F*3(vp(`zgm}7Nmp7>k59SeO8 z9k{NArbk2fMmX!)<|y8$h>d8)?BQ1LsW!q6wzJqI>O@%441}4*G73g zt#`X}*pea^c(mwQZ&(X$G%xQO#C+;cRl@=&PfU10dDz1ECYq9$)AA>Qiz(uV$a@~| zyVaUbttoE#Nz9!V?S?~t4dSeLv-~uSvr)xkvxiVKS3Ui<0E-5Sg`6g66<*fyU5~Y9(o)WO2=xF zTjEEnmQ+`yM|!(+ceF>gBJ^kmdPIBiJJdvb(TF(Oi(ezPO;6YALX7j53u8Rc)ht}- z$`R@N0%xKWXQgAHWqzq`M46r{I(~a^QB|WW99ndBtah0!w9At*USa~&EDYA@Mmh?z z-viuM5xHuRYIjah+=V4#&loY#_%CnJCf(LvW*PS=KoWHT>i6#yQD zX#|Es*QhtC8WXN!{A;ufv0`r%EWp;v(NOCMV={^YXaL3WS1|8U{2zxG_hz_&s2CE1 z^}NX&S1N&b%2kLdW?qH}3s?GV&s`ao0!jRp5<|7&V+F9F3Hd=k4+^#gyx}$ky7y|m zHmPVsvXq%?k~6s-Z9-OjR=1LwP>LStdbS(7QL7&Z*5= zUER%$F+MB3lsEIk?4?<4B%9A}xKroQIk`TfwQrzf;D@=y;~NSA#WLxoMW?|z-o`MH zK=xJEOL5S_?S$T~u=Tc_3BJ9-5{@^ssFgLI3hWKu0n4GPtD^9DGrRze8q@pGgCvXZ zM*4#78G0MJII)~eO{}PpGlb{FW-+Eu4T?$j8pXXEezt+RQ3bA17*<_=Bz3Vg8oD3U z?vcgXSv!kUl!@`9p}>gt`Y&Oxp>}OrpBq8;#+%yv*=&8;O1oco>dta%;iw~1-PeJB zJht|As;hns`i|7wGaS#_*pImmbAqgX}*L~rjJXG zH!#C0;|^)PXYq#i=ItBqk=Q;zd$RdyLT$&;GGBJDT_#ml>O{GfDL4tqXAt{3g*ok) z#p~D*Z%8WR0ZnF@Gd?XX^E7UlCvklp;J~|^ccT`QmA&jnu;q|533wsNH2&rZ@40P_{vCU zb)lUpJGCfU9`6jaCTP-8Q+l zTY4n2(ba#PtNO)<&;gg#?JTaUy(jWq*m@K2qFss=-5yRltlXs~PaDMFOMGxLx4)R= zaA!;#?VwYp^;D;@M&`*C=!Rr3U+XxOEUsWCReZVldVW&JYh3c}C2ezM_dVBJ3+(pZ zIy)m*Fm~C!5OmOfcD}v#ZMR9T;8N{Hzu;<#KBkllYFWnQS29W(ttR_hN=BjFY7k9g z2j+vs309)?hvA}V?eT6?bnPj(SM-)&+q&4yU)ynjOLRutG6SQ&ZL9YwP|j$3$NsH7 zQp=dsW%X8~hexC?j`~6t_Oy~1+D5?$ZNpysWJ9<5{S8#&U^-#9Y72*c1(~;~maY9z zUD0bxDsK~a6QS9*H({U6?wzRmqWSWA%A;l&oOYwfRiJaot-0cb z0C#!&I#}xqH0E>uaqpWTc!qXQ3)L@Doi)6V>HbTSTK`w29r+}W3=TR=mqr=WL8mfejNej8HhQj6tETi1UGwQ_7xN>MR3cEG&ogE6l zNTr{P^_LAv;sn}b%H$NM$etis>ID%_n&&qb(W74}Y6VQxvr zJOhsSPUTeNG=tU*e|0nM2Tn7XQDX$gFgd!kCRJJTGLxrsN?bI$ytbXEON_-BR`FNQ^F9*soL9~19wcX(ONUa-E_vc|#bvmrv)URqV zkSkKC{dIHzD-ARE1KQs;@_#X3KvUEert6OKi8Wq(Eie8xn*gku*PI7BTI=3$Rs+q2@t(E#n?;6AUT5~C5 z1obG~Y}JdVUY4U2g!UpFdL~SHPpnC*ss4dgHhEqrRubsax_1!Mbh>7^(^wm;zqa&B z^S}3GG*qsbYLm)X!%{{s?y8J_>8_$*8f!bzCJVhkV|>y|+ot_^2k*k6J0kY`H|RWq z&Ipv&U{2^-5fEgrsy4IYznH$ooJ{Q7553!P$CO!)!^2kw#M)##^*giop0G35UwgaI zX76>Z>zhBfmakRGoN5KbOxw3u@F!sm!lJKKcYw&nHlHGQ0CRV9^yLR7vN@LSG zE{J!R8PjI$pV;rR{wFYB(OVfyhU;=bOZ#-SUsPgsS;C=1VcuA^k*@5j^;B*Rhu(aX z7!xt~U$-gViPak5*j+7gwHC}L#SF5XV#d7@>{43$8`4{xz!NLy{Kd>CE;qbv6HZmt zE>^2LV0Sb?1Bv=xexs`P)wDJJk0q07RlkV+Pu7Q>vZIZfT)Uy!!16d}0hNNL){4b;aNy{gS9IRFMge_t}{2&gF zQt2^)z^?>&_e6MB8PQXo>Lgat%yKFRyp2>iblq5wq{BXJ5WB&xjhXUqpH@M#!TH33 z?}|CQ-t<7su&Tr&{so*DU2lk=XKo0GCXek@9dK@GcxmK;Er0 zG}BCY+kn(3{z*>MIFlGAmC&H6`KD@Gy8fc#<7}UV^S~eIj@}1iIcGNt7>1n#YU(3ESdJ zDXwAt+JTG73oA!L&y3Ns5nXEp!|03(SPziYBK1@JvDI?oNj1{}pTah_R$a1yNn8ZY zPhw&v(J!f`=gXG-B0?k4hyO&aav?V+erst8hdRSb#D~Yek@{!IoZf7eH@nH@?GLPx zMTTktR*ljWA9O+LyLWU4;7IrVEr@pj%F*;g7QhN~nXXEoU>~q9G;OZ>WwPu_Q2F@a zBv6lVsC0OC&tc`-n!`$}_OOz!PZ)Z9Y=?49yU=`1^BckVgsEK#mjq#vk}s3C+&M%z zi!d8u&MndSG~&s(Mng7YJHlHxM?(?H={JfRzLU*k{ZrJW^V&n>yqjrbx8|D89grt; z#HXUT3m#@kCG9(f@RrC*$qA2_4~KC25Ax?-7R+xQ2ic4<=lNif^AU50pX8qO!zz>9 z-ftz(J!tK<6W4>2dcgBQQhBHAIQ%ve)bNjBD|+j>@-|liIwY(!51IA5}-YQv6JNe$xmBj&DZ+L^i2a*2T?0g=iGMXu7mA;?PMZ&F*iY- z7R*hJ9$0@pyaB_ZS4V#ZEAgfQ=RpQvl^o>6<^6oJX}uhny0J#H>GC57N#3S`4F{uj zC!y|J{n46dcl~g^e;qp+SbB_^&iO@ItDd_4!vH(om@$v6INOBHyP< zdtJs<^>EB%e^+MRPhg{5Rric?%X3E|lUn8Fb$?g#?|%eyD05o$b4i_b+5u4$oJ{sZ zV`+`c9NHRWo(_ku4E?Du4z%Qpp=UrtSYx4hA9m5lkbWex|30#w+4Ul%G3?2s876Kx zrh!uNH7G-Ac%?JLM&#txPlPWE>yvkXg){T6Ldp7~M4G>!d^ zQNbVdzlT;rLZE!FPG%E0A8X1hqc!McAtBDUGBRpCJeVlO{OPD*GDdQLA!ve(=D+>g zz(t|P&}QyA;4y6ld)UzX@D!yh-{;TJli^rd)kk8_pg*yfpM7{{%Wg$w zp?!K1aa(}mKQvzsW*h8G3e977Qs_`WW?BNitAnouKGBfQC`7(ENBJ(gN722B?o&kT zCUlSbRC%us8poJVl@rhHhxZJ#r%Ur+ohxx(sWknhqAdj1Au-0KN^A`~6mw~&jonT) zJ8mx1dM(yA*I4Ld_uM`7#H9?w)Lu^gGb)+S$9YAGF}Y?ql~_QRDZ>4!c1Tss8 ze+zm$4$}$W!ZdH=(~y43OV;$yO**g_r%JI5d4&8+lWxp4iFlakj8~=zH3yLY&&21$*3-VRxhivxoYe3&9LwslYTo z=3jg+3infy-o*|7Pk`3~lKr6`iOKOO$#gR`G# zaJ;Ap?$^)h%NA^8Wtr82-ZZ@yl~-UxfxNQ+T#hD7N0D(TRF zuiQu}CtXj!J-2crYg7XJ_)V8jy&6{rsyEv-5C-3&;V4fC$~T+hxgDoxDX(-28q^x- z7TOn{avlBhySzuCH?F+LWe_>&*LD`GAb%3mS?FR5TOZJmg!T?I@Ffd}eyvb`rXM^R zT@N+jfvI%jo=Qwn37SfnRDuRyHXP;cCeDMbA?1ooQEOBV`uCC#=)Y(l3EeqNb+X~m zU5X%Hh*+Aa-6qWF^q0}e z&aj?xZdaOdIy43$4rkyI=O8XYT!L6aEFo?{+<c;Nd|5N07{ zAn0;nOMs_&m$Gu>3aqx3>*>hH`%Gc`n=%EKg!n>}Ox9uTV+P`Z7x9IQnc>bSO03t7 zh9-s^pdXKm{0rg7Zx4r_2tSS!R0C_N{dgp_aAZpz>4w144*OcCo8n~@WBl#a3)p<_~=zNe{E)FY*y~Hu8=qJn%vDwiFMV6HT?{7 zo>$6h&iaWl<2q}$A27*UhT8y`jDmVapIEQNC*u4a!_0hIxwS}>N57~;YM(N3{&{?} zyp*nl$?zuQaQcu+CNtXZDtDXinzzq&R-!BJtcyd5d4r~EVrIITTSI=vWLowU=N;w7 z>XV?gQE8iGkA&t70h2&Y4gT;I)wQw`W~M{yp>-AQ7V2bN?q$rDcQY@uDvC$#nowL26&$#$}*-o~8z=ec(7G{K2>(s=3W>GXjBG@&9_ zLQiupP*|K-gjaD}KH3wKNfz{`k@GBnf&SxPpVM3Z{ki7qvl8)>y9O4}C5kGT$t{y! zP8G6E*rk}M^frrqL9ND@&N#G%CoVA8Qn)@R-R{~K6d1cA#6KSt$UIjMPPp3?;m(DM zaLeaXfqfy?!rc)cT*Zn$9$|tB-1C>8UrTGP@!p}+;RMa|z?#Y87irw(=YKI0@(yu0 zx1eXq<-PYmAJmfF%d|7K1zpRYgij_twV_dRKp|#;;=CB9XKbi_h{(HIU|(_G1b=Lm zSnh#mvi$NOvvb_nnrd@-`6YPb$K&J~FTXcLa=UOnkRwaJqzC3^HyolSLWhwB7R^l+Y!;qQ

T6i<*f={<)sW2Ewg6=SSlJX_c#XpC4M!YWJM@!FB!sBxMq)ew` zHFP%{UGFH?BC1`lX}tsbvljqs%K15vz5@{cKvyZft4Z$oaM8&NtUB4zH@2+bH#YNr1xB@k@A8==bA4uGQ%+T z`L5K+K3fMEx1OhdE9;>XQHu$5*Z6^xJ;dlkPrIAj(Qn#cl0O@A#|=JB@LE;2oS-^r zo8Cpen5KojfXmF2bjMg7R>PXJrFz6;l=ew4+j38RE;YL1JfBNvTqbEzdO}Y8X_I4F zs%!o{SGH?>92RkjD;&BZTqOySn>r{gXw6x$!YHlT&?Z>Kd_0$j-vG2f3S@|X!wG)M zh5j*2b+hpIHjIQe!)Jh=iKLjbZ%FW@Sb#YtBY}9}4YZoBIC!TB@JFmEc1k+ePypVG z;#QB_Q;)MJX;Q4K3_jj5e%KvQ!t9~mla00^Kat~()D&|#d737%F1E$yBE~eAPOK@8 zg&l5z$LXQpf&XGBwWUfWF2=>WqWQE<_z&Q;J-2D>Tsj;tw8c7*~<5H#4=nWsTHWCuOjtle8Y5{enLc);aXa3_QNBzMC@4vqnp#OX@d<}X6+Ghy`ay$n3kwdfAOno4u-%ua&{;NLZ;gBo*PakqY zoPoPT*xXrdYvf0vnV}x%nYn+2=Kea4Lj> z*I*?f^5jVBS)_D0DRRCt8~Sma*HJ8>BVNT}*`v{PGT>%#+FQA?SFg@#Q;XB2zJOZ% zDxi4npe+d^G5@H$DN^=k_`trQtit;Jy85t96QNG0l#A8X)hp8IS~TDHtZl0Q#`Kw@ zL6qR1;l%zs;mmIp5n2cq(uN4Wy={z_R@i8ZuPa{!c*l)t2_AC&mmjaJp6cjZcG%Y8 z>#JUp(Yq`~Va#bYu<>S{53G>|{%-+`_X(V@nLz3Pen^e-yP&c}Ua#be%x-%A?cPBZ z^w>mx67(_#^iS}PgvM}QiE;n}@Okr_0=(cDBfNAB`RIu=Lmxqat}Pg<`xk7 z7KIOPBqtPiCGM<1`aPuoS{e1XyB?=7cro8H5;_&8-UqrF9ZJgl|H3)5LP9w{KDY(( z3Bqv+jGw-%JzaRhj2pgTQd6f8`g z9T>lV?4NzlLf`2;^YXBw63@c^kOZxhfHO^;d?w6I(VPi~lEyfRH(&NWW$yPawV7KO z)0Zx$$MhsqVA@<0Ia9*RA1in^PXr$0Yhv0=TRiLHaZdutQ2|a=C;T-|dz&^>ZxvD< z4voA?M?FC_RMRLGEs7t&oi)m{gzwY0uuWBqR} zGl;8N#K~=#saM+Aom5t*KA+H^6vfWN8N8O* z^4QzsDn3>6-G?z6#$e^NiVV;KxFyexkUxH9|{FwGu?`t3MjdPQW?00=CgCMNX;T_#r&~vOjCYbtAho zXfC@w=mQ-VVvWV3L%c1&yz6MtobV%GGGcwgExw~cQ^IY&mxC6ryE(>O(bc26y^S3f z3LUbWXNNU6X?l(ZrzMzC&XUmQcgPIS?g4BMu#L12fA_x}oD120ZC7kiAL|$(cicVn zL8^CUW;h1ij`y31vA)M4v%Ev*`L2KiINphWEq^j__%hkl za_VUC;e^d7|^e14;&5VB_#NJREq&iw$s#mb_2Bj<`>&& ze>26qZ4SACe-)*!PdI~8B)GU9t*(CoZ&oG5`1h$w+R)1t<291?zeA3M9M`uwWIb)m zz2Zsa)FiNNS!kEOA?q6gF9+|zXn%eBXs`zUMXej+DslahS)L3RxeMEXOC4XyXVBY3VB-0+wh4t$Fv3FJ^I=2H=8Be%9nxT z&7Uaxy-cIa$?VRsrTddb;U&Hx&cWT5|J!X+b{W`tI#>^Uu&#L&wf`GkbQ= z%{dc`UNU?3^$CIr8bGe`^|rj;-gPPyQ$Tx7u(ppNzSbwe_b}OU%yzgfoJOuokz*1v z{BuO;r+1Z1d8?Uu`Y(_axL~-joBF^DU4hTlC2dT>xd4R)-?*)q$K7ao;D4_GBAMcM zA!34sxkcoAVuIn>mI(CB5-meZSBUi7^nx?!*F*0G3HNee49nv_JX)6DwcB=6n{c2) zwg{(mjf%>>F5`*09I!Ft%oot%v;@PqasKNgHFAIWU~ZiM_e!?q2D83PjZ_x2MOv(u z3VDXW+-R1lW@l${QGmv(?K_L<*Q(tb|Dg<81I~k@Ug$k`Gc&nAyoqtn5Y7f>9UwwJ zf(3!Jhr_5}n-E-P0pIJgqi&eh?(F(+tu1wiu2EV-idsN1u4~IyPuwo)0j)>Dnrr`()e1 zmo0`e2h~M2v?VFY8PK8)?ks*k&;#oZbK`pf+A@n(csyV>bOe|gF9%~|-)}w@_z;-F z2or+(7~s*IU*UEGqb8vfE0QmtJHanHyyuwPzFpgMU+B}QublcOFp#PQXkSvXYM}w1 ze%{C2b`F@kB7q;!SFxZV)d>&!4_(%;S?;IU226|jP&}>h+NIF6fDSAsxw*17Mt#O= zE5*~Yz9J?QJx&Gws(ln@oWBz1E{Ob=TX-cF{&Tp;WROq)qM4Rpb`bf$-MKOo>zJDf z%ICgx$nChKWkK`$V|rQW%{YIqoEU=|hte?D^d!v0myM1jB{kmy{r4Z-c?0cbd9pT^ zew_wvw4y{Bbh&EZF`N6+arbZppV|Ut7DD^7bVaU&IQ$9!<}i4$t&)PG0%nF1Luvi9r#Uh zIBtAS6%*v+PU8j-rjr;x4}hL6`_yNIW!l}`-h4TbC11nGnlgvBL?ES#K#HZ1V)K2% zD=P!+p7aerF~|B@$nk8WT}qQQ+ZoIg^m8MfUzP&mselLL1I$acrjG+>;m1%q&|X?G zz_06!%xJcOu9E1!wzK%ymje9P9HKp75~7e3yT|DVoeKjfViebDJqdp1#<#@h=H`67zmF$-=N`ei zR<*-%jM+2AvEj?T;*Zc8xmz7%)n+NBZINL^1gF2GZE|V7Ttbg84Z3r6kcs4*4SEA= zy<68d&CrXU&~_-j*jfBhplZs*mvh7gL-m(F1`SPu#%5>n2jjiHWoNPNON*Eg(f!l& zRq$$lC_|+3Xhxd}dl1FlNx0qQiwzc>do+r6@P?g(F?ol@IgwH^A6sU=FjoaGdR?Eu zU4;Be&j?Xk#`tcU84Ub%<~Oj3hAOmQZ!6Q_4w@91I5OHiUt8mtEHD0pUu%aF{f6Gp z)~YNP1Kp>GL#`o`eJmAxlepymTkgNr6+P2=_-bkPf9W3nRiNqX_DBBsm3`&muf<1b zE$kGVcZJMMDX{>cJysYrH~ z0**5VNzf9%n4VO{%{;M2oLg6z4|zFzaI?5oJQqm5+V}7Fo9`a)_dSmBUSIU@3xp%T zZ#EG!YwG2d@pj_wx#^+fMRws8D8@jq+bPXHQRtY-00={8Xx1s<{%8-ol|=Soq{K@IQd8i?iMit@lY=GJF&=HZU_uzT(%V z(c6#|yBq808qwA=78<5{#aS_sJ?R++rM@{L;i)^|*B+*CX|AqkVfCCAs&T7GtXR=_8vp*5B&Xtx^h~Yej4M?oSxCu zYQv7!b}LRjyx6CT84j70{_5sxp-;t|9gVjBW&FvOU}i$f=?YQPLkzUeRcvH_@U5XxWC%z=wJ4AM9Q*Yq>qh{2j>** z)&0;yEg96`x4e3r4d?8tcPPc$bV#o!E@+IzxHxT#QmluDO`d?3Ioxa$4lN(-fu;=l ze)vg$63~g=(4mndR2rKAScXF%LW*N46fE=}E1Z_Ym!WQAnknXrE(!JFyuphj3{DM& zE%cOpU%*y9(-W1bSl?p*%lQEt?Mvu z<~5SNLLUxw<6BKPbAwu8;`nKo{mdSsH@Tp_jrah@+)g1>uz@wxaU~BIpl>Qa^);jV zHQZEijM^Y*pS0e@aueF0>{~7+z#~8PbOL;6xge>+dDMd4w#1XXymFA2Z$f_`2=j6g z(kke)c-+x7egbFqQTT-uRtSd~p%C7@THIk7SAK_L(i=VWpSjsV{|k7WHdi~-Hx#t& zlT0nFo|nf4XPWk5+Eu!!AaZ^$fWcgwTB;bZfzpj8r1TZTKbK58% zc?sHBUfw&%?J>;Jn$LGJ&*R)B{6gmcj0itR_#cG-z4M=8*}MCd~>yNK`* zf)jz3J&X7{L&Pm%Jzt0WGO}4cAYEX?4qpr_&GKj0<+;aKE7 z;pLn`z}2$PHo1%413Lw!(zvgTZ3IlMOUsfsB)8m!xl67ox|GDR2GxFY-K+3Ep!bm# z!>Y-kKO2=(z*b&s6skDi zp9G)4G0f~vlGA=EzYg&(W;X-8U}pY3(5(h+0(`Ad&soe{`)g-@~NK5E-jPZZh1*15a6n^7pW|o6rhBw2efFF=CQvC=s^ARhb*WElHXL{>W{p+;wOhbi-0H^3 zwr^L~=~3E4E4Swyt^IYBf7r*#`@gOE{Ybu>+ZxILGxG2Asa{F}#GVbSMBcz}oO+z>FQPOXARN(`$kvj<0zk30l%zPiZSV2x;e%_11GL=!w+tG!F@5|$82YPC&6VV z75ua2d84>jqVa<-BVYf9z@t5SPd!15y~3GLPI3gC+~(vT4NoZ5yEwUQ7v&`EhNRu*6#Qg!FJ^b*x{j)j&U#VrxA-Oa*$-+?t?K};evl`q%BUh)Cu9STel znn~X$dlNvvi8Rmc%EHr(HF@mRI^e7?V4y~^tS!$@) zB;b1R`c=`5L2mIsC+-@vYZg38=4b6Kzmra5&YljS2=_uyrIC~y0M0f!+~l|hi@rEz)ty$u<)}TX9Gz#L8}bO@tZ%a9f<1()`)l7+ARZ;5Rez~y@55eGX!8-} z5!(}`JQ5V@!~h9}u6c@ks-dqORMOMH=*K?`~3DaOpDg#|QeNv+!?hTHxHi)@R&td=XisQ!a zv7dk))UL)9==R2VDjRc~b}k^<40P&U^XoygK1`Uz}&y> z1z>+{g?1JjRp8OL;7I|cC5*j)lYX|z4&$)}vF;hrXN&5h&>b#)hPa_>ec3^IwBaBy zI%Ap=nx2E)h2jP+80KcC8Q>4^E~EE;3r)%BevDGm6NaXkrdoTt2Rc>;aIo)BXgV0o zH#|qRYI+lC+GM>k;c~|cwI?=9>rL?6`X{x<8@WR48RK^N;u`#iTw1N}DPUc$a>aFHerY`IAONw!>6u5|30!1a*-v)lzrx%~L%3}Y zAJtn^OKevvTPv&fs{EtF3Z5IN)o6|0ae4YX(X$noXTF2B5@slE)9IshH|Bo}?#~d4 zsr`i86-{8WR91H->1?Pu6VHS~vpgPYs&26? z%7O$Gy$F&QvSg!tGSC9V-KV&1N}Od8-!@0#j-L0mFNkv!SI>eTi1@0_W%S%==hswb z;cxgKBDDJg&HbPYAZZzNWPS!qvPR$??S#Hc5>M8JyBt#?={HvO1R(1N4XHY1#Q6I@ z^p5>|FQH-34zEt?Ck_(tuM)b_l&{+u(x&~So#jr4yhu_p^GsQo!*UC~$pr#9Y@mr9 zLT4RcE-tH30sFSHaer_G#ux{x8~wz*voWD*t3A_OE(+-1Dt}Xm`r4MzH&2_NDHju( zQV^Tgx(qV{#}6w}`FDoS)NFK5@+YaIHYLA}!~=&-upEWN2^#X+WfkgCe|m(f#TJRpro7FuOZz_F(o}A!K%_{Fku8 zT=fF=Ep`U-FaotV8EwczTV>roy7NHjtPkyX6I&K-r$$#cNz-dzRjBMo{HrZhL%=ya z0i2)sY_&I8tNxOBRNJqe^~Gify@~z|=tIV%|o8>;H2WrMJ%wnioMP z)jNl>+_v_)jk|iw{EhcG_|qJ)5R+psDYP=iNob<9t22h*hq;kff|P~e*Jk-WA7czG zQ-6$g_g2sWL}8E|ZJh&nBag$&1Z*E^Co{D|ZH}uT9T@aqhJ3X>0dQxO>l|3+Lz<|Z zC&4Pe8y5UU=((wy0phj56{UtWWXb2LpF(wvL1^dewzB+0~a=m`vz&1k3ST81w# z=KQN$8?la&%$D}*qkDGMOoYB6a%H=mw1TPpBU{K8AJSRGr}b3!#wWAN-uNMi2lh$t z$i!+?b*bg|SDs!G-}d_}YgZh(_^#`JHO09Z0c1m~UlG3CVsMF*nI)XJch=d-A6$8+T$wZu9MIbl@Il3q1Mt ze|hf5exPaF)i@W=(fhfHhkbJ!w_krcA^9>re-mxVv9L1Gde1ywq4NHhm^JI^+1)POk6`_8zpl=r_(_q`Hj;GKQBL%x0 zD}7XV#2fBJk4s{NSn-lQ&hvZVRea-Rxo5x+J_Af9b490ASy7F7stpovi^E)14HTG8 z$6Q~O_jB_y*P@Reb*^biLSIO_R#{_)U4Js0?^O8*%DZYT*L#l2ua~1GkILp*dNTM# zccK?k&r;@%@R}E~Uh3=us5R0qj09%Ar<4XW9n1ROvkR@hV?j!jY0;Ukl%|xdYX;gi=HijraS=NK$MkE}o-rd^Ym7-6ekOIrB6({zaKLq%_T~Zf)}3ZE51ho>@hsCYtA$ zKI)&a9QAM}+{Ip>@;~kwg0FzBv%8x@n%h z^F3I3rMsj^p!_}BGu^zWdgM)x{XoQcue*F7kTng0`=Pu41x1>NyLE9t7s-PmnUaHngHl{Kx;^Wvw zjCaCQobA5Lt%G*=wZP{g(h{dJLOaK#G8(~DazWe!)D@Tfq#+XcLBSH?r8)RELKEpb zdjV%Oe&+xqfK~;)xQbB4ZZi8}hl-x^DNwc|fj>jz=xS4S{hoT#-8M^epo@t;6=s6y z`)Q@D2l@rendzba^@m74EQMzQwPcfF4A7^u6rFa`TG~WtBZh3Zgqq!`=rL`#j=&me z)snpYFS21kwwq8-B7yqI$FiYTKkhyIB`@LY{A)fhSZ`ixp=-bHOL@O@bxU-1!?)vY zeI@u%-t1)N%KBZ{zxiuz=nG$mizSx*ttX1OG9^N-7;V9JQ0nq@`YM;WQUj!OTR?z#ML|8qAfjII~#hO z4wiMR=QUZkS5u)McaN;g88-EvNyi;Oc!jR>8th?X9Y{+!GFXuuMf)@rgQqNmrYGuc zU39-ndrjJ}qRu!g>SAITUvKsA1wBy>SO6Rt1LTyFA>|@-| z#r@63F(Td12ObXforAcaj{7h4_N~9m<*pYT)Vto7^)5;S+YO94wdiaiTqylGuHZd8 z;WeH2(heP{I2c1yyZ0)Rml-{8VWl3Vegm{2eJl0${^Ecd4{TEg_#OJY8&1gEXRL4d zOT!c1Sv8u8L`nURLP_zT6;G&~avU;<3=eOycsOvPTU|L4Fo(Mt5Gu^j&l6JC+u^+@ zCFoT(Bp8!jd+nfD`D}4_t5vit`QB9nO;#!^%Zh1Z=IUBahpy{GE(>`q1K-65tvP>f zwzR$m-p|6&R|H<=Gp?_jsNYSFT=2PY{gexO7eG)-c5=o)`?&01d2wasERTCn$e&m@ z+f~qR*=%3xWjRjlh)Amr@di4}!V3O-Uv2h0n`ui z8sjbes5>FU2fd-ny=_N!S??1i2%j=)jTUgR56EkcTV0#wM&s5ct9|L&W4+qZ1(eRX z-k#?zfiCYSNV~ORH_~l;yg_cXo*8D! zAYR`auR};rZu6*&w9_@Rhw%S%HV>TOxLObT!DQ)Z!{;ulVd4b&%aobE;Xi3v*7XYb zE1|%(?oIM4Vs!|oW3;^+3)G_-xh=$ZpuIosSQbc@H3n(Onxs;!$i_%A*6@PX zrfp3dAvwm_Fr`29JoqE)>`7kJGYPn>@zTo8LEn&@!2Ayd2P< z;}So-95R0!u3U&Yi;;zO4mKQwe)yAjDeiwpsRtORdF12^+wFuD~(N^$5*`K0iIJk zt-f2e315=6j8Za4b$B3RGqX{AMP7+3e-EK$t%8j+?8P%-5n`tMn}Emogqxm*?G|KJ zv`3`%8#1UcXIA4I>#V@N&Fr8(h70|QIB&pD>GRr{jy+Ng_SakNI_#0su}6w&nv?v# zf;&|0OMm8D#G*~DxlNN(F8-H1c3^)L&4czwJ3xb-^6hAxk9)K~%8l-iZu0I5?31I< z(f+6c&(XWNiLJhh##gUDJvrsFGW%iQ(rk-jGMfLLD|N4XJ!&QqI=?Q2kZ||(A*18k zAOppXQ0;0_TPqE`U!|@GW@MN9m+nb!sxzbbW35d_tx=s}bg`ntI5UoIxv@GhH zdM+sZn;T?U5onbJ?mQdT8v(aY~GI?QY% z(IJcX{Z$tBwnKjjrCEcvU$yl2lztV`v-JJ4>BuupI~)6l8oLvkHce7_*tUK4bWr=`>@utZr}ydN`Eh?6YdsT={eILS>yOzHaOSG0{M9|CV=nDvR?Fj z;VX9A7X7$S;5@LiY$eJ%UhJ*oo6wF#QCx+sVnURjDjCf)XFp(Y*B!}t2K(!1Df1O~S?&pC`!Np9!JY~igvcaX<_{CY>8(*A_UE3X) z0bc|~pt9oB8h0V6u&Az5$;IUs+QWXRzE2DW%H;SigT7u~;e7Y|{;dB;(f=2|=h+A5 zv?;3)*2}A{I=EkCyM$hKqcxXSr246koJ;aB9_q|fPuX4{!$~X6wg3v zv>P2*3(4DlmX#q~2NgOI(xSuQVI#v0b?Sq~2DV8<;oQ*%x zsxog*<;_Q$DxF5Brh_*N#;ML2v(CBB`H9ncSbgVdAIYE8cb=pX&#s`XCg_51z>$Pw z7!FqMEE|K6%Q7@4cvM-#J<=hqS)CE*oaUTaRla1de}!tTlQ(_lw3%X;#G2MF(RcL4 zAFFCuvev2Ujbo-MO9+*+FLp!KC(h{8^d!Y{roUsIKCf`hX$M5yrqwRA?ud+$=ova4 z#${K;W#-aVrs@8ee%qaAmN2+ed2LCDbGqN4e{HGS2o$-FxlYrPiY4Zy^>R!{H8f%d z9f3}`{tUc6ZD0P~BlU7JuC@A(N9*M@mw8#mvYpGmS(d)Ma=8zPC_5e*`RLq7M?O~Z z*kU|sJkr0kUQTDe#}-%B%VyVff2{5y{|arroN29>N4V-`lhZb`ULM&|FK0OGzWcGSzcNIe=y9uDh~dU*`Hfcy%OA|J7ZcycUa#u@76@rW&AyQ>`7 z=hn*;aNJ_7mnR~{tw?d3;dZQ`{#rxxK+xTwmHn?nBZaIJLV;hmGQYh=ZmxshAfmO+ z$3ABfi|ND~W&FbTqb8SXA5`Ru9_F^>b4^Ev@Ky^3$xgcpCP6@ zuptcJkz8y8{h}X@|V3hPzFB%pr9Lo=_wavMm@`_TD?p zIigZJaj&)1a69v-g$8#Spv_Eox&se|zg6~Fb<{&fb9gHCiTu$rM$dxVhfX1CsN zzaOF}v^FN94NBf-P z(756X4f(p9)84o)E|yBeGGcq*<-#Zfu#L^%$%Q$EwreJ0F8d&4r_Mb~s5eFL3E z-#}-l9lK!P#6TbP7vu1*+1E6p-_3G|x7XD)cOLDZ(#HHFPy_wjmr3Uggnl?nHZj(z z9(0>yk5u5cfNL=k&y7MEsV#KERgBnJf&3Thgv&lZW)N#Ka* zjk*Ne9oCh^bGO3UD=(o1wu8=#zPwQ(4{Uubmm!7b%OiomMf&V~NgiJW*#I-s4sfuT z=up)(>}8`Sd7hS2t?yA~2#>2Q>x^gY^)%30 zaGbuLg4*5y8y1qU|Ha4E@FFxZtz+DI*)nV)xcs3tdD$UP66EMIxMFHCxh8Lv&NFh# zKd&azJVMOu?~QfmjT+*O1m2JEHHX}1))4LkZyD&>C5^yJ7}sG!yvnm_lKS{J zCs_vNX%dh7Dy5NPst5!e@e3Tx{29I=F6twI|I|lyJ{#)|)jRxrqTIiB7lIctPtv=$ zW4A_npk-lZM%fBbwgTeg6~c=tr4__D@FQ+_kE9~ zAN%^zHHrA@{vN*S3HN8PEr`mV zZDsIItV)#%TQr-uw-BF4>6NRq&q32nq+GU_oq}(?7^F(U*K~SF7I@qT>t5N1dQ%JJ zV{(x24QgKypV~|Msm#A9f|`TQt!g)W9(dO%pB~z&!e+Knz3nuxb|ctR3u&r0)o%D0 z1RYK|CJsK14jneyEAZ+i5GH@UAAuh2CgmDJvQfg9c(csopdZ;}#GkNya}Y`qB1 zPxd{Y^ig-8Jlfl8abCVE7TUgZ6e&e1)(jKo)@2TR#~Vm{yC>b0G{%wI9e5Vw#O&N7 zB}4zWU3r#}ur$iOtx{}DN)@c|aRt85wYQ{7X%94Pwyxpwx7I>$6h4fYe?!pY(?Xv% z#{3T-k5Djopg(Y46)YzNguMBLPi^^&M`QWQt2H0<)ul3$%is&h8?h5U!oEDq?&<6; zcR#PCDy4dtI~@{F=rZ7+K_}QMh6DGZA2<(h2e%t*BW6dI5f01%H!D?CsKFAAxNh$n zPz-ETxz_`ZUMcx_oza)C(YphdXqKvN)fUXMs|2H{XsFfQDn>1vMv5(ygi~Z$*44h; z@lT(nihGk{sQ!dBUpqJcf^UcYVC(Osfg-dOXFv|$9q-;TsXw?$I_D?2GswMX4Og%S z_0rtU^4dH!zY9Ukx`hwJs}DCy-&!isNO&I_6|2x{{l&hr4aGN`_nlfWaNnG2pwYtu z1G88fG`F@5b8s(GKD#55Bfk9Ovnrr*{{b4Cq*5x zvmU#A(MoR}=wX?7tF4z0y!wywz~WQBX&FLTv)o$vcYK>p{SJMh`YqoipfVC|Lp#M` z(0syt4DFeOcK%In3(bD{m`P&Vq2HX*wuTTi>_B2TdRCaiO2oPqUuw^BR1(8jy)SG$3spZT$q`E3oo*TaWVX9I*OAt_%A)nW zDb)dgf(PGJ&$Jy`Vo9~xQCD5*I9kn&yBtNB7dgy}lwVQvVE9V8ImhY*c^4$B)CO3V zLT<{t)Tf!zIIoXe1s>%*HE8n6`XKgg@b(GGkstK)1+?!V)~V!AZA^Tu&m;V>kS9vP ze1tVf1Fg+)pfKv2(2CYpJZZ2jMX&KD+%vwR>}q6b3OLqkZ}k0({cBm#VZMQ+;JhnZ z(tfA(_!_Lo3+wFh;E-pqV89V1UaEOsFfgn;`Xn=c6|aeb-@Q&RT}7%_Tkw>PRN1n;F<{Fy;s5ZiOqN#y8G~DX5==?ff8_;C_ZZWM6+#> z%8UJ0!>5Y9KcoFmX4LLb@hcUF z`QgQ$4BQdY&5hUz)dMXI4(Pccm;OCuJ40n2*NB;Dt|xp_>Lb)Y)#!ItH@|{b-y`UO zy?A3CAEck>=32Y!l~`-i6OZq*7syrbnC!hucK6dYspn|yrX*=t{~gX{qa<;0tl z11}z=SS9zvAHL4uYwo|lmv%#X(0ZHU>xyMf@UT(iJuG|df6@FZfwzEQ;9hz7WUg?L zqo4E<*6%dzKEr`!&!;?`x1$ zrO~r~Q?gOhQOl}?qgqf_9vKpLu^Omu}c^p+#4VMgA{{IyX( zd-2oE@Ikm$f(MIRwmQsGBB)2$%ABTMX*h5k@=NmKSF3pOE0HESjzF5;>7!?1yI9g+ z`QC{hyEGhDL*q}}ykGuZo`?Q$wFx$?u5h6I8u`4U{!t_wy5jl^qQ*;{QKGgLE^ggw z=vY#TLqR+N+`$PVtkPBM?Q2_)Br~I}ltH_lp7>7bhi5QuBA;%ZNIGk(6`E18Ufacp zX}f&Cakc+$;QUSqmg7Anhri#z%)_&H z%^Pr{2yL;q+XX4h{SKD||A(1u!6?KtAop!Ws?!-KT@h}8fI71-84DD&MN7<25i ztrKbNeY&2(UmWufQ8dNLFNh8nH60nuq@7$@(cieUA`mF+(VF`k%@wrn1p@CKip8GLso8EbUzx9rSYbeJm)2E5m<`ugkyz%w~OSYMSS@eSkN*@Bz@4A?crnXDThQaD2GiBz56ri8^>n*tDU^sb~08vmOQmI)?snz zB|_F%=)k)e;Q%F-e1ODD_$_ae4a%i6GSd(JTcwq<(bXO2p-WC3Z)fk8=7hn6A{*q7ZR~@3<_zGe)F*1Az(Q zF^DPgv5W_N{{4C>4m`#9p;gkS+M!=2-TT#9)sU>x7NBtbAbsH&CT&Sdz4v#?nWZnz zm;zj=Qfb?4ppXfvC8Z9l=zljHIM_n?>p*BZz9s3E8_B$o zty*`OaHIH^as@GpSGchWQi6g%#d*VlrwwDLXIEQNL>=N?B3E$Jo zI#B}TGqt3fa&pMGVbz!jcEBGE8IhXS1nS?^&*`~-`}te)G8{M? zG?~c~nAx6e8Pvft&-+54YJlPcUSBxSro=8r?5*yxZp_^>m-8m{0I_1iGTaIsJb%e5 z_y8VAZ_b+Gp*LTUxoyL1a`W)syd>qlq!@n*J|RKxt6<=O7iN&E?Zo58zfQa|Ll zI*9az^c}f*$G!9HZ1gcN?L)8z)d^vBAqQLnZsTd60PYvd4tw?DKhXm5qF!3xVy>}T z(!G^652o_KcbRP&=2eM?^zC@hJo$iIRcJ8gIGl$KSutKpDI;Yx-6gN8u*+AMmSnl0 z*y5gt4kS>6V8i#FvV%DyRad1XZ-g(yM4)S>im|6HRVFd1G!WPt?36}TL1VMD)8W0F zc0}+y51mAGO`m-(RGaF z(n&{_`t&_W5sMT*J-feFkKGk;p=y$V47C;-Hf)sa zB^#z#5gHW(nEzSDf_pH=*#z)7OtLB$Xj53tuu94Km>s8Iu3bWu80?gR%@q#BfHST; zY|K)7Vv2;U#$NqK+Kt2_?b;>4A3MNIwu^(1cf|pJ^J@(vm=mQ;f*;RQ3p&4P9uaBd6(lZ8pNu|HzTk;P~M4o^4 zP|pA3;oh`e)ZZ1=R`s+W#y+{gMZRHm>{DOA{f{+kf5*M?Q(35Hzv&4`*mG;z;g13H z1Zl=bcL<@tU#}zL5%uI$ID)ih$BUo34J|szsxVVxPYdn)tYAAdl{uoVjPiEL*z(O9 z6?g>vC}_+nG~ytIi#dp)Kef8RbJjJhrxKlB3-sEvA(Acx0*ip%nYoVW0@{s)16-&g z&5{H@IOGRezzV}o2(p8#z9(9iwy^B?&`y}YilMXB%Cb_St;&jNW@P@aTYlH2(?5Jx z_!G;HX=j$?cIIC!pO%FV?Cs5jt7o$l1`M;LAZG3jG12=o?UkJ+yt6DCGXGuwk>ba= zk{jaso}1M&1?7vD3MCp7E!Fcsmdc-X!&9_seX!x>AL6Qu&kq68MckZ`7c|xHUii5B zzy)#YD;Fj`(S6~MPYk|bNFH)weJqXdcP=p(Q-1#2dc$JkaqC_b#Ah(;-059w-y~L@ zY=Rc?Og9%&UHYKQ$QglLs1K>Si{UAGlWqFB)be!wdtv$N@K9qw7an{D_e(TkZPyli z?8($lp4W6mtSpUuWBW%68!^oNrA?6`l#BuG=3l+e9&?iXNB`5sMu3kF?a1i;eWALm zZ1fcGI=kxlO4x1(UG>QoC!d<(}BYLx0&19JV`RU*dVJCG9gqlN*c=eW{-Vb=57 zBuc4##~9VI*FZ}ia_PiZI{OK>bG+>Z-^X1>?LM0+r0t$|j@KJQ+RI!>b1AhXNHsZ` z;oKb#0-={m5))2RN}vn(LkUzN&BZvS6uPd+EiQk9s{wVi%C);orK>27mL=$qiI%09 zh5Pk9qm+f?P^X0pk3BPK!AVt7MXBwa&bB?Q+O(syAGgE)iTIj$&+%EF2i*IxgQ>th zE~E{ZP>wF!@DkM35;h`QuV{PzgpFE09UkSLvvDPTHMTEW2jk-4uUb=rH(!0pE`(H< zsU~#BY)_PVs(g^&DC%VDI*a z7Xy}|@HY|C`Alv2D+XN@gK}l^@1AM8Y``^m2JrHf6TN%crQAWuQ4Yo;oUR#Vc0f8A zn(pTu(fq9kX}5GR9E}-#LyX}d^M7^_dnYsS!Q-7}{h?_OPpVc$_dczkg}6-G6O@|~ z`ir!e0)hx3V|3viSCG!X=TMzi?fvok%prP~4y?nyJT+!u_nW8so0Gu_G)?{BQk*71 zKfGbK^qzg#FD;&z*SrVb6KB+Cs>7^cwlwUQ#TR*gE9@xj7deD!2XwSH62Q&-!L(`h53fev8!` zxQz?H1<&E1SP!U7GBs&YB->H(I{m4|#I;{-MU z2bTq^8!33Cp!nY$;QlRM*G%zo9^K&>#6J;qVc+$Blct>7LJs`ufEst5y?0gRgeTvZ zH{sIOUD7oe%6dSRc9^IooIp}~{|=cmUJZN&-?ljqUk!Leqo%%Kw|l|i#NE$ABS4Gf%)c7=D3n^@^Ik&ZdG~$!o#ouCt1%^*T9p!CIfGvp^zK#KGnaC&1M~4 z!)aXfeZO|EcJFphrF#X(1HV##M7RShv2Jg|L44cUCDc=m{uQ>_6*N{Icvh9Bo~ka_ zx9ZZNHRKmmLmfi;)xh$D6ldsQ9i-91m0t~1!-kx$$(N=8yzi@lxfll>(A?cxq39MM zPSuZwCf6By^9 zRA?0r``$(Q>3d<1FQRvVE{p_Df+v49Fyb0CXoJ`dV^@k@ySDqwHvFr<;-}o_P<1ur zm%wwVv&_srG)V`aQ(J(P9dm-a!Ug~_`=q+OR(j6f06d21cw?>e@Xa+ijQiu^yL15b z_OnVMFP(EWa2}eR%%sPAyMXFIU(tGL`m@?;)zFhpgl>%%de&Frftb7XikBn`MTddH z@3T#v20kar|J9Hu^aMVFbVN|(B(Ft!0$-wSiQ}Chgs=;NtOTiMBUKYpsg+b80im`h zaO8$`!1TU@=9JiD?23!oumjl`;j3KIKayEzslm`&UzAGM9Dj_Ef}mU7WmIuBoHddS zuf_!{?LeOrNroB^PP^RPKMOfMC;+)k6o0NDWG_HDdIF1~OFvmDMMFdjoQ0tR05j`+Gi9`Y42C?b*r$yupWZW32Kk--W4%} zKBwoR`9<&1cTVfpA0kQIsL1zj%@sD5VlpBJ+;7{V+mbU7w4%UhM3a7x0GWF9zd#aT ztAH;nB%fdLjPw-*=qnKaiR6rfkPC-0kgnVZt~zNS=!y4SZw}?JxDvPG{D7+`5QJQ6 zemhA65+W|7wE5q38AaoG*je;g&6)n;ar*RRu?6uLd-j#u#l51+tjFF2ejIvEOv?9A zUueCw_}P19bmgsIlPd?@EHdUS^> zr5MD%2sxz0-qnQNT);w;0PU-dJTc&mN5cPY;FI7{|6 z;Y^3KLEeiv6L4mL_L^~gw3M-40LOcBgO|2$}DR!^hv3joJC3zjUGpnX*7FdQyT!rB9T zDF#G(qe<6H(z*%VM&PS3Xb42k51V3yXDdVV-O>y8OwX4KcHw(Ca~7ni(D%HwQb=sM z_0XWHp1IrMmjV7448y&bTY!Z)D#g2X0eCtdzAFoI@(3)wW?<#U_Y^|5jX4Kvx49kr z>r*~;Ii$wuS)>!SJJRJ#b+C*JJ}TEj90R8mHB$-hlGM@`d$Py7U>)j=N`SYs*mRU5 z13qv0O?JLZ#RF?MhU(1HxZ-zhZ04v-u#_naZ`h#%vve$l_@NvV(G(=j?aBK z58*GQily@&taxPM^3j!S^1Oxfjdxcpt7eh&(LDxZBqQN)LGlvy4dJc0rZmpp_?q5p zU>zv;=Pq8neBt7XdGnY4;^B&_MXcEAv@fk%^w3Y8tZM0!JRHAxWYPQ@=lsg$^XFA9 zTZ-4;x@hsDiihXl&ggv~4F&F1Z^-wC8brK-`&wL6sKfQE2xEKWV{lE+#r0n6d&BtN zaM}E&m5UeMa*J`&%$d_?-eN3XxO9HSyvL2WxkxETEbC2ToH_rYs%6XPQ;Cfwr6qaA zC3hMTS5>jlIB#jyqw|;kn6x)Dv7&0>{CURZi;b1Yb@_bba%uj5JUai;s>=Dd7&GVn z`1q_xDl6wNTlU~13l~0aT-y6u%IGGK_r4kZb~Y1m=y2$97;p^4k%S`^hfy^Cz!%<6AD;g(y4weR zdFSJV+J7nzYX3zzsQsV9A>eo(2lc~GaAf5!9c$PZ4Q(r;A)DMA4zz9ELcf+fo*4Lc+1J0U zzazIKwey>C$#>k+X#M7y$0yzX?wS+7Z94YCtp%^|{>prH@`T%7zg&8)|Eu{g{f#A6t3ft*y&eoSr`D5o+%ocD+Yiqo-71Klbe%l}z_4j_A8EKlGk2eh~faVf4Rw zOgBi1#(%qj=_WrEJ@3mE13Yscs(qfu(CJodw*Xz9BJwNb3A8%WMMU%RrPokn=!l4XrE@JbK_6Ovjp@x6ADw^ih+AUzZvG*%f>UDt zPk$<7|L7Wk)T)0#w)=m23W@eYHxX z4d+Vak7b&vTq`xJviViegVy0fh@R8XWOu7(%eb$k`~T$cWG?#TXr`NlBOb?XIQokI zzs2>XxoHSD3kIgLU5|@N)nwgxJzy9Z5-J<(`wdMSJe#R(eU~hKICI{3oo&=K+;}}E z-LU<}>j`%ZK5*l;s+<|nF0AhtJ6V%;<8{ImgYCxa_jd0&MJdrnMt$`9^UA$+x@VxCip7Po{|CWjUcmqW literal 0 HcmV?d00001 diff --git a/boards/siyi/n7/firmware.prototype b/boards/siyi/n7/firmware.prototype new file mode 100644 index 0000000000..b4c1d9362a --- /dev/null +++ b/boards/siyi/n7/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1123, + "magic": "PX4FWv1", + "description": "Firmware for the N7 board", + "image": "", + "build_time": 0, + "summary": "N7", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/siyi/n7/init/rc.board_defaults b/boards/siyi/n7/init/rc.board_defaults new file mode 100644 index 0000000000..a7d3d20bf9 --- /dev/null +++ b/boards/siyi/n7/init/rc.board_defaults @@ -0,0 +1,14 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ +param set-default MAV_0_RATE 100000 + +param set-default BAT1_V_DIV 18.1 + +param set-default BAT1_A_PER_V 36.367515152 + +# Enable IMU thermal control +param set-default SENS_EN_THERMAL 1 + +param set-default SYS_USE_IO 1 diff --git a/boards/siyi/n7/init/rc.board_sensors b/boards/siyi/n7/init/rc.board_sensors new file mode 100644 index 0000000000..e790785884 --- /dev/null +++ b/boards/siyi/n7/init/rc.board_sensors @@ -0,0 +1,21 @@ +#!/bin/sh +# +# board specific sensors init +#------------------------------------------------------------------------------ +board_adc start + +# SPI1 +bmi088 -s -b 1 -A -R 2 start +bmi088 -s -b 1 -G -R 2 start + +# SPI1 +icm20689 -s -b 1 -R 2 start + +# I2C1 +ist8310 -X -b 1 -R 10 -a 0xE start + +# I2C3 +ist8310 -I -b 3 -R 10 -a 0xE start + +# SPI4 +ms5611 -s -b 4 start diff --git a/boards/siyi/n7/nuttx-config/Kconfig b/boards/siyi/n7/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/siyi/n7/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/siyi/n7/nuttx-config/bootloader/defconfig b/boards/siyi/n7/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..1acad37918 --- /dev/null +++ b/boards/siyi/n7/nuttx-config/bootloader/defconfig @@ -0,0 +1,93 @@ +# +# 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_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/siyi/n7/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0038 +CONFIG_CDCACM_PRODUCTSTR="PX4 BL Siyi N7" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="Siyi" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3094 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=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_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_UART8=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART8_RXBUFSIZE=512 +CONFIG_UART8_RXDMA=y +CONFIG_UART8_TXBUFSIZE=512 +CONFIG_UART8_TXDMA=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/siyi/n7/nuttx-config/include/board.h b/boards/siyi/n7/nuttx-config/include/board.h new file mode 100644 index 0000000000..d6b690c293 --- /dev/null +++ b/boards/siyi/n7/nuttx-config/include/board.h @@ -0,0 +1,381 @@ +/************************************************************************************ + * nuttx-config/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * 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. + * + ************************************************************************************/ +#pragma once + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + + +/* Clocking *************************************************************************/ +/* The 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 + */ + + + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 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 */ + +#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 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_2 /* PD6 */ +#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_UART4_RX GPIO_UART4_RX_5 /* PD0 */ +#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */ + + + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + +/* CAN + * + * CAN1 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_4 /* PH13 */ + +/* SPI + * SPI1 sensors + * SPI2 is FRAM. + * SPI4 is BARO + */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */ +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_6 /* PI1 */ + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */ +#define GPIO_SPI4_SCK GPIO_SPI4_SCK_2 /* PE2 */ + + + +/* I2C + * + * Each I2C is associated with a U[S]ART + * hence the naming I2C2_SDA_UART4 in FMU USAGE spreadsheet + * + * 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_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + + + diff --git a/boards/siyi/n7/nuttx-config/include/board_dma_map.h b/boards/siyi/n7/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..6577106c23 --- /dev/null +++ b/boards/siyi/n7/nuttx-config/include/board_dma_map.h @@ -0,0 +1,45 @@ +/**************************************************************************** + * + * Copyright (c) 2023 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 +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 FRAM */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 FRAM */ + +#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_0 /* DMA1:81 */ +#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_0 /* DMA1:82 */ + diff --git a/boards/siyi/n7/nuttx-config/nsh/defconfig b/boards/siyi/n7/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..766d2b554f --- /dev/null +++ b/boards/siyi/n7/nuttx-config/nsh/defconfig @@ -0,0 +1,250 @@ +# +# 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_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_EXIT 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_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_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_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/siyi/n7/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743II=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=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0038 +CONFIG_CDCACM_PRODUCTSTR="PX4 N7" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="Siyi" +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_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_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=3094 +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_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_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_STACK_MIN=512 +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_SCHED_WAITPID=y +CONFIG_SDMMC1_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_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_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_SDMMC1=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_SPI4=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=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_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGTSTP=y +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_SERIAL_CONSOLE=y +CONFIG_UART7_TXBUFSIZE=1500 +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=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/siyi/n7/nuttx-config/scripts/bootloader_script.ld b/boards/siyi/n7/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..43d36e7dc9 --- /dev/null +++ b/boards/siyi/n7/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 board uses an STM32H743II 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 board 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 STM32H743ZI 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/siyi/n7/nuttx-config/scripts/script.ld b/boards/siyi/n7/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..d6019c0d13 --- /dev/null +++ b/boards/siyi/n7/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 board uses an STM32H743II 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 board 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 STM32H743ZI 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/siyi/n7/src/CMakeLists.txt b/boards/siyi/n7/src/CMakeLists.txt new file mode 100644 index 0000000000..c1386c4181 --- /dev/null +++ b/boards/siyi/n7/src/CMakeLists.txt @@ -0,0 +1,70 @@ +############################################################################ +# +# 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_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + 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.c + led.c + manifest.c + 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/siyi/n7/src/board_config.h b/boards/siyi/n7/src/board_config.h new file mode 100644 index 0000000000..e705c87890 --- /dev/null +++ b/boards/siyi/n7/src/board_config.h @@ -0,0 +1,310 @@ +/**************************************************************************** + * + * Copyright (c) 2019 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 + * + * Board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* PX4IO connection configuration */ + +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS4" +#define PX4IO_SERIAL_TX_GPIO GPIO_UART8_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_UART8_RX +#define PX4IO_SERIAL_BASE STM32_UART8_BASE +#define PX4IO_SERIAL_VECTOR STM32_IRQ_UART8 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_UART8_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_UART8_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB1LENR +#define PX4IO_SERIAL_RCC_EN RCC_APB1LENR_UART8EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK1_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +#define GPIO_nLED_RED /* PB1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1) +#define GPIO_nLED_BLUE /* PC7 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7) + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 +#define BOARD_OVERLOAD_LED LED_RED +#define BOARD_ARMED_STATE_LED LED_BLUE + +/* ADC channels */ + + + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA1 */ GPIO_ADC1_INP17, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PC0 */ GPIO_ADC123_INP10, \ + /* PC1 */ GPIO_ADC123_INP11, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13 + + +/* Define Channel numbers must match above GPIO pin IN(n)*/ + +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PA0 */ 16 +#define ADC_BATTERY_CURRENT_CHANNEL /* PA1 */ 17 +#define ADC_RSSI_IN_CHANNEL /* PB0 */ 9 +#define ADC_SCALED_V5_CHANNEL /* PC0 */ 10 +#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* PC1 */ 11 +#define ADC_HW_VER_SENSE_CHANNEL /* PC2 */ 12 +#define ADC_HW_REV_SENSE_CHANNEL /* PC3 */ 13 + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_RSSI_IN_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \ + (1 << ADC_HW_VER_SENSE_CHANNEL) | \ + (1 << ADC_HW_REV_SENSE_CHANNEL)) + +/* 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_VERSIONING + +#define GPIO_HW_REV_DRIVE /* PH14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN14) +#define GPIO_HW_REV_SENSE /* PC3 */ GPIO_ADC12_INP13 +#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_VER_SENSE /* PC2 */ GPIO_ADC123_INP12 +#define HW_INFO_INIT_PREFIX "VD" + + +#define VER00 HW_VER_REV(0x0,0x0) + +/* CAN Silence + * + * Silent mode control \ ESC Mux select + */ + +#define GPIO_CAN1_SILENT_S0 /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT /* PA7 T14CH1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 5 + +#define BOARD_NUM_IO_TIMERS 2 + + +/* 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 /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3) + +#define GPIO_nVDD_BRICK_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define BOARD_NUMBER_BRICKS 1 +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_B /* 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 /* PF12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12) +#define GPIO_VDD_5V_HIPOWER_nOC /* PG13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7) + + +/* 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_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 15 /* timer 15 */ +#define TONE_ALARM_CHANNEL 1 /* PE5 TIM15_CH1 */ + +#define GPIO_BUZZER_1 /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM15_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 */ + +/* 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 + +#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)) + +/* Board never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#define BOARD_ADC_BRICK_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK_VALID)) + + +#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 +#define SDMMC_PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_2MHz)) + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_HW_REV_DRIVE, \ + GPIO_HW_VER_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + SDMMC_PIN_OFF(GPIO_SDMMC1_D0), \ + SDMMC_PIN_OFF(GPIO_SDMMC1_D1), \ + SDMMC_PIN_OFF(GPIO_SDMMC1_D2), \ + SDMMC_PIN_OFF(GPIO_SDMMC1_D3), \ + SDMMC_PIN_OFF(GPIO_SDMMC1_CMD), \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_TONE_ALARM_IDLE, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +__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 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/siyi/n7/src/bootloader_main.c b/boards/siyi/n7/src/bootloader_main.c new file mode 100644 index 0000000000..cec6abd467 --- /dev/null +++ b/boards/siyi/n7/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * 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); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +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/siyi/n7/src/can.c b/boards/siyi/n7/src/can.c new file mode 100644 index 0000000000..c71b2e8793 --- /dev/null +++ b/boards/siyi/n7/src/can.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * + * 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 px4fmu_can.c + * + * Board-specific CAN functions. + */ + +#ifdef CONFIG_CAN + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +#ifdef CONFIG_CAN + +/************************************************************************************ + * 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 + +#endif /* CONFIG_CAN */ diff --git a/boards/siyi/n7/src/hw_config.h b/boards/siyi/n7/src/hw_config.h new file mode 100644 index 0000000000..a6b71126e0 --- /dev/null +++ b/boards/siyi/n7/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,115200" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1123 +#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_RED // RED +#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/siyi/n7/src/i2c.cpp b/boards/siyi/n7/src/i2c.cpp new file mode 100644 index 0000000000..124fc2375c --- /dev/null +++ b/boards/siyi/n7/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), + initI2CBusInternal(3), + initI2CBusExternal(4), +}; diff --git a/boards/siyi/n7/src/init.c b/boards/siyi/n7/src/init.c new file mode 100644 index 0000000000..46cf4ae4aa --- /dev/null +++ b/boards/siyi/n7/src/init.c @@ -0,0 +1,269 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2019, 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.c + * + * 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 initialisation. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#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); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + board_control_spi_sensors_power(true, 0xffff); + 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(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * 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. + * + ************************************************************************************/ + +__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)); + + board_control_spi_sensors_power_configgpio(); + + /* configure USB interfaces */ + + stm32_usbinitialize(); + +} + +/**************************************************************************** + * 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) +{ + /* Power on Interfaces */ + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + board_control_spi_sensors_power(true, 0xffff); + + /* 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(); + + /* 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); + } + +#endif /* CONFIG_MMCSD */ + + return OK; +} diff --git a/boards/siyi/n7/src/led.c b/boards/siyi/n7/src/led.c new file mode 100644 index 0000000000..df40a23dca --- /dev/null +++ b/boards/siyi/n7/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 px4fmu2_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) + 0, // 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/siyi/n7/src/manifest.c b/boards/siyi/n7/src/manifest.c new file mode 100644 index 0000000000..4bf33cab90 --- /dev/null +++ b/boards/siyi/n7/src/manifest.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * + * Copyright (c) 2018-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 manifest.c + * + * This module supplies the interface to the manifest of hardware that is + * optional and dependent on the HW REV and HW VER IDs + * + * The manifest allows the system to know whether a hardware option + * say for example the PX4IO is an no-pop option vs it is broken. + * + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include + +#include "systemlib/px4_macros.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +typedef struct { + uint32_t hw_ver_rev; /* the version and revision */ + const px4_hw_mft_item_t *mft; /* The first entry */ + uint32_t entries; /* the lenght of the list */ +} px4_hw_mft_list_entry_t; + +typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry; +#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1 + +static const px4_hw_mft_item_t device_unsupported = {0, 0, 0}; + +// List of components on a specific board configuration +// The index of those components is given by the enum (px4_hw_mft_item_id_t) +// declared in board_common.h +static const px4_hw_mft_item_t hw_mft_list_board[] = { + { + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, +}; + +static px4_hw_mft_list_entry_t mft_lists[] = { +// ver_rev + {VER00, hw_mft_list_board, arraySize(hw_mft_list_board)}, +}; + +/************************************************************************************ + * Name: board_query_manifest + * + * Description: + * Optional returns manifest item. + * + * Input Parameters: + * manifest_id - the ID for the manifest item to retrieve + * + * Returned Value: + * 0 - item is not in manifest => assume legacy operations + * pointer to a manifest item + * + ************************************************************************************/ + +__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id) +{ + static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized; + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + uint32_t ver_rev = board_get_hw_version() << 16; + ver_rev |= board_get_hw_revision(); + + for (unsigned i = 0; i < arraySize(mft_lists); i++) { + if (mft_lists[i].hw_ver_rev == ver_rev) { + boards_manifest = &mft_lists[i]; + break; + } + } + + if (boards_manifest == px4_hw_mft_list_uninitialized) { + syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev); + } + } + + px4_hw_mft_item rv = &device_unsupported; + + if (boards_manifest != px4_hw_mft_list_uninitialized && + id < boards_manifest->entries) { + rv = &boards_manifest->mft[id]; + } + + return rv; +} diff --git a/boards/siyi/n7/src/sdio.c b/boards/siyi/n7/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/siyi/n7/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/siyi/n7/src/spi.cpp b/boards/siyi/n7/src/spi.cpp new file mode 100644 index 0000000000..c78c7bb250 --- /dev/null +++ b/boards/siyi/n7/src/spi.cpp @@ -0,0 +1,53 @@ +/**************************************************************************** + * + * Copyright (C) 2020-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. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortB, GPIO::Pin4}), + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin4}, SPI::DRDY{GPIO::PortB, GPIO::Pin14}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortG, GPIO::Pin10}, SPI::DRDY{GPIO::PortB, GPIO::Pin15}), + initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortH, GPIO::Pin5}), + }, {GPIO::PortE, GPIO::Pin3}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortF, GPIO::Pin5}) + }), + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortF, GPIO::Pin10}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/siyi/n7/src/timer_config.cpp b/boards/siyi/n7/src/timer_config.cpp new file mode 100644 index 0000000000..c9bc0acd46 --- /dev/null +++ b/boards/siyi/n7/src/timer_config.cpp @@ -0,0 +1,50 @@ +/**************************************************************************** + * + * 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 + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/siyi/n7/src/usb.c b/boards/siyi/n7/src/usb.c new file mode 100644 index 0000000000..6d42476b71 --- /dev/null +++ b/boards/siyi/n7/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 px4fmu_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); +}