From 21093b829bf56102278f4d4deb5273e607ef5f7d Mon Sep 17 00:00:00 2001 From: MAD-CRAZY-MAN Date: Thu, 24 Nov 2022 10:30:08 +0900 Subject: [PATCH] boards: Add ThePeach K1/R1 --- boards/thepeach/k1/default.px4board | 107 ++++++ .../thepeach/k1/extras/px4_io-v2_default.bin | Bin 0 -> 39952 bytes .../k1/extras/thepeach_k1_bootloader.bin | Bin 0 -> 10580 bytes boards/thepeach/k1/firmware.prototype | 13 + boards/thepeach/k1/init/rc.board_defaults | 7 + boards/thepeach/k1/init/rc.board_sensors | 11 + .../thepeach/k1/nuttx-config/include/board.h | 271 +++++++++++++++ .../k1/nuttx-config/include/board_dma_map.h | 93 +++++ boards/thepeach/k1/nuttx-config/nsh/defconfig | 230 +++++++++++++ .../k1/nuttx-config/scripts/script.ld | 146 ++++++++ boards/thepeach/k1/src/CMakeLists.txt | 50 +++ boards/thepeach/k1/src/board_config.h | 182 ++++++++++ boards/thepeach/k1/src/can.c | 130 +++++++ boards/thepeach/k1/src/i2c.cpp | 40 +++ boards/thepeach/k1/src/init.c | 318 ++++++++++++++++++ boards/thepeach/k1/src/led.c | 96 ++++++ boards/thepeach/k1/src/spi.cpp | 49 +++ boards/thepeach/k1/src/timer_config.cpp | 50 +++ boards/thepeach/k1/src/usb.c | 108 ++++++ boards/thepeach/r1/default.px4board | 107 ++++++ .../thepeach/r1/extras/px4_io-v2_default.bin | Bin 0 -> 39952 bytes .../r1/extras/thepeach_r1_bootloader.bin | Bin 0 -> 10580 bytes boards/thepeach/r1/firmware.prototype | 13 + boards/thepeach/r1/init/rc.board_defaults | 7 + boards/thepeach/r1/init/rc.board_sensors | 10 + .../thepeach/r1/nuttx-config/include/board.h | 266 +++++++++++++++ .../r1/nuttx-config/include/board_dma_map.h | 93 +++++ boards/thepeach/r1/nuttx-config/nsh/defconfig | 229 +++++++++++++ .../r1/nuttx-config/scripts/script.ld | 146 ++++++++ boards/thepeach/r1/src/CMakeLists.txt | 50 +++ boards/thepeach/r1/src/board_config.h | 182 ++++++++++ boards/thepeach/r1/src/can.c | 130 +++++++ boards/thepeach/r1/src/i2c.cpp | 38 +++ boards/thepeach/r1/src/init.c | 318 ++++++++++++++++++ boards/thepeach/r1/src/led.c | 96 ++++++ boards/thepeach/r1/src/spi.cpp | 49 +++ boards/thepeach/r1/src/timer_config.cpp | 51 +++ boards/thepeach/r1/src/usb.c | 108 ++++++ 38 files changed, 3794 insertions(+) create mode 100644 boards/thepeach/k1/default.px4board create mode 100755 boards/thepeach/k1/extras/px4_io-v2_default.bin create mode 100755 boards/thepeach/k1/extras/thepeach_k1_bootloader.bin create mode 100644 boards/thepeach/k1/firmware.prototype create mode 100644 boards/thepeach/k1/init/rc.board_defaults create mode 100644 boards/thepeach/k1/init/rc.board_sensors create mode 100644 boards/thepeach/k1/nuttx-config/include/board.h create mode 100644 boards/thepeach/k1/nuttx-config/include/board_dma_map.h create mode 100644 boards/thepeach/k1/nuttx-config/nsh/defconfig create mode 100644 boards/thepeach/k1/nuttx-config/scripts/script.ld create mode 100644 boards/thepeach/k1/src/CMakeLists.txt create mode 100644 boards/thepeach/k1/src/board_config.h create mode 100644 boards/thepeach/k1/src/can.c create mode 100644 boards/thepeach/k1/src/i2c.cpp create mode 100644 boards/thepeach/k1/src/init.c create mode 100644 boards/thepeach/k1/src/led.c create mode 100644 boards/thepeach/k1/src/spi.cpp create mode 100644 boards/thepeach/k1/src/timer_config.cpp create mode 100644 boards/thepeach/k1/src/usb.c create mode 100644 boards/thepeach/r1/default.px4board create mode 100755 boards/thepeach/r1/extras/px4_io-v2_default.bin create mode 100755 boards/thepeach/r1/extras/thepeach_r1_bootloader.bin create mode 100644 boards/thepeach/r1/firmware.prototype create mode 100644 boards/thepeach/r1/init/rc.board_defaults create mode 100644 boards/thepeach/r1/init/rc.board_sensors create mode 100644 boards/thepeach/r1/nuttx-config/include/board.h create mode 100644 boards/thepeach/r1/nuttx-config/include/board_dma_map.h create mode 100644 boards/thepeach/r1/nuttx-config/nsh/defconfig create mode 100644 boards/thepeach/r1/nuttx-config/scripts/script.ld create mode 100644 boards/thepeach/r1/src/CMakeLists.txt create mode 100644 boards/thepeach/r1/src/board_config.h create mode 100644 boards/thepeach/r1/src/can.c create mode 100644 boards/thepeach/r1/src/i2c.cpp create mode 100644 boards/thepeach/r1/src/init.c create mode 100644 boards/thepeach/r1/src/led.c create mode 100644 boards/thepeach/r1/src/spi.cpp create mode 100644 boards/thepeach/r1/src/timer_config.cpp create mode 100644 boards/thepeach/r1/src/usb.c diff --git a/boards/thepeach/k1/default.px4board b/boards/thepeach/k1/default.px4board new file mode 100644 index 0000000000..4d4ab00a94 --- /dev/null +++ b/boards/thepeach/k1/default.px4board @@ -0,0 +1,107 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" +CONFIG_DRIVERS_ADC_ADS1115=y +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_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_OSD=y +CONFIG_DRIVERS_PCA9685=y +CONFIG_DRIVERS_PCA9685_PWM_OUT=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_PWM_INPUT=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PWM_OUT_SIM=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_RPM=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=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_L1=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=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_CONTROL_ALLOCATOR=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UUV_ATT_CONTROL=y +CONFIG_MODULES_UUV_POS_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_DUMPFILE=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_MIXER=y +CONFIG_SYSTEMCMDS_MOTOR_TEST=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_PWM=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_REFLECT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=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 +CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/thepeach/k1/extras/px4_io-v2_default.bin b/boards/thepeach/k1/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000000000000000000000000000000000..25a00e2357d781ece9c0d41447c3f4a52c6d19f6 GIT binary patch literal 39952 zcmeFZiGNhp{Xcx}GFvi`$pT~pW(hFKuml1c#buaDZk7o~iTxG<+lxVa5j0WM#x61t ztRuk|janowXlz}eH8T)P&^S@Fb*b$POA7=_6zi2l>m3Npoow^G&rDGI`#!JddH#S0 zUN`s7J=^De&gXpgb1Nqj^P+U3KbrUdU;kfmpzkEgyiuaeQi)O?Bg#`Mv7~y8)vd0S z!}M;fYH{fg6Xn}st#V+5QC5$*RX*=qd6~+m;wkl8nFP19#B7{E%!ClL_cfw_48NnD zq+qUR-VOQUDlyA8w{mXPyy_B>7mZ@3G-s(>VYp0jwr9F@t#hh4Nt&T-xqrr>chMyJ zJm{S{A!wwHo(lm8yfr-=I5}Ye+6PO5Z{9Qz^C4G&bN=1J zv{`Qw-H=wb_3QNqQ#i%Qx%&;=UZ=ZX&;1p(emwN+^9#Bv_`IXE9Wi%*r8Engw4x1$(CmyypANdTwf&~dv?KazPSJ78RGXO;q6aQ3XtHEk zFh9Z#5yf{S#Q|;qzv>s$Iy)uCM(deeS;1_9m{A)StNa&^&9)@hEFS$L{zYI5R^h+jFY&Vthoxm}IrPK=)0ys6FR{d< zpI%mb^ZL5Gvl^D`58wTnw0BrJzudqn(>bQ(GjXNf-A^)24b7ruu%qq?b+w5p%nyS` z>z`0>BL+Jg(%adv!S5dQ)}=RmBBnPyq1KbswYEWLogQyVUFzzL2EaV%+)xLI*+P8~ zb?Z;d&Fga;Zj|<_KQcS}SyzfktUZBt{A#Q)b$Zu-Kd%mTRq<7Rw_;}E(MP_6**3WS z9t*HBh<@@KvZbE$PE%t=^ZI6WOX8l_a0^!NQdtk)m3Hz%qTh#;_@e#Zf_}Zsqk(vI zMcgbf%4YSOz{9{`X}1mU4ZOh^k1mZ5%BIdO>yM~jLX^J`9Z`M7JrOf$b{RuQ)NSVJ zj?gMD!muepVtZfpnQ;}Hx`}y2F74!mHpzcs)5crZnuI;;uM7Dv?AWLcInObf&$x0! z4N5k_NDc4lZe3g7U^oh_g2HEvl`DFUt>Mb%X5jrfnG{_WdQx3o zyxY$>Y6rdd8iTciWCO8fx}Q|*&7>$R=(G}RCiqD)*DS8Sn=qW>ykA@|6T8 zo>V1ZV#YAB(x-Hx`zw=^Q5p^qQrh|OdTmva@D$!N${jv@feaD$Y5&57h3{PC9B9h;lK`*!F=E(zQDJ-khQ367TooJ$PY= zIQqiGT-u$fOyu%|brP}3m#xrP?9vKl=Vk{Pv#I+DbxW}cqq_Yj%&0$Z_L~zh6Xo3? zR?1S^sS&oUHw#--(G-ua9^1V>t2(ct)s-J&FEqO7{iO@{;jRe-)AJ`*5-U;u7PDek z*+Abm?Bc_s*btBI8Qs;;{Z%Q}>XmNH(85=qm2qFfRsI_?iBysV-=_SV(o;P8Ui?f$ zoj*xeF9K>xU+ZI(ioBqpQq-|k+Zr@NtLy4tFToTgI`-&k_z}O}%{Q>laD*wk#S9kp=UlNK-9#ajV`01l10<(~t{cV`ce$8ztvYC0^}w?h3Ic%+RJ|ZW$Y3krm#`CGQoQ$M6`?n(99oAnazeL znB&opNBY2d{xZ_7YE2wUvN12V0~DE4tpIP! ztZwWiwk+YMCZ9_iVoG!lHezC<;aVkLGL3ohR(^mpZ6#?IxAeI4QoE^Aq4O5;VQG%P z{nq!SHgeqgQQ%c7`7mY&;6#rzQfrJiFjivOl~0u4#)x&kAT}|ISEVb_8D|!WO~7wV zH;0dy`2KKXH*I%oF41c}rcQ2vWMK})jN*zB`<@_nGxlGyZ~As=S8->#v_~pX7=Djf zCRtW5k*Zg_q{HG8iEG=Mn6Gs(?pn!Pl}2`@G1J{57I*iYWiysYKFJB`<<;tr5Jz^< zXwwH%!1G$DjK=SYwu^E+dVA0<9h0a8`Cfi-lC7U%QrxU~CO~x*z(a~V4IV>f4md}y zpsz73efPZ1@{EfO>!3RocXOguWJ-#}3-b1FNZ$@zyKp^=>q%VSp4WJ%DSR3m`u4nG z(__M&0vj>27_WKG*^%0{!g`@V(Xmf~kM*e*!RIoBNMttS|4KdeaTBgsB zzqA))aMO9cZ_{~$kHUtzkTkog({##IT9(cYY~i?w=;ki0cBf)rf<_a%jY*_fo#5f^ z&=bLvyd{}{RRcK;{#2sM+QgIBc3w`ib79^?+kPX1E{e}!Zxvt;rasbF+DR!Tr#h!5 zQ>+tnJUP|v7x}t_DnF-I@h&*1X3epR2i5#Jc~VvtQ_@SA#ZwNE85y1;A)_kQJXIvh z1MwokRK=Nza!=fbwc7}p)91E{NT>17zKTZb)v zOQ?rr%v-mkg4koB`t^kZ<-Lv0wmY*c=A2b)%Ue2P(~9Q=m_@wc6CM|KyN(6P3{X%C zbn?{pmb}1jx&zGhE!I2p0&@ba%6V^Z?*2;sO;-d=4SOj4k*%QoWXkSAXTaOAj5W?q19l0uHibIwLws6pmsC0BgfQ}On6ofB_n?6%`|94F`MDevn_Ni=#K9U7| zR*xkxXb)ce*&Dzi|Da5NCwp*WwCxpl0i!qa^lu7(C-AB)X_jtXtBIKOPGF-5_{`~@ z+r(TkS&3`sg_yaH1jNZbH_#Lhtm|60-Y(=xSixz!6SQ~Q?gn5HINU_b+7e~!)^jK9 z!b&`UEw8*Y)o;g|uUpSpP`-9Y1#LIC@iRa%h5wfv?MxF$q()03t2FGn-k0zZ@UQHvD5vrBJe(D7~ZgE&F2A%y|K(WG7u? z+e!O8?LP(o+1E*mswWhZzb zg|Aui3TeV*;nuZ`a{pM9AJC0krn&*Get)?woYaaICOC-l2vLrWY!ZmQKdgylr`(8f z$42;RO7Ag@RwXnmPCca)y5s%Ahv&W7lwah87Yd8}c1u%KChwSzJ366I6VBCXj!;YG z)zQDoDTT3crc#i`g(iT8;?d_vQ!I*ndHodBPdVZeXz2^1{4`UqArikTgqDMemP|Os z@~!L=lI?$u8W&Ia%b7#JA29HDw(K6qEgwo!DTR(g{@KWriCywZlSVKK4*w^T8>{|_ zsIj$(RF?uRk$6-YNj?|gxqtlGgy%0th!tz6OBYH3)v3gp4uQwU>LL;zM z1Xj@w5lb=d?2rxfz)CHt9qhfAfrh)Siv-s{PxVwD+za~9SbNiAKc(<2(%wkzG@`V; zP5lGBz@z*JWA)?Z8Ki!^{O2fd?7XyJ>euICCz>KTX-;L6*LhA?@;tcSn-^Rgbtm4u zuyx}PVa-m;eBQM#)Yx5uX9LP(lpAbHQs(#cc=d_)mfIi?G6HS6%;GfYQJ3miA3L)x zNwX;@&up_kmaOw}fbwPsBwARuKGwHwU#zG&BR~Qfxr+RK+m~AE$Jc~AS>N&!`tOrp zY7yyfP1Kg<+gf&^1_>nIWkNMSjB@XR(%B)&)=v^~ts;g8j~n1%M{c=Yc0 z#lWvHeo#)zJJ&hWJ@M$`cZhv!nA-2pyHbFKO&goT_xl}Ey|_+l7YC#>;?Lzp{(8wF zwoB{8Gtz*#0lNe`0PIs95-bCDMhaGut_M*xBTRxah(Z!i1$Z|+3=TyYOLDCS-=Zs_ z0q26Ytt|$nJw0q|VjSAz%wk(3{r&QALVLH=ueUU|t)(*40q+%m1bcTiB;GXZvBVtKULRmy+fng`>#NY2 zZJ$HO2;J-moY_LDg;|vBi@D+$cIWveI`Gcz!c<_*q4Lu*dY53oF|UK);gKk z(Sv9C+pS7k!cTi*6H$s`_aw(Nb?Ryus~M{pkERaSUW{+3_YzyXH@Q+Z`xk-_mO`hp zji%ISgnco#xY@LPjhu%%)n*j=3gFW#(mc z5o>PaIeA{uPzd^?V^G$2Qrq%haq7>6<{9K)Ci-hIF0oO$o+(Zi*d|{GDJlJP;5ygHn@ki;d z;r}6XLQYe*kSj1H^ZoM*)v!t6nwSOi97CbT3bm8N&d6<=SELWksK?m8u1q*jZ%0#o~6mVMWFX;Pmk4}cw&{o7-!r4fZ(a9{@^TMqP6XAF85poX>jl? zDcG~=1GNX(_}SPJk0eYLSsU|ONh71Y9D`lOFv^?5yzQDAn`o05$Bn1VQV)D}@4=e~ z%KOC>;R?`+S;~>NyUI^mG2;nho>W-*thaC@-Td;ailsZD~l3>)j4 zVaB>!%Du<#$@g-$l15fJADih(^&^%uG6Q!;xiwaRJGJj@iT8DJMzIa?wv5UWXc@{d ztGt6~&kj|C)|AeOvP)%@U&Kaao3xU=A}>)FH0DUmzLe^_M`O<7)_(06mb*6tiGF1=OO}oFZoPnoAyfVl%JNz$Ub9VU)+zeK9j3b|vI= z{fF*3GLYz#N?j^5!f|fuP>AY1@#rUUewy|K=ulnb;u97)JVNl+bAqX}axcc;lC%md zF2?Vn5Nw6tH>tTcC|e047(ONeO%gi8Nkg?sD)zJMce?b@;<+^x*U9?CEXzbndd@$W zDSciVUxV?lzcl_rvp_X2N?Y&&#=oa7hcA~m9C7&a_=!i8+DJS)Ii8UBv(KNh3(Pg~ z=*#hfK)*cO`yW}?Df#u)#L_W*?mRo339l=3fDOyt%ytQU`|A-dVbg=(xYEd+v+*Uo z@V?mxeSJFO9*1KZ;h5jpwoA?TvaP9Y7J+F^XY^LT zoJHZksl-WbpV!gnvt@hWKe!lpX%ponY}<2csoA!g!<{$PuWoN)5lOZw2f0jldov#? zV=WJ?et1rHoMY#Z^7I$YOj{`^Vxwz_jU~2mX_MPoUXt6p-OJtESG~9&sG=o zF$=y#AM<1UUvEx{AyeKZ>7zS;4Ks zPQfeOC`>}{PmBrqi{6?ounV;VTNrAI4#Zy}@ch`zLS#T^=uye`8&U6}F-m} z-Zl9Uv+!+~5^hkmM3y}&UyI1VbiKel&L}lwn+4_>Gw6*;8H-*!c5~U^LFX&TVM^^J z1fKX!g7+r)MZ(`nl#cJBlkhZ}F>clb@XNz$k9nDDHdS@4TH7|x7xm$EVOIrF@>HgH zm+RXwV^(DboQhFCA42>j!EZI5Y^l`W{1E40!yPdr{D=(-i@%gt@`ApT_k0n^mIz`g zL|KC98e&Idw2bn+<$kYZ1}{FW?t&-euZV3XwbZ{L-bJHbqM0biiIk4$5Oh`&lyb4?%PEUA^OVpcWNQp1deQT{n*7g*d6 zCp<)@;49=U<`kn$06ddPX*Z3-(0L`>M?lxf`Fw+zBeCTOnrdw&Q?k_Y9`qYFqG#3c zSoAkso$7Ni*w*~niFGD`{=l|N=OT}bBZw8qlLtn zD#fE?!)g9?>lceJQ@EOw(uYMvFH0yoCjQRAq%x}I-;uG_# zwfFh04{mj7!(1ebDel5vR7O?4&ny&3@MbGa?2^4&3R%wmd?nRswv4YSINe_LQsj+w zXsH)syo|3>WX5qmoTQqvcaG?Y`LDR>USJ9+#EjA$Gj}ly&9f5`G+?KUE_m)2yni;`Tnb;lefS&1JZB6mi1^bM#zd_bReM(!`eBr3)$A@> zuXN}f?4Nez6Hv=*f?#Okg_yq#JEAzb0}r9pmt6HpRg|_ijI=+bb?C$Y zCx+ya9}oG?Co+@f=|c=629w}Lq22@VIqh+|{UMFxVwi^(NtE+yM7~59-B%Jll~BBZ zn1LQNz%i{PaTmUVPWo_>wy_BFKrGGT*M{Bv!@$n2;_3Mj;Tb<4Q zsoYfO!~LmfLzMdXkB7Dn(O3y$$Ya#^^L6Y^@KwO+PJ?bm>{oMpNj_q!n-*l+=;+dD+@ zo0^Cqe+Dl>Ji2VGy#*Nu_3h0`UnG2CC{6Cp{QU*+J7gb7@_VAZK1OU-cr&xHlZr;I z0x&XPeUX<~nJp}E{mF2Wk6_mlc*6?pp28boS(n*8qM6=jdH#&Q^l7Gt{w0ca zL?cxCNkr7mzTXaAH+vD4$8Wfz;U4UY%n>S+*;&~)kVuba*8OH$Vv&1}s*^kG)R;`^qZuc=eC^xq}Ncs6^V+GPVdGkZsq7-;K<5uLMneVfDk&i>H z>>Wh8_N~SWN^@60{!D;IpHDgX_-@pJLm{srUg~7FW9LOX{LHJ!j~k`BO+2a}o#ST( zL|U$Qh;{IfY9EY8^G9ivr&vhrpXL&&eGT>VmxPGrxXKq#s{|GH^<nJea-a3jAL}KJUQm` z{5f>9x(X1~1A-n|o7nqz#l8eJr)a;$UrzgVLN;9wJBiv#Z(R-j;p3f)OFJjPo8^QD zLr}kvvi!DR>~?XGX5gQY6$KLfdBg<&Uo__QPpBlyi=!P~l%iAd+(v10ToxgRMQI&P z(wDs}8!O8X!+&Pu?l*N`T0h9PU;ejjL!^4V4J^?A2if+I1DE=sGR6q|ZbyPQEC_Ag zOA6;*7Bg~7)H}0AonCdfI8pjQHF}wa)4J&1H;vBjD;8k=*&dfxW-~|ArTJa$uB?;k zQejtC)fc&6%O)X3P-LIPl_j4Fg^AUe$Ec}~YAzXlk4sOx+6Nf!Ex*h($`a71<&7 zv!P1A;RYTUoi7!FYpjh^jFyOv-4vgVPKwX|{YiY%b_sd6&g^e*>E)TD;P+~K3(f3k zZ$?Jo*@-3f^^leOTz4As8v>yzbMfe1bN9?x*WM@%X`YMTl?^@bF)aal+^8 zipoB(zir*JyxZ!t!C#4O7mr}yY~(igN6^s{u{@C8vEZkF1-xLh^DQhQY%Za z`I(K3!ZGovJ3hM%8C(47JiGAcvlD-C52%5I52g|O_+UQGw!6u%FEb<8q$ijD<*T#H znvr4CSRn})WSlr~MCEVa`NO{$0Wo+&PB&Jh2=tjvJQI=vTb&U&@RjB2r5Mab_zu1R zA7MR=0P0Z=0>;aKXJelwf78Bbjr+PTFYg^MSFz6~(-@2LL-q9>O(cz5oy?&_1S^!w zl)ZnJ$>e9`Am5f$SdiiHdr4pVQ|}J1Y5G!cpJ-M2Rc*e{rG|dDyP?0%Z5HahM7cSk ziK$Lx3+!jmBh4&o?0hNmGM_EHY&Dh<%T(cuTrTpmmMH#F4tpw}C6Qgsiq$VgjKsKL zt84jfT*Sy-1ji?e4qi7abeVYcwYXhq?53WD(dYw-2sF*L)l(kbJr?yLDirG-i~eoo zM%c=TN5p#EJ!uhnG`f3~18?I`nc?r54(sAVFJu0}C;ISit$8g@+;+xh9I-fgCN}A~1++9AJ;b>JhA`_n#++Nz#C%JnQZ8Lih zpJhx-M1y~aM^Z@dN{WH5FOy;>mx=5yG2F`%I;kp)j5hB|0PGG}%i1xQ3ZnSa3L@Zmo zaIe)@FTL)%;_ypS9W

|4XnOt-iXvREO#KtAVz_>YVyIYgwh&d>Le%yUt7dEQ#0q z_=T6KisFa9of$9izYcAyXgbdHzzR^iXGoSrjzd{|w(v*bKPcx5??Unt_cJa?tqL!^ zg6!eMnUY7|jgXZ2{V7~ZKcl-4HqGOYK_*qCqu9eM%l$};@ z?%5G+&kN+-BRaQ_u7VU=hb>{Y6cM-&zIjQ~jc=UIpQ5p7>m?~v<>BUOu zKOQMt9FkL^5pi9Wq8@KJK@Z8FA!Ych5&dDX3ST0ZlNITSnpBAuTKryrGkg=dQi@1x z7!Wz}pv>W?T3D-VC=7dXKkbLWl4K=hfOf4A>8RkY5`DYOUx~gqyJ{7}P6{%TN6ZmX z3+2S-25g*|+4b&ONQ{c*35Y^x$$|x4sbWc2HTpqxx&#^2VpLv%ix5Og?%j^KNvep* z3CC8t-Na1cq56MgCo--qWfCjtJpZ0@W|%F925*BaySjXUfoJ3|YO$D*7O)X6*$k$d zIcI&9Qv@sgq!Wb|U8mKBUR>L8?ZVaZVL7Z*n@zk5^#5wbSaizha+P0PSAOpB%5vq< zjtclogI_^DG~w(Ty=cxXz1#g3cnS&f(5T)?byVbW3iJJy(^&h$V1x2Ql6*J4@C9TU za6?RllTzI~gB&3I-z6>oRRXM<>H17Bd@e|&55fPL@!lrx<2t$5VYlVcY)TFC2$3B+ zz;!fMC^%IyL1^jF3GA!1>{`S^3-L@8LFJ!kuAuw=DOk3mpMgE0!TW5rP+)e_r$y>D zVk)xpXb$X<+$^zcTV1+C?@8gCiKSV35ApG4F?@4lg~r2N&50ThyV{*tId*<(Bh|Sb zRYdO!aQj}&2(|#${u_0UknV;^JiQ|>vG=akWBUhE;GrW#^bJLC`>N%BPZmJseKDZ0- z)~9Lkjv#jxy{!%7jg*#3Yc(X_6k?3zSl+chls2ZZ!NNiFcjGt9x>@>&PH$Iq`qS#k z7xfXnK1b1~<%Ru1Y9BM}G1W*WM2snevYAGAu_81>ueLmT_)o6i59qijgSi5+9*hvq zhdj(lWz))15F7fqTo=B!>`H;mb1Ifii^^^hQjoc2lX8(Mh}`A5{|PbIeGO>Vq#590 zV}X~oY5x;m+(qH$Lzqv4F-QW=05DZY>^8;3y+hBb)wKnjt`i#e=#Bk4Lux3+N?HM% zp$h8&A4A)&0fXVk!0QRkr;r2p9L34Jl&8>26(&s^3b?%Iws`}&?0`XcF0d@`P+)c6 ze?#jH^aKiFj~s|BPiqU6$JxO-sKqQoR>1f; zDUtZqpURZ7w7cmFasvjI(o2SF%->P*;divhTz~XSM2izqQxc>xAia<=NbboGG8QYm zyZeUEU0{bNxebn)!fZivvbZGRBFNW2cf7IN;J>mYD*v$Lf=t_W_{mJl^=@A`1F<$l z1Jq*Z!;VMWbh@KV!t&IsSM-~;_MldnBYiDvabl11E>2*}T5%=-PoU+P%po5ty@@Fy zg+pOeZes|OGD{ta zK0SIKYivim(dfNztDVh=Wwf}`1oI)M^e7?9H6vO<^8c>MYetSjOi*W##;*1z=Gy06 zniEtiY>v^$UP|Bppd=psc?|KHMcpp>@EzhSjW~CauoFh2KZIV(3lF26?vRLB)K3sk zM9#ExEPBU*#+h%Bdg<6L#bu`Jh%!GmIbuq?7^ZLH(Yn~b5o1wnX|91!n1Y-?XjRI- zp-q_41!S*Z*L#yddGP*VN<_yzqq4;xnOa;eg5hMPz|4pl3`QNzp+e8Sf)=gNL8QV-@zJU##2 z(6@8Q$z71ANvsVlm*o7tvW2nK~(&A!z4%O*9d|qV@*- zCPQSdMp)F_-1H`TpMQePo7X!Ubpyv~y}O%g`(^!~@ZN|_4}FBeZ2D26K`zN?v?758 zoCc5-QytDV)Tw5oQ*?}0(P`NMCY=muP4JK-j!0`4k7e~2@TI|PgfkQdzE4&0H{S5_mU9qp4$PPc+axY{K2h-Z$wM zz{0*o(wA`Wz2%xLM8hW7sMKHW!n{YL=SL-s!l?hoF8&qtxrh7<*XH}zNJjsz3Lg3! zV8oeCvI)`X#S)XnJt;UB@$`fAR)8l zO6at$i`TC6pOd&J@+6O6qNiSfAzF7HsGY(|ZL@dd>jZvJuE2f#lFKfx6*C1*M6bCR zCIw$7@NriDSO-pVlwJD-bmMe*9}J9%?GshIgV?_fjp6+E*Rb5T#J>W}8a|P!#h;Oj zvBxI}k90uiAGQcM2@2oR9#Flp_Y_Y4A$xrXY1OnL_X)Jao}i^yBZjU+#Nu+zG#>4Z zf3KNN+&86DGp@7Zd}bnwJ`#QSvM4%@IGCJNi%n!GP4j`@O&6+qkwL561e#*!PC5l2 z(`)hQEf|;YW!iQ~_AcbB@juy1Y>UOhz9qm$S={6YUim?poqJT(Z=Z3>WFCt;;u@iJ zuOU)^a}A@>CvdKTo^u(C>f(L!ahyBc-LN!I8Vg->G`qs)8apoK0>HJGf1IXGRMTYUF(ddbo9k!$f z)JNmmqtX4KwG`~U(db&_SiKm$Q))%cR@D3eltm-xyzn7H5ej&g zcSyvaU!3$KnmW@whz&}6afXHzrJTxrh(77aNsO{Wx~&Tq-vVk0X7=SFxiIq#qn_`v=nvl_!5rka zPK0-OKaCiS$3>B4f|dLz$oc4rIW7`MboBio=cPF>9|rYn627g9q@_svr5Pxv#`lgq ze0c^6)e+KaW=NDbEsWDVCz{*)lXwB%oN3`LGz*nYWSu=4XDrASgies6a(IIb)x~Gv z?Wg_IHKq17ARNy&7>yQ=eG}k?UH;7v89j97@u)?m-(;XXc>(s&C#q#5rOies_1}(0 zOWvWSiQK4eiWk;%$!E&$r#@4v2T)JaM8VQUzg3{tjzy(+GP=g1`myXjHj+s_oT)3y z$+?4G&Z_eU2&8qw2>SEy`0KVV2XfINT8 zAX&0HmpJ@*#`(!v3splSap1|C;?qHc%`974-lJ^x?#44IS`j+nVvdt}w}f}Pyh@Ar zx!g=4e3t3yfp$SN(Akhr`m3rZJ6$w-cEj-$Ut8c%t_R-36tB&z_nlV1?s38^C3+92 ztl25B{YH2aUx)TE7JXopkMODUh2_*6#g0V(F=Y0UIj)dH_>ph|d5o}>j5mqt{u8R+ zyj6TIP?Y^d;02e}JJVBmd}CfP@XE3mv#mI*SM7ZpeP=qSyZ5MU<5;wMbfZk>T|fBC zH;Ci3TZ${6mPEef^ zVr%dLd5}AjB4vzwpR&baoN*Y5K08EcIr(|lyVYK;apa-Id09#F{W4emfSYTq zNZui(|5uIg%Pg0bU20d?RSo!(P*Iyc3Dw=-Lxo(M%b}s3Q2p~X_WWysz&FtB-Rhbm zR2&ZsZ9ebuAB>n8%@8+chOg%Z=aT-36Q6a~_D`vNXILGXKJ-XTKb-%$aoC_(j7#v9 zmF=#S;|H>hk@$SClD%oW3um`B?TN6)tIINS1H-DKABOHTY>2!ZDC=j-UUV6bUz0`ZeXRx^%~XnFA;mu!mlCk#lFgPYQE#QBRpTY(hPv((yHA zyUKOr**$S*j7H#ST$b%P({0#ho+PA?c@&pqcP!}^gT_atL^ zKU2P^oFC!_4S*MT0M>rv-Ba#_WzLpfTlTvFqXtk%CJv{sVutmxrvl~u#`4zy^)GW6 z%oV|+HG-#IelO;{^yAiXl#c3VVjnwpW#u-Dp!P@@(8}<#4#ikE!0}MH3 z<{{mA!?1qnG3Qjb!|3kk%U&vHhnRC@h&gXKoNqB*GTIL?-?DRcH4oV$kEM`@dy@;?hpg`C5aLqGEG9hk_j z8PM?jkS=P)NYmYar7MeYFvaS8=($FDn=tUDNr->xF8}h-{sDI4TFjp*?UV6!5jkDh zCT|kDWWBHfSCveu>e{kQnbJ#vOyv~kW5LOu2&B4OU8(fk_jfX>Es*18#&acM<@%so zpytZ~e7AvXcQqh8F;TzSYuN-&&-i)+j|Nhltd~kF6Li3m&Iz8CTiXIVTon{LeC^s>!obu3!t%=xl)wagusT+Ept2m+g6~lg2AR}h$iTP{XsaC@%m2oy_ z32Z*L3VMKz%3C!dN0i#Q`I!zzxo(JB2rpD34@+egSYy`bYMx(uGkj^hB?A#pd^>4m zkBb#9grBKt4xHIcY^>4R%(ed3L;cJwBB4)Jeu|!1MOL-u)+$bU9OwVs7hfR5(d|Pu z=ib2mPXT(3;bB{-td2Xpy2%=(b%p)lt(ZNj%ZavO)E<{@Op-dn$|Ezs(k9CDpY!!vD9e|wG%NA2JB zVWWL8Od%Iul9)9&^pt1ex_=tN`j64) zBnJmp-djH(%$JUs0q&dT}ZvjCYOa(*QvU0b+?))lqV z^tn$4=L>(1T*p+oD}%cEADIe8lw6UHNQYMZy)1!d6W`JxjGoeQI0rc>cxQ&+Z8ldEm6Y2XGb%fIKjd-rXH5+Yi#=W3=hR1~SUOt={r}qpz<%+2x^HPhas7Yt$ z23#4_L8I3XJFtr!jf}E?v;&%q9w$U{t5<`!8WMQdGf9jE2mkfQ+qY)C`VO)r+3ovO zoQ_a_tWIj9KH)zE-V971Y8fsP7&ENjy{T0t0`;6C4-B-nZFG~6^7uPnk|5oScEESdG%k!L`m+Tn3td_RjDSi-HCi3FVSw!ZRt;m506 zDTIUG4Xxg<Zx*pUc0;n}$z#6q6QKoaI=)79i`{f=y0_8C%=ZSI@N+bJ*^&Wy zftpEn;fn+o+?kRNc^5J|^S#;Lew3sWeOI=Z?YqU!9h>H5=CdX5p!~w|e6K2hk{x$6 z)^51L7koDo*S`d5L(k#94Db1Zw5wFMHWyDD5lQLx9*8hFA^yIXos$~k=J4T|@6mvz zpXW!s%%X1s`bfO=Gx;rFo;G^qZJd0aJcpe7qxbYz8pUW`aCPOLwR`sb&yV)}d{5(^ zEjxBRihm?a;qYx7#zMxq8Lwt345tfcVI}#nsH+L`Hh6Zp67S#S4L%+*P!2fFcW>~m z(7J*fe4Jv&ua^V&dEb#Ez6Fmy3duviw$wNFro8XMhZ~Xejqj#?cu!7YX)wpqff`Q) zyn+A7*Z65^qU^q$*(fXM@I`!9(95^-eVgyyiuJF00{y%{@&x9yQuCW5?u$a^v#yq~ z1M=YX$RqOm=ecwqUl?SSJ4d{7`MK2kXI)o@-}2c8z4du~p7Aa3{o`+E<85MX>k;b^ z7H(mc2Zw+1e*=L<_+13&xgeKJT{G25&L7Cb<5WBBt(D1~je|?y_`*%)2ahk}4Z%-a zmdKn6fB7@)AIc{v-HzaH9H-v~?4w=3Vu&t5$JCQI38zfhA_qjdHzW1_pQbKa zd8PelA?>jR_Ip6z8$wi5t?s+aJ`}#nBlhuTqP#-6`Gy^?{GjXHp8DnP)9Ro%KiG3V zt@u?$aWts$^mvWwLFdIU+{@j`vWesa_%QXh%)Zm=t6nFhDYXl>j?g}TIrOSZ5^bCC z#3pK*5i6bQnbtVfGriF!z2NFPM9dC}8>rwMqDA^B&mz)YbXr}to%S`UaxA)Lgv!W| zVNVd{!!h_C_4_0Gv_h3ly%5IOyN=36j{`i{=o!Y9DdyNdl~Zw_V*5x=@kDUZ?}$>I zJ&3Cb*W0)r0^ah0!>xFxe1PJY;*{dIw6pr$Br+8J%b0Dct)`&5bnkA+tAZo-zT-N} z(M&1DVL86rhX_nVy>DhH6Y+`ib2rj+BKPQnIYLeimE<-lXURwI75O;nz*xnh=%Zsc zDa`?ifceuLs7#!cW=c{Vnc{K!-KW*|sql3VAC?hAz&PdSesEJJqDR?5&hig@v+eaI zhcO2V8->+}yND~*^NcTj(0dOTrW7+2{oy-pzD&i8R>Y$5@WF(vW^x)Ku^F6eNVMOE zcKAvVe3d$nu9|8vx`YNp^%-Kr*@=(ge!_o91JN`}_svUII;mjZWr^f0s+i>)s@cpD#<>Jk7 zbRcHKcQ>49%i;@eS!Kk@<2r)Ak)iE8hWlfd%^XHQ~I@h{^9oIq5SuBK94}`K+dbN=CV!Vdu}d!9#9q`q8uuGLizz0^CbAX#EDfSQAg|wwEZf^*c_tkTt28F`Ax>ZBM+X=la5Qrr1OWpl%Nqk?tY1$ zG0Uq-G1G6EF=)pqh>1ukX8J7``l}kh82r*Fe!1~0PsbjmT+!5Rlh&YwPn2AtnkAFM zlSo+aF;pWfC30-p3K6t9NKlS*ed2O)hxi5Xpf6yYMqIsb-bH5PPQO${Y?O~>)_kOr zV#Fgo8P(bNLNSFQ6EF;^RQEwvd~usD6o&MECGq(Ye!GNe=#-D_}m`TTj0`#OBsk@cuq~`+S{GHO?Ix{6nz);0KQYRq@y)`1 zzsXVx{&-M*PQ3=F-LDQUu-5x19&wu1L<&noR4c6amiSicm?KtCuJ?N{B!m2w)9RBw zCt+Q53~+kL5)KxIA-~!K%fbb3o_uJ2-fjhAg>tA7`w0rV=XS}J?kbP{^wI(y!b#06NyybalBZ6A* zqxq}#-nW3eEY7JEZF)?dU7TU#Thn%P$Yhwyv8@w#Gp()Fsk>V%DF!D*=5Q2;EY7oe zh3vi0sdLQrK2k)K$Gw!kTdLEZF-hs-CYLstoE60=omaj0IdyLFbFsPRH4fde5{%4q zRNpD_ZUk(%`2)`0zU7^$Gj&k{$Ddar-voko#Od<3a1rIBTiG z-H%=v3(XFx$Bb$!ZQikHYdk%f9bmf_>&s((*UPWLHd&MU9B}O^pLBd;+hgjyj!e}+ zGHgui^&aEvH1}d2GhsLAEM|x>24dF-%N0fg-ZL-5{|>+J?6XC%h2OU#U}@(<)I6XTv%pWRN!e#z@VsTYFZAPj*2>p7Mfkh z)WotP$x=zPteZ;~pq6MlX5Cw6-3D9&m!x%a=+=Pfynry@|I9$y{l4yZ=l45vmiL_V zp7%NXbDrmabVcT&HZpvI?u0G{?YRli{XqnC_m?+xlcx zcjR2FYrMr~Qhv@1yO7(S=Z%%|PN4oW%F66sr>{#H@dBvd-W!Jbb`2yFYgz@8XR-Gb zdU^Vz?V=KWz1R6=FG^iNU7z)C%5FdpISfw48=6Nio~oE5di3(Ciru2Qm)Gmp=WuOu zCLi)v&uW0c?cLcxqE1yjk&D$?naGOXg0*_MrKsZL+iLEyDJdp*NSUGEDC z!K)!nH#2+6f5c3|yz7!`>vv-0r>?O2U0CT-t-+!SeI7wRvAJGfU0-Rnx)SFhGUz<{{a_8h-&n9pUB^5yqxsbD_m2;=)T6^S_XdTW# z!kE#JtKcOG&IVP*UP!XU>Y}rg^@uSk7&;Kool;daiGRAB0Mt+#7LiRu*;6Q2qM{xv zV^Py(5~Z3FmIs}=3gUQyXGSB}G)cm6{C6PFt775h!AKqIPWfY(3VfS0mnD${vM=C_ z;E;71umcGAXiS7CYYV=%*Lkx?kzI|p*uU@Dh53rMNy`6lz@}? zqC~*YI;cCOI{+Q+9%luAmDG+lo zf*18lvKrO4?2D}&*A0U@QVuqss0N0UFoh%8)Mlo;* z0-Izx4CIE0T)VccHe4lG>!F>tHXroULSm!;d-`)gTShr3?YyFQTUdPxFL!?}!qH|K z)kZZ@igK#!lF=VSAgjeBN~3x3uv|EO_r!7Q&D?j&O79Bb1~WJIYanX}Ibo5*OCMSh zX(w!`IfV~Y%C#yU2z5%&ih|-8dA@rZ!;)%q7cq$$kjLPna|`bD>A8E*Y3REty*z!z z<+Nc}HLoF2AFWH_gA6XG3KIAfn+5o#emOMnEgo(1JV&@h(k~cQa z?a_~OD$d7eGr*SAgNJB=TqS zi!0TT>;*^rWp#?Sy3V`s2--mZSU~q*6f^3znt{+yD2?O}^nfcs5&|vIJ)=7oi71}5 z9|xCJ;1CE527%yFvSAnvpM?=5P)c3cJqo)UE;3keCfJLcBym=(eS132;Ct@8Y0&4#&zs)aTh@xLtltt-E_Wq9qOjb6Qg+D z>RKkAwKBWeSg$4y$S#8qaTzS|fxiLoUdzvpm$fl6-!{2#5p5CVOpyma@1Fst-qdu7yO|h zTd0>B*^ZV%+}>ia+|GNU*CvC$uz++4N#s*CHFwso_i7@M#nA!ymqv%+Uvdguuu05z zruyieuI22teRtNH>^7#FNnxrwY&87SIOaxi>JNQkcimwMgh^AuWpu~$gke;)jz@xM~nWZH+rb4%gcVq4qd;h(BC=5kl?6KDxaNWCsu3 z4t9fXIP(;`k!mRII-OfiQ8_fsQGJNIGH~c*;E7ghWLe^7=rv^q-Z78KY$IYwt}P5T z(2xsmoS%Kc2!*0IF#j=MC^5duVR*=NeeKF^pPIZW82z91(Wkev!Z2f5?M2AH$lH=d zIQtgAhJDk^8fl|v|3n%CbprjHb>U`#KHR`V!qsUDMqa~UQjs?goWU?-TCMdKyAZi# zzK7I*hvc0%_;I)IQHgEvVJxpg0x*ugrSJLOMh0^nuQuqIoO{k6f!9Ryq!Ql)b%XC) ztsqyN%(7M~a%;JF3jhe@r zZ}M+`wBLx^u#{DrN38R*=VeKuot9^XWVMPjfd67(RI0KlbD3D(w%h!Wetbn(#mwx+ zP@>viM|W{l0%fCldN%loN+vlS|DZUK@rn18$u4K0D;{X|kfM%XW4(lL+y$ytYRWEB zl<<4bCHD}vb^juK-(m0C7NFo>!rA*&$V7bWj_s)-;l&L@a&7Bg=TN_8)jCu#pVg`Y$mG6995aZUOJ2a#bRKe7Onw4P<<~w|Kwkw z?Q`&zw$gB@ySy4bu#{cfY{dJWUm9plf?*8??}L0vKSmB#FRJ-FCjNPEF3%kr5{>X1pT`r@_=_#^>2*2pkPIn+dXWwEXL*?9!!_i*?UH zM*K8CbgD4U4{I*Y!AS$cR7o?V)sA1xj55(gcdRpUzX%JwRtEbeqUy3~qPsEknDjeM zCVi-hQ?=Qa>X+s;nH11hQJ4g(Teij7#vJc*Yw&i2T&rWoS7|;qd7Hjz5UQ@(iu47! zA?2HR%p6JQ>-L3*;Dlk9>x4$_IAXSyGb3kP*^$I?&`fo_4w(0?VQ^32ETDd!=>{fX zk1PSa2a7E78Jr$|zecjB0xka_dTyR$-5j=6!$R-!^*no_WKyP}jS~pl1VRqF#RR3_ zWh+|4jSXX>pyj)7jn*!ggGbRb4H5+}c4t$0pnHsCN)Nd+)r1(bmNij4E8D*&jO98^ zMZsDIm?kvt6YjXlh@09Mmz8~HqourlF9D@of>Ory1Sin)#p=Fa6K#R0CCca-5!TJ7 zWtHsllyqC=Ecwab%Xzr5XpOXulm5AcwfAV*)WGv#98TojbMLQ9SnZA*>yG;^;@bM+ zva$;{fpVQqs9bAfmE|^0sjz*9_I*wUen0H+o!J6%miS8hId3H5c z^i$PLnz`;S^pf1|CU5DKEj5Cw6zBoHsFS~Tn$OtBy(o?whPI=C96}tKLROG{0QNgZ z&XJzy8HBHygGfmgW*N2;Cq<l2wvB@a$8|QPqs^w{>ET+ehx>O(Syx%For_M%Q@eL z+9fB;7log%8>+8u)%b;#qweL>>m+Uma*WMl$6dBX{hpg3G8q!Y6;_I}?9;i)7NXyX zgP{Q^K}u~XFe5@Mlvx2%2DfPiBFwv1sM=){sa~=9AzlWdCvb7KavHCEAaeMH7pu0~ zBzTrdz%c;@egaybKc3v=zqNgidbYyw7+-0m;rAP$#|GYU^c=W zfN6y3g^AryBoFK7W(Sv7=%nQjPrk`l)U7oE>N5M%s;cu*3$G$QG z8GE*h!MR;REfbm7v2z9G0lw3V)50i;eh@e(C%eS%l>^YW;P-+K4)(gEsH_B)Cvo6C zO)xDm6zf16anCuvHwLoHRD+3NKS24CF5E2V88f!lR6fGUINx_Qu*5O;MiL;)$Q+_g#_Meh(J(=eS z@bZU*488MJu7j2wc;5=0?6uTQPi*q3-p`ZD)+aGrvA~K{`c?;<{9thBWCV$P&W2lb zIq*sdYxS)THMQA%cPmVOFu!7DyIV8yuHikg2DB~O|2Cn0(XoN{!9?`=kKqO@cOuqy+8s4it5$Lbq;RV1$6dYWIAh_NtJSS8Vm4+*NmtD#-EQI8(JwKs_Nf{pi=la{gO z&dY9jyO&ML(W#bXU?SlLS_ef+^5AdK{&M#A$0{JtKw?MUboRECc$*kU5=Jjb-$1%~ zcds0-)woaK30`Sdw8-MvI%xxmRkz<;dG>a?>K%(LMV`Xi&Ez|qUmVUyV!5j>74m?F z7e#(2mM13$O(bUvGANd?caAJeVUXpxjrl$sZYCu#P6;kMJ=y1hHBHyxCqQ2#%!e>% zVWz?q!z_TQgmKH1gUfJ)RMha!ecdE}Fh*ZGuI}&2>-aW_j=(|Cwj)F7D6Ddi!jQ0X z?CL>HW5i{6k$c2-IcuO}C#jM5A!ZnmcNPp$B_0n!Y7*szGWQuXY?GI}yud`x^xxpQ z8!{1lV_LokU{Yb!Fg)sj-nFSh{c%_6h+WXF#CtE|mOCobA*qKni~F73whGim>hVE( zAME5w+^B1U=w!FNASYFXj3883AXQDjly}CTqMQ}#8s6=ZznKPJ&@+U(dFRoSWavAZ zz^mmrZG5elAm%fO8PHAruk_NC)GzI3Mzz}L9n0U_Qcu%&Gpf%e40MDkvdPAI-nhG& zQPNtVywI&RI9X7g&JpQoOa7$4B@63wJUk3P-HBYY<9RdvPPL=LOz(qZq{s9(`Ie`` z%5U=I=yQB<;t@VXO>aIq!VgkIGI<|~+{v@@ojh0hoFp$s(8dU|?M%!Oet_~hK4>bp zBc|#6Z7%{Ox866<2G>B&KELO6xJIB|j&jB55R-@wxSVf55{#=R*gZXOPUC~X4T!_P zSqR;7mQhuygLp~2LMsH4dKPXA9l-ju1wmtaLvKs%9=ywy5NwUniILYj%%r8j z&92Bv=7SQcoJmlk$KjlC(tmkk$AJF2}b`EV+3f?Xwc#aaZY(#p^Y;z zqXOgG8>;%^>T~qJ$E9@o`Tr5uY*XhjQGvis$M~1@JICZ-rE3L9iG6}mS)F@bcls^vkRt*%GRnaz}E+>&{>3Gb89CxWyyJZUM*)L$p@ z*$sl2NzGIfFvIE{8LSU6OR@j&b@ucOaE}9tHc34+9Fui;#i%ch9ILMd7pJ)A`cLasw|_e8?g=H>Ipd7C z8+Rmk(>ePfv`gOWL9LTL`~bNtW}H=gfV@cWvnIQY&>79_asA{C8RnjMMTgMp(c&dQ zdHcDc<0mH4r%fr7wKmAYdBHE}_Z-{B-PYQDIYo>Nd-awkwtAQ5Mk5n5#LC7ft^W0_ zinb`cM;V~!T3H1o+ZLYYgO#BhJpEvON8P(`wRv-oXdX!ihg&(w;l%8~ar1Yg@3@|P*f8vgrDVew%f^FrbGc(oJ6k~84MX*XSq+yS$$GzNx ztQf0CJ8W{GOMAk{yXV(qeX?XrAWN3sUXkpPUb)qX`;W`hOeuyWa816mB^!63HROkn z$o7j%F)%#a($pLPZYQaV)z8s|RmgX{oKN@Ad`a|$hE&sen?KeAL-qdd^+3hZ2tA1! zTtPX!kORzqS0is`T7}_|Wm{(pV_#X)Did?BK-aNc3t6_4njsgN(ZASE^SOzBy948* zErF_|SR1G46lV01$yGR&9kF#pt?w@I@eE9|d^9wybzL_1oTL|e*0t_^37wDVd_vn2 zZEuu*w7pUKQNGgCHM?|Afv4mLN$*$g`9pU{rc>f}VJg3IisuFg-SFKVt)pwI2;Bg~ zX+8@YBBWfnUA|keU6g}W#P(#YA|7yw=sUMSW&`zfwf`MJW}p}X1C3-vx;15yw*IYl z?<7IYgP5Hdhirl}dL)^Po1t!7#{-*y-e&i!l|Rj5w==&s4X6tQ_jRZpYSs%Olp_uN zQ=kCIJCz8-SqVZRI)WGsD~b4bpP#`~hP`XMz14F=l*Bp?G7O&7RVOIM#Fsb`3MQZ1 z{)|#^@J}cOj~^Ew!L1WZuus_0?HmfE0nxQs;3YCUfphNGyyl&;|AAUyQd86d`7zG8 z$#_jHx}009T9gK)TWid>7*ladhT9Ucm9*jRifG{GyPUsZzPo+36MBXmX4Y#w zy?K(N^WrYswiA%Ej#n6=qygX%y@je%Ij=4Y;?2v+l>faX<7DcxQ7rXB5Oa z=-uz+4;(h!+nr>Z^ySMQoHmL{AwzDjbr%ed3&x#mxT`MIL=h|KJ#}|+e~}2hDK4EN zA>efK5D@SA{yU4dVeR+lUi9;Qw3cFr#rV6Nv(K17^#N#6Fh(ax{oz7@v$4 zH^mId>)5aYn6GEX9+&E#h}f zPG@qLvOe0VuH}FP&9y|k@tx)ZUvuXqH##}!=fUI{>Xr%eU`Cw1{b~OCv;lF9&KG=0 zRwuvaofVwUXoS|h4l@&y?w=6>xe-52vaC<}kcC44GV3u1$Gr%vFso7x5e0zGtU}z7KBCUO@Tx*}^zptA~k~tuA ze~0)zXvrq&_KPd#61ANng>CEEp4dT6N85l(+InuP#DYXlAMtZpi<*GP?Z=Gov{Eia6~Y;JcsB8;;c1;#%Kv%6 zChPlJ$g$virPf5m3brKSzo`LVjy(Z=J1zG>3;y#Yx)g;+L#{u(lbQkB~dw6*p2$kO$8Rq0|YH0}!XTK00b#?Y!JK+g43T&!s`uNPfZOY-bVxNV1Fdt;|H*8Zu!u;xdJ zvxΝDjmKLeu@b5x2(Odk5GHb*(bggUoTrLQuogHNn~sEmn1~)>8``P%4qdjIuJx zOxkf<9=?-)W3YvOWdvx)`3bDFz9gU-C~Rl^!Xd$EniSwzpC@QglW2?DP5Xd0vho27 zxkKqlze4*vRgque0Hj8aMT}0viYPTzG$(b38L??Q!pWKiRDv&m9 zv7HGCZ^20{OT%bfDdP6~L0QmCt)Una^U(uX%O;EvkQH&fua#K#w*k@n4&grR+SV=^ zzrXcdzWf@4Hd&NGTPAIxSo!BEfkU8eWl4YQXAw?g(dSd`xwJL+KXRF2`X!Wyk>v|Mf`m~M8H^kz zkWr5;E_rNZ(eh9xIjmY$+HHd_rJ%Mfwk-|2> z;|=?403qN`5_1$GKCtNve5s8L{iyvd-YbWF4!lBYZ{i3?ZDb^XP34e<)c?7J0O5=f zxi1mJru#Pu^}pm#ykHx?2R^~ET5A2qOqlqtU;x&Qz!TuCA zs2xTm%ZCujtw;~u>W31^mIxw=DjOM9MzV`bOO!JT%9bFJ=ST5(D2?cRKxxr$%i*Un z9_V|X(dS>ZY|$#RXyuBLF!NV0D=9aX6s;;LUR1UcgnwY!@?`}}OCBUMmzFFgu?tF< z7p#gU(aTnsmc}5j+9^ar4b8W{&z4S|Jt{kIys~Un!OB&OmMxT$$(fVKD;KORDN#nP zj#riztXx=9whC@3i7Jzl;_*?dm1PqW%cIJb1s-dG$67ieYBebmUduea_2&#~#| zm4;6~{`||zSN87O_Uu!e54`vH*N+`NdHU0{=l^x>`sGF!-*)%=AO3Cspr-!J;dkD8 zdCcRpWkBMvAz1$ z+V?FdjvU(mW@oR{@#A-`zkKx1uRgnR_2MNEz_5Dd6YHiuG=KKw9BoF(;DK@>>n)2I zHZpp`_>@sovelEO&zv{+u@&X(7cVU?dT?Cg*vP2(I1wZ93mp`wc=zDGx9g67c`8KxQL2FyQT&cmQO)!}khP1_L}vy6$ScK=V}c}Dvi zeFh%kA3uTT8SR_&S;8Mr+%6hU^Q3maq5YS-X@1nu=kB~`!?BMBuDr_*bCcZJDV55(QRR>Pf8r+pPjNx1tobuCb2BGr&X_*uzZMonnEU5U|62)C=hLj+ zgz76UVj~M>f-+A}$u?>ED&=DZrHhK)wWXX|P_(3E)qjR({SiKWwukV=$WCi4SXPF- ziyu)+rKHG639WR$3w1k}Rxo~1#Y##e&pQ_sEGorYAuE73Eq0HQ*rlRXO{BvzVMUlj zh>H~vMk-*|qpkVTsfq{%ewe$~ySso$jFiO1NC@X8VJBkl8bYTv;w2OlDRI%RgZaya zxyzHk4Eg)?&|5u)r|?(MRUZg~a%*hi1;mpFS;b%4B^`_9R_~CVk?Bv~gocC67#q9j;P_2P=Hs zpG-gFzy3z{J$*S*{CIqU@2@APdF=}MWU2Utj>V?YZx!9zzoU3>a>X^@H&0w&Gx*l! zmWt-aSK@Nt_d30<_HW{Z6SfxzSt^U=9}H?&)-29iQGffJ^fQ~DymU3R^@kfvryal4 z@#*G^8z0(PsyKUKN%7jw!k%BwmpqdCNR}4A+zUZwVEU%?p zI`Q)x=f<I*H%&2fSVm-s$`8DWApb6DBN`yi!{HA~Ub(r;ce$mJ}A0hBqaaY@R|2 z+yA{oRQkkQOxQ;qlBZ^U;&DZ&y5FG2&W!OXNSw>-e;ax%Fag}H_ke`dAZW-(t`Teekk~t zZ|66U?mXWd6S>n`bL_y^pAMXGbj}8!VB+OojVJ#7{!z~@AyBlj) zjhl4Y{@&w_dxC~t6KouCy)3}H==)7+#Vt}W(;M`jf|FDxuEuNYGrViPS{_E^}Z-j=wFTOVF~RsKcJjfKl^ z)^~RPcIJ8QnGXhDe!j-=^ZqMW{#MoS`X}d_Qm41y%xhbCs$t=*5C48cbbO+IOkLL1 zIG?86FzI`DbGR{vwSx4Ie>2>id2```-=1HVwC2nr-L|6z7eY5K_;6q2@~AQ28K>`f zT=oSw$@^6O05)>uFyYKIX(#^??R~m#`@_fL1dET(d)xK(xumbG$DiHX96#vYZ|2sV zE3O{aUi8bW`xmd4RxM=@io9N(IL5bi^Fr}T#VjIxD#x-TaP5ij-i@n$A~o!NS@rXc z+kMVl{_%s~uCI%@dCmJ$aj z?DgkmABWu(KK$HoY{C~cuJ!Kq2&VYI9xRl&c8@4M&(#o4=y(4)#n3(OHBMi=KR?5w z-o4HrO@pz9A*qbo3u^=EzP@$IebKFdk^di2)MP5xUj}T$es}*7gSvi!9)2b1kN4+i z{pA@$gK2p(z%xL3xPAW_?|<>DiR1S&fIh#w|D2Z6M~VI4pF{h79{P->URs_kq7FrQ z!uDZK>yOfBTWS7b)WfRr=l(I_1oI55c6;#04k8dNW7TlFf81c~Q3$Jcd+;Y1LdaCY zs^N71gi1_EgjJKipD2Qma>ALBL}$?uis@xX*}ucz>Mx?JVMQ-S2n( V{<}Zab34kRt)-SkQ}G=NF#{1n*bW{u@&E!*gw zk!(tG)A#;*-}~d~`)1F~oF8*$=FH5QGXh}5?=Jv;FQ%uzkl+hHN<$N^rjW4zmFJ5x z{(maJ&;Q>Y4`wL|f%4yvlLTD;nx~5QgK}xI_Y!XdrTR6GKYhJrr%{-GhJfDUe0Yt&Ct#!FTxqB)e zeK(Gr7n66V>#dJ@#|~NJDFt~IZdY8{m)4W+t7rH z1Wspfaq&BZUW(J!^j{{%z4nEHP&O$Y z?B*ZM3bebZrk*N_FY{;CN^VlRAega!nfr*{G$1%T-0UbcvEyFHA$w*&C=XA8;y}G0 ziGxyw`RPef2Bl?6axZhYjqyIA>RPxAbpadj93}(Gol_(DLCTUhs*;f3MZe^BJN=e& zmPknFY*!7%r9GW)sfQ6kDVi>kI$g74LG@ys=Uf-uuxu*isiNa^^JS$ju>P+q*Y;Oc zXg{a&w!Oz-u})s@VSWV4&}4eoX%#%*RSjEDt32)Btpw#>om$d$UIi;ya7K267>}-w zv-{W%uv{Ia_%l;%NB(NTa_Jm7f;uV?n8vkd2N57W!kq5)kVJJiAN`|9UFy|zN^<-DHWHXQd?6- z<5sQ^u8y_-^%5v-YFb7Xe7Bm*r}R_;!@d{Zjpfh6t@s^Fe3fwCk}{l!KTLABY4&mX znwR3ykFFK1h=e{4Q`vvMMm2c5mFZv=mSrtA<;_+iF(QspF)06x^SEcSPJxtql<~|Y zC#yIUh$9q-<7@4-=bd9ZpunMUs6S%Lab#_lovA$!?zDKyuV%6gw)rbH%L+^4(Vt(F z!&K7KlPRMlgLYI)z-{O!VXa)}kJq)snNSu=Oof$hXiwjc}=VRn863 z5#rg}FdgA{E(4BQ^);O315ns^wWgIEghT8BqLNfnawdF11%c|eC}G2elUr2Ivd?Z) z^r+>z#JH_Ww70w!mb@w#55bB%LJ#My4r+dMR?RY>=#i?8GM~>X#BeA7+9;&!f^Et- z9Bq*@wk^Us+7yu`w|^QUCEeH;o64;Yhcv$cbB0P*w+*MTgWZ~uHkOnOs6q+1tZmq| zY&68(Mo0U&{q#9HhwrFahvQL5%(}pS@ClvavoX!SKsdS9FD_25F9Fv`7A7|XB3&PD zg8RVBIG?G9l50x z4>=wSg3=wsKJTNJyC;G7vdsznPQ*VH)chg~*XYlXMkjOoIHY=H`gWO8dnk3pyJO=g z_oB27Nd48pdt%<$tD_6j>(9{^{u%3>!MaG$1IjJ2Hn}d+k2z~>aZP*W+R$R>0sETJ zqIDEsGfW8V2PH3-q+Sq%gFgG($TPo28#m6{cszRR^x2P-Yk29j(zPRRPKd4n%}Y!^ zT?6sx;%TZ&=XC0^-b>1Jbk*guxfVU{*nqvbGC{w}#8dVUgZ*LTEd9G={WM5S`_Dd( z|Lw#N?tWbJ79d==Gk>W*XvQQi)rYcu+QR1pAQI72#X5~H3W25ow*>gx{DKqOIT;q& zB*skgLAmuB+V~G?X*ZTuBuawBn%l5ccunJc!knKk$}DPXwGriH4+MJfj4j7x_3uAs zlUigdW%V^E(8#~ElYxw5*53Il2l43XDY9}r48S1$It)mYw`g898uUTIzp(=N>??X1L%&LPlltj=u#=)&?4r89fFm!tz^tpzKnv+>0EL;NQn^GA zZpSl?%B3=?Y!-D&?TSag`dae*q&Sa1})1MUq??uu02gtGlC{j{W}W z0+Xf!ibg}9hAF+^Pp_?uyk9K3Kq;OQ-8|A%A_Rmr2n`4~&XlWXU_C;r6(}2CQ*o^m z9D7je6M5dR!4m84&@$+C+&RVfQr#xQl+NSVeua}Ovwvxakf%3GCAn7QyM5|2+)F5) zck0)f-1dm~n)4la4Q?#}&;%(ruelwmj-VL;V|CGjwwV5V*(i<3?jn0?A*y#N6 zehz15YC`KAbkkMV=peXeh!UTmUKmkQUxfhmD|kOqrf2H(uL20j2g{b1J}z*IwUE=6vr&}niPI?0mM4RkS3I-O~Plls;qaYa%rfv;vV<>@7S*r_KC$qqHPOODjr*qD!1G7`q9$1H|G7Ur>J1JJ98d*h^(kKgF3bJo@5`h?XT49RbIq3ukr ztEQ{7WU?v&mrqt#ixNrfW}i;jq{`}K{_=#qS~TmBa$(G7URzCbrr1B>ZU^XR87IrC z1*}P*T#Yr}21xAB|1mMULT-R5E3hsav*LHt#0sbNzpT-snhf{s z8eQf*XumB)J=<*DtryEnY6_hh?!uZ}_kMd?Xi1Hv#L0fUJ~Y_9z@j~eE9;vLju-4@ zfjk)&i&V#lL3wOKBU^ixYEd|ccbionGn$`?}$M`Jo?Fm ziszSaC0Tq5=gNocgsxv|i*(LzT-OKa9(?2eaZGpYXgTnQG0mQHbZ>J_jN;v4MDEnYY2z(b!}>%mVaLL{nh8wN zFqfoj7!EVZT+_#4xS^ddlPldISBlKamGDmRdAUe8BNuaDkV{*WA|O%yXnQOzWa>>1v?xRLOCv#{i8{+gU$Enr4 z9B1)co%r4nA9@rDZwcY)78f6lM~}x{`2BVKFn(W*ckbHiGw%|2LVMG$c=UJi%;fmu zj8HiXd#e5O*rt~G8z+{v+4ma)V_DNb{<$)$I0!|#!1-pPq37nAS{;?c4I5&xK& zA37GbXq)wzHeqVriWbDtFEsNuPnDyY4C7^Hm?h=IOgXKm`=iGFrW+R5DQub}rj5pR zbIyJn(qg(P64R-Rh7Fp6VFSm+bkXWzjb@F5+$t;|4ryF(x)S@`(sH*UkmES$Q2gbt zRyP!|iybj;{EAL@_CCRZ9xCJ;UroT+bl(F z4LJ^i<8l)1u&*h{@dnmoUNNxAyo1v0$Z?b>XdDqpa8l}Ij#>xVkGr5s4vKPehCqSe zzcI#>a+GDmwToLt73E7i&&y-R&vpp3#Gpe<0fQ3rT*@NbW0erF*_(5$5R4oz~!3 zmP#n+_X(bnek`YxB0_FZ0C+NWNue=1?i5ZIard1@k$~j$CMn8-G>>Il|d2ko(Pr)(z&-fXnhx|L;BI@vAb8c7C2C}P| zV?u9||D)zv{$#nJWwuP)%59!$a|YgtQ1GYj+|g6(d!op2j?z5&t#;Kan!48c?sT8- zK2Sv@7y>C<7J60x9C@9OlXrEo?m3Ga9|P%toty(v?cL_qPO|2WyPmPLK~g#vM(??l z#>qbXma~WIEXsrK1660#Q`VPzi1Ar^10Ap9PkB-3a?9tG>;T&J4n=E}YK=O0E zCm*+TmAmJNFv%K?D!<0)A)=?sCbZ#Wmn5DfqKwlaE=3IJ3$7wC{9xJh};O z63Vi1x6Jln&b$R%7J7OA(>`LRcw3x^e4-4Aa#^D6@t=5nPQiQ`bz`$8nbHdPGrqhE zX;-^F=lmH}Z*%(Q5pIOZ%-nUzE}TEId1IH+6I9Pxja@aqr+o*|GqrfJhrM7K3kq^9 zjB^pDF~0S_g|a1uu{?b&OU?+g7`MCPB^bNPZ)MzOSLV*!eb3kn11a(<{2E`5%GWdPKeg*ec(yRGNY0U&18n;;yb&D4$O>Y;_vU^*=V&)b zcmwS)?dnxI>mfUb@vcsl@!sJLhDirGluI;-#hJCTBaCrCTz(B}tp_Rq^_U|Z9ZBWxuK4`D!{xyc==ubgoI5Bq}mp7zh1gOIiUu1QGFry)p-qLjL_F@Ma~1LbGBUO1!{nZJm7D+ z3FFEL@53^cl~SY&redn-(O#Fqp$raX%<>-00lo@(-p53FND&ugi}+w(kG@tvRO`E| zYnHOs2SsX#yDo`ENf7uk^1Xp6l;Ah)%u-zGnITSD$dMv#kU>dz^-wM2(S3m=?4E(A z@E(@bU+@z%MwjqDunOZPPpU;YDjwY9cR%;$vxB=@A3SP$0p~tX{#kcQMJdwJQ*r+E zQ+7?T5OYKEM6{&$<>wYu{CdyfZX8F-`{4OqZOorYC`tZ6qArGxsM>O^SP9Y zJ55KLI`?3#09(E?^}Jevar~?RBe4lOs!4^lb5Cc}6}oej!)O`v)G-dva2OTwPQHeP zQJe194=wKzWi8z)%Hz?04e&dEsIDLSp<3Gq!)fqjB^%^#sjM6c{VfbX7Ug#?a}vA% zSQROJ?=qXI=}^ukI9tp7Y;#-F-d%6+att$4+a6AygFSmQ4zG;(UhX>bT)w;AetK8h z`I4?~^s30D(cB%|eRZQAH55gBuPL*|qfZ9F{8`w9E1TY>zB|PwdQsLpi?0oM{ICc{ ztF>QKZ?P41kz2T%lQxLEr*`5m8oP8w!AR#!L!SHiV>469|$}@Va2f=AMAXl-99oPHFq{i?w{@%#NB&kKqF}r znk`GnN^;1r3I2UJ?^+8+3xYb!lAy+tABsn(FjlS~Jo4O!&vuy1?tbKFE+)B!UYs+; z#s;}jE1^BUIbPNU(ro`V*#BXCC7^LF^r2o)V&YLUm9#MFq1>({Cp{~qd;g49Lp5Mg z16`1_qy-s^6iRZx`?^l@A`Z;7oPllq=W+HSV;5k{2dbV|t=5K~=hb4X#-a^veU_f; zr@ND$$gDLd3dr&uZW`T2I zbuvo10HZ2J0eghYv_}N9$(2ieGW7k7t|Q~|ZHe2Z1LF)0M%P>?p1iKP3E3>-jZVO_ zv4;9@ht(nLMm28@^*ikd)12w(<))iYs$3z#ueyZq#XEMrfN2e;zhOMF3?auuJ-!9h z142lH`U1>nV-gBE@3pX}D#vN6F|FH+Z+oU1$Zxmj4&>D2)EeD6>(NukJ66MX8Utx~ z;FtD{fw{Hw)>C*b>WOF7&c%HCz($ozbzpigjNjb9gmI5teV{7*1$Y@FP3U{zoxhPn z9llRsY=D-(EHO?|dBT>AwPg*#5WQRD?H?q3ZDJjXn{GhB`lLTkM-si4nR0Su|6Zo! z^?Cf?%NnO$&yMV7sSlm>pp$LF`!Mv6a9+d}_GsxGMZ5`JNa0k7YQka}qo)|tp#J8C zmVOn=q{y`<$1uq_p+a`z=16_xA^zX~q88O>C{N&h`U&ozLTfF>=igGH8EeH8s;~~B z5K>{OUE%F-Af)vb3T&!~KtZ2+$%Zt}85+wBjpcQ)8TZ>_t4K{&C#%4TQ@A{)eY~qFFuQ0`wsHjQ5(N*nAB9N zg@@Nwpag+RCgT}f?ZZ!PELROS!?>^&>ug5HoXrj;8|@by7Dws^Sn+nyAhDBL*mM6| zVeRNDq8Tr~kLqnx^KF$0PU{VvSvPS0YKHTV_rDZAh8p8YVMLtjUl%E93biygLgDLy z#zvdswKdjvj)N!EQqc%SzYkP2viLUsTA)JlR#eo#GG4Yl92#h;i#)Z>v=wgai!brp>1*jEG%zDx=}R}jaPtLS+FAXicC1ll z@qRGcO>am^3W|5Ay2IpFZuv){5pDHZtcQ~=rWPim%=_(l-wH-aCrt3S zY6v@C+_VY3!=KdWSG?7-U;Rj6#;r}Tbj#+fK%K&u*C||iiet+Lx>|la?p?71xos<= zp|2ok#sh)PYgyYFMkFKUEL&kJJu#M&xk;6*M^#l!?V_6fMpXrn4%#a8bRurE!pc)x9$H|(6*|#-&&IKf7C-*b*0}> zqPb4Tt(xfPO88*EE-ye|)3NG`3f;W6tBD%Zx;8DfULphdm+m zQojuIC}Ok{85PNwVZri;AS~kooYf>}zDoVm=}Sx{jP!%2ifY0stme&8fV$zgG+7Fl zPBp{WnqD0)uOXlwAYHu zm*YQf=o`?$5FEzhN?BrKSL5nVJF=%@r_M(gM+G2xGf09(0=BpD(tt0>qIu@oU($ zzO+PMyLK%kb1SVoXLBXjb1QGfV=AGq4Le5p5VA86wZb0(Iz|+$oq@U;nCKkV>u1We zTa+$!2BL45ke4w7GiM;}9c>5wJp2)un}7_=n}IjYK=k|Y$3V^uG|j-=8JG?Agh6FA zR549bTkl`I4D=EW5litwwH%1B1z2G-=!9bE!I + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ +#include "board_dma_map.h" + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The PX4FMUV2 uses a 24MHz crystal connected to the HSE. + * + * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 168000000 Determined by PLL configuration + * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) + * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) + * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) + * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) + * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL) + * PLLM : 24 (STM32_PLLCFG_PLLM) + * PLLN : 336 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 7 (STM32_PLLCFG_PPQ) + * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK + * Flash Latency(WS) : 5 + * Prefetch Buffer : OFF + * Instruction cache : ON + * Data cache : ON + * Require 48MHz for USB OTG FS, : Enabled + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 24MHz + * LSE - not installed + */ + +#define STM32_BOARD_XTAL 24000000ul + +#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 + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (25,000,000 / 25) * 336 + * = 336,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 336,000,000 / 2 = 168,000,000 + * USB OTG FS, SDIO and RNG Clock + * = PLL_VCO / PLLQ + * = 48,000,000 + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) + +#define STM32_SYSCLK_FREQUENCY 168000000ul + +/* AHB clock (HCLK) is SYSCLK (168MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* 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) + +/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* 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_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8-11 are on APB2, others on APB1 + */ + +#define BOARD_TIM1_FREQUENCY STM32_APB2_TIM1_CLKIN +#define BOARD_TIM2_FREQUENCY STM32_APB1_TIM2_CLKIN +#define BOARD_TIM3_FREQUENCY STM32_APB1_TIM3_CLKIN +#define BOARD_TIM4_FREQUENCY STM32_APB1_TIM4_CLKIN +#define BOARD_TIM5_FREQUENCY STM32_APB1_TIM5_CLKIN +#define BOARD_TIM6_FREQUENCY STM32_APB1_TIM6_CLKIN +#define BOARD_TIM7_FREQUENCY STM32_APB1_TIM7_CLKIN +#define BOARD_TIM8_FREQUENCY STM32_APB2_TIM8_CLKIN +#define BOARD_TIM9_FREQUENCY STM32_APB2_TIM9_CLKIN +#define BOARD_TIM10_FREQUENCY STM32_APB2_TIM10_CLKIN +#define BOARD_TIM11_FREQUENCY STM32_APB2_TIM11_CLKIN +#define BOARD_TIM12_FREQUENCY STM32_APB1_TIM12_CLKIN +#define BOARD_TIM13_FREQUENCY STM32_APB1_TIM13_CLKIN +#define BOARD_TIM14_FREQUENCY STM32_APB1_TIM14_CLKIN + +/* SDIO dividers. Note that slower clocking is required when DMA is disabled + * in order to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. These values have not been + * tuned!!! + * + * SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(118+2)=400 KHz + */ + +#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_STM32_SDIO_DMA +# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_STM32_SDIO_DMA +# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* Alternate function pin selections ************************************************/ + +/* UARTs */ + +#define GPIO_USART1_RX GPIO_USART1_RX_1 /* Console in from IO */ +#define GPIO_USART1_TX 0 /* USART1 is RX-only */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 +#define GPIO_USART2_TX GPIO_USART2_TX_2 +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 + +#define GPIO_USART3_RX GPIO_USART3_RX_3 +#define GPIO_USART3_TX GPIO_USART3_TX_3 +#define GPIO_USART3_RTS GPIO_USART3_RTS_2 +#define GPIO_USART3_CTS GPIO_USART3_CTS_2 + +#define GPIO_UART4_RX GPIO_UART4_RX_1 +#define GPIO_UART4_TX GPIO_UART4_TX_1 + +#define GPIO_USART6_RX GPIO_USART6_RX_1 +#define GPIO_USART6_TX GPIO_USART6_TX_1 + +#define GPIO_UART7_RX GPIO_UART7_RX_1 +#define GPIO_UART7_TX GPIO_UART7_TX_1 + +/* UART8 has no alternate pin config */ + +/* CAN + * + * CAN1 is routed to the onboard transceiver. + */ + +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11) + +/* SPI + * + * There are sensors on SPI1, and SPI2 is connected to the FRAM. + */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 +#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 + + +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/boards/thepeach/k1/nuttx-config/include/board_dma_map.h b/boards/thepeach/k1/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..96a4c81517 --- /dev/null +++ b/boards/thepeach/k1/nuttx-config/include/board_dma_map.h @@ -0,0 +1,93 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/* +| DMA1 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 | +|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------| +| Channel 0 | SPI3_RX_1 | - | SPI3_RX_2 | SPI2_RX | SPI2_TX | SPI3_TX_1 | - | SPI3_TX_2 | +| Channel 1 | I2C1_RX | - | TIM7_UP_1 | - | TIM7_UP_2 | I2C1_RX_1 | I2C1_TX | I2C1_TX_1 | +| Channel 2 | TIM4_CH1 | - | I2C4_RX | TIM4_CH2 | - | I2C4_RX | TIM4_UP | TIM4_CH3 | +| Channel 3 | - | TIM2_UP_1 | I2C3_RX_1 | I2C2_EXT_RX | I2C3_TX | TIM2_CH1 | TIM2_CH2 | TIM2_UP_2 | +| | | TIM2_CH3 | | | | | TIM2_CH4_1 | TIM2_CH4_2 | +| Channel 4 | UART5_RX | USART3_RX | UART4_RX | USART3_TX_1 | UART4_TX | USART2_RX | USART2_TX | UART5_TX | +| Channel 5 | UART8_TX | UART7_TX | TIM3_CH4 | UART7_RX | TIM3_CH1 | TIM3_CH2 | UART8_RX | TIM3_CH3 | +| | | | TIM3_UP | | TIM3_TRIG | | | | +| Channel 6 | TIM5_CH3 | TIM5_CH4_1 | TIM5_CH1 | TIM5_CH4_2 | TIM5_CH2 | - | TIM5_UP_2 | - | +| | TIM5_UP_1 | TIM5_TRIG_1 | | TIM5_TRIG_2 | | | | | +| Channel 7 | - | TIM6_UP | I2C2_RX | I2C2_RX_1 | USART3_TX_2 | DAC1 | DAC2 | I2C2_TX | +| | | | | | | | | | +| Usage | | USART3_RX | UART4_RX | UART7_RX | | USART2_RX | TIM4_UP | | + + +| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 | +|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------| +| Channel 0 | ADC1_1 | SAI1_A | TIM8_CH1_1 | SAI1_A_1 | ADC1_2 | SAI1_B_1 | TIM1_CH1_1 | - | +| | | | TIM8_CH2_1 | | | | TIM1_CH2_1 | | +| | | | TIM8_CH3_1 | | | | TIM1_CH3_1 | | +| Channel 1 | - | DCMI_1 | ADC2_1 | ADC2_2 | SAI1_B | SPI6_TX | SPI6_RX | DCMI_2 | +| Channel 2 | ADC3_1 | ADC3_2 | - | SPI5_RX_1 | SPI5_TX_1 | CRYP_OUT | CRYP_IN | HASH_IN | +| Channel 3 | SPI1_RX_1 | - | SPI1_RX_2 | SPI1_TX_1 | - | SPI1_TX_2 | - | QUADSPI | +| Channel 4 | SPI4_RX_1 | SPI4_TX_1 | USART1_RX_1 | SDIO | - | USART1_RX_2 | SDIO | USART1_TX | +| Channel 5 | - | USART6_RX_1 | USART6_RX_2 | SPI4_RX_2 | SPI4_TX_2 | - | USART6_TX_1 | USART6_TX_2 | +| Channel 6 | TIM1_TRIG_1 | TIM1_CH1_2 | TIM1_CH2_2 | TIM1_CH1 | TIM1_CH4 | TIM1_UP | TIM1_CH3_2 | - | +| | | | | | TIM1_TRIG_2 | | | | +| | | | | | TIM1_COM | | | | +| Channel 7 | - | TIM8_UP | TIM8_CH1_2 | TIM8_CH2_2 | TIM8_CH3_2 | SPI5_RX_2 | SPI5_TX_2 | TIM8_CH4 | +| | | | | | | | | TIM8_TRIG | +| | | | | | | | | TIM8_COM | +| | | | | | | | | | +| Usage | | USART6_RX_1 | SPI1_RX_2 | SPI1_TX_1 | | TIM1_UP | SDIO | USART6_TX_2 | + */ + +// DMA1 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +// DMAMAP_USART3_RX // DMA1, Stream 1, Channel 4 +// DMAMAP_UART4_RX // DMA1, Stream 2, Channel 4 +// DMAMAP_UART7_RX // DMA1, Stream 3, Channel 5 +// AVAILABLE // DMA1, Stream 4 +// DMAMAP_USART2_RX // DMA1, Stream 5, Channel 4 +// DMAMAP_TIM4_UP // DMA1, Stream 6, Channel 2 (DSHOT) + + +// DMA2 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +// AVAILABLE // DMA2, Stream 0 +#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1 // DMA2, Stream 1, Channel 4 (PX4IO RX) +#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_2 // DMA2, Stream 2, Channel 3 (SPI1 sensors RX) +#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI1 sensors TX) +// AVAILABLE // DMA2, Stream 4 +// DMAMAP_TIM1_UP // DMA2, Stream 5, Channel 6 (DSHOT) +#define DMAMAP_SDIO DMAMAP_SDIO_2 // DMA2, Stream 6, Channel 4 +#define DMAMAP_USART6_TX DMAMAP_USART6_TX_2 // DMA2, Stream 7, Channel 5 (PX4IO TX) diff --git a/boards/thepeach/k1/nuttx-config/nsh/defconfig b/boards/thepeach/k1/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..e087c61fcd --- /dev/null +++ b/boards/thepeach/k1/nuttx-config/nsh/defconfig @@ -0,0 +1,230 @@ +# +# 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_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_DF is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/thepeach/k1/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F427V=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0001 +CONFIG_CDCACM_PRODUCTSTR="FCC-K1" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=2000 +CONFIG_CDCACM_VENDORID=0x35a7 +CONFIG_CDCACM_VENDORSTR="ThePeach" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DISABLE_MQUEUE=y +CONFIG_EXAMPLES_CALIB_UDELAY=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_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_LIBC_LONG_LONG=y +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=2 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=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_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +CONFIG_NSH_DISABLE_TELNETD=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_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=262144 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SDIO_BLOCKSETUP=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=32 +CONFIG_STM32_ADC1=y +CONFIG_STM32_BBSRAM=y +CONFIG_STM32_BBSRAM_FILES=5 +CONFIG_STM32_BKPSRAM=y +CONFIG_STM32_CCMDATARAM=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_FLASH_CONFIG_I=y +CONFIG_STM32_FLOWCONTROL_BROKEN=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=y +CONFIG_STM32_I2CTIMEOMS=10 +CONFIG_STM32_I2CTIMEOTICKS=10 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_OTGFS=y +CONFIG_STM32_PWR=y +CONFIG_STM32_RTC=y +CONFIG_STM32_RTC_HSECLOCK=y +CONFIG_STM32_RTC_MAGIC=0xfacefeee +CONFIG_STM32_RTC_MAGIC_REG=1 +CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef +CONFIG_STM32_SAVE_CRASHDUMP=y +CONFIG_STM32_SDIO=y +CONFIG_STM32_SDIO_CARD=y +CONFIG_STM32_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SPI1_DMA=y +CONFIG_STM32_SPI1_DMA_BUFFER=512 +CONFIG_STM32_SPI2=y +CONFIG_STM32_SPI_DMA=y +CONFIG_STM32_SPI_DMATHRESHOLD=8 +CONFIG_STM32_TIM10=y +CONFIG_STM32_TIM11=y +CONFIG_STM32_TIM3=y +CONFIG_STM32_TIM9=y +CONFIG_STM32_UART4=y +CONFIG_STM32_UART7=y +CONFIG_STM32_UART8=y +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_USART6=y +CONFIG_STM32_USART_BREAKS=y +CONFIG_STM32_USART_SINGLEWIRE=y +CONFIG_STM32_WWDG=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=300 +CONFIG_UART4_RXDMA=y +CONFIG_UART4_TXBUFSIZE=300 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=300 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_SERIAL_CONSOLE=y +CONFIG_UART7_TXBUFSIZE=300 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=300 +CONFIG_UART8_TXBUFSIZE=300 +CONFIG_USART1_RXBUFSIZE=128 +CONFIG_USART1_TXBUFSIZE=32 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_RXDMA=y +CONFIG_USART2_TXBUFSIZE=1100 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y +CONFIG_USART3_RXBUFSIZE=300 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_TXBUFSIZE=600 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=300 +CONFIG_USART6_RXDMA=y +CONFIG_USART6_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" diff --git a/boards/thepeach/k1/nuttx-config/scripts/script.ld b/boards/thepeach/k1/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..6d92733df8 --- /dev/null +++ b/boards/thepeach/k1/nuttx-config/scripts/script.ld @@ -0,0 +1,146 @@ +/**************************************************************************** + * scripts/ld.script + * + * Copyright (C) 2011 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 STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000: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 first 0x4000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K + ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * 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.*) + *(.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/thepeach/k1/src/CMakeLists.txt b/boards/thepeach/k1/src/CMakeLists.txt new file mode 100644 index 0000000000..a7db4590f0 --- /dev/null +++ b/boards/thepeach/k1/src/CMakeLists.txt @@ -0,0 +1,50 @@ +############################################################################ +# +# Copyright (c) 2015 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. +# +############################################################################ + +add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + spi.cpp + timer_config.cpp + usb.c +) +target_link_libraries(drivers_board + PRIVATE + arch_spi + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer +) diff --git a/boards/thepeach/k1/src/board_config.h b/boards/thepeach/k1/src/board_config.h new file mode 100644 index 0000000000..4b1542e547 --- /dev/null +++ b/boards/thepeach/k1/src/board_config.h @@ -0,0 +1,182 @@ +/**************************************************************************** + * + * Copyright (c) 2013-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 board_config.h + * + * ThePeach K1 internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ +/* Configuration ************************************************************************************/ + +/* PX4IO connection configuration */ +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS4" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */ +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + + +/* PX4FMU GPIOs ***********************************************************************************/ +/* LEDs */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12) +#define BOARD_OVERLOAD_LED LED_RED + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver + */ +#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 13) | (1 << 14) | (1 << 15) + +// ADC defines to be used in sensors.cpp to read from a particular channel +#define ADC_BATTERY_VOLTAGE_CHANNEL 2 +#define ADC_BATTERY_CURRENT_CHANNEL 3 +#define ADC_5V_RAIL_SENSE 4 +#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15 + +/* Power supply control and monitoring GPIOs */ +// Signal is not connected +#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8) +#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5) +#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15) + +/* Tone alarm output */ +#define TONE_ALARM_TIMER 2 /* timer 2 */ +#define TONE_ALARM_CHANNEL 1 /* channel 1 */ +#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 5 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) + */ +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL 2 +#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2 + +/* By Providing BOARD_ADC_USB_CONNECTED 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_BRICK_VALID (!px4_arch_gpioread(GPIO_VDD_BRICK_VALID)) +#define BOARD_ADC_SERVO_VALID (1) +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_OC)) +#define BOARD_ADC_HIPOWER_5V_OC (0) + + +/* 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 BOARD_HAS_STATIC_MANIFEST 1 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +extern void board_peripheral_reset(int ms); + +/**************************************************************************************************** + * Name: stm32_usbinitialize + * + * Description: + * Called to configure USB IO. + * + ****************************************************************************************************/ + +extern void stm32_usbinitialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +#include + +#endif /* __ASSEMBLY__ */ +__END_DECLS diff --git a/boards/thepeach/k1/src/can.c b/boards/thepeach/k1/src/can.c new file mode 100644 index 0000000000..5a32d62832 --- /dev/null +++ b/boards/thepeach/k1/src/can.c @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_arch.h" + +#include "stm32.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 diff --git a/boards/thepeach/k1/src/i2c.cpp b/boards/thepeach/k1/src/i2c.cpp new file mode 100644 index 0000000000..63ec5a5228 --- /dev/null +++ b/boards/thepeach/k1/src/i2c.cpp @@ -0,0 +1,40 @@ +/**************************************************************************** + * + * 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), + +}; diff --git a/boards/thepeach/k1/src/init.c b/boards/thepeach/k1/src/init.c new file mode 100644 index 0000000000..107312832b --- /dev/null +++ b/boards/thepeach/k1/src/init.c @@ -0,0 +1,318 @@ +/**************************************************************************** + * + * 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 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 initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include "board_config.h" +#include + +#include + +#include +#include + +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* + * 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 + +/**************************************************************************** + * Protected Functions + ****************************************************************************/ +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + /** + * On resets invoked from system (not boot) insure we establish a low + * output state (discharge the pins) on PWM pins before they become inputs. + */ + + if (status >= 0) { + up_mdelay(400); + } +} + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + stm32_configgpio(GPIO_VDD_5V_PERIPH_EN); + stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 1); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 0); +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void +stm32_boardinitialize(void) +{ + // Reset all PWM to Low outputs. + + board_on_reset(-1); + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure ADC pins */ + + px4_arch_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */ + px4_arch_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */ + px4_arch_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */ + px4_arch_configgpio(GPIO_ADC1_IN13); /* FMU_AUX_ADC_1 */ + px4_arch_configgpio(GPIO_ADC1_IN14); /* FMU_AUX_ADC_2 */ + px4_arch_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */ + + /* configure power supply control/sense pins */ + px4_arch_configgpio(GPIO_VDD_5V_PERIPH_EN); + px4_arch_configgpio(GPIO_VDD_3V3_SENSORS_EN); + px4_arch_configgpio(GPIO_VDD_BRICK_VALID); + px4_arch_configgpio(GPIO_VDD_5V_PERIPH_OC); + + /* configure CAN interface */ + + stm32_configgpio(GPIO_CAN1_RX); + stm32_configgpio(GPIO_CAN1_TX); + + /* configure SPI interfaces */ + + stm32_spiinitialize(); + + /* configure USB interface */ + + 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. + * + ****************************************************************************/ + + +static struct spi_dev_s *spi1; +static struct spi_dev_s *spi2; +static struct sdio_dev_s *sdio; + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + + px4_platform_init(); + + /* configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "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_AMBER); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_AMBER); + } + + /* Configure SPI-based devices */ + + spi1 = px4_spibus_initialize(1); + + if (!spi1) { + syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n"); + led_on(LED_AMBER); + } + + /* Default SPI1 to 1MHz and de-assert the known chip selects. */ + SPI_SETFREQUENCY(spi1, 10000000); + SPI_SETBITS(spi1, 8); + SPI_SETMODE(spi1, SPIDEV_MODE3); + up_udelay(20); + + /* Get the SPI port for the FRAM */ + + spi2 = px4_spibus_initialize(2); + + if (!spi2) { + syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 2\n"); + led_on(LED_AMBER); + } + + /* Default SPI2 to 37.5 MHz (40 MHz rounded to nearest valid divider, F4 max) + * and de-assert the known chip selects. */ + + // XXX start with 10.4 MHz in FRAM usage and go up to 37.5 once validated + SPI_SETFREQUENCY(spi2, 12 * 1000 * 1000); + SPI_SETBITS(spi2, 8); + SPI_SETMODE(spi2, SPIDEV_MODE3); + SPI_SELECT(spi2, SPIDEV_FLASH(0), false); + + +#ifdef CONFIG_MMCSD + /* First, get an instance of the SDIO interface */ + sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO); + + if (!sdio) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO); + led_on(LED_AMBER); + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + led_on(LED_AMBER); + } + + /* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */ + sdio_mediachange(sdio, true); + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/thepeach/k1/src/led.c b/boards/thepeach/k1/src/led.c new file mode 100644 index 0000000000..8a70a4cb29 --- /dev/null +++ b/boards/thepeach/k1/src/led.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "stm32.h" +#include + +#include "board_config.h" + +/* + * 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 + +__EXPORT void led_init() +{ + /* Configure LED1 GPIO for output */ + + px4_arch_configgpio(GPIO_LED1); +} + +__EXPORT void led_on(int led) +{ + if (led == 1) { + /* Pull down to switch on */ + px4_arch_gpiowrite(GPIO_LED1, false); + } +} + +__EXPORT void led_off(int led) +{ + if (led == 1) { + /* Pull up to switch off */ + px4_arch_gpiowrite(GPIO_LED1, true); + } +} + +__EXPORT void led_toggle(int led) +{ + if (led == 1) { + if (px4_arch_gpioread(GPIO_LED1)) { + px4_arch_gpiowrite(GPIO_LED1, false); + + } else { + px4_arch_gpiowrite(GPIO_LED1, true); + } + } +} diff --git a/boards/thepeach/k1/src/spi.cpp b/boards/thepeach/k1/src/spi.cpp new file mode 100644 index 0000000000..77d0c37214 --- /dev/null +++ b/boards/thepeach/k1/src/spi.cpp @@ -0,0 +1,49 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortC, GPIO::Pin15}, SPI::DRDY{GPIO::PortC, GPIO::Pin14}), + initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortD, GPIO::Pin7}), + initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin10}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/thepeach/k1/src/timer_config.cpp b/boards/thepeach/k1/src/timer_config.cpp new file mode 100644 index 0000000000..c96e7c5664 --- /dev/null +++ b/boards/thepeach/k1/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), + initIOTimer(Timer::Timer4), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannelOutputClear(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/thepeach/k1/src/usb.c b/boards/thepeach/k1/src/usb.c new file mode 100644 index 0000000000..6fbea86a0b --- /dev/null +++ b/boards/thepeach/k1/src/usb.c @@ -0,0 +1,108 @@ +/**************************************************************************** + * + * 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 usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#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_STM32_OTGFS + px4_arch_configgpio(GPIO_OTGFS_VBUS); + /* XXX We only support device mode + px4_arch_configgpio(GPIO_OTGFS_PWRON); + px4_arch_configgpio(GPIO_OTGFS_OVER); + */ +#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) +{ + //ulldbg("resume: %d\n", resume); +} diff --git a/boards/thepeach/r1/default.px4board b/boards/thepeach/r1/default.px4board new file mode 100644 index 0000000000..4d4ab00a94 --- /dev/null +++ b/boards/thepeach/r1/default.px4board @@ -0,0 +1,107 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" +CONFIG_DRIVERS_ADC_ADS1115=y +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_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_OSD=y +CONFIG_DRIVERS_PCA9685=y +CONFIG_DRIVERS_PCA9685_PWM_OUT=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_PWM_INPUT=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PWM_OUT_SIM=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_DRIVERS_RPM=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=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_L1=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=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_CONTROL_ALLOCATOR=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UUV_ATT_CONTROL=y +CONFIG_MODULES_UUV_POS_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_DUMPFILE=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_MIXER=y +CONFIG_SYSTEMCMDS_MOTOR_TEST=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_PWM=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_REFLECT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=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 +CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/thepeach/r1/extras/px4_io-v2_default.bin b/boards/thepeach/r1/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000000000000000000000000000000000..25a00e2357d781ece9c0d41447c3f4a52c6d19f6 GIT binary patch literal 39952 zcmeFZiGNhp{Xcx}GFvi`$pT~pW(hFKuml1c#buaDZk7o~iTxG<+lxVa5j0WM#x61t ztRuk|janowXlz}eH8T)P&^S@Fb*b$POA7=_6zi2l>m3Npoow^G&rDGI`#!JddH#S0 zUN`s7J=^De&gXpgb1Nqj^P+U3KbrUdU;kfmpzkEgyiuaeQi)O?Bg#`Mv7~y8)vd0S z!}M;fYH{fg6Xn}st#V+5QC5$*RX*=qd6~+m;wkl8nFP19#B7{E%!ClL_cfw_48NnD zq+qUR-VOQUDlyA8w{mXPyy_B>7mZ@3G-s(>VYp0jwr9F@t#hh4Nt&T-xqrr>chMyJ zJm{S{A!wwHo(lm8yfr-=I5}Ye+6PO5Z{9Qz^C4G&bN=1J zv{`Qw-H=wb_3QNqQ#i%Qx%&;=UZ=ZX&;1p(emwN+^9#Bv_`IXE9Wi%*r8Engw4x1$(CmyypANdTwf&~dv?KazPSJ78RGXO;q6aQ3XtHEk zFh9Z#5yf{S#Q|;qzv>s$Iy)uCM(deeS;1_9m{A)StNa&^&9)@hEFS$L{zYI5R^h+jFY&Vthoxm}IrPK=)0ys6FR{d< zpI%mb^ZL5Gvl^D`58wTnw0BrJzudqn(>bQ(GjXNf-A^)24b7ruu%qq?b+w5p%nyS` z>z`0>BL+Jg(%adv!S5dQ)}=RmBBnPyq1KbswYEWLogQyVUFzzL2EaV%+)xLI*+P8~ zb?Z;d&Fga;Zj|<_KQcS}SyzfktUZBt{A#Q)b$Zu-Kd%mTRq<7Rw_;}E(MP_6**3WS z9t*HBh<@@KvZbE$PE%t=^ZI6WOX8l_a0^!NQdtk)m3Hz%qTh#;_@e#Zf_}Zsqk(vI zMcgbf%4YSOz{9{`X}1mU4ZOh^k1mZ5%BIdO>yM~jLX^J`9Z`M7JrOf$b{RuQ)NSVJ zj?gMD!muepVtZfpnQ;}Hx`}y2F74!mHpzcs)5crZnuI;;uM7Dv?AWLcInObf&$x0! z4N5k_NDc4lZe3g7U^oh_g2HEvl`DFUt>Mb%X5jrfnG{_WdQx3o zyxY$>Y6rdd8iTciWCO8fx}Q|*&7>$R=(G}RCiqD)*DS8Sn=qW>ykA@|6T8 zo>V1ZV#YAB(x-Hx`zw=^Q5p^qQrh|OdTmva@D$!N${jv@feaD$Y5&57h3{PC9B9h;lK`*!F=E(zQDJ-khQ367TooJ$PY= zIQqiGT-u$fOyu%|brP}3m#xrP?9vKl=Vk{Pv#I+DbxW}cqq_Yj%&0$Z_L~zh6Xo3? zR?1S^sS&oUHw#--(G-ua9^1V>t2(ct)s-J&FEqO7{iO@{;jRe-)AJ`*5-U;u7PDek z*+Abm?Bc_s*btBI8Qs;;{Z%Q}>XmNH(85=qm2qFfRsI_?iBysV-=_SV(o;P8Ui?f$ zoj*xeF9K>xU+ZI(ioBqpQq-|k+Zr@NtLy4tFToTgI`-&k_z}O}%{Q>laD*wk#S9kp=UlNK-9#ajV`01l10<(~t{cV`ce$8ztvYC0^}w?h3Ic%+RJ|ZW$Y3krm#`CGQoQ$M6`?n(99oAnazeL znB&opNBY2d{xZ_7YE2wUvN12V0~DE4tpIP! ztZwWiwk+YMCZ9_iVoG!lHezC<;aVkLGL3ohR(^mpZ6#?IxAeI4QoE^Aq4O5;VQG%P z{nq!SHgeqgQQ%c7`7mY&;6#rzQfrJiFjivOl~0u4#)x&kAT}|ISEVb_8D|!WO~7wV zH;0dy`2KKXH*I%oF41c}rcQ2vWMK})jN*zB`<@_nGxlGyZ~As=S8->#v_~pX7=Djf zCRtW5k*Zg_q{HG8iEG=Mn6Gs(?pn!Pl}2`@G1J{57I*iYWiysYKFJB`<<;tr5Jz^< zXwwH%!1G$DjK=SYwu^E+dVA0<9h0a8`Cfi-lC7U%QrxU~CO~x*z(a~V4IV>f4md}y zpsz73efPZ1@{EfO>!3RocXOguWJ-#}3-b1FNZ$@zyKp^=>q%VSp4WJ%DSR3m`u4nG z(__M&0vj>27_WKG*^%0{!g`@V(Xmf~kM*e*!RIoBNMttS|4KdeaTBgsB zzqA))aMO9cZ_{~$kHUtzkTkog({##IT9(cYY~i?w=;ki0cBf)rf<_a%jY*_fo#5f^ z&=bLvyd{}{RRcK;{#2sM+QgIBc3w`ib79^?+kPX1E{e}!Zxvt;rasbF+DR!Tr#h!5 zQ>+tnJUP|v7x}t_DnF-I@h&*1X3epR2i5#Jc~VvtQ_@SA#ZwNE85y1;A)_kQJXIvh z1MwokRK=Nza!=fbwc7}p)91E{NT>17zKTZb)v zOQ?rr%v-mkg4koB`t^kZ<-Lv0wmY*c=A2b)%Ue2P(~9Q=m_@wc6CM|KyN(6P3{X%C zbn?{pmb}1jx&zGhE!I2p0&@ba%6V^Z?*2;sO;-d=4SOj4k*%QoWXkSAXTaOAj5W?q19l0uHibIwLws6pmsC0BgfQ}On6ofB_n?6%`|94F`MDevn_Ni=#K9U7| zR*xkxXb)ce*&Dzi|Da5NCwp*WwCxpl0i!qa^lu7(C-AB)X_jtXtBIKOPGF-5_{`~@ z+r(TkS&3`sg_yaH1jNZbH_#Lhtm|60-Y(=xSixz!6SQ~Q?gn5HINU_b+7e~!)^jK9 z!b&`UEw8*Y)o;g|uUpSpP`-9Y1#LIC@iRa%h5wfv?MxF$q()03t2FGn-k0zZ@UQHvD5vrBJe(D7~ZgE&F2A%y|K(WG7u? z+e!O8?LP(o+1E*mswWhZzb zg|Aui3TeV*;nuZ`a{pM9AJC0krn&*Get)?woYaaICOC-l2vLrWY!ZmQKdgylr`(8f z$42;RO7Ag@RwXnmPCca)y5s%Ahv&W7lwah87Yd8}c1u%KChwSzJ366I6VBCXj!;YG z)zQDoDTT3crc#i`g(iT8;?d_vQ!I*ndHodBPdVZeXz2^1{4`UqArikTgqDMemP|Os z@~!L=lI?$u8W&Ia%b7#JA29HDw(K6qEgwo!DTR(g{@KWriCywZlSVKK4*w^T8>{|_ zsIj$(RF?uRk$6-YNj?|gxqtlGgy%0th!tz6OBYH3)v3gp4uQwU>LL;zM z1Xj@w5lb=d?2rxfz)CHt9qhfAfrh)Siv-s{PxVwD+za~9SbNiAKc(<2(%wkzG@`V; zP5lGBz@z*JWA)?Z8Ki!^{O2fd?7XyJ>euICCz>KTX-;L6*LhA?@;tcSn-^Rgbtm4u zuyx}PVa-m;eBQM#)Yx5uX9LP(lpAbHQs(#cc=d_)mfIi?G6HS6%;GfYQJ3miA3L)x zNwX;@&up_kmaOw}fbwPsBwARuKGwHwU#zG&BR~Qfxr+RK+m~AE$Jc~AS>N&!`tOrp zY7yyfP1Kg<+gf&^1_>nIWkNMSjB@XR(%B)&)=v^~ts;g8j~n1%M{c=Yc0 z#lWvHeo#)zJJ&hWJ@M$`cZhv!nA-2pyHbFKO&goT_xl}Ey|_+l7YC#>;?Lzp{(8wF zwoB{8Gtz*#0lNe`0PIs95-bCDMhaGut_M*xBTRxah(Z!i1$Z|+3=TyYOLDCS-=Zs_ z0q26Ytt|$nJw0q|VjSAz%wk(3{r&QALVLH=ueUU|t)(*40q+%m1bcTiB;GXZvBVtKULRmy+fng`>#NY2 zZJ$HO2;J-moY_LDg;|vBi@D+$cIWveI`Gcz!c<_*q4Lu*dY53oF|UK);gKk z(Sv9C+pS7k!cTi*6H$s`_aw(Nb?Ryus~M{pkERaSUW{+3_YzyXH@Q+Z`xk-_mO`hp zji%ISgnco#xY@LPjhu%%)n*j=3gFW#(mc z5o>PaIeA{uPzd^?V^G$2Qrq%haq7>6<{9K)Ci-hIF0oO$o+(Zi*d|{GDJlJP;5ygHn@ki;d z;r}6XLQYe*kSj1H^ZoM*)v!t6nwSOi97CbT3bm8N&d6<=SELWksK?m8u1q*jZ%0#o~6mVMWFX;Pmk4}cw&{o7-!r4fZ(a9{@^TMqP6XAF85poX>jl? zDcG~=1GNX(_}SPJk0eYLSsU|ONh71Y9D`lOFv^?5yzQDAn`o05$Bn1VQV)D}@4=e~ z%KOC>;R?`+S;~>NyUI^mG2;nho>W-*thaC@-Td;ailsZD~l3>)j4 zVaB>!%Du<#$@g-$l15fJADih(^&^%uG6Q!;xiwaRJGJj@iT8DJMzIa?wv5UWXc@{d ztGt6~&kj|C)|AeOvP)%@U&Kaao3xU=A}>)FH0DUmzLe^_M`O<7)_(06mb*6tiGF1=OO}oFZoPnoAyfVl%JNz$Ub9VU)+zeK9j3b|vI= z{fF*3GLYz#N?j^5!f|fuP>AY1@#rUUewy|K=ulnb;u97)JVNl+bAqX}axcc;lC%md zF2?Vn5Nw6tH>tTcC|e047(ONeO%gi8Nkg?sD)zJMce?b@;<+^x*U9?CEXzbndd@$W zDSciVUxV?lzcl_rvp_X2N?Y&&#=oa7hcA~m9C7&a_=!i8+DJS)Ii8UBv(KNh3(Pg~ z=*#hfK)*cO`yW}?Df#u)#L_W*?mRo339l=3fDOyt%ytQU`|A-dVbg=(xYEd+v+*Uo z@V?mxeSJFO9*1KZ;h5jpwoA?TvaP9Y7J+F^XY^LT zoJHZksl-WbpV!gnvt@hWKe!lpX%ponY}<2csoA!g!<{$PuWoN)5lOZw2f0jldov#? zV=WJ?et1rHoMY#Z^7I$YOj{`^Vxwz_jU~2mX_MPoUXt6p-OJtESG~9&sG=o zF$=y#AM<1UUvEx{AyeKZ>7zS;4Ks zPQfeOC`>}{PmBrqi{6?ounV;VTNrAI4#Zy}@ch`zLS#T^=uye`8&U6}F-m} z-Zl9Uv+!+~5^hkmM3y}&UyI1VbiKel&L}lwn+4_>Gw6*;8H-*!c5~U^LFX&TVM^^J z1fKX!g7+r)MZ(`nl#cJBlkhZ}F>clb@XNz$k9nDDHdS@4TH7|x7xm$EVOIrF@>HgH zm+RXwV^(DboQhFCA42>j!EZI5Y^l`W{1E40!yPdr{D=(-i@%gt@`ApT_k0n^mIz`g zL|KC98e&Idw2bn+<$kYZ1}{FW?t&-euZV3XwbZ{L-bJHbqM0biiIk4$5Oh`&lyb4?%PEUA^OVpcWNQp1deQT{n*7g*d6 zCp<)@;49=U<`kn$06ddPX*Z3-(0L`>M?lxf`Fw+zBeCTOnrdw&Q?k_Y9`qYFqG#3c zSoAkso$7Ni*w*~niFGD`{=l|N=OT}bBZw8qlLtn zD#fE?!)g9?>lceJQ@EOw(uYMvFH0yoCjQRAq%x}I-;uG_# zwfFh04{mj7!(1ebDel5vR7O?4&ny&3@MbGa?2^4&3R%wmd?nRswv4YSINe_LQsj+w zXsH)syo|3>WX5qmoTQqvcaG?Y`LDR>USJ9+#EjA$Gj}ly&9f5`G+?KUE_m)2yni;`Tnb;lefS&1JZB6mi1^bM#zd_bReM(!`eBr3)$A@> zuXN}f?4Nez6Hv=*f?#Okg_yq#JEAzb0}r9pmt6HpRg|_ijI=+bb?C$Y zCx+ya9}oG?Co+@f=|c=629w}Lq22@VIqh+|{UMFxVwi^(NtE+yM7~59-B%Jll~BBZ zn1LQNz%i{PaTmUVPWo_>wy_BFKrGGT*M{Bv!@$n2;_3Mj;Tb<4Q zsoYfO!~LmfLzMdXkB7Dn(O3y$$Ya#^^L6Y^@KwO+PJ?bm>{oMpNj_q!n-*l+=;+dD+@ zo0^Cqe+Dl>Ji2VGy#*Nu_3h0`UnG2CC{6Cp{QU*+J7gb7@_VAZK1OU-cr&xHlZr;I z0x&XPeUX<~nJp}E{mF2Wk6_mlc*6?pp28boS(n*8qM6=jdH#&Q^l7Gt{w0ca zL?cxCNkr7mzTXaAH+vD4$8Wfz;U4UY%n>S+*;&~)kVuba*8OH$Vv&1}s*^kG)R;`^qZuc=eC^xq}Ncs6^V+GPVdGkZsq7-;K<5uLMneVfDk&i>H z>>Wh8_N~SWN^@60{!D;IpHDgX_-@pJLm{srUg~7FW9LOX{LHJ!j~k`BO+2a}o#ST( zL|U$Qh;{IfY9EY8^G9ivr&vhrpXL&&eGT>VmxPGrxXKq#s{|GH^<nJea-a3jAL}KJUQm` z{5f>9x(X1~1A-n|o7nqz#l8eJr)a;$UrzgVLN;9wJBiv#Z(R-j;p3f)OFJjPo8^QD zLr}kvvi!DR>~?XGX5gQY6$KLfdBg<&Uo__QPpBlyi=!P~l%iAd+(v10ToxgRMQI&P z(wDs}8!O8X!+&Pu?l*N`T0h9PU;ejjL!^4V4J^?A2if+I1DE=sGR6q|ZbyPQEC_Ag zOA6;*7Bg~7)H}0AonCdfI8pjQHF}wa)4J&1H;vBjD;8k=*&dfxW-~|ArTJa$uB?;k zQejtC)fc&6%O)X3P-LIPl_j4Fg^AUe$Ec}~YAzXlk4sOx+6Nf!Ex*h($`a71<&7 zv!P1A;RYTUoi7!FYpjh^jFyOv-4vgVPKwX|{YiY%b_sd6&g^e*>E)TD;P+~K3(f3k zZ$?Jo*@-3f^^leOTz4As8v>yzbMfe1bN9?x*WM@%X`YMTl?^@bF)aal+^8 zipoB(zir*JyxZ!t!C#4O7mr}yY~(igN6^s{u{@C8vEZkF1-xLh^DQhQY%Za z`I(K3!ZGovJ3hM%8C(47JiGAcvlD-C52%5I52g|O_+UQGw!6u%FEb<8q$ijD<*T#H znvr4CSRn})WSlr~MCEVa`NO{$0Wo+&PB&Jh2=tjvJQI=vTb&U&@RjB2r5Mab_zu1R zA7MR=0P0Z=0>;aKXJelwf78Bbjr+PTFYg^MSFz6~(-@2LL-q9>O(cz5oy?&_1S^!w zl)ZnJ$>e9`Am5f$SdiiHdr4pVQ|}J1Y5G!cpJ-M2Rc*e{rG|dDyP?0%Z5HahM7cSk ziK$Lx3+!jmBh4&o?0hNmGM_EHY&Dh<%T(cuTrTpmmMH#F4tpw}C6Qgsiq$VgjKsKL zt84jfT*Sy-1ji?e4qi7abeVYcwYXhq?53WD(dYw-2sF*L)l(kbJr?yLDirG-i~eoo zM%c=TN5p#EJ!uhnG`f3~18?I`nc?r54(sAVFJu0}C;ISit$8g@+;+xh9I-fgCN}A~1++9AJ;b>JhA`_n#++Nz#C%JnQZ8Lih zpJhx-M1y~aM^Z@dN{WH5FOy;>mx=5yG2F`%I;kp)j5hB|0PGG}%i1xQ3ZnSa3L@Zmo zaIe)@FTL)%;_ypS9W

|4XnOt-iXvREO#KtAVz_>YVyIYgwh&d>Le%yUt7dEQ#0q z_=T6KisFa9of$9izYcAyXgbdHzzR^iXGoSrjzd{|w(v*bKPcx5??Unt_cJa?tqL!^ zg6!eMnUY7|jgXZ2{V7~ZKcl-4HqGOYK_*qCqu9eM%l$};@ z?%5G+&kN+-BRaQ_u7VU=hb>{Y6cM-&zIjQ~jc=UIpQ5p7>m?~v<>BUOu zKOQMt9FkL^5pi9Wq8@KJK@Z8FA!Ych5&dDX3ST0ZlNITSnpBAuTKryrGkg=dQi@1x z7!Wz}pv>W?T3D-VC=7dXKkbLWl4K=hfOf4A>8RkY5`DYOUx~gqyJ{7}P6{%TN6ZmX z3+2S-25g*|+4b&ONQ{c*35Y^x$$|x4sbWc2HTpqxx&#^2VpLv%ix5Og?%j^KNvep* z3CC8t-Na1cq56MgCo--qWfCjtJpZ0@W|%F925*BaySjXUfoJ3|YO$D*7O)X6*$k$d zIcI&9Qv@sgq!Wb|U8mKBUR>L8?ZVaZVL7Z*n@zk5^#5wbSaizha+P0PSAOpB%5vq< zjtclogI_^DG~w(Ty=cxXz1#g3cnS&f(5T)?byVbW3iJJy(^&h$V1x2Ql6*J4@C9TU za6?RllTzI~gB&3I-z6>oRRXM<>H17Bd@e|&55fPL@!lrx<2t$5VYlVcY)TFC2$3B+ zz;!fMC^%IyL1^jF3GA!1>{`S^3-L@8LFJ!kuAuw=DOk3mpMgE0!TW5rP+)e_r$y>D zVk)xpXb$X<+$^zcTV1+C?@8gCiKSV35ApG4F?@4lg~r2N&50ThyV{*tId*<(Bh|Sb zRYdO!aQj}&2(|#${u_0UknV;^JiQ|>vG=akWBUhE;GrW#^bJLC`>N%BPZmJseKDZ0- z)~9Lkjv#jxy{!%7jg*#3Yc(X_6k?3zSl+chls2ZZ!NNiFcjGt9x>@>&PH$Iq`qS#k z7xfXnK1b1~<%Ru1Y9BM}G1W*WM2snevYAGAu_81>ueLmT_)o6i59qijgSi5+9*hvq zhdj(lWz))15F7fqTo=B!>`H;mb1Ifii^^^hQjoc2lX8(Mh}`A5{|PbIeGO>Vq#590 zV}X~oY5x;m+(qH$Lzqv4F-QW=05DZY>^8;3y+hBb)wKnjt`i#e=#Bk4Lux3+N?HM% zp$h8&A4A)&0fXVk!0QRkr;r2p9L34Jl&8>26(&s^3b?%Iws`}&?0`XcF0d@`P+)c6 ze?#jH^aKiFj~s|BPiqU6$JxO-sKqQoR>1f; zDUtZqpURZ7w7cmFasvjI(o2SF%->P*;divhTz~XSM2izqQxc>xAia<=NbboGG8QYm zyZeUEU0{bNxebn)!fZivvbZGRBFNW2cf7IN;J>mYD*v$Lf=t_W_{mJl^=@A`1F<$l z1Jq*Z!;VMWbh@KV!t&IsSM-~;_MldnBYiDvabl11E>2*}T5%=-PoU+P%po5ty@@Fy zg+pOeZes|OGD{ta zK0SIKYivim(dfNztDVh=Wwf}`1oI)M^e7?9H6vO<^8c>MYetSjOi*W##;*1z=Gy06 zniEtiY>v^$UP|Bppd=psc?|KHMcpp>@EzhSjW~CauoFh2KZIV(3lF26?vRLB)K3sk zM9#ExEPBU*#+h%Bdg<6L#bu`Jh%!GmIbuq?7^ZLH(Yn~b5o1wnX|91!n1Y-?XjRI- zp-q_41!S*Z*L#yddGP*VN<_yzqq4;xnOa;eg5hMPz|4pl3`QNzp+e8Sf)=gNL8QV-@zJU##2 z(6@8Q$z71ANvsVlm*o7tvW2nK~(&A!z4%O*9d|qV@*- zCPQSdMp)F_-1H`TpMQePo7X!Ubpyv~y}O%g`(^!~@ZN|_4}FBeZ2D26K`zN?v?758 zoCc5-QytDV)Tw5oQ*?}0(P`NMCY=muP4JK-j!0`4k7e~2@TI|PgfkQdzE4&0H{S5_mU9qp4$PPc+axY{K2h-Z$wM zz{0*o(wA`Wz2%xLM8hW7sMKHW!n{YL=SL-s!l?hoF8&qtxrh7<*XH}zNJjsz3Lg3! zV8oeCvI)`X#S)XnJt;UB@$`fAR)8l zO6at$i`TC6pOd&J@+6O6qNiSfAzF7HsGY(|ZL@dd>jZvJuE2f#lFKfx6*C1*M6bCR zCIw$7@NriDSO-pVlwJD-bmMe*9}J9%?GshIgV?_fjp6+E*Rb5T#J>W}8a|P!#h;Oj zvBxI}k90uiAGQcM2@2oR9#Flp_Y_Y4A$xrXY1OnL_X)Jao}i^yBZjU+#Nu+zG#>4Z zf3KNN+&86DGp@7Zd}bnwJ`#QSvM4%@IGCJNi%n!GP4j`@O&6+qkwL561e#*!PC5l2 z(`)hQEf|;YW!iQ~_AcbB@juy1Y>UOhz9qm$S={6YUim?poqJT(Z=Z3>WFCt;;u@iJ zuOU)^a}A@>CvdKTo^u(C>f(L!ahyBc-LN!I8Vg->G`qs)8apoK0>HJGf1IXGRMTYUF(ddbo9k!$f z)JNmmqtX4KwG`~U(db&_SiKm$Q))%cR@D3eltm-xyzn7H5ej&g zcSyvaU!3$KnmW@whz&}6afXHzrJTxrh(77aNsO{Wx~&Tq-vVk0X7=SFxiIq#qn_`v=nvl_!5rka zPK0-OKaCiS$3>B4f|dLz$oc4rIW7`MboBio=cPF>9|rYn627g9q@_svr5Pxv#`lgq ze0c^6)e+KaW=NDbEsWDVCz{*)lXwB%oN3`LGz*nYWSu=4XDrASgies6a(IIb)x~Gv z?Wg_IHKq17ARNy&7>yQ=eG}k?UH;7v89j97@u)?m-(;XXc>(s&C#q#5rOies_1}(0 zOWvWSiQK4eiWk;%$!E&$r#@4v2T)JaM8VQUzg3{tjzy(+GP=g1`myXjHj+s_oT)3y z$+?4G&Z_eU2&8qw2>SEy`0KVV2XfINT8 zAX&0HmpJ@*#`(!v3splSap1|C;?qHc%`974-lJ^x?#44IS`j+nVvdt}w}f}Pyh@Ar zx!g=4e3t3yfp$SN(Akhr`m3rZJ6$w-cEj-$Ut8c%t_R-36tB&z_nlV1?s38^C3+92 ztl25B{YH2aUx)TE7JXopkMODUh2_*6#g0V(F=Y0UIj)dH_>ph|d5o}>j5mqt{u8R+ zyj6TIP?Y^d;02e}JJVBmd}CfP@XE3mv#mI*SM7ZpeP=qSyZ5MU<5;wMbfZk>T|fBC zH;Ci3TZ${6mPEef^ zVr%dLd5}AjB4vzwpR&baoN*Y5K08EcIr(|lyVYK;apa-Id09#F{W4emfSYTq zNZui(|5uIg%Pg0bU20d?RSo!(P*Iyc3Dw=-Lxo(M%b}s3Q2p~X_WWysz&FtB-Rhbm zR2&ZsZ9ebuAB>n8%@8+chOg%Z=aT-36Q6a~_D`vNXILGXKJ-XTKb-%$aoC_(j7#v9 zmF=#S;|H>hk@$SClD%oW3um`B?TN6)tIINS1H-DKABOHTY>2!ZDC=j-UUV6bUz0`ZeXRx^%~XnFA;mu!mlCk#lFgPYQE#QBRpTY(hPv((yHA zyUKOr**$S*j7H#ST$b%P({0#ho+PA?c@&pqcP!}^gT_atL^ zKU2P^oFC!_4S*MT0M>rv-Ba#_WzLpfTlTvFqXtk%CJv{sVutmxrvl~u#`4zy^)GW6 z%oV|+HG-#IelO;{^yAiXl#c3VVjnwpW#u-Dp!P@@(8}<#4#ikE!0}MH3 z<{{mA!?1qnG3Qjb!|3kk%U&vHhnRC@h&gXKoNqB*GTIL?-?DRcH4oV$kEM`@dy@;?hpg`C5aLqGEG9hk_j z8PM?jkS=P)NYmYar7MeYFvaS8=($FDn=tUDNr->xF8}h-{sDI4TFjp*?UV6!5jkDh zCT|kDWWBHfSCveu>e{kQnbJ#vOyv~kW5LOu2&B4OU8(fk_jfX>Es*18#&acM<@%so zpytZ~e7AvXcQqh8F;TzSYuN-&&-i)+j|Nhltd~kF6Li3m&Iz8CTiXIVTon{LeC^s>!obu3!t%=xl)wagusT+Ept2m+g6~lg2AR}h$iTP{XsaC@%m2oy_ z32Z*L3VMKz%3C!dN0i#Q`I!zzxo(JB2rpD34@+egSYy`bYMx(uGkj^hB?A#pd^>4m zkBb#9grBKt4xHIcY^>4R%(ed3L;cJwBB4)Jeu|!1MOL-u)+$bU9OwVs7hfR5(d|Pu z=ib2mPXT(3;bB{-td2Xpy2%=(b%p)lt(ZNj%ZavO)E<{@Op-dn$|Ezs(k9CDpY!!vD9e|wG%NA2JB zVWWL8Od%Iul9)9&^pt1ex_=tN`j64) zBnJmp-djH(%$JUs0q&dT}ZvjCYOa(*QvU0b+?))lqV z^tn$4=L>(1T*p+oD}%cEADIe8lw6UHNQYMZy)1!d6W`JxjGoeQI0rc>cxQ&+Z8ldEm6Y2XGb%fIKjd-rXH5+Yi#=W3=hR1~SUOt={r}qpz<%+2x^HPhas7Yt$ z23#4_L8I3XJFtr!jf}E?v;&%q9w$U{t5<`!8WMQdGf9jE2mkfQ+qY)C`VO)r+3ovO zoQ_a_tWIj9KH)zE-V971Y8fsP7&ENjy{T0t0`;6C4-B-nZFG~6^7uPnk|5oScEESdG%k!L`m+Tn3td_RjDSi-HCi3FVSw!ZRt;m506 zDTIUG4Xxg<Zx*pUc0;n}$z#6q6QKoaI=)79i`{f=y0_8C%=ZSI@N+bJ*^&Wy zftpEn;fn+o+?kRNc^5J|^S#;Lew3sWeOI=Z?YqU!9h>H5=CdX5p!~w|e6K2hk{x$6 z)^51L7koDo*S`d5L(k#94Db1Zw5wFMHWyDD5lQLx9*8hFA^yIXos$~k=J4T|@6mvz zpXW!s%%X1s`bfO=Gx;rFo;G^qZJd0aJcpe7qxbYz8pUW`aCPOLwR`sb&yV)}d{5(^ zEjxBRihm?a;qYx7#zMxq8Lwt345tfcVI}#nsH+L`Hh6Zp67S#S4L%+*P!2fFcW>~m z(7J*fe4Jv&ua^V&dEb#Ez6Fmy3duviw$wNFro8XMhZ~Xejqj#?cu!7YX)wpqff`Q) zyn+A7*Z65^qU^q$*(fXM@I`!9(95^-eVgyyiuJF00{y%{@&x9yQuCW5?u$a^v#yq~ z1M=YX$RqOm=ecwqUl?SSJ4d{7`MK2kXI)o@-}2c8z4du~p7Aa3{o`+E<85MX>k;b^ z7H(mc2Zw+1e*=L<_+13&xgeKJT{G25&L7Cb<5WBBt(D1~je|?y_`*%)2ahk}4Z%-a zmdKn6fB7@)AIc{v-HzaH9H-v~?4w=3Vu&t5$JCQI38zfhA_qjdHzW1_pQbKa zd8PelA?>jR_Ip6z8$wi5t?s+aJ`}#nBlhuTqP#-6`Gy^?{GjXHp8DnP)9Ro%KiG3V zt@u?$aWts$^mvWwLFdIU+{@j`vWesa_%QXh%)Zm=t6nFhDYXl>j?g}TIrOSZ5^bCC z#3pK*5i6bQnbtVfGriF!z2NFPM9dC}8>rwMqDA^B&mz)YbXr}to%S`UaxA)Lgv!W| zVNVd{!!h_C_4_0Gv_h3ly%5IOyN=36j{`i{=o!Y9DdyNdl~Zw_V*5x=@kDUZ?}$>I zJ&3Cb*W0)r0^ah0!>xFxe1PJY;*{dIw6pr$Br+8J%b0Dct)`&5bnkA+tAZo-zT-N} z(M&1DVL86rhX_nVy>DhH6Y+`ib2rj+BKPQnIYLeimE<-lXURwI75O;nz*xnh=%Zsc zDa`?ifceuLs7#!cW=c{Vnc{K!-KW*|sql3VAC?hAz&PdSesEJJqDR?5&hig@v+eaI zhcO2V8->+}yND~*^NcTj(0dOTrW7+2{oy-pzD&i8R>Y$5@WF(vW^x)Ku^F6eNVMOE zcKAvVe3d$nu9|8vx`YNp^%-Kr*@=(ge!_o91JN`}_svUII;mjZWr^f0s+i>)s@cpD#<>Jk7 zbRcHKcQ>49%i;@eS!Kk@<2r)Ak)iE8hWlfd%^XHQ~I@h{^9oIq5SuBK94}`K+dbN=CV!Vdu}d!9#9q`q8uuGLizz0^CbAX#EDfSQAg|wwEZf^*c_tkTt28F`Ax>ZBM+X=la5Qrr1OWpl%Nqk?tY1$ zG0Uq-G1G6EF=)pqh>1ukX8J7``l}kh82r*Fe!1~0PsbjmT+!5Rlh&YwPn2AtnkAFM zlSo+aF;pWfC30-p3K6t9NKlS*ed2O)hxi5Xpf6yYMqIsb-bH5PPQO${Y?O~>)_kOr zV#Fgo8P(bNLNSFQ6EF;^RQEwvd~usD6o&MECGq(Ye!GNe=#-D_}m`TTj0`#OBsk@cuq~`+S{GHO?Ix{6nz);0KQYRq@y)`1 zzsXVx{&-M*PQ3=F-LDQUu-5x19&wu1L<&noR4c6amiSicm?KtCuJ?N{B!m2w)9RBw zCt+Q53~+kL5)KxIA-~!K%fbb3o_uJ2-fjhAg>tA7`w0rV=XS}J?kbP{^wI(y!b#06NyybalBZ6A* zqxq}#-nW3eEY7JEZF)?dU7TU#Thn%P$Yhwyv8@w#Gp()Fsk>V%DF!D*=5Q2;EY7oe zh3vi0sdLQrK2k)K$Gw!kTdLEZF-hs-CYLstoE60=omaj0IdyLFbFsPRH4fde5{%4q zRNpD_ZUk(%`2)`0zU7^$Gj&k{$Ddar-voko#Od<3a1rIBTiG z-H%=v3(XFx$Bb$!ZQikHYdk%f9bmf_>&s((*UPWLHd&MU9B}O^pLBd;+hgjyj!e}+ zGHgui^&aEvH1}d2GhsLAEM|x>24dF-%N0fg-ZL-5{|>+J?6XC%h2OU#U}@(<)I6XTv%pWRN!e#z@VsTYFZAPj*2>p7Mfkh z)WotP$x=zPteZ;~pq6MlX5Cw6-3D9&m!x%a=+=Pfynry@|I9$y{l4yZ=l45vmiL_V zp7%NXbDrmabVcT&HZpvI?u0G{?YRli{XqnC_m?+xlcx zcjR2FYrMr~Qhv@1yO7(S=Z%%|PN4oW%F66sr>{#H@dBvd-W!Jbb`2yFYgz@8XR-Gb zdU^Vz?V=KWz1R6=FG^iNU7z)C%5FdpISfw48=6Nio~oE5di3(Ciru2Qm)Gmp=WuOu zCLi)v&uW0c?cLcxqE1yjk&D$?naGOXg0*_MrKsZL+iLEyDJdp*NSUGEDC z!K)!nH#2+6f5c3|yz7!`>vv-0r>?O2U0CT-t-+!SeI7wRvAJGfU0-Rnx)SFhGUz<{{a_8h-&n9pUB^5yqxsbD_m2;=)T6^S_XdTW# z!kE#JtKcOG&IVP*UP!XU>Y}rg^@uSk7&;Kool;daiGRAB0Mt+#7LiRu*;6Q2qM{xv zV^Py(5~Z3FmIs}=3gUQyXGSB}G)cm6{C6PFt775h!AKqIPWfY(3VfS0mnD${vM=C_ z;E;71umcGAXiS7CYYV=%*Lkx?kzI|p*uU@Dh53rMNy`6lz@}? zqC~*YI;cCOI{+Q+9%luAmDG+lo zf*18lvKrO4?2D}&*A0U@QVuqss0N0UFoh%8)Mlo;* z0-Izx4CIE0T)VccHe4lG>!F>tHXroULSm!;d-`)gTShr3?YyFQTUdPxFL!?}!qH|K z)kZZ@igK#!lF=VSAgjeBN~3x3uv|EO_r!7Q&D?j&O79Bb1~WJIYanX}Ibo5*OCMSh zX(w!`IfV~Y%C#yU2z5%&ih|-8dA@rZ!;)%q7cq$$kjLPna|`bD>A8E*Y3REty*z!z z<+Nc}HLoF2AFWH_gA6XG3KIAfn+5o#emOMnEgo(1JV&@h(k~cQa z?a_~OD$d7eGr*SAgNJB=TqS zi!0TT>;*^rWp#?Sy3V`s2--mZSU~q*6f^3znt{+yD2?O}^nfcs5&|vIJ)=7oi71}5 z9|xCJ;1CE527%yFvSAnvpM?=5P)c3cJqo)UE;3keCfJLcBym=(eS132;Ct@8Y0&4#&zs)aTh@xLtltt-E_Wq9qOjb6Qg+D z>RKkAwKBWeSg$4y$S#8qaTzS|fxiLoUdzvpm$fl6-!{2#5p5CVOpyma@1Fst-qdu7yO|h zTd0>B*^ZV%+}>ia+|GNU*CvC$uz++4N#s*CHFwso_i7@M#nA!ymqv%+Uvdguuu05z zruyieuI22teRtNH>^7#FNnxrwY&87SIOaxi>JNQkcimwMgh^AuWpu~$gke;)jz@xM~nWZH+rb4%gcVq4qd;h(BC=5kl?6KDxaNWCsu3 z4t9fXIP(;`k!mRII-OfiQ8_fsQGJNIGH~c*;E7ghWLe^7=rv^q-Z78KY$IYwt}P5T z(2xsmoS%Kc2!*0IF#j=MC^5duVR*=NeeKF^pPIZW82z91(Wkev!Z2f5?M2AH$lH=d zIQtgAhJDk^8fl|v|3n%CbprjHb>U`#KHR`V!qsUDMqa~UQjs?goWU?-TCMdKyAZi# zzK7I*hvc0%_;I)IQHgEvVJxpg0x*ugrSJLOMh0^nuQuqIoO{k6f!9Ryq!Ql)b%XC) ztsqyN%(7M~a%;JF3jhe@r zZ}M+`wBLx^u#{DrN38R*=VeKuot9^XWVMPjfd67(RI0KlbD3D(w%h!Wetbn(#mwx+ zP@>viM|W{l0%fCldN%loN+vlS|DZUK@rn18$u4K0D;{X|kfM%XW4(lL+y$ytYRWEB zl<<4bCHD}vb^juK-(m0C7NFo>!rA*&$V7bWj_s)-;l&L@a&7Bg=TN_8)jCu#pVg`Y$mG6995aZUOJ2a#bRKe7Onw4P<<~w|Kwkw z?Q`&zw$gB@ySy4bu#{cfY{dJWUm9plf?*8??}L0vKSmB#FRJ-FCjNPEF3%kr5{>X1pT`r@_=_#^>2*2pkPIn+dXWwEXL*?9!!_i*?UH zM*K8CbgD4U4{I*Y!AS$cR7o?V)sA1xj55(gcdRpUzX%JwRtEbeqUy3~qPsEknDjeM zCVi-hQ?=Qa>X+s;nH11hQJ4g(Teij7#vJc*Yw&i2T&rWoS7|;qd7Hjz5UQ@(iu47! zA?2HR%p6JQ>-L3*;Dlk9>x4$_IAXSyGb3kP*^$I?&`fo_4w(0?VQ^32ETDd!=>{fX zk1PSa2a7E78Jr$|zecjB0xka_dTyR$-5j=6!$R-!^*no_WKyP}jS~pl1VRqF#RR3_ zWh+|4jSXX>pyj)7jn*!ggGbRb4H5+}c4t$0pnHsCN)Nd+)r1(bmNij4E8D*&jO98^ zMZsDIm?kvt6YjXlh@09Mmz8~HqourlF9D@of>Ory1Sin)#p=Fa6K#R0CCca-5!TJ7 zWtHsllyqC=Ecwab%Xzr5XpOXulm5AcwfAV*)WGv#98TojbMLQ9SnZA*>yG;^;@bM+ zva$;{fpVQqs9bAfmE|^0sjz*9_I*wUen0H+o!J6%miS8hId3H5c z^i$PLnz`;S^pf1|CU5DKEj5Cw6zBoHsFS~Tn$OtBy(o?whPI=C96}tKLROG{0QNgZ z&XJzy8HBHygGfmgW*N2;Cq<l2wvB@a$8|QPqs^w{>ET+ehx>O(Syx%For_M%Q@eL z+9fB;7log%8>+8u)%b;#qweL>>m+Uma*WMl$6dBX{hpg3G8q!Y6;_I}?9;i)7NXyX zgP{Q^K}u~XFe5@Mlvx2%2DfPiBFwv1sM=){sa~=9AzlWdCvb7KavHCEAaeMH7pu0~ zBzTrdz%c;@egaybKc3v=zqNgidbYyw7+-0m;rAP$#|GYU^c=W zfN6y3g^AryBoFK7W(Sv7=%nQjPrk`l)U7oE>N5M%s;cu*3$G$QG z8GE*h!MR;REfbm7v2z9G0lw3V)50i;eh@e(C%eS%l>^YW;P-+K4)(gEsH_B)Cvo6C zO)xDm6zf16anCuvHwLoHRD+3NKS24CF5E2V88f!lR6fGUINx_Qu*5O;MiL;)$Q+_g#_Meh(J(=eS z@bZU*488MJu7j2wc;5=0?6uTQPi*q3-p`ZD)+aGrvA~K{`c?;<{9thBWCV$P&W2lb zIq*sdYxS)THMQA%cPmVOFu!7DyIV8yuHikg2DB~O|2Cn0(XoN{!9?`=kKqO@cOuqy+8s4it5$Lbq;RV1$6dYWIAh_NtJSS8Vm4+*NmtD#-EQI8(JwKs_Nf{pi=la{gO z&dY9jyO&ML(W#bXU?SlLS_ef+^5AdK{&M#A$0{JtKw?MUboRECc$*kU5=Jjb-$1%~ zcds0-)woaK30`Sdw8-MvI%xxmRkz<;dG>a?>K%(LMV`Xi&Ez|qUmVUyV!5j>74m?F z7e#(2mM13$O(bUvGANd?caAJeVUXpxjrl$sZYCu#P6;kMJ=y1hHBHyxCqQ2#%!e>% zVWz?q!z_TQgmKH1gUfJ)RMha!ecdE}Fh*ZGuI}&2>-aW_j=(|Cwj)F7D6Ddi!jQ0X z?CL>HW5i{6k$c2-IcuO}C#jM5A!ZnmcNPp$B_0n!Y7*szGWQuXY?GI}yud`x^xxpQ z8!{1lV_LokU{Yb!Fg)sj-nFSh{c%_6h+WXF#CtE|mOCobA*qKni~F73whGim>hVE( zAME5w+^B1U=w!FNASYFXj3883AXQDjly}CTqMQ}#8s6=ZznKPJ&@+U(dFRoSWavAZ zz^mmrZG5elAm%fO8PHAruk_NC)GzI3Mzz}L9n0U_Qcu%&Gpf%e40MDkvdPAI-nhG& zQPNtVywI&RI9X7g&JpQoOa7$4B@63wJUk3P-HBYY<9RdvPPL=LOz(qZq{s9(`Ie`` z%5U=I=yQB<;t@VXO>aIq!VgkIGI<|~+{v@@ojh0hoFp$s(8dU|?M%!Oet_~hK4>bp zBc|#6Z7%{Ox866<2G>B&KELO6xJIB|j&jB55R-@wxSVf55{#=R*gZXOPUC~X4T!_P zSqR;7mQhuygLp~2LMsH4dKPXA9l-ju1wmtaLvKs%9=ywy5NwUniILYj%%r8j z&92Bv=7SQcoJmlk$KjlC(tmkk$AJF2}b`EV+3f?Xwc#aaZY(#p^Y;z zqXOgG8>;%^>T~qJ$E9@o`Tr5uY*XhjQGvis$M~1@JICZ-rE3L9iG6}mS)F@bcls^vkRt*%GRnaz}E+>&{>3Gb89CxWyyJZUM*)L$p@ z*$sl2NzGIfFvIE{8LSU6OR@j&b@ucOaE}9tHc34+9Fui;#i%ch9ILMd7pJ)A`cLasw|_e8?g=H>Ipd7C z8+Rmk(>ePfv`gOWL9LTL`~bNtW}H=gfV@cWvnIQY&>79_asA{C8RnjMMTgMp(c&dQ zdHcDc<0mH4r%fr7wKmAYdBHE}_Z-{B-PYQDIYo>Nd-awkwtAQ5Mk5n5#LC7ft^W0_ zinb`cM;V~!T3H1o+ZLYYgO#BhJpEvON8P(`wRv-oXdX!ihg&(w;l%8~ar1Yg@3@|P*f8vgrDVew%f^FrbGc(oJ6k~84MX*XSq+yS$$GzNx ztQf0CJ8W{GOMAk{yXV(qeX?XrAWN3sUXkpPUb)qX`;W`hOeuyWa816mB^!63HROkn z$o7j%F)%#a($pLPZYQaV)z8s|RmgX{oKN@Ad`a|$hE&sen?KeAL-qdd^+3hZ2tA1! zTtPX!kORzqS0is`T7}_|Wm{(pV_#X)Did?BK-aNc3t6_4njsgN(ZASE^SOzBy948* zErF_|SR1G46lV01$yGR&9kF#pt?w@I@eE9|d^9wybzL_1oTL|e*0t_^37wDVd_vn2 zZEuu*w7pUKQNGgCHM?|Afv4mLN$*$g`9pU{rc>f}VJg3IisuFg-SFKVt)pwI2;Bg~ zX+8@YBBWfnUA|keU6g}W#P(#YA|7yw=sUMSW&`zfwf`MJW}p}X1C3-vx;15yw*IYl z?<7IYgP5Hdhirl}dL)^Po1t!7#{-*y-e&i!l|Rj5w==&s4X6tQ_jRZpYSs%Olp_uN zQ=kCIJCz8-SqVZRI)WGsD~b4bpP#`~hP`XMz14F=l*Bp?G7O&7RVOIM#Fsb`3MQZ1 z{)|#^@J}cOj~^Ew!L1WZuus_0?HmfE0nxQs;3YCUfphNGyyl&;|AAUyQd86d`7zG8 z$#_jHx}009T9gK)TWid>7*ladhT9Ucm9*jRifG{GyPUsZzPo+36MBXmX4Y#w zy?K(N^WrYswiA%Ej#n6=qygX%y@je%Ij=4Y;?2v+l>faX<7DcxQ7rXB5Oa z=-uz+4;(h!+nr>Z^ySMQoHmL{AwzDjbr%ed3&x#mxT`MIL=h|KJ#}|+e~}2hDK4EN zA>efK5D@SA{yU4dVeR+lUi9;Qw3cFr#rV6Nv(K17^#N#6Fh(ax{oz7@v$4 zH^mId>)5aYn6GEX9+&E#h}f zPG@qLvOe0VuH}FP&9y|k@tx)ZUvuXqH##}!=fUI{>Xr%eU`Cw1{b~OCv;lF9&KG=0 zRwuvaofVwUXoS|h4l@&y?w=6>xe-52vaC<}kcC44GV3u1$Gr%vFso7x5e0zGtU}z7KBCUO@Tx*}^zptA~k~tuA ze~0)zXvrq&_KPd#61ANng>CEEp4dT6N85l(+InuP#DYXlAMtZpi<*GP?Z=Gov{Eia6~Y;JcsB8;;c1;#%Kv%6 zChPlJ$g$virPf5m3brKSzo`LVjy(Z=J1zG>3;y#Yx)g;+L#{u(lbQkB~dw6*p2$kO$8Rq0|YH0}!XTK00b#?Y!JK+g43T&!s`uNPfZOY-bVxNV1Fdt;|H*8Zu!u;xdJ zvxΝDjmKLeu@b5x2(Odk5GHb*(bggUoTrLQuogHNn~sEmn1~)>8``P%4qdjIuJx zOxkf<9=?-)W3YvOWdvx)`3bDFz9gU-C~Rl^!Xd$EniSwzpC@QglW2?DP5Xd0vho27 zxkKqlze4*vRgque0Hj8aMT}0viYPTzG$(b38L??Q!pWKiRDv&m9 zv7HGCZ^20{OT%bfDdP6~L0QmCt)Una^U(uX%O;EvkQH&fua#K#w*k@n4&grR+SV=^ zzrXcdzWf@4Hd&NGTPAIxSo!BEfkU8eWl4YQXAw?g(dSd`xwJL+KXRF2`X!Wyk>v|Mf`m~M8H^kz zkWr5;E_rNZ(eh9xIjmY$+HHd_rJ%Mfwk-|2> z;|=?403qN`5_1$GKCtNve5s8L{iyvd-YbWF4!lBYZ{i3?ZDb^XP34e<)c?7J0O5=f zxi1mJru#Pu^}pm#ykHx?2R^~ET5A2qOqlqtU;x&Qz!TuCA zs2xTm%ZCujtw;~u>W31^mIxw=DjOM9MzV`bOO!JT%9bFJ=ST5(D2?cRKxxr$%i*Un z9_V|X(dS>ZY|$#RXyuBLF!NV0D=9aX6s;;LUR1UcgnwY!@?`}}OCBUMmzFFgu?tF< z7p#gU(aTnsmc}5j+9^ar4b8W{&z4S|Jt{kIys~Un!OB&OmMxT$$(fVKD;KORDN#nP zj#riztXx=9whC@3i7Jzl;_*?dm1PqW%cIJb1s-dG$67ieYBebmUduea_2&#~#| zm4;6~{`||zSN87O_Uu!e54`vH*N+`NdHU0{=l^x>`sGF!-*)%=AO3Cspr-!J;dkD8 zdCcRpWkBMvAz1$ z+V?FdjvU(mW@oR{@#A-`zkKx1uRgnR_2MNEz_5Dd6YHiuG=KKw9BoF(;DK@>>n)2I zHZpp`_>@sovelEO&zv{+u@&X(7cVU?dT?Cg*vP2(I1wZ93mp`wc=zDGx9g67c`8KxQL2FyQT&cmQO)!}khP1_L}vy6$ScK=V}c}Dvi zeFh%kA3uTT8SR_&S;8Mr+%6hU^Q3maq5YS-X@1nu=kB~`!?BMBuDr_*bCcZJDV55(QRR>Pf8r+pPjNx1tobuCb2BGr&X_*uzZMonnEU5U|62)C=hLj+ zgz76UVj~M>f-+A}$u?>ED&=DZrHhK)wWXX|P_(3E)qjR({SiKWwukV=$WCi4SXPF- ziyu)+rKHG639WR$3w1k}Rxo~1#Y##e&pQ_sEGorYAuE73Eq0HQ*rlRXO{BvzVMUlj zh>H~vMk-*|qpkVTsfq{%ewe$~ySso$jFiO1NC@X8VJBkl8bYTv;w2OlDRI%RgZaya zxyzHk4Eg)?&|5u)r|?(MRUZg~a%*hi1;mpFS;b%4B^`_9R_~CVk?Bv~gocC67#q9j;P_2P=Hs zpG-gFzy3z{J$*S*{CIqU@2@APdF=}MWU2Utj>V?YZx!9zzoU3>a>X^@H&0w&Gx*l! zmWt-aSK@Nt_d30<_HW{Z6SfxzSt^U=9}H?&)-29iQGffJ^fQ~DymU3R^@kfvryal4 z@#*G^8z0(PsyKUKN%7jw!k%BwmpqdCNR}4A+zUZwVEU%?p zI`Q)x=f<I*H%&2fSVm-s$`8DWApb6DBN`yi!{HA~Ub(r;ce$mJ}A0hBqaaY@R|2 z+yA{oRQkkQOxQ;qlBZ^U;&DZ&y5FG2&W!OXNSw>-e;ax%Fag}H_ke`dAZW-(t`Teekk~t zZ|66U?mXWd6S>n`bL_y^pAMXGbj}8!VB+OojVJ#7{!z~@AyBlj) zjhl4Y{@&w_dxC~t6KouCy)3}H==)7+#Vt}W(;M`jf|FDxuEuNYGrViPS{_E^}Z-j=wFTOVF~RsKcJjfKl^ z)^~RPcIJ8QnGXhDe!j-=^ZqMW{#MoS`X}d_Qm41y%xhbCs$t=*5C48cbbO+IOkLL1 zIG?86FzI`DbGR{vwSx4Ie>2>id2```-=1HVwC2nr-L|6z7eY5K_;6q2@~AQ28K>`f zT=oSw$@^6O05)>uFyYKIX(#^??R~m#`@_fL1dET(d)xK(xumbG$DiHX96#vYZ|2sV zE3O{aUi8bW`xmd4RxM=@io9N(IL5bi^Fr}T#VjIxD#x-TaP5ij-i@n$A~o!NS@rXc z+kMVl{_%s~uCI%@dCmJ$aj z?DgkmABWu(KK$HoY{C~cuJ!Kq2&VYI9xRl&c8@4M&(#o4=y(4)#n3(OHBMi=KR?5w z-o4HrO@pz9A*qbo3u^=EzP@$IebKFdk^di2)MP5xUj}T$es}*7gSvi!9)2b1kN4+i z{pA@$gK2p(z%xL3xPAW_?|<>DiR1S&fIh#w|D2Z6M~VI4pF{h79{P->URs_kq7FrQ z!uDZK>yOfBTWS7b)WfRr=l(I_1oI55c6;#04k8dNW7TlFf81c~Q3$Jcd+;Y1LdaCY zs^N71gi1_EgjJKipD2Qma>ALBL}$?uis@xX*}ucz>Mx?JVMQ-S2n( V{<}Zab34kRt)-SkQ}G=NF#{1n*bW{u@&E!*gw zk!(tG)A#;*-}~d~`)1F~oF8*$=FH5QGXh}5?=Jv;FQ%uzkl+hHN<$N^rjW4zmFJ5x z{(maJ&;Q>Y4`wL|f%4yvlLTD;nx~5QgK}xI_Y!XdrTR6GKYhJrr%{-GhJfDUe0Yt&Ct#!FTxqB)e zeK(Gr7n66V>#dJ@#|~NJDFt~IZdY8{m)4W+t7rH z1Wspfaq&BZUW(J!^j{{%z4nEHP&O$Y z?B*ZM3bebZrk*N_FY{;CN^VlRAega!nfr*{G$1%T-0UbcvEyFHA$w*&C=XA8;y}G0 ziGxyw`RPef2Bl?6axZhYjqyIA>RPxAbpadj93}(Gol_(DLCTUhs*;f3MZe^BJN=e& zmPknFY*!7%r9GW)sfQ6kDVi>kI$g74LG@ys=Uf-uuxu*isiNa^^JS$ju>P+q*Y;Oc zXg{a&w!Oz-u})s@VSWV4&}4eoX%#%*RSjEDt32)Btpw#>om$d$UIi;ya7K267>}-w zv-{W%uv{Ia_%l;%NB(NTa_Jm7f;uV?n8vkd2N57W!kq5)kVJJiAN`|9UFy|zN^<-DHWHXQd?6- z<5sQ^u8y_-^%5v-YFb7Xe7Bm*r}R_;!@d{Zjpfh6t@s^Fe3fwCk}{l!KTLABY4&mX znwR3ykFFK1h=e{4Q`vvMMm2c5mFZv=mSrtA<;_+iF(QspF)06x^SEcSPJxtql<~|Y zC#yIUh$9q-<7@4-=bd9ZpunMUs6S%Lab#_lovA$!?zDKyuV%6gw)rbH%L+^4(Vt(F z!&K7KlPRMlgLYI)z-{O!VXa)}kJq)snNSu=Oof$hXiwjc}=VRn863 z5#rg}FdgA{E(4BQ^);O315ns^wWgIEghT8BqLNfnawdF11%c|eC}G2elUr2Ivd?Z) z^r+>z#JH_Ww70w!mb@w#55bB%LJ#My4r+dMR?RY>=#i?8GM~>X#BeA7+9;&!f^Et- z9Bq*@wk^Us+7yu`w|^QUCEeH;o64;Yhcv$cbB0P*w+*MTgWZ~uHkOnOs6q+1tZmq| zY&68(Mo0U&{q#9HhwrFahvQL5%(}pS@ClvavoX!SKsdS9FD_25F9Fv`7A7|XB3&PD zg8RVBIG?G9l50x z4>=wSg3=wsKJTNJyC;G7vdsznPQ*VH)chg~*XYlXMkjOoIHY=H`gWO8dnk3pyJO=g z_oB27Nd48pdt%<$tD_6j>(9{^{u%3>!MaG$1IjJ2Hn}d+k2z~>aZP*W+R$R>0sETJ zqIDEsGfW8V2PH3-q+Sq%gFgG($TPo28#m6{cszRR^x2P-Yk29j(zPRRPKd4n%}Y!^ zT?6sx;%TZ&=XC0^-b>1Jbk*guxfVU{*nqvbGC{w}#8dVUgZ*LTEd9G={WM5S`_Dd( z|Lw#N?tWbJ79d==Gk>W*XvQQi)rYcu+QR1pAQI72#X5~H3W25ow*>gx{DKqOIT;q& zB*skgLAmuB+V~G?X*ZTuBuawBn%l5ccunJc!knKk$}DPXwGriH4+MJfj4j7x_3uAs zlUigdW%V^E(8#~ElYxw5*53Il2l43XDY9}r48S1$It)mYw`g898uUTIzp(=N>??X1L%&LPlltj=u#=)&?4r89fFm!tz^tpzKnv+>0EL;NQn^GA zZpSl?%B3=?Y!-D&?TSag`dae*q&Sa1})1MUq??uu02gtGlC{j{W}W z0+Xf!ibg}9hAF+^Pp_?uyk9K3Kq;OQ-8|A%A_Rmr2n`4~&XlWXU_C;r6(}2CQ*o^m z9D7je6M5dR!4m84&@$+C+&RVfQr#xQl+NSVeua}Ovwvxakf%3GCAn7QyM5|2+)F5) zck0)f-1dm~n)4la4Q?#}&;%(ruelwmj-VL;V|CGjwwV5V*(i<3?jn0?A*y#N6 zehz15YC`KAbkkMV=peXeh!UTmUKmkQUxfhmD|kOqrf2H(uL20j2g{b1J}z*IwUE=6vr&}niPI?0mM4RkS3I-O~Plls;qaYa%rfv;vV<>@7S*r_KC$qqHPOODjr*qD!1G7`q9$1H|G7Ur>J1JJ98d*h^(kKgF3bJo@5`h?XT49RbIq3ukr ztEQ{7WU?v&mrqt#ixNrfW}i;jq{`}K{_=#qS~TmBa$(G7URzCbrr1B>ZU^XR87IrC z1*}P*T#Yr}21xAB|1mMULT-R5E3hsav*LHt#0sbNzpT-snhf{s z8eQf*XumB)J=<*DtryEnY6_hh?!uZ}_kMd?Xi1Hv#L0fUJ~Y_9z@j~eE9;vLju-4@ zfjk)&i&V#lL3wOKBU^ixYEd|ccbionGn$`?}$M`Jo?Fm ziszSaC0Tq5=gNocgsxv|i*(LzT-OKa9(?2eaZGpYXgTnQG0mQHbZ>J_jN;v4MDEnYY2z(b!}>%mVaLL{nh8wN zFqfoj7!EVZT+_#4xS^ddlPldISBlKamGDmRdAUe8BNuaDkV{*WA|O%yXnQOzWa>>1v?xRLOCv#{i8{+gU$Enr4 z9B1)co%r4nA9@rDZwcY)78f6lM~}x{`2BVKFn(W*ckbHiGw%|2LVMG$c=UJi%;fmu zj8HiXd#e5O*rt~G8z+{v+4ma)V_DNb{<$)$I0!|#!1-pPq37nAS{;?c4I5&xK& zA37GbXq)wzHeqVriWbDtFEsNuPnDyY4C7^Hm?h=IOgXKm`=iGFrW+R5DQub}rj5pR zbIyJn(qg(P64R-Rh7Fp6VFSm+bkXWzjb@F5+$t;|4ryF(x)S@`(sH*UkmES$Q2gbt zRyP!|iybj;{EAL@_CCRZ9xCJ;UroT+bl(F z4LJ^i<8l)1u&*h{@dnmoUNNxAyo1v0$Z?b>XdDqpa8l}Ij#>xVkGr5s4vKPehCqSe zzcI#>a+GDmwToLt73E7i&&y-R&vpp3#Gpe<0fQ3rT*@NbW0erF*_(5$5R4oz~!3 zmP#n+_X(bnek`YxB0_FZ0C+NWNue=1?i5ZIard1@k$~j$CMn8-G>>Il|d2ko(Pr)(z&-fXnhx|L;BI@vAb8c7C2C}P| zV?u9||D)zv{$#nJWwuP)%59!$a|YgtQ1GYj+|g6(d!op2j?z5&t#;Kan!48c?sT8- zK2Sv@7y>C<7J60x9C@9OlXrEo?m3Ga9|P%toty(v?cL_qPO|2WyPmPLK~g#vM(??l z#>qbXma~WIEXsrK1660#Q`VPzi1Ar^10Ap9PkB-3a?9tG>;T&J4n=E}YK=O0E zCm*+TmAmJNFv%K?D!<0)A)=?sCbZ#Wmn5DfqKwlaE=3IJ3$7wC{9xJh};O z63Vi1x6Jln&b$R%7J7OA(>`LRcw3x^e4-4Aa#^D6@t=5nPQiQ`bz`$8nbHdPGrqhE zX;-^F=lmH}Z*%(Q5pIOZ%-nUzE}TEId1IH+6I9Pxja@aqr+o*|GqrfJhrM7K3kq^9 zjB^pDF~0S_g|a1uu{?b&OU?+g7`MCPB^bNPZ)MzOSLV*!eb3kn11a(<{2E`5%GWdPKeg*ec(yRGNY0U&18n;;yb&D4$O>Y;_vU^*=V&)b zcmwS)?dnxI>mfUb@vcsl@!sJLhDirGluI;-#hJCTBaCrCTz(B}tp_Rq^_U|Z9ZBWxuK4`D!{xyc==ubgoI5Bq}mp7zh1gOIiUu1QGFry)p-qLjL_F@Ma~1LbGBUO1!{nZJm7D+ z3FFEL@53^cl~SY&redn-(O#Fqp$raX%<>-00lo@(-p53FND&ugi}+w(kG@tvRO`E| zYnHOs2SsX#yDo`ENf7uk^1Xp6l;Ah)%u-zGnITSD$dMv#kU>dz^-wM2(S3m=?4E(A z@E(@bU+@z%MwjqDunOZPPpU;YDjwY9cR%;$vxB=@A3SP$0p~tX{#kcQMJdwJQ*r+E zQ+7?T5OYKEM6{&$<>wYu{CdyfZX8F-`{4OqZOorYC`tZ6qArGxsM>O^SP9Y zJ55KLI`?3#09(E?^}Jevar~?RBe4lOs!4^lb5Cc}6}oej!)O`v)G-dva2OTwPQHeP zQJe194=wKzWi8z)%Hz?04e&dEsIDLSp<3Gq!)fqjB^%^#sjM6c{VfbX7Ug#?a}vA% zSQROJ?=qXI=}^ukI9tp7Y;#-F-d%6+att$4+a6AygFSmQ4zG;(UhX>bT)w;AetK8h z`I4?~^s30D(cB%|eRZQAH55gBuPL*|qfZ9F{8`w9E1TY>zB|PwdQsLpi?0oM{ICc{ ztF>QKZ?P41kz2T%lQxLEr*`5m8oP8w!AR#!L!SHiV>469|$}@Va2f=AMAXl-99oPHFq{i?w{@%#NB&kKqF}r znk`GnN^;1r3I2UJ?^+8+3xYb!lAy+tABsn(FjlS~Jo4O!&vuy1?tbKFE+)B!UYs+; z#s;}jE1^BUIbPNU(ro`V*#BXCC7^LF^r2o)V&YLUm9#MFq1>({Cp{~qd;g49Lp5Mg z16`1_qy-s^6iRZx`?^l@A`Z;7oPllq=W+HSV;5k{2dbV|t=5K~=hb4X#-a^veU_f; zr@ND$$gDLd3dr&uZW`T2I zbuvo10HZ2J0eghYv_}N9$(2ieGW7k7t|Q~|ZHe2Z1LF)0M%P>?p1iKP3E3>-jZVO_ zv4;9@ht(nLMm28@^*ikd)12w(<))iYs$3z#ueyZq#XEMrfN2e;zhOMF3?auuJ-!9h z142lH`U1>nV-gBE@3pX}D#vN6F|FH+Z+oU1$Zxmj4&>D2)EeD6>(NukJ66MX8Utx~ z;FtD{fw{Hw)>C*b>WOF7&c%HCz($ozbzpigjNjb9gmI5teV{7*1$Y@FP3U{zoxhPn z9llRsY=D-(EHO?|dBT>AwPg*#5WQRD?H?q3ZDJjXn{GhB`lLTkM-si4nR0Su|6Zo! z^?Cf?%NnO$&yMV7sSlm>pp$LF`!Mv6a9+d}_GsxGMZ5`JNa0k7YQka}qo)|tp#J8C zmVOn=q{y`<$1uq_p+a`z=16_xA^zX~q88O>C{N&h`U&ozLTfF>=igGH8EeH8s;~~B z5K>{OUE%F-Af)vb3T&!~KtZ2+$%Zt}85+wBjpcQ)8TZ>_t4K{&C#%4TQ@A{)eY~qFFuQ0`wsHjQ5(N*nAB9N zg@@Nwpag+RCgT}f?ZZ!PELROS!?>^&>ug5HoXrj;8|@by7Dws^Sn+nyAhDBL*mM6| zVeRNDq8Tr~kLqnx^KF$0PU{VvSvPS0YKHTV_rDZAh8p8YVMLtjUl%E93biygLgDLy z#zvdswKdjvj)N!EQqc%SzYkP2viLUsTA)JlR#eo#GG4Yl92#h;i#)Z>v=wgai!brp>1*jEG%zDx=}R}jaPtLS+FAXicC1ll z@qRGcO>am^3W|5Ay2IpFZuv){5pDHZtcQ~=rWPim%=_(l-wH-aCrt3S zY6v@C+_VY3!=KdWSG?7-U;Rj6#;r}Tbj#+fK%K&u*C||iiet+Lx>|la?p?71xos<= zp|2ok#sh)PYgyYFMkFKUEL&kJJu#M&xk;6*M^#l!?V_6fMpXrn4%#a8bRurE!pc)x9$H|(6*|#-&&IKf7C-*b*0}> zqPb4Tt(xfPO88*EE-ye|)3NG`3f;W6tBD%Zx;8DfULphdm+m zQojuIC}Ok{85PNwVZri;AS~kooYf>}zDoVm=}Sx{jP!%2ifY0stme&8fV$zgG+7Fl zPBp{WnqD0)#Aot(OxSq zUylE{p}!LZKfIp7AU^?btO(!AG6^tPw*CAT1~AUWu#^OUGXSVfe%hVJQAY1{1B`px0hA_74;z6g`{rO@WD?l7s6TgN{ z>q|@IwQJWxGPlyYb2e9UJ-6~!Jf;%*+OT7k4 + * 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. + * + ************************************************************************************/ + +#ifndef __ARCH_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ +#include "board_dma_map.h" + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The PX4FMUV2 uses a 24MHz crystal connected to the HSE. + * + * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 168000000 Determined by PLL configuration + * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) + * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) + * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) + * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) + * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL) + * PLLM : 24 (STM32_PLLCFG_PLLM) + * PLLN : 336 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 7 (STM32_PLLCFG_PPQ) + * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK + * Flash Latency(WS) : 5 + * Prefetch Buffer : OFF + * Instruction cache : ON + * Data cache : ON + * Require 48MHz for USB OTG FS, : Enabled + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 24MHz + * LSE - not installed + */ + +#define STM32_BOARD_XTAL 24000000ul + +#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 + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (25,000,000 / 25) * 336 + * = 336,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 336,000,000 / 2 = 168,000,000 + * USB OTG FS, SDIO and RNG Clock + * = PLL_VCO / PLLQ + * = 48,000,000 + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) + +#define STM32_SYSCLK_FREQUENCY 168000000ul + +/* AHB clock (HCLK) is SYSCLK (168MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* 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) + +/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* 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_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8-11 are on APB2, others on APB1 + */ + +#define BOARD_TIM1_FREQUENCY STM32_APB2_TIM1_CLKIN +#define BOARD_TIM2_FREQUENCY STM32_APB1_TIM2_CLKIN +#define BOARD_TIM3_FREQUENCY STM32_APB1_TIM3_CLKIN +#define BOARD_TIM4_FREQUENCY STM32_APB1_TIM4_CLKIN +#define BOARD_TIM5_FREQUENCY STM32_APB1_TIM5_CLKIN +#define BOARD_TIM6_FREQUENCY STM32_APB1_TIM6_CLKIN +#define BOARD_TIM7_FREQUENCY STM32_APB1_TIM7_CLKIN +#define BOARD_TIM8_FREQUENCY STM32_APB2_TIM8_CLKIN +#define BOARD_TIM9_FREQUENCY STM32_APB2_TIM9_CLKIN +#define BOARD_TIM10_FREQUENCY STM32_APB2_TIM10_CLKIN +#define BOARD_TIM11_FREQUENCY STM32_APB2_TIM11_CLKIN +#define BOARD_TIM12_FREQUENCY STM32_APB1_TIM12_CLKIN +#define BOARD_TIM13_FREQUENCY STM32_APB1_TIM13_CLKIN +#define BOARD_TIM14_FREQUENCY STM32_APB1_TIM14_CLKIN + +/* SDIO dividers. Note that slower clocking is required when DMA is disabled + * in order to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. These values have not been + * tuned!!! + * + * SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(118+2)=400 KHz + */ + +#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_STM32_SDIO_DMA +# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(1+2)=16 MHz + * DMA OFF: SDIOCLK=48MHz, SDIO_CK=SDIOCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_STM32_SDIO_DMA +# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) +#else +# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) +#endif + +/* Alternate function pin selections ************************************************/ + +/* UARTs */ + +#define GPIO_USART1_RX GPIO_USART1_RX_1 /* Console in from IO */ +#define GPIO_USART1_TX 0 /* USART1 is RX-only */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 +#define GPIO_USART2_TX GPIO_USART2_TX_2 +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 + +#define GPIO_USART3_RX GPIO_USART3_RX_3 +#define GPIO_USART3_TX GPIO_USART3_TX_3 +#define GPIO_USART3_RTS GPIO_USART3_RTS_2 +#define GPIO_USART3_CTS GPIO_USART3_CTS_2 + +#define GPIO_UART4_RX GPIO_UART4_RX_1 +#define GPIO_UART4_TX GPIO_UART4_TX_1 + +#define GPIO_USART6_RX GPIO_USART6_RX_1 +#define GPIO_USART6_TX GPIO_USART6_TX_1 + +#define GPIO_UART7_RX GPIO_UART7_RX_1 +#define GPIO_UART7_TX GPIO_UART7_TX_1 + +/* UART8 has no alternate pin config */ + +/* CAN + * + * CAN1 is routed to the onboard transceiver. + */ + +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) + +/* SPI + * + * There are sensors on SPI1, and SPI2 is connected to the FRAM. + */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 +#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 + + +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/boards/thepeach/r1/nuttx-config/include/board_dma_map.h b/boards/thepeach/r1/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..96a4c81517 --- /dev/null +++ b/boards/thepeach/r1/nuttx-config/include/board_dma_map.h @@ -0,0 +1,93 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/* +| DMA1 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 | +|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------| +| Channel 0 | SPI3_RX_1 | - | SPI3_RX_2 | SPI2_RX | SPI2_TX | SPI3_TX_1 | - | SPI3_TX_2 | +| Channel 1 | I2C1_RX | - | TIM7_UP_1 | - | TIM7_UP_2 | I2C1_RX_1 | I2C1_TX | I2C1_TX_1 | +| Channel 2 | TIM4_CH1 | - | I2C4_RX | TIM4_CH2 | - | I2C4_RX | TIM4_UP | TIM4_CH3 | +| Channel 3 | - | TIM2_UP_1 | I2C3_RX_1 | I2C2_EXT_RX | I2C3_TX | TIM2_CH1 | TIM2_CH2 | TIM2_UP_2 | +| | | TIM2_CH3 | | | | | TIM2_CH4_1 | TIM2_CH4_2 | +| Channel 4 | UART5_RX | USART3_RX | UART4_RX | USART3_TX_1 | UART4_TX | USART2_RX | USART2_TX | UART5_TX | +| Channel 5 | UART8_TX | UART7_TX | TIM3_CH4 | UART7_RX | TIM3_CH1 | TIM3_CH2 | UART8_RX | TIM3_CH3 | +| | | | TIM3_UP | | TIM3_TRIG | | | | +| Channel 6 | TIM5_CH3 | TIM5_CH4_1 | TIM5_CH1 | TIM5_CH4_2 | TIM5_CH2 | - | TIM5_UP_2 | - | +| | TIM5_UP_1 | TIM5_TRIG_1 | | TIM5_TRIG_2 | | | | | +| Channel 7 | - | TIM6_UP | I2C2_RX | I2C2_RX_1 | USART3_TX_2 | DAC1 | DAC2 | I2C2_TX | +| | | | | | | | | | +| Usage | | USART3_RX | UART4_RX | UART7_RX | | USART2_RX | TIM4_UP | | + + +| DMA2 | Stream 0 | Stream 1 | Stream 2 | Stream 3 | Stream 4 | Stream 5 | Stream 6 | Stream 7 | +|------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------|------------------| +| Channel 0 | ADC1_1 | SAI1_A | TIM8_CH1_1 | SAI1_A_1 | ADC1_2 | SAI1_B_1 | TIM1_CH1_1 | - | +| | | | TIM8_CH2_1 | | | | TIM1_CH2_1 | | +| | | | TIM8_CH3_1 | | | | TIM1_CH3_1 | | +| Channel 1 | - | DCMI_1 | ADC2_1 | ADC2_2 | SAI1_B | SPI6_TX | SPI6_RX | DCMI_2 | +| Channel 2 | ADC3_1 | ADC3_2 | - | SPI5_RX_1 | SPI5_TX_1 | CRYP_OUT | CRYP_IN | HASH_IN | +| Channel 3 | SPI1_RX_1 | - | SPI1_RX_2 | SPI1_TX_1 | - | SPI1_TX_2 | - | QUADSPI | +| Channel 4 | SPI4_RX_1 | SPI4_TX_1 | USART1_RX_1 | SDIO | - | USART1_RX_2 | SDIO | USART1_TX | +| Channel 5 | - | USART6_RX_1 | USART6_RX_2 | SPI4_RX_2 | SPI4_TX_2 | - | USART6_TX_1 | USART6_TX_2 | +| Channel 6 | TIM1_TRIG_1 | TIM1_CH1_2 | TIM1_CH2_2 | TIM1_CH1 | TIM1_CH4 | TIM1_UP | TIM1_CH3_2 | - | +| | | | | | TIM1_TRIG_2 | | | | +| | | | | | TIM1_COM | | | | +| Channel 7 | - | TIM8_UP | TIM8_CH1_2 | TIM8_CH2_2 | TIM8_CH3_2 | SPI5_RX_2 | SPI5_TX_2 | TIM8_CH4 | +| | | | | | | | | TIM8_TRIG | +| | | | | | | | | TIM8_COM | +| | | | | | | | | | +| Usage | | USART6_RX_1 | SPI1_RX_2 | SPI1_TX_1 | | TIM1_UP | SDIO | USART6_TX_2 | + */ + +// DMA1 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +// DMAMAP_USART3_RX // DMA1, Stream 1, Channel 4 +// DMAMAP_UART4_RX // DMA1, Stream 2, Channel 4 +// DMAMAP_UART7_RX // DMA1, Stream 3, Channel 5 +// AVAILABLE // DMA1, Stream 4 +// DMAMAP_USART2_RX // DMA1, Stream 5, Channel 4 +// DMAMAP_TIM4_UP // DMA1, Stream 6, Channel 2 (DSHOT) + + +// DMA2 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +// AVAILABLE // DMA2, Stream 0 +#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1 // DMA2, Stream 1, Channel 4 (PX4IO RX) +#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_2 // DMA2, Stream 2, Channel 3 (SPI1 sensors RX) +#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI1 sensors TX) +// AVAILABLE // DMA2, Stream 4 +// DMAMAP_TIM1_UP // DMA2, Stream 5, Channel 6 (DSHOT) +#define DMAMAP_SDIO DMAMAP_SDIO_2 // DMA2, Stream 6, Channel 4 +#define DMAMAP_USART6_TX DMAMAP_USART6_TX_2 // DMA2, Stream 7, Channel 5 (PX4IO TX) diff --git a/boards/thepeach/r1/nuttx-config/nsh/defconfig b/boards/thepeach/r1/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..0d4bb0a5cf --- /dev/null +++ b/boards/thepeach/r1/nuttx-config/nsh/defconfig @@ -0,0 +1,229 @@ +# +# 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_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_DF is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/thepeach/r1/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F427V=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0002 +CONFIG_CDCACM_PRODUCTSTR="FCC-R1" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=2000 +CONFIG_CDCACM_VENDORID=0x35a7 +CONFIG_CDCACM_VENDORSTR="ThePeach" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DISABLE_MQUEUE=y +CONFIG_EXAMPLES_CALIB_UDELAY=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_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_LIBC_LONG_LONG=y +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=2 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=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_DISABLE_IFCONFIG=y +CONFIG_NSH_DISABLE_IFUPDOWN=y +CONFIG_NSH_DISABLE_TELNETD=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_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=262144 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SDIO_BLOCKSETUP=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=32 +CONFIG_STM32_ADC1=y +CONFIG_STM32_BBSRAM=y +CONFIG_STM32_BBSRAM_FILES=5 +CONFIG_STM32_BKPSRAM=y +CONFIG_STM32_CCMDATARAM=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_FLASH_CONFIG_I=y +CONFIG_STM32_FLOWCONTROL_BROKEN=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2CTIMEOMS=10 +CONFIG_STM32_I2CTIMEOTICKS=10 +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_OTGFS=y +CONFIG_STM32_PWR=y +CONFIG_STM32_RTC=y +CONFIG_STM32_RTC_HSECLOCK=y +CONFIG_STM32_RTC_MAGIC=0xfacefeee +CONFIG_STM32_RTC_MAGIC_REG=1 +CONFIG_STM32_RTC_MAGIC_TIME_SET=0xfacefeef +CONFIG_STM32_SAVE_CRASHDUMP=y +CONFIG_STM32_SDIO=y +CONFIG_STM32_SDIO_CARD=y +CONFIG_STM32_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SPI1_DMA=y +CONFIG_STM32_SPI1_DMA_BUFFER=512 +CONFIG_STM32_SPI2=y +CONFIG_STM32_SPI_DMA=y +CONFIG_STM32_SPI_DMATHRESHOLD=8 +CONFIG_STM32_TIM10=y +CONFIG_STM32_TIM11=y +CONFIG_STM32_TIM3=y +CONFIG_STM32_TIM9=y +CONFIG_STM32_UART4=y +CONFIG_STM32_UART7=y +CONFIG_STM32_UART8=y +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_USART6=y +CONFIG_STM32_USART_BREAKS=y +CONFIG_STM32_USART_SINGLEWIRE=y +CONFIG_STM32_WWDG=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=300 +CONFIG_UART4_RXDMA=y +CONFIG_UART4_TXBUFSIZE=300 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=300 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_SERIAL_CONSOLE=y +CONFIG_UART7_TXBUFSIZE=300 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=300 +CONFIG_UART8_TXBUFSIZE=300 +CONFIG_USART1_RXBUFSIZE=128 +CONFIG_USART1_TXBUFSIZE=32 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_RXDMA=y +CONFIG_USART2_TXBUFSIZE=1100 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y +CONFIG_USART3_RXBUFSIZE=300 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_TXBUFSIZE=600 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=300 +CONFIG_USART6_RXDMA=y +CONFIG_USART6_TXBUFSIZE=300 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" diff --git a/boards/thepeach/r1/nuttx-config/scripts/script.ld b/boards/thepeach/r1/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..6d92733df8 --- /dev/null +++ b/boards/thepeach/r1/nuttx-config/scripts/script.ld @@ -0,0 +1,146 @@ +/**************************************************************************** + * scripts/ld.script + * + * Copyright (C) 2011 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 STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000: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 first 0x4000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K + ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * 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.*) + *(.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/thepeach/r1/src/CMakeLists.txt b/boards/thepeach/r1/src/CMakeLists.txt new file mode 100644 index 0000000000..a7db4590f0 --- /dev/null +++ b/boards/thepeach/r1/src/CMakeLists.txt @@ -0,0 +1,50 @@ +############################################################################ +# +# Copyright (c) 2015 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. +# +############################################################################ + +add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + spi.cpp + timer_config.cpp + usb.c +) +target_link_libraries(drivers_board + PRIVATE + arch_spi + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer +) diff --git a/boards/thepeach/r1/src/board_config.h b/boards/thepeach/r1/src/board_config.h new file mode 100644 index 0000000000..e82847897b --- /dev/null +++ b/boards/thepeach/r1/src/board_config.h @@ -0,0 +1,182 @@ +/**************************************************************************** + * + * Copyright (c) 2013-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 board_config.h + * + * ThePeach R1 internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ +/* Configuration ************************************************************************************/ + +/* PX4IO connection configuration */ +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS4" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */ +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + + +/* PX4FMU GPIOs ***********************************************************************************/ +/* LEDs */ + +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12) +#define BOARD_OVERLOAD_LED LED_RED + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver + */ +#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 13) | (1 << 14) | (1 << 15) + +// ADC defines to be used in sensors.cpp to read from a particular channel +#define ADC_BATTERY_VOLTAGE_CHANNEL 2 +#define ADC_BATTERY_CURRENT_CHANNEL 3 +#define ADC_5V_RAIL_SENSE 4 +#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15 + +/* Power supply control and monitoring GPIOs */ +// Signal is not connected +#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8) +#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5) +#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15) + +/* Tone alarm output */ +#define TONE_ALARM_TIMER 2 /* timer 2 */ +#define TONE_ALARM_CHANNEL 1 /* channel 1 */ +#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) +#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 6 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) + */ +#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL 2 +#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2 + +/* By Providing BOARD_ADC_USB_CONNECTED 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_BRICK_VALID (!px4_arch_gpioread(GPIO_VDD_BRICK_VALID)) +#define BOARD_ADC_SERVO_VALID (1) +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_OC)) +#define BOARD_ADC_HIPOWER_5V_OC (0) + + +/* 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 BOARD_HAS_STATIC_MANIFEST 1 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +extern void board_peripheral_reset(int ms); + +/**************************************************************************************************** + * Name: stm32_usbinitialize + * + * Description: + * Called to configure USB IO. + * + ****************************************************************************************************/ + +extern void stm32_usbinitialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +#include + +#endif /* __ASSEMBLY__ */ +__END_DECLS diff --git a/boards/thepeach/r1/src/can.c b/boards/thepeach/r1/src/can.c new file mode 100644 index 0000000000..5a32d62832 --- /dev/null +++ b/boards/thepeach/r1/src/can.c @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_arch.h" + +#include "stm32.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 diff --git a/boards/thepeach/r1/src/i2c.cpp b/boards/thepeach/r1/src/i2c.cpp new file mode 100644 index 0000000000..e9f26f9a9e --- /dev/null +++ b/boards/thepeach/r1/src/i2c.cpp @@ -0,0 +1,38 @@ +/**************************************************************************** + * + * 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), +}; diff --git a/boards/thepeach/r1/src/init.c b/boards/thepeach/r1/src/init.c new file mode 100644 index 0000000000..107312832b --- /dev/null +++ b/boards/thepeach/r1/src/init.c @@ -0,0 +1,318 @@ +/**************************************************************************** + * + * 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 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 initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include "board_config.h" +#include + +#include + +#include +#include + +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* + * 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 + +/**************************************************************************** + * Protected Functions + ****************************************************************************/ +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + /** + * On resets invoked from system (not boot) insure we establish a low + * output state (discharge the pins) on PWM pins before they become inputs. + */ + + if (status >= 0) { + up_mdelay(400); + } +} + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + stm32_configgpio(GPIO_VDD_5V_PERIPH_EN); + stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 1); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 0); +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void +stm32_boardinitialize(void) +{ + // Reset all PWM to Low outputs. + + board_on_reset(-1); + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure ADC pins */ + + px4_arch_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */ + px4_arch_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */ + px4_arch_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */ + px4_arch_configgpio(GPIO_ADC1_IN13); /* FMU_AUX_ADC_1 */ + px4_arch_configgpio(GPIO_ADC1_IN14); /* FMU_AUX_ADC_2 */ + px4_arch_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */ + + /* configure power supply control/sense pins */ + px4_arch_configgpio(GPIO_VDD_5V_PERIPH_EN); + px4_arch_configgpio(GPIO_VDD_3V3_SENSORS_EN); + px4_arch_configgpio(GPIO_VDD_BRICK_VALID); + px4_arch_configgpio(GPIO_VDD_5V_PERIPH_OC); + + /* configure CAN interface */ + + stm32_configgpio(GPIO_CAN1_RX); + stm32_configgpio(GPIO_CAN1_TX); + + /* configure SPI interfaces */ + + stm32_spiinitialize(); + + /* configure USB interface */ + + 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. + * + ****************************************************************************/ + + +static struct spi_dev_s *spi1; +static struct spi_dev_s *spi2; +static struct sdio_dev_s *sdio; + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + + px4_platform_init(); + + /* configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "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_AMBER); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_AMBER); + } + + /* Configure SPI-based devices */ + + spi1 = px4_spibus_initialize(1); + + if (!spi1) { + syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 1\n"); + led_on(LED_AMBER); + } + + /* Default SPI1 to 1MHz and de-assert the known chip selects. */ + SPI_SETFREQUENCY(spi1, 10000000); + SPI_SETBITS(spi1, 8); + SPI_SETMODE(spi1, SPIDEV_MODE3); + up_udelay(20); + + /* Get the SPI port for the FRAM */ + + spi2 = px4_spibus_initialize(2); + + if (!spi2) { + syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 2\n"); + led_on(LED_AMBER); + } + + /* Default SPI2 to 37.5 MHz (40 MHz rounded to nearest valid divider, F4 max) + * and de-assert the known chip selects. */ + + // XXX start with 10.4 MHz in FRAM usage and go up to 37.5 once validated + SPI_SETFREQUENCY(spi2, 12 * 1000 * 1000); + SPI_SETBITS(spi2, 8); + SPI_SETMODE(spi2, SPIDEV_MODE3); + SPI_SELECT(spi2, SPIDEV_FLASH(0), false); + + +#ifdef CONFIG_MMCSD + /* First, get an instance of the SDIO interface */ + sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO); + + if (!sdio) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO); + led_on(LED_AMBER); + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + led_on(LED_AMBER); + } + + /* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */ + sdio_mediachange(sdio, true); + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/thepeach/r1/src/led.c b/boards/thepeach/r1/src/led.c new file mode 100644 index 0000000000..8a70a4cb29 --- /dev/null +++ b/boards/thepeach/r1/src/led.c @@ -0,0 +1,96 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "stm32.h" +#include + +#include "board_config.h" + +/* + * 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 + +__EXPORT void led_init() +{ + /* Configure LED1 GPIO for output */ + + px4_arch_configgpio(GPIO_LED1); +} + +__EXPORT void led_on(int led) +{ + if (led == 1) { + /* Pull down to switch on */ + px4_arch_gpiowrite(GPIO_LED1, false); + } +} + +__EXPORT void led_off(int led) +{ + if (led == 1) { + /* Pull up to switch off */ + px4_arch_gpiowrite(GPIO_LED1, true); + } +} + +__EXPORT void led_toggle(int led) +{ + if (led == 1) { + if (px4_arch_gpioread(GPIO_LED1)) { + px4_arch_gpiowrite(GPIO_LED1, false); + + } else { + px4_arch_gpiowrite(GPIO_LED1, true); + } + } +} diff --git a/boards/thepeach/r1/src/spi.cpp b/boards/thepeach/r1/src/spi.cpp new file mode 100644 index 0000000000..77d0c37214 --- /dev/null +++ b/boards/thepeach/r1/src/spi.cpp @@ -0,0 +1,49 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortC, GPIO::Pin15}, SPI::DRDY{GPIO::PortC, GPIO::Pin14}), + initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortD, GPIO::Pin7}), + initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin10}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/thepeach/r1/src/timer_config.cpp b/boards/thepeach/r1/src/timer_config.cpp new file mode 100644 index 0000000000..7bf538a032 --- /dev/null +++ b/boards/thepeach/r1/src/timer_config.cpp @@ -0,0 +1,51 @@ +/**************************************************************************** + * + * 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), + initIOTimer(Timer::Timer4), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannelOutputClear(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/thepeach/r1/src/usb.c b/boards/thepeach/r1/src/usb.c new file mode 100644 index 0000000000..6fbea86a0b --- /dev/null +++ b/boards/thepeach/r1/src/usb.c @@ -0,0 +1,108 @@ +/**************************************************************************** + * + * 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 usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#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_STM32_OTGFS + px4_arch_configgpio(GPIO_OTGFS_VBUS); + /* XXX We only support device mode + px4_arch_configgpio(GPIO_OTGFS_PWRON); + px4_arch_configgpio(GPIO_OTGFS_OVER); + */ +#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) +{ + //ulldbg("resume: %d\n", resume); +}