From b064bec1b3f288859e6b316e32a694f065cff83e Mon Sep 17 00:00:00 2001 From: ZeroOne-Aero Date: Wed, 28 Aug 2024 17:10:04 +0800 Subject: [PATCH] Modified according to your comments Modified according to your comments --- boards/zeroone/x6/bootloader.px4board | 3 + boards/zeroone/x6/default.px4board | 104 ++++ .../zeroone/x6/extras/px4_io-v2_default.bin | Bin 0 -> 40160 bytes .../x6/extras/zeroone_x6_bootloader.bin | Bin 0 -> 46752 bytes boards/zeroone/x6/firmware.prototype | 13 + boards/zeroone/x6/init/rc.board_defaults | 29 + boards/zeroone/x6/init/rc.board_mavlink | 13 + boards/zeroone/x6/init/rc.board_sensors | 177 ++++++ boards/zeroone/x6/nuttx-config/Kconfig | 17 + .../x6/nuttx-config/bootloader/defconfig | 95 +++ .../zeroone/x6/nuttx-config/include/board.h | 560 ++++++++++++++++++ .../x6/nuttx-config/include/board_dma_map.h | 87 +++ boards/zeroone/x6/nuttx-config/nsh/defconfig | 330 +++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 +++++++ .../zeroone/x6/nuttx-config/scripts/script.ld | 229 +++++++ boards/zeroone/x6/src/CMakeLists.txt | 75 +++ boards/zeroone/x6/src/board_config.h | 514 ++++++++++++++++ boards/zeroone/x6/src/bootloader_main.c | 62 ++ boards/zeroone/x6/src/can.c | 142 +++++ boards/zeroone/x6/src/hw_config.h | 128 ++++ boards/zeroone/x6/src/i2c.cpp | 41 ++ boards/zeroone/x6/src/init.c | 286 +++++++++ boards/zeroone/x6/src/led.c | 235 ++++++++ boards/zeroone/x6/src/mtd.cpp | 136 +++++ boards/zeroone/x6/src/sdio.c | 177 ++++++ boards/zeroone/x6/src/spi.cpp | 89 +++ boards/zeroone/x6/src/timer_config.cpp | 80 +++ boards/zeroone/x6/src/usb.c | 105 ++++ 28 files changed, 3942 insertions(+) create mode 100644 boards/zeroone/x6/bootloader.px4board create mode 100644 boards/zeroone/x6/default.px4board create mode 100644 boards/zeroone/x6/extras/px4_io-v2_default.bin create mode 100644 boards/zeroone/x6/extras/zeroone_x6_bootloader.bin create mode 100644 boards/zeroone/x6/firmware.prototype create mode 100644 boards/zeroone/x6/init/rc.board_defaults create mode 100644 boards/zeroone/x6/init/rc.board_mavlink create mode 100644 boards/zeroone/x6/init/rc.board_sensors create mode 100644 boards/zeroone/x6/nuttx-config/Kconfig create mode 100644 boards/zeroone/x6/nuttx-config/bootloader/defconfig create mode 100644 boards/zeroone/x6/nuttx-config/include/board.h create mode 100644 boards/zeroone/x6/nuttx-config/include/board_dma_map.h create mode 100644 boards/zeroone/x6/nuttx-config/nsh/defconfig create mode 100644 boards/zeroone/x6/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/zeroone/x6/nuttx-config/scripts/script.ld create mode 100644 boards/zeroone/x6/src/CMakeLists.txt create mode 100644 boards/zeroone/x6/src/board_config.h create mode 100644 boards/zeroone/x6/src/bootloader_main.c create mode 100644 boards/zeroone/x6/src/can.c create mode 100644 boards/zeroone/x6/src/hw_config.h create mode 100644 boards/zeroone/x6/src/i2c.cpp create mode 100644 boards/zeroone/x6/src/init.c create mode 100644 boards/zeroone/x6/src/led.c create mode 100644 boards/zeroone/x6/src/mtd.cpp create mode 100644 boards/zeroone/x6/src/sdio.c create mode 100644 boards/zeroone/x6/src/spi.cpp create mode 100644 boards/zeroone/x6/src/timer_config.cpp create mode 100644 boards/zeroone/x6/src/usb.c diff --git a/boards/zeroone/x6/bootloader.px4board b/boards/zeroone/x6/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/zeroone/x6/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/zeroone/x6/default.px4board b/boards/zeroone/x6/default.px4board new file mode 100644 index 000000000000..c20a99462ed1 --- /dev/null +++ b/boards/zeroone/x6/default.px4board @@ -0,0 +1,104 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +#CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y +#CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +#CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +#CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +#CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y +#CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y +#CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y +#CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y +#CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y +CONFIG_COMMON_INS=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/zeroone/x6/extras/px4_io-v2_default.bin b/boards/zeroone/x6/extras/px4_io-v2_default.bin new file mode 100644 index 0000000000000000000000000000000000000000..145089ae0d7c21936cb60cc5c39501280771cf92 GIT binary patch literal 40160 zcmeFZi+>YU-amfkl1tM<(+kiWG|3c98^A(Aig*c0JG4!;DDEx-t^-APN)f8)T37c= zps3;EE`sZWR9&>Xi=rzD)Q74yDC@45bvNO%PoW@PQ6sIF2`yyWw8{5U&-vWX7{?OR>~t88(R*6;R)_u=QO-xT%EKd!vToR^^7-F~ZdLhIJf(ggBK|`xF&$4MCPIj5>Z?TW z#qUTvDVpxO`sM;@nUpO|ubN(cbxoPXOKDP;Jnbf@!f;vAR9B&Vy?vrIPM)l6dSLQ^ zd-gc`Jm8)@PMV1OBjYAYMK?{AvgM)ycTvTFdsen&u4SH@B{I*EX;V%!yM5j~*`g?H zo`m~=bZhe7vm$X~(C=Qt@9&xeIniQBJqj+0;K zP8?^RW3Fd@_xDhmk+o;z%E48Di{MHlafQcSkIO!WBXtV7k8$NmO$&&hCybp-nRZ@r zW+{Bi;eIyzwxG>LlyuD^waCcnZud_Yw~0)cPkTA6*OCF^_`W~mH*TS&Kf`lcC8dUr z!~O3Sr(g9Z(G6);p;xazV&IfC&e@y79k4rl_1xc3>&~Iy^v~>Az~`T!?TD%KYo$fh zq@OseRvjjochG*F)1ju>$-rTU@1nczT#(h)0VlP7oiDRp|#35(iJLyj_CE62T|4&`+&(Fk38*nXzO~7S?S01HJqa3ZdC;nDMk-m zw%=&ZHe-H-8zPElA;kf0|3B)N(mK0kMxgbKj%qS`-=%nHD>qTYIY1UUflXRN-$~cXh%vJ1IJk`M{MtS0GUMkmGZ0v383^2$ zP1*Wr{ zscvG9M?Srx_QutV)?}|;tUtEqU-E&d(!V%`Qwlkz>|fGSy|b5O8P~Q*=7If-cBspZ zOmRUFG+MtyT|rW;Y(Q^igDGC;fO}EK+E1j6wL8>$lG-2)*ca*XmMltLp1Bq<57^f& z0>o^w-jBNVXG1Nk^VTku52!yk*?U=sK_ZsJzBc@7T3~ED>$urYvs^4I3bhx_furUfmlThvX7d;Z$nv3mcrr}^l~&209?Bg=p63vW{R zl(ZlFI*dMy?VDB~SKWjt{}?*1dP)z6O{B$<7C5eMGZoqb%eXMZ8vI1~v+6P7Dm8Wz z({QM~ofBJS@5K%4?`SZJudTiz;JvtOy*6OKz+^q+$P27ha!7fnu=ai39S!wsQ%(Sr zplVyJQqgOKwRbEhrtd=n-q{D-cwZQsjQ1Bpq-1X3DRp`2J}+ad8*ty3=C2zd>xhu$ zd`hi1k&vF8s>z$aPnXft@!hJqh^(EvGsUitpO?fuOVm$JG{M_0_-Xzp70BTBKs|P6+ zxj{kYs3X(}Yc=9d$F-x7Tze%XGbdIN@VL!`bZjHWjz`9fSk{6Hj9J)Yzg|RlB3YER z+_KgxQdr+zcTBP*_Fs|*Em|Ir=wg<&#B>ajCdq@2NsRE4x{Lr9rR8)M7Ov_OItvF| z_1DmqbC}b9r1{a+`QESBmUeLaOFQF{Kg5YO5>P`#8C2^A9$iF=ir0QXXSMSL_K8X0 zXAmW>TG!ewW-+_;1Jz?EO3B~})L?`Xk*y|*VbCOY0ap)$PK@m-wZv?~iakF<%(|+0 zWcP>`GX~!uNv>Z!a*rQ)gWf`4tJ_r zBZrbnm>0Vr6q%TlL*5DLlFsdv*yf!i-Ll*6#2T(&Cny}Z1pF+krm39>+2SqD9)~u- zl<912*vLkLbxOQ!67#|xd>?1rLekAn`APfbb`#}d`|Z-B@-%PT9q-GnQ|^)}zy48XaI(1n`j3_7qo2RW3M3o~W-)x#_)ro%tCD z8`MExD(&PXi^P4paP7hMEUu?;ec!KfPg3}FHt>Ca%7!PzRU#WUu^6vq z+WFzS2JwY(Eo)J9?C-#_URU>jJzPg?r}^FedXKw5#Y15L%p~1vY&V`UmRDqOeVaHg zEIGN0%bls%e?%!v=q*NxVsDI#w?YR5?{Sx90VWM(Ecj5F8qy}7+(LgS-O2@d7j64( z2H^>J<0PBWm_Ei*!USn3gYR zS2JbZgqb(tD4Cq;DiJfQQ%w^kqR8pYz&R2Qc z=NQxdFVa(harL-}k?6@6q-QZtOs`BN`VF|U+TB8f$h^vfme$A1JIO9YmNa z+a!}nX`8~JZ`Zo=WqQ%IO6p0kn>lcaN$OOek9>0{kghoqWo(*k|_e}Av< zB#Nkx7dVNoRV2g!Hlh#}<0_{I4HZv1NH|_bf|QOkRL1qBgHxHh!Jx6zF$urtu_|*T zu??b}SW4T+x{jSEw{3Hz1V32b0uJGZL`sKFxB=8t+W88o`n~05F&tuM7M5^fJr}}n z(9$hm1Ag*6(I0N05E9Hm@69d+Y*oXdWx!WqJ25e@5G5KT)`NaxVs~lw-=Xr+Cd$ji zddSQC#$5}DbuduBx>%$fxyjzTDrdp8^J-n?*8PK%N~igl*}UixpA`2wy8L7^=*^debaob%DL}q>HJ##ZATca4m&I3@h#XV$(lLA`qi6MW_zPi*3)2*uvUc0z`!MDCg zN8i{*#=N6p`+_R$?m)~Wa{FQB{PvJ)H62o?7>&LZ-v);{(4|f_GBfqd4h@zVGks6e z*<1FaPM6A?G6#CrYXSzVE|{s<({ub|Od6F*WoEq_8e<&{W)8U5=lBh#fe@K`DCm<( zNkw3moUPb-XYevsC}d`FM+1e7j!H*Q@zHVOzM|ljaMNcB@BggH1}MHZg*+;|Umwl} zK8s@s3|jq{e)R@$$UhXKzmq-KG1~S8_W+{{dHUDDuL53``7QDt4Vth~ZwEF~fY03S z>CMbFHss{mVh|9)B2j@zQ&Hm)mAZI#tKf-oua+dcGG}G;BW&iYfY3juI5fz z#ie-uCbV=_s@IA&Z(PloQQoj?0c|(E>0f|i0{>Yk(w;7oaIKbvmuY^g@~%g`_414I zJbRY2O>%in4a_U7GJA+=B{uf7seve$M*igJ4N{95bn0x8$BN4u#)*7*d}0oN9MMg> zp_@!|1&F|dkHdajN~V>P`o363& z;?_*xZih8kg&vDih~giibn=Ih&$kIrWcu<^mg8S1SBV9F4tCo_CsF=1GSN$S544*& z#l{~-%7G2Fg(>50{vZ+7D(Sj)%fq1uWR1dWj)vAX5L<6xqV&M>P>2w$!GadqE#A>^ zgDV}F9WOrY1(l3ifx14e{!pb5Oll*u5_?p6oG99n4I;7j1~uUv!$OQXb%dX!ba%mm zuNGSryPmED-BVui!+v)T-I2M$S>n8&eewjA$?wu}C&m4F<7N|M-5;T%0L+QqSWe`HuQX=*p!FG=d7 zyoWJ>Z=|f)+BVu(2KW}Z%AU(yg|5^ehc)1Amw5`A7CM#WD`Q<`+B0IIJoXe_qvOL? zO0kdE4g9K!C}krjfw}Jd0}ky`$`zL;xS|p`4+>qUIUib?gm3;Q%^ERHw0S>~oml%% zB#p3DqIwo6io_$I4=10C@O*mo*@)+V4igLD)@6w0z}!C)zp}L%B9(R@j@BEGdhZXz zjuBbqpYV{C;(k;WfNMZGziy!WJ_g$FQys*wg5SfR03H^PtcbNW&+}3`&n9h6)P^I< zFW#a40$$`%erv3Lv^lU<#E3WTi6&R(}=RgZIkPzM!8Mulg~+(9vj-Epr7j#R&i73 zt_8+$Zh9a z#nwIOh4>P!@&;&|$C9wkR#;B&KetU2j?dQng-4lbd{_Neli1c0kK7i&w=RN|=! z?@mO)w+LfSuHE0?rYoZXKZ9njEd`yfiVDq)O?#4=Cp6LD&C!IWZ?0c$Zfb3ylGFz8 z7JnRcyqrR`EQYx}nw$%z-L2YT^St|`{_u66ZL4|Jiq-kP9jiWCW`ay>OK?@DjPCfh7EPGZ zbou|-@@Yr~&+ec9!M6Qa-K1`j)GNr8!lB311jLXJ_Kri~SZshoxH-mB`Mlw(ClYgL zxY5VFvTMN`j;{mfwtWuGBXFC|cWx7<7G`#`FXoyqNVfj@I`EP0;zVFAU*#udcF)KD zV_qf7Blwj9t$}GhwfV?-{w|A>p77(I+5lS?Hd1mtqAWWETS^HHr@MG@i9Au zx0$h}K_YM)s6OwMi1HzN(wyr2S`Um)dYhTYZGiTcXah@3gzrVnQW;xG2gxsh?e)xX zPKUAc>XQE8r4V=}$6S}KGFNAI5KCUuh0xU{Ljh=+wt|=9yu7V>R79!^4eW`FQd#KHi`Pg>Rj(_lnX4#R>C6u`BG@xV{si4Q{69mSnA@Bq=7~(%4DZ#&YS1Wh&CJZJZ9{>k1!_Bo z-I3RPb%{Q3RgJYe8#rl-HA0@w57?y1E~{K1bIn)Vt`CwabHv&Xi?|ki`h)X?|KL3P z%aY|eqT0!aCooQ`gZ~4Vz4{%{S$fdmy}D#VFdlg?&NaX7J-3;I_RZO{15?B{nG~h= zSWwOeo~qOw`}`y+qJ3J#W1)KaDzQNPB*coJ;v&Mwm_aJ{H#!gQqY%Y;_V1H;XOx2- zEd0<6tUqY{ekxBGVeU(Q>k?P27L0GRmEU!y!RlN_?xJdl=W(xMq|Q{an=fU@n1;Ns8GW1bvZGz7)P0a54k$dNM#3OI07ExELue#*3tF!H-?*rnHDA%TZlk(;$U>Y-( z=nF7@tySNi)|FCot6EyR)XVlAW^VN&6n(f@9*5%pR+(8s8z=NmMY z5?jh?c!4(=P`0Qesq<0)0W+`Fm$ix5E(X63F^Xd_40ta0H-J8Q)EB%t^8O*WVozyW zz|avfUU_@ED@~jzH(@mwME7|6wsP=1u{K@cRk=mp?cgA((}=FeDmohlsim=AI?_l? zZBjWf#ZXKo`pBxuruOz_o65_2AUjJ~4;zlpq*k)#3^AEjCM8RGClO35HL&RFH!;eC z>cK$^Ayx(4@jJRNNME8)Djg|r55~EPLjkI<#3P@?`AJ&v)K+z+gHKr1@bV-)@WeWu zT9czvZNa7ZeVixXM}4`;G1n?v;DhHpRN8QET1ISRPp7#G?bIQ_ zCJHMVC9Eb}64U3QBDpUC*%{z84fCb2d;nN9faNEbVVPwTsn$g4Egl&g2Q;Jlg3Xi1 zryRF=^7*kRlG*_+Psr%0{b#Hqa~*u2@giSuXsY|Wkgi?!>T8I3fAm5>8_j}O6>@vs zVkfg*2A@4T%q6UI;bYs4m#M;tE}!lT|g$csJD_4cTf+}zHz)?$&}nc6y2 zWOf=_$XM>k0Z_@OK3fr~Mk{#gsvxs02b1@s> zo%$;=UjKr})_cSmq6XG}p?F5M?jg$IL4MM;-B$EIVF>G^aN4x)$Gx|TbD^0sN+Tqx zCQ;gidReD_20ITv{y}rkOz{@fAj(U?qjP8c(UMh8prTQL@m- z=a9`-F>Ng|32~Zgl~3zZ^`+hN&!wcdgz{%*!cSD}D{CMC zo)qg+XO%Lg+KT5L8p4br7I`Rk zTg9iK%q8R)rB4#Tyw-z>y5re~?orOB z4`zsa7Q`a+Vod2C$M-?Tq=p#q8b(POg0~O*TjR=+OTFBB&c*}}!_T}{Vd39P@>5>a zxAU$qd^s{fe1j-AA>sw!X^gfrw&$3k*(h(sOx`xRTjpS?7{Mn~!6(bX&wk`kiq|Qh z^P&_`c6-|#=|Mrx_wJTokPQ{PrNv$YXyV>MVv?lGJTnJ&|M?JK#VAV$F8~wcNH~-) z$3NSo11D+MiYrY-X^r#ZcJOg)R5OXkE+@*yxD}pJ9&yZrkn9@h^NhlekjecNml`D$ zIM2?^gMGT>K19OXH$iin<*ok}W8+~>)Za&hecIm0N&Vr!N0;KelNLX_}ZuuN z5?+6-l4&qRX`RwO#rfCX!?K%tOEzBi5u^d<(4y_BRYbO{!op*TmTiq$uv@4vhf1A? z;`I4kjK&|6`-t|bwoeepyR_i&6XkfMU^v~|xO$%S679Vu2_-u{Bfw41hF2^*xN5ao zHaJPqs+HY|5r~q39iIWLshwtd)oM#G!+syK$lub{$N1sa26_7dd|)mgxc#sDKSd$A&_Il(zIRbDLhG81V_59}10Q$xLC zUqW*|9%W2tN9A?P71ElRo^80_Yk6pkLmTA6IZSB>_Mu```5u#4B*UYuOdXYlG`0(y z1vq~&_uyRU&(U&2Kru}l$#81$iS`D4Um+^%ieE7D+^I1d*U=z*!^Z5+AD$r}cMGSInR7vbD5;i7k z{Vi_o$U#3u`D;9^cq$2+GLY>?yg2zxSI%VD`BkZv%Dg4=5^0sZTlxySRS8vs_CE1eKwE8&n>w7h-w(T|D`1nI@RGDh=xJ1kfxn2M z5su{k|Lc|h2ei6<)XzYy{|Xwh^Pe6e*7gAMTh^V#T>mjt+`LC7$}2-!vGjml&N)Do zc36=&2G(I5pS)4(ms{ZxV1(l4t?;3?NH+Nh#^;v*hza;bF@6}kI3Fvl4ktAiG9@0_ zKZIJI3q zYBYDPq;0Pi*U6<1Yr|>Gt_A4-aoYbmv_SlS-MNFi5pcRz=PiP@TNliq1xdg|nh@IPt?11`n zElJ-XY&(=DcW&(=x?{^hXRC&J%3olQ#v+dlfy+wN4xsYQ*#2ki6RKfeZdLJ4QE5EV z@(vNGF3-XnnS=fQ_J{>`u-43&7^QuL2o_OmX7T*S2$hwPy3msuP$uW5HW8I`G(HxO zTuA8KvB+~nqq=`W-^MD9@^ub0r42HxQxiHq@|^^3WszzUr>XEs)G-llk$e&R-w2yJUv_$tL!@jP-rqrYQ5v5A*ENyv>kHm{txnY(_5GOpdP(6*oeClJZWZN z%K=h+^%Zdwr%Zh~e;O*RUL%c_KTy-$%&bWrl;?z_Q+rCqnb@&U%1d*Y6B+W1jy6a3 z=?uBJBfI*Gyl+BA(I6@zkIYphpNhq?HIUm;V-MZCnLSU+PdnQB81AJ$j(?$#XP%V4 z4O&GFDD%_kYtm>um*$XeApWE-JGNGkUEawenSzYXYj?v-mE~=fiH)3T>ZCArN0Ykp zhJ>!{ltt+esmUZ9!Y57pJC68Y#F3XQVCChNni$;mZ%o{voFL$puo-=Y1Nx3@H= zVU07y)(*;xw+`;D-`j}YmupsZOiJF@^$qoiXClj?54_&JsIR5G)7jYO_$GiHDwSH` zq2T9<%#sTsZLPjtxFUxFd49u!+=VcJs^$qL>HI zZKc@`=UR|4cYbVHeLc;YYiay+A}>x>bee~~&c=O?u_uo-mcSEEu=llbPW-&Fq~i1X z6^*y%uc*(#z9d2vUSosEnsNbm5^9=T0;{EV3LtzpN_Ek~AK<(&3TG4G)Q-a01poV) zAAD+v!ZcFOmn{n34eP1ZACJ5cpIT9*==kONR`Dz`36`ku^- z&bwRgK63Z+j`6Tj>js`*x98&XO~4DOucurFz8b&1F<0D!sCG}Iv7+bhT4XW)I(Dvc zdE@76QY*5g`i9Tf2=GoXS_#eSzH@7KuY?WG;=V$$oLjR*f}ba`UySXJHN2QA_IBjK z-rDHM3+C3E<%|R`%USUL`P>=EfFiXPlQa@}CML)nM$E%rHP$Ry>9#C^cg}s^?v=*Q z`FFp!rq;6IZd$wN?vY4K?A)4U-E(U+iMn*ub8D!-g3=YGf$I4Q+JSdY5nf(HGpSa* z32)(=gjP1XtB7C~>+g<7-i{^P8DN()BF*!;MZFx;@W4-S5HgQ-F(T}BO8lzAatFPv2!V@@tGBbtd+boyc!g?Kz1_kn&ia(!cCJ3s2*$cA1 z{ARZR4~Vf)P}yZYl11g0AFnU~;%Udr^)(yWSBUlHyOPcr+R6`gL{$0vDC_)FYUvY80PuDD4g*>WC7J3B zlB;hF=)zf=$vAQGhGQ-?4&;Hx+kt`Wj?(@fil+%<>i~*#|71dihny%wsRgi=cy~ zdS8T%Xz?t{PqmFbx!2d~Tb^6L$Wl?|HjP5XITyKUfAiw?9)1?hEugrdZ%X1t-dCZ& zloZ0|Pk0w5%VtQFc;x2zRM7`q9|;wRAHYf;gLl+Nl;fpV2T|@tZOR+z8I-IJy;KEh z>5_A#p-?L1C)ZIW>G6gW^^hotRd{RQYhj@4e1%LtR-$JmQe{@$>UDctVDaY328q^4 zLG;pvGMktBtadtvg0M6W(S8VQ5LQP1U&j)Oj@q=qAk(+EdaKa)Mn|1O*l~VFc1gJs zYN4D6PQb=VSsm}42ftphH~~@MJefJOBULKvs6ju7DV8BmR*Hm{;DWdOzU}axr%Ldi zb8MB3z4BWuK5A+xg1_2q=K5l>00tFfIW5g%+>qK@hEo+EcM8pO5!dtIuo@cJ1bn@T`FG^kpdY%^V z?a^Y9*-f9c>UGi>RGB?om`$a1z7Js4^#-#jz9)8sZ%kj< z^;X!H?g(V#Zc4WY-U0T*oV6;H}u z)SI5(m8fS|dN))LxF32R?^dU$;vGSjVD$iL__1g5&~H&HCraIGFPD;slH9ZKD{vL71Mhrh`_=;YsIDF;8(PVJmisK)u(?GU~cFITr1O422AxFu+@ONkGl_CG_73~Ou`lUniXi= z1~KbQQjGa7x-U#vK{0YE$TJ|B)s7W?4i+^sspi`1JEhT`pkwkuS_(g_@=v$H!tKNi zQmRD)pHI~w*Se=KCFM@6$SKXIh+^2oe{n;K7~ZQa9NIGEzVN=g;)0RQvl~lbrG~kn zpkx?mNuFW^rF6RW`&<=S>X_?FK{0=Fmkb=PDN&50HT0OlyY4)NN!JFv4)=wBy8qC} z=s&Co`>OLl_PsWWSGt0^VqNdK`zYkw=_;>%B7nDRQ~kM!t)=*?eIHMtWg9~j8wLM{ zjkm&!(~A`?*Xp|!dtfbl=g`LCcfu*@i@H)uZs|JvHLEO{u@L`E3l}=*SVox*^Ex&_ za}7QV(a{D+M`PfDF^ETfdjAfe0$uBO(2btJWv~=0~jW&T#j^dMHoYMnITrLi^ zLWBJ&yZ~fZDt5C|&Xf5aOv1vyG@=hVu|i#12B(_bPNStelndN30q4MBXWamQ-!bSD zf;`#0YeA9=u(Nk9`0gvc<*%Xl#94^(?G~%>R}AG1xa*i8GlTT7Gd}Xwh2~$-a(TU6 z`i%oMZ}gASBL@z`frH$V`;pJ<80hvoUh|VFzs#enWeJpy(k$&MBgo8tU;MbzdU|hP z3in>+hoIMq71X0JB}iH)R{Zg+55=<>liZo@UuBI5zd%v=ZDG5(x z6Xb|q%p4&17Wf&n1%Akb(F+&Z=s0JJZHhQm)SNCY^En7|zb~9@>P+#@DT{=DR(3H& z+nElKDL5UgGG^06>YJl^Vl-n6ybez^c0FFbt8sF|?z>hkMbyW(xmBk-!60*lD0=mp zUX#}9*NW5RZ$es}5`&zBUyZSVcbl!HBauBSwXY_W(X1n(URWvImGlEzOJk86V?+?{ z?zx8`vxt+=-4&1gbSMIkAC1t*A~TT-G}LYEj78QZ{Dg<)#)g8tr(oS=i)5qrWZXIk+>^qhp2s=BjwY04X+e625}@}fev&-_bnooz=!+>tnD)@Tl$f4 zt7EH}a=J=nX2c^;q7HYe3boB~YtJdj6ne53zP`f-*w2go%N)y8o2jmME5r8jnLA|@ zbFAZimAFyE#P@x|FIvo1+$mAt;8Hw2|HIQ6iS`*m)PkNeI3{+75T~9>PfVQ-QYgT| z42vqEaqtQtNe#20I~QQ-=%#(u^?uARQcFsYBu6Tx&&g5fQ*spgbVhoCW<~3jp?>my74-N45$dga+UMKe&7a>lmfv1A>X~tbI?UT#AHfZPbU^lk` zPP!g?p5|T{c$(#==aX?NYHi^B;Siaw5oe>{H_`8mQ{?KayGJ7TCi>pjT-O`Y|0mv4 zdrlu_Fqbb;qCr;uNaTS84v=pzD}caiTBMqY4qhOwqSLZ{Oa|%G8VMp`JapQT$j@Wh zy+wSv|2pwp0*0QD(oQ2V1Uj(><>fdXlHE_P$-#mvQgE?HDgcf<{mt^#jjDWEkrolQ9aTehDu3 z7~;?W%R8%~z`IgT^X^%|15b!3ASVa;d1c7YE2HOpW+B%~fi0sIAKmXh@VNZofrbMf zM{$7WA%017OuEZtvU8n`43;^tGIq{uX!Kr?xgGiND$4X+2{1(KUI49AIH_g!Uc6D{ zU&|A@k6(0Hr3NWW)P(h#OF>ffO#&b1Lq|5VVir!3X9u#--^V)U#BOUI3<;9FsL?{>cq1}!_?Jn6Hi)@b@dZLMZM8=jL zoY#<#mC)`g?;waEB{MJS$%>v(Eb=g7pn#4)gTLeW??a{7`(wn%_v4gJ)GU_3Dxjx3 z`AKQrXK)q|k@;O@r=~R?F@UPrQ?zs%;^I2Q2(Gj@;*sw7kM_pcgA>{{qm~FxOrkf< zso}``BR|?h)W>hMQ`4ci=BFDV`e`Q!?k| zetF@6F&1RBG7>$p2+zLIbU@B)nCa~voqK+eO}yJJ8#?kEQagD38i`yzbWpCB4@g`+$_kLBiMV$ z^Yzo*E$t)^GJXoh>Tcu%E4L16M0WbPGw?mX5|8``&SD^|sCAcY?LcN9|BC}em?stY z%m+Bm1(mo5A@l+vdiH+446{nPVD@Hdq|9J)^Y zCK1(N2(R+ZgUDv-ZUf%hfVW2Et(A9bzyoMZawKvic8>x4ZzRGZ`|Jh(DtRYr?nKR> zVt>_9 z?8bQ!nj=w+)9%D1JZMBd4UK-7RaP*0Ib?l7YkaUjBs_?W%~4-|dAk#y-lZL!g_+FB zc@LUIzB(4!6sJB<;X!z8CSOd{HMYb5^2h;i!6Q#$lqK?t4){W5QXffHPd=h|^p_D{ z9b!uBNj@)@)KCphn}vh;T}FK>45F?|JA9;5xT`X1Gpj9fDxw&vl1oxLGi9H5r)oSr z?vd9j)ssJwkE!G^VxN<*?_f-er11|5QsIMnV!ilP2$4K#(t~Pf5i*jJ{#Y85C~r>_ zb?`y7P;)R{&a^EYCi6i>uY%NS@* zRHvi3xg2L`9HeoESmgX$#D6{Vfsw^~Hk_E)1UM3XQ+WSRd0*6b1n=KycE(7=JMyiM7x#GC^=U2&c`R}; zMo$k?*)|iin6JLDo>EJboyG=6A|0KyG?7WxN$1rB+8QfXP8z2&=|=Cm{L@rN?HrDr zQ7?vAmqAQ=tl2}#xKD*>Prn{E19!0q1OFJZX9iZhF?Y02)6iU$+z=u~KMN@b(>$r-nA`@B zR{Thpcl-pR0y#?`lB^Xe-q+@``eK6PV)5b9M#^4Xd-;4E@bi; zkUyUE+U7_}ei)DZc8~!+e}l{cBTgI+M^6601$TH;MMDL0Fv@nqhN1G46H|I{!Xb^v z$y8zu2N<<;Kp`#CZ}@62%D;efx0ayFnuBJ0I@2uY(l73#tGv=WBcPeqt?vgd+2) zcaSI@9j}M=Y4@Dx|4xc=a>ka|joe7}46?|eO9=SZ0z9zG`{pymmX8wq6(z~{w>s+k zoLtj_Z1jpr$ti~ zbJ~1-$!5F5aPqC3v~YZeTgln5-GOs)8(s^uY1dX{=J}$kqK`u7ji!WO@>TS*6)!ka zPF|Obv)?n_3b)|})FvC)^6M&A<`J{KH_blDODw1D$To368+e@Uh<`?5BDT8V6M2le zt~c}M!l8|7do(sYHd^o#eKbw6q&a#um3tk!lfTXd6f@bQdmZG$dG}M|v^>;P#zu{( zM^rk#reaT}ZghP1=pOKllWwEITOIs(&bex-Z6Ek4Y=)of<=Z^t?!>zZyWzoBtU4y&ZUCgA`LYdoeCBrDE)iq9OLeb9NHd z50^N{rB(Jam9JIuL)<_L-~}Flwcom5tF&L(=4Q*UuXwpHO#`UIW1|_%;O8Cuov*St zt@0H>{p(x?v%CN3E0y=1WarYFDVq7cWPWq#y|78Q)ovNm4cGQ^X_JR^19iOxHy@0~ z1`CI_0fyWP(~zz|C8{5K!amVyOLO+}6)#q@L(By-#Pp|}Ea>BT_;O0Cj=oqao_rr2-HH_;W zTvU%@l*Ms2cRnnAwi~D8oLii<_R=&nT`TY8gIX6^l%cvkG(#%d@r5-EF;u+7{orjYMG6EG^v5r(HDW!|p_`PZjkbvr0tOns!ukiZINW zotJ)3qLI%AYcITk`vvH{wHK!2>DxhjZzW-@e1O(@9&i3ONUnP9rnkgH;w#8ib6$E5 z@7^CIc-o4m&OydJ|I$-2bUNAmfd%lizR22h_l&oiqK`Pch5I&zOP%AaF8 z!1xB)B1R*-e}MOQqwwkjl8eHd+q?l%EUzgVX&S7Lwm%lr1sW%^LBa&=-&7X#p9_=@O7>-w|u-EA{>* zm4>64dsC5}pFh}%uXCk7^9phiXG`}=cYDSwtk#skBE?hj;JlkoU=^~Q4y%%n zy%|+5wMU09GS@J(|KxbePt0_c=$PNDg*AV2WXKGBAQ{rTT?NQB!Ko^#BUDhu$k!Kp z{8~vX7fyf5KSTUW_y(rhS>@Nw_{dl+p^s}a5N*^-Z6SO+4j#kA_e=<*r!@RQF41>^ zM*jwVZ5U;r;l4e<5i6ccahYDw5lX`*JQv_vh&DyI7u8J0Ombz9BO^fXnRv>RQUj)& z%&wAVor&vnWEO%#jt$wcgKSMWb2qXd5f(kp>EzWc2VYG|U|-K9G3OsR`=`6MWbW-y zdFi0ax(})Z`{k$VxYk1C*}m?3(^ojOHCiGvCipxKq*j-Sh<3Q+k%^$S=SJM3;mLQu zqWe(A6~IOJrHZ-GnCLL>R2FJrzfKS#+f&Y}O?&cgrrrZa`CRSsYI+GredmVY0q-sc z{2w*Pz(<@o1%1p-xmcU`EmdzciJN_l@+Z~g?H?`eM;4iWYIl&f#W%GOmpdMMOVt|B zhd9@B?lx8HF5K{0h~kyvdXAMsu@U}=UE-|3J=RHqYpgP~6wvnlzprNcDw(fy4*PUg zrfXNFJ&3(D(&}ohIdYz5c6#F2cTUC5?Q}EBzmIlnSu=4(YBt- ztAoF(*-0TBaIf3x{yMbn$9h*0^Ol>FHBWbWDo+Jwsu}q5)9qGcSE0Mf!_08|?C@~9a9sZ)Bn|Zgyo8w8%=Eb`TbGBY^@u*b>3%EBAjZ_`W~ZeFxM_TF z(6iZR?&bMmH#7TNAB`;hEA+M}M;kf*j{9P0{4{dmkM6TyYm_w0%xkM&zWe2ufBN&6 zUw-+Xb-#Y{$&L6&vK0>BCt}Pb!N-PhRy`Zqr7oC_mE?mfpz-qpym?%i`|qK39$s0` zbHHhVbDd|Y*5O|VP1}TDFZu3wzZ(jBW^UdLsYAbP)f0O&bnxPb>ygioZ`6HwZ*Fn9 zKi9k;HFo&izVAZUd1+~)?Ec)TC@b3U341J{m+wROZ@g~{WI*)}^z)bD9UG3!~! zZ-OON__pEjme8O3xeOj&H&$sGZozB?M49sW{4~DjZBLOmv5NI?yMKxA=eg@IAl5W% z6RSKOUGx7jrdfPBjMH?=9dTpF6m^_^StvS6r&0G$LuA_ef!p5r!bznCG;?Ms@Qx>rpj8r0Z6TBFc!zx0K3u`^jVmVAJHt{1X;&Z>Lec1TZZtvnW`eLgs}7w5%j z+xzguCTf}xx0vXf)HKmm*d)lmcXS*jCY#LlE#PdDS^g;BOrsi)pH-J_r+tlsB$kkW zk8dRl$w;JySG#UsTp#VN(FvAyQPI5Gs@WvVsR$lf;3?Y!YQ)i6?QS(5H# z9lo?@nuxseDANNeBei+(jl;DQTzP?|9$@j_EX3_9FD%3t8gj+VS}Mf_Id}d?&Lss5 z*3}{nMY=`=Io-AiF+l;@Zc98nbh_h9J(U-Ja!VGXxjBB$j2y^;SLdHi@TP^xT%s_h z;hySx#*;DNzLyJ9IvI)_=xp_5DJHZbW{r#YCuA~{+XTtX;B1PY&gV9?!#9@Tht|1t zHB?K{CA1W(vk-w%UKmb(Z)yH7lC)I%|5JbSX#F#&U-dOZjHth^J*zhBX5`7p*@+YGJP9*$1(*fW4sjltwR&A!|IF+ZB6Hz#`NIiD6v~72B+2ht9egz zJQ5o=dfg}|J*Fn=zrp#s=AtS_xshRKOupGgRy6UjA2&FzI%!myhks@FEmK2X9keaG zk9##9xehUk&$`)G?imwS*Cenzg=Tg)2bgv`%Khw4_W8`J`=Bj2hNd+AJ#-n8m~bex zqG`KjOfA`AlJ)r3a5NDMHOYC1&qpH%Rh-RH+?XMa6%aqg1I5qnxL-^6KkgJ)d5M%Sr@O8(<;!F7h1#*z z!;xR8*U)|j8NntwE);+olHa-f$GgN&=Sjzs)?gB3o8Pf$*1M2783l<((U_Xmfy|9R4|Jv9wG20((ne#Msktb-#HJnTk98&Jz*n*&1B#kD#5>FCAsMvTAbh zwPy-P7T_3<6VhYo*_+ZPJEinexBdg4fgJM)jg$g@lNVz0ASK{n=f4|FV$M>^$`42<~`fsRt%Ae)V za9>}0!_D>JSVoTb&#lRFJ1^+j1D-s`oxx1uni^*3oT~JFWG9iw?xWr)oXLrA6c2fg z=2Gz6Pt@ns>+tn~8v`>f^&X1P=hSi|DZV~HHNkqf&9hX;94~U^xnYBjp1g+sucjjJ za*E-M3 zn_qxFQlr*;=vO)G-3NffY|gHfZg@hSTAC^FJJa{kY?^L zp2ksJvdZ;Qx0rL_Idz(;-a|?d!E#fY|4mK$Ge$W>+ThUolXIe&rL(GcKc`MFeQt2N zX{AlqWy8okM>QXtdn0g61jhxv?sc4}KHw>|-ya}X5n=uXz2B9aVi{yAFx8Cj?Tb~DZXsdo#AxCk5YU8y)-ZCHGxD_wYOTprdrVa@!s zM*q7r=Pz3{nMa)$3K$o9IuK{g)wsWb9vL&u_o~P2YO4fy3|RshiM$yi%)v_YSn0b% z9k5YWralL}yDG<>9NYT88~YOQri%6bIVWk7CTW{CEu;&OHnenwE^JbfG-=Z%g#ra- zQ_>AuC=e)UL6jh%L0o_evZ>YTy$CLC0i|p~yng0Pg7|A@0=8u z`@i1b&GSrVIdf*_e6xS^eeXQWji^_0z9dM))J!nS_Yu^?2*z(ep~lgmDsYK zj2L6*hzVT_--VVwTJf5$`R^uJU*blnf2V6A_z0FMVV2{dYBZn!6#gq|jTbnE^Z8!k z_H3qkAJ7ft^G>PX@t~h84fP(R@pGk8`84F8!uYvH3mE4JH#3^%pXFqHu40Wjp=;E; z$5BI+_HsT4wdW-+%~WC?-au>L+mkf-R)Ju+p~N!SK{0CT4M`a9X3%!p-&o$pzqsRyduI_yQozTO^s^{hJbam4(%52Y_!4cDo@)w#{+HAnGI zqi*ThI_nJ4((`rJoub9(A2B|XCvYj4LZI_+(&_NugB>98t+Othi1k{P%C^wDbdt*U z;SH@I&CIXiszmmM7y~Dv@6}m91VZ(KyafeHJlkxbZ$#K=s8*S7-VaX4?1m=njwH=# z)oEBEhWh|HI?{wPRrf8lqI^sDhzfItpYQ87_Z2{bGYzw@M{2S#%0N^5Fzu>q0x zbQ&%UKU!%G2D;D!>{MA`;N==8<)vYy32jK_f)$YGkD&Y5n~((vZv*FQ{?iz37~h>Z zPoLh`Ox@CN9JDkPwP{?QHa8WkV^u>6_JtU)0bm@Iq=L}_=ct zM&p3=YNnYCA7e*pnAtd61D+DNO`4p0%zfPfeZzBoaN0ViFTI*1q+)jn`P$~?2guMN zlhlUMbX-n+KFSPj#L34+aq#(w{wE6liTemi zI0wWHdV<^sDKc@+eaNrlPH^r=4!RHU@oZ z%?KgRSbe#L;&r|=-+TSqx|Y9dK6?hXsvWZT88eeZg3<9^)3HYsAnJy(ItYjI;)z%vJ5wiCPuMh_jJu z$0sXrQnbVwN!%DSHq&}@b^)VI#FziY{_@vwK76fj>P^(EwPxs3`52yQ1kIomu*n?- zi6FY}1E;{b{s@&(V`F_=BcSsE+@cvIK~Cio2o0w;$)tzId}Ivl6bUcRU0MY?}w6nq|s zfiEU8Zfs2Bg0%96XMpje;er$tXM-X)0ZEfk%w9Xv6UPD%zEz&bK#Ghg^sA~GA~eEP zUfSs!3PC?TBzNw9&)pP=E%-I?`A`<$*j+Z(n8qpiuO+r;(7qYXIxSI)@^&|(pNEG+ zUyDhW#&Q_lJX8vRk3;D#|HEl9y{ADin7Lf1gJddX{zXn-W0*Cnov>k+G%i@J&}%rz za;m*rxDavpa8r-Bb26x*%W9&m}Q9ytA5vw zhTbk0xEa8h#;I9~%2rd{Tudc{y!d9cf84D%610lfai-`%Yq39~sG%e_t67w!2OkTF zwCQQO^z?K>hA}aRX}g9F6jMX7ICBv9;Xbmt>_D7>x}Sh_(&nbrJZPA7_$oGYlG=iH z-|)$J;_6Gv6H+P3-O45!v!?GQPB@v$MBGJJj?QCZ@Kz8R*1`!bpJDA&KCIsGF?w`} z@JIgty2HDo)f#%bH{A}+o0Ykh^F0|61?oxIUa31I52v4LQ#q-kpuN!F-zD;&!VOmo zpe1vXNZf?m+W3?K|HB|UnKiU;IRQx)7Z4CX6*Bvni%pNhdj(fCq zjtsZ_#zk?~`JquVxM+D^M(-T_F54?u7BOtD{$;GaXL4dQGgimVS^X4|xyA0OT;=NQ zcB%9!qT?#x!r3Q6%4vvL2b&!xb`yk{`a?{sr*fsMQ9o{PjMCN18<-^4&g^32eOm<` z9|{KV6J)YLW&Q@deLXiLQSM^o{w{_8T-qu~t>bPxrgcT-2K~{#sLX~H5~-f5Hwk*Fu?>u;`F8Lej(gWPPu;J(Do8avMF}qi2Mue|H}LRu}9M@H^djCK8p#By-=+ zPTH~`_G>!Q5^N9}UvG@C2#paY4wBE^jy9zA3(Q!g%>gGeyga=DC|>iCO4hr0>u-<* zl!2EwxECBNt*84#+a5?HCeU2^pWkX>FxPQflYz;*-K{uEY&1=}E*@wY{D)NwQpG7Q zYnLK5S?}fRBIt(*HIm&xIxh0veHxOg z?7pak$~w!`T<{syOlk)HL2=wkKxC69db)!>iMS^K()Ece?dR}~J3+P0x~j7jpZ#|C zb~nN{)>Yv9_RAXDfHZs#=kt>xGx04S+gn3EXH^|UklVqqh?h!NRQGtA9V~QYnQ^S? zZ3n$4O=^16Ax!xDh18r>obLNTZ}zLc6rM}?k^}s#&zKbK4?lA`A|GYrRCYm}pPh+& zq4|^a12`>{wbogO<(>^Iw#Y26Sy;_e4sUqR1t8|+X{wYa3;1AVmJU#??q<%i#+&ah zakaiyu8e=hHYMU!Q%G(k7nCf}EOgNQ=bEnN@A~H{7XVwfcqQ|od`7~0NWz?kZUP1{I0!YJR2^2{hdg7VQQ4^)MHr7Aap$H{SbXWog# z%}=B_B&Vl)_#F|r-@$nyIl(4+3*S!EoHAE#5|}bg0=2|6Q2k7?)kL|ipO|nWVzw3~ zs53bEy-HIL@Z+hhZDywx{qcpvG=F9dk@GntJ$%w}VlS)g$_ z78w`iwVIXCb5fdxn(K}Qx#fAXYP)JHLM}Ek<7#vtn`P#2nte1E9VN!1{Lt$49Oe$_ z-ql8g;&fuC=de!eeB0uvW=71gvm<~dW+5ZA&b^k}m5lSi?FWEQsOx2%>>YVhJkEXP zQBQ+Yes!hfB`aD!WJA#7R?lRiv3Z3X`D#IXu_QZ7=n@EhTtXkgS?r5Z`kjuFm4Y$h zOf)q0Ygg*q6$-}rzvVW$IoXUD^0t-H;HK2A3}*#h<`R`2sLp&` zkDJDQ4{?w6$7SW8IA|$Nx06uHU)|ti-&Q5j^2Hmju8g&*qG%btBf{z#w5*bsyd`~R z^8<<_zm;=;OUX*9OCbGo2}j+g`JHxW;QvwNy7s@6a0nmw9X@Uu;x7EHgr7Nt>eUV( z^(qIeu6792O2=mOrKjaYy#@A}Pd>SC|Gs_qNx;*MWG(HG(e5Gz1?^g_>?doPbW7tc zdMgZVHwB9(JykEPNrR@?7K7rI<6LH~V2d~*25m>=YQv&!<2F~Xc)Edx)g`rA2pPuSDr zSR2dOnb`2wsm3|xsm8>n2=lZ&Wwj<#X_mBwgGbeEFPI2f0IR3_6;CY2t~4`H?+|{; z9%;zWxr7#*X8zK#Zt&oQp4JSs*$h10-=Lew@b3U~!7?7{(Uwc`rbqMdp0Gz5A`RnF zf)BaFj+Rlbabs6KdPjJ=cTUB}b|&BF;1p zH8ynU0>Z0N_X_DHlCTXa#^Rg^%_<^9r?v^g~n~1UJ+*9#$_f8IvC9^ z-DBWHY(hVvJW*xCM8q1v`Rt;;plTAo%3jrwi!eDyL-Y;V#_XKXYUUoMqj}j>^i#s^ zL^!l@(>B5`)hNvitMAFLbFF0yb%hy0yP##hMQPq&E!weS{zj9%J_)*KgRUQ4|!#L4|{ndq8qc6~MP(;|mhNwqN9?db} zy~r~P@Y@5YfNOTxLqpk--qeP1?1Zb12;&CM06K(KgAO^kbHy_dR4}N+tJhGSW}E_8 zn!R7I#M2i&&@5~t30v)fIZuEiMO&$u-xUeel$S>9ht?OZD_TDcu-j+B%!8rzwjDOD zvqaecf_WT<)@1|iW+zhQ?h2dMt2OSwoA$E2`10KQH~pK7OHYCPl! z1&4=u6G#_*Uaf1~Z2-Ewj{5uO=bumTbUzMVsO|!cl$NuqY+z#(&9;2Sh|@T=dLbvo zAS&Mj94VA?7`}1#mfS7*zSb+;ZoXjrUqWifyzB(XY>uj|!nkX}#1@3_^@&E%f z%I;t^h_iGLFwcH+;P&H_%OX_qLQZs2+xdn?QyqYN2F#ErVA3E>p!s%AKpd4<)>}@^f%ZIZcDUuxJRY2IZz~hYxCJ*Dmm)A!OX9BDn~?VVx=|P8QAGWa zk!)srMX6gk_9VUCz~8Q{o|U_mW7=lV(YXC@Y~=)Pa>!B3-Tt>B6;8-*VJed*NFX&o zK=Q7hqdiXVnTdZl@cv1Ud^bU@YrvmkMt|-QIDZukP1x7`4{&P&1A;FoMg##t@LyHh z&TFaPK33oi@(qNX4ZVX`VSxT5xZz5J{N?2JRqOqB*KuU?)yFV%u>x>3{C6pF3Xi*t z1wD5E-C<@%6R-<(i&Vk|>0s2;T&!<*=_cG-@$PRFj2hQZK}tVEQ%rThaJE?q8hHZ2 ze~}v;Y`ptIOtoNmm_7VAno{cj`iJ+(@bBycsIPT5y6ITz4u5zyWid^4l$-Wirfq7%PklCJ|;h%nTS_ z_8bzAZxd@h*ZsAdBo4+XOvl&AI|W_erqGeN0D7HdC>@P8{Af(a;(>R>*mFad$|K@O zUf|wB`%hA@=tskerD?+uP4b~oyiKBgQRaSQfo=BX%X!C6~wH`?mBx3kHdmV3~F2)`jWc0(1o+OOCD2z?z z6dcd^Nvt{40RQ`y)rygz!iF$P&e28GjxOB(glBAjdR6KeFQO| zM$CLS^+T?t-;XhOWQT*^cYW0{_BhR((R?alphHeki`LDN;T~;9O>2R!LpRprq(O5$ zPh_C2_VnFW>(i9yolOD^hx0AY=PdL)wYVdS-pI#D4;rsV${DXaQ2E-(yy}(I;G?`#G!7l1KOF9<Qw~ zHUwv=O1%#!xi<&5xDH_bTp`e?U)$H#@DlR!B&qCi1~JlFjTyBP80Xf!R4yc$N~MG( zOZE#o&I_oPKjZefiTes7{PY4~z=;zjE>^Oem!+5v>=BYs-u!5u(#oXmZuC!3S{`X7 zYVR!N>9+Jy+DzzL_HNMbs)l98njU_Q(iyl`>9Pa_Kwfci-fZ33IYAf|$?99CmCqSg<}PHLpRl4fP|LmN#u8Ev?cL32Z3H=mFV2z8t5PHfRkeH^>H2{ET%p#0;utXt4BVC3|PF#QBa+N!dQmq=o6voJ3E z0v+2k?XoBp#&w`@VjSqXGk_llk{yyJXlJUKl;F6RF$Ph+0X6zD9V=7Mv+>aFFO7m~Dvs zEk}B;uXU47a%pUnFy7}vbi-JT_|m8`#s+Y6O7C2{wnlT~+DX1A{D56CP{pBpGO3r& z&~fM!BkrKq$xGY-g$LU7;=N>xr#rNd>@0_#Y}OsmH5sIz@4O@0hgOdkF99y#kIh}z zm?%G&S}yNsmPc^HpV03GELIfyc7K5~PL4f$TPwSJr|xnK6F0=p#;NUrO{|8tDCDCK zG736aB_!hJALmr+u(jTPu%@f=oi|)E!GpR7Gr%2J4>J2wn$Cah8s5X~fPacmZ=*D# zbfNU5<0GXn9b5|ybn#Y>YI07;A4>bnzGr#pfq>)4qwo*g( zYveS8(tp_ zK$nD6`)pP05^fdcVJ)#W6>EumJtCUtQ{FsZ>(7G&atA#d8(2<;kF=*%6gItaGh?Z5 zTnc6<#u=5&|NO%S&&DlWF8es3QP5leezJ3r{T$OU4!E#X_Lxd)+=T3tR?vf+p}>bL zfsfvFTjFxu*yz1)O9H)KDht7BfiZWOB8^SDaJs`gn2UrGQkXbh!AN<@@cmLw~K2n|#Bb^(cmu7aPcr?**9Oe>zYd!dEF$MSw# ztRb=jx4UypvcP^7d!ehq80EUR_2PDb1Sh?Zp8Spjb@I9(#hg9;MK2B%m2Z*Ldh0D3 zoS*_?Gw#C+GgBN1dKca;AR7X;xmu7x(Ft&Zw+}a9b9e7qs>izL&uAw<{sHYoihTtW z=;=Or!VLNkKn>gjNlBbRBtgR(yL#e`;Zm{Mq%EzWYwc3prg&n^A*lhVSA^CVkgo^> zIh#Qg+vO77(|d3DkS4mD_ph2Q?&k5kdb?wR+UolH7l#y_^{0`F^#qB6mN9Z(cY?0V zDPDjHHU2Bk?N8Y1R#8d9x@ExA=jpnko?`5%a7ReFAs!MIVICjQ-Y?EeS26Hqh%*FZ zfZ*a?x(d^}>_ANZH(ag#JMPj`%Hv%4PE2p=>2B#!H^r7~8w9|;7PQ6kI9IcQK)NHF z;&03Vu0k?s=*7y2a(g(g!3k27mD5ScBrCEJu~WKue&Y%ff_a1ZGA; zjzVIP9JeI&0z>pPCpiw>E@+&0HD@>qHSkLv1<)` zCw@@t0T(IIcAT0lv8f?FV9ws`BmsCMUt-H;^V=t@we3^XYsQ_jwYWS2ZTqRo&~EP{ zC<_rV;~u;egwgGi4JFl@vrhrVFoQ(8S=TA(MiV!Cdv1FQ(YgpJY|n?5in{%h*_^!< z=_7tVYts_&dIOkoJ$AbDu0c3<*a*)hfiyh5$4>bm&pYJ(UkkYoe6Q4=j94mL3jSN0 z@#R<()7)vf2iovoATex#8>S%GPN~E+>)3#1`mUha2r7ZjzrCk*_G#(&;H!9-7A_0Y zW7~*rE$FW!Lnu`RTY=EGrah{1O}nOYfgPIZ#VsAmk`HVxstj$8HbZ;ZHd_}8X>N?L z$d{(5cCOK?aCccC{25(n`pz{Oz_8TOlqT3;b1`fNctDB{Ir-3~7J!4{!guJ|^SL@x zhn4_KI6!%}-ep-MI;)iww5KpE-sp>;($es!`ofwQCC(+<4uX@GSQ~xs=N8<2cl#}1 z6f}0oQ4ezGJ{v&|Pt~dP$82`3O7E?OwJ4RyW0o>0wN&KXU-0Ct|<^UYe}q4%hNu{MV8%bBR44>=~w7~qbkxX9)P!zVhLl= zu_8)M4NXbgWkGD(j=+nwfojlH)#~Q96S)Lb)H}E983Ue@h&G%^vNVjwl_Kt4KPU@& zX?d)Lx#$6`Z9T>Y$W1uk(@Si1E=ytEO(Hnvex_40uCC)$q2eNgHd&HMTPAIxSos#H zp|7v+V9DLq&mx@0qR%I{=hN1F_c`Bsb;Q4=(bZQVJ6qsLfm@zPAFnnzMt%Q3mOhdnE#(RD+ ze|+yao-Ku$i}e2Ly`p7{9v+jlXawxJ5PcQrISVWUx;L5iIQpu|yN%2b*T#Pi-U^ zK<#gluLAZdhOpFLFCYSHBOxJdD#PnT{hvyRh}s~&7&hI%NT~mXK;jGAbQKtaur2Ec z6B+E<=oli0ee$Cu;s?8J{wU%PoA{0=0kE49@B`Ba$x)i6j?>hTnvp)bEx~o-s1FV4RxIvSRUkDVdlxah!VIva&LD^om4v zWzn+vWmU`JmXhcyDJdNny+U0zKDj!&T3zI|=6S6}u`F7I z7THPwd5dZn`};*A&JEgsHw>+1JEx4&QCbYlNoZ@l)r zb?uWiFTAvCm^yBF`n{u4ho}Mv2!wvp2PV&a$e5p{TT)&$uWI>Yt2RFOlx5r2-Fq6| zvmJhWU)}3HPz(6syN;he_~?sIE`NRY90*`qvFy>+Q|_NTV`82@Gj#Akg%2x}N5+hZ z9X~E@>lRPFWIx#`SNCLtJ1uNfqv-a8S3Q~i^`U)SWfO!Pkvycx@>V# zab;O)zYo>z^)@d@-K`*!i7-=Oro+sH$$-g%L6vGF6s(qSXQLN0iL{dM{v_UKv_BF& z0}t)@pV0e^_Feic>GvnRi-yxQseRYb{!QI9J!_-&eq|p#J{%1K|&({{Htd5}>t7 zNiasGQu3ofT{wMW=G@FIeL-f{+`?%Y)3WAHpHw(=l0GX_jqT$9|1`T`+T5J1jLfX5 z%T|I&zi(Xh>b3d`|E@|B~O zPpJOlA~upxC#egJlx*2cma88ws;nsGYfC-3sAOT;@_!G{`8|B<3@_nJk(|D~XmJ(N zE`3lfm6DQjN@z8o7wUF4tzi73OVyM{-aO|ORa7EZoT;Nti}`Vq5ez}An!pd+tO#=q z@c@31kqRNC<3j@IR7QM+0hrs?@LfP8#+$^$NQl5!!cM^4HiS-l#1~4JQsSXq2lJZ; zbDKAPInwv*Pu~ye`y>4Tq#uCv75(WekbYo)`hiG42^h5g7M;4|3 z`>&+9xX3j3p$F&8hJ^J4_fMZzICV0A7+-yUpE@Q&@^n1pPOdXLFKTM;JP$~WR zPo|&oUwz zA8$Cj?*1K>%9DE+magh4zVp+WvZo8?Fu@lpMI|NU1Kc~linoeh313lB-(aPK`ds&Yr8?#nYrFKT;^y>+#+HFd?DD_LLoeR*l- z_~!j@C0~dcN4}Y2nex>q1B&dnLtO_WHKz~UzjND>F9O~;e)#3XY^=oUGq>@A{G*}Q zWercQUNRyuzkJ62K}8>oPn!4M=8Q`Zi{@n2I8jayER)qR(I^jyXpSMt8v);fOC>E_payS_ZT;ChAr_JzeG4c7T@+Yg(* zu1XSS{xC?8HaB0o@62ky%l9tznY=H99i~voPCTiWpNT$H{=k6^OVqyS<~6Gj1er5jNU!Pl?vhqZQ;h6(PpM|ZPcdWK$N%ZLN%BOC7 zMEl^t)~I_qG9aKV8&fA@TKD&-6Np-nGeNF4OeH?!+c zmF|w|Ect0q-GUX;nnmoJBHuj|M*DYcm@i(Ye1P~ok!RZ$yz20G?<6!lIyU@0`R?ah zw)&ko|HJ#gURoV_<)Z9d%h@M&-<@-D2QHT{UibBoe-1dYc6LnDt#2QxU-C%y`>JcR zBv$i+0MDoCqIq*<;Lp5V_I$-V#oSrX!lJA%DhE`5C$0UZ#qXx7d|9T4186f^(t z-2+VaiP;so7av)CU*3Y|cP`EP^1?jX6|FP9bxh$q$KL$M%SXRi^F?F!bX=QO?a8ABh^^5hV07|H`&7tC#c{&6(@ za2m#H@yGv|2<%M=tK~iTV+RokV6j>_`JZ4gA@>qi%X{!A974!s!fN5~gj)4Ll+ X)A#=FhWu{R^tGrg4>p#39QgkqC*?Zt literal 0 HcmV?d00001 diff --git a/boards/zeroone/x6/extras/zeroone_x6_bootloader.bin b/boards/zeroone/x6/extras/zeroone_x6_bootloader.bin new file mode 100644 index 0000000000000000000000000000000000000000..a4195a61fae0cb631867533474bbbdac5d9a4cb5 GIT binary patch literal 46752 zcmeFZdwf&%{XhObmt1p9I={kix7~4YW894?K1 zJ$zZW)n=vTtVRp*X7ti*AF$ccS|q)L4|U#(oV@utq)saXS*7yf`F5E_?tv^H z+OT8(-ix%QH}6EA*(D}plIyghLr*p6IftCOtZAr2m&MBYtUhPZcUrjz>NJBRP*aPPpqBQFWHb!VkGPAc7acMPio)>+>h3Hm|02g5KjNHdOyutbok?($Mk%yW4m7nB%?FE#t z)06)_1B4>3q_?iq!M|>t>Md?4ii&G@!_jaY>YcY zO!g}|i&mMFkcu_y@vl8bSDo3(?AvB%&+otbMD-;6b=4nz%bZ`8|Hat5Yms+H zuCCe0bj9YM|F@j?S(x)o{@=dI`T9DBT*nj?n-CLV40t4U2H+5|mpbG6*XqJsn`7^a z7cEj;ONN;3Vs;Sus*)`+yNP@@l-fds>5|1|5V^xvtmn&-xl65g$UIlypV|<`RC&No zbYJG7g$A@xjeXTHgRXO;S=T)4{QiKB&zv56jtjUP+|_bNoQn~-A$}m$MGP6;cTU%y z$yjL3&nSqGyeG2Gb;bYV>HHb}!m`NQe*Z>1jbB(DdAjU>VLJOssT{WIT9X#;h`hVt z*ExA}oQw070@J0qPWe@47HN{J_|=h=Tj=*EntOa2Cv6?@(#C&Ay0y6Cap`bneT92B z-Zj%v8H#BODuX!>;h@yO3MwBqm*PoFUCcWNnC;5{fwkk+~3RF`ZH}?hxdS4u{*e-&ihv}MB9ohrP(bof2b6BF&r!n8(I>lpT9(AvF9hb*u%QkG|AM< zuxT#EpVCae$v5u?`C=Vuu0elwVRXEwmFY81E9N^WEhOLBm#-U{A|mGvW*j8iKd)hO zw9Q&Cn-l9zYw0j)*Ah8XAqH)0>{`xA>x^BSW?4Wa610< zC!0P=o=#M;iK&yO2xiiDs2>=jnK?>iUSZxLt7N+|EIPk6$4`eK4i-(SCy z6lNa5bs)g7|0zA=lALMI(R6t(Dw+Fn9SE3Nb58K=r^<_;mGd6B};v*DW7 z?YXEY`*9hO%10`nWFS?8R1KMkl!BB(l4*)TiWx^!98#Q?rZh-tIGRdCDzWvVoXLW| zkQ^ZE*6TfFZu`$q(Q*HO8J{_4P8S^`+RQX4?7Y(66vwLmOh;*NYQg>enFXc2;}<;8 zpShs4cY^p}f2LU4JF!se&nztM)fZLvXBL(APAYz=KeM>BH?5?qKeME?H{H3qKhsJ3 zU)r0o5OsbOowJY6((&*)zwDy(b-gWmKM>&AxBb`0_y4pSd`|dU%^_Nzt{eI)T(2j( zjy#J!Ner<>YsIB)X5=}e40Z`mA*-3lB?|rD7$!LmuTEwXIdQI+xs6kpbS5YN6S;YQ zFEjPmn%A2wUiLOYVOMZD`cLlFEa+8<6WUTUQ$>fuSD8evkB`^nq@1~+T`OxenhQ~_{`(SnpvTYU{OyeFXL3I9O{!+PNlwUD zU8rfM_!7MUwp=%e)tFD@Ns3AY7bd4Er81+P`Gk6M{2c8N-=Aq$dw-y05xwX8N|u%L z>@H;T_~`*3=C+QGja7)GZOv>3O@EchQ-+B7wKjG)F{lpzNZ~{I&9qj7$mGSyx?x7% zF&r~J=p!@uF14ZcV!n-$|L5KOR=StN)^PA*ILoLiijltpe>qNJj9gLcMJ@7_zeC#c zu!q+Y9+M5)Q^d$sco!4T5{j>HU&siz-?hWU2iB`C)%DH9XaJU35atBE>DFT5Csy%R z=dGnDFR60XLQg#}|8Qtdu|fQviPa{su?+R75FP%Dw|8C1!CR5F}#9wL7^nvOdoza2`8+@~mvd?CchuZ{5X)*)VqDWWC*I;x74 zoU5oKcgG+jKRi0@&y`k?Cg7;Uz)@uyl64aE^5Hn5eFe`hJWIG1;<^`C5v~OpM0<5A z(Y`;0;$V`+%ZrCpPTRF7?5m9Ac^>_}W7r^498B6iYb09TYteivC+N`1(Xl)Q-{c7- z5Ul}uervAA+Qy4%XMlU32JZb9SCY{Z4yr~>qGqAC=vtFanPVe;?-RT0Y0wF*Ve49X zJPBbOA0`s*X7uy7W^Hr)nV6Eriq*Qp!}hhai>2L#YG;~+%cX54CYAG=KTV`%X#VSC zrRBAhx48lSzXkX|9LyWFpuY*uTbp@tvII!WB_`%o&cN&O71g z9Go`Fii~K+y9Y-Ax$?Z;ca^#4r8FU0?ax7Op(ab;%z@FA`Dr_eV$|R;?1PNPndmBkkp* z57rj?=E4Zw5!_+9Ra4FgBoMD*UafyPU*zQ9gc;H5sd&7{L(7DNN5T`knY|?E>e+-m zW;Qq;d0jXkHM}>XZ(&}gC7upbnTa_|%vZbye0fu$EqF$V;jjL7N$07Tw%G}=0+AGd z__E5GE?GRPl4L2lC2c!1J8d)FaiopT0i}y6PF-`Fblj7Sdjc1zNVDT#B$a5wV#ol!vX*GdhbE~`OS&Wc&t%1cFDn!{hq#U z95{Q{qVfJgs+acKIqzCIo@lzwqN7T1)mK%xPE-*?qbncK!~mLTT~-g*kj^t5;MLr; z=M>JW3w6!m;FT~xMRj(Sos;hzrJuIM`3RA zkXP4Ad-6VdqK@=rXe81T@Px!L>{ps6ij$mb?5fF9ICxt)(Nnd0o~y$Xfo@Y|o;N-6 zCguA#LF!;{PV#a$r+S&2Q+*GuHcGJ$lJ(H4t_bH(K&{R#WckYrjeQ ziuR1Zj6Fo>O7FBbPnMoK91il~)vGDQ-!l5SgST z2lomm*NrlJXzmmWuO4PHO|J#i6ZvL^1FU`F3kUl^2R|KaC%?HqI>RQn0n!J?;2s+T zIO&JhdrXgSwX1zxz`$5rw1C*xNBC}om?Z`L9N;uM+XgWobH_bdABDMZNnqej<@-jW zaHeZzE%81IncrPeRdKJMv3v#UrNjPw^%!aEh$mTp!9^(*lSTIwC!0nMEli#Plqw1( z`H+byl^iF=)bL{Vkpe3x>qZ%~My#dnQ0(`u{sf~{pphI{{i+`$n*UoPEHyzwA_RHxDjGL<+Vr-SCv%nLajG|Z634zRTC$l z7^bj%%zxu?*nqn^`HSI5PtBb^oq>}lgowG(i~Y6kV}Cg4AIYxSFA;gph*~7(>0X;u zbcDz@^uXy|haNOZn_T_UJ~iKwUBd|5Y$=X*0ei)3dk>SOYVFbR0_<1i0iB(qubBKy4h#g8wMyc983WR2lqd*n+>Ge7p0n1E%% zlyjMJslV{)jSZqod`_GtW{T$(^L`@t4DwTM>q5ISrzWy_h@TSQ^^9k+I2U`Ik)Om@ z6~2OABb9RYhaQ^lA2fE)78gZw98mZv|2TWFidX{PS&=v61~2>L_7#hHi(KW{Wk-6Q>j3nu;HfAa_H`}&E zF&^gn>Jp9xNa9T2Uln2tH+|vyGis#ynSIxqex+Cq%S6sFZ9SFp9#{{Kcy7-&L9XCZ z9DJaF?Wqq3TfymVRx%DV^6i7+pc0yhJ;=#1Azl!E5)P8#r6L!BNoEdXeZ!vwC@1mb zoW&%`l_sIzgzY=^$UA*26ZtM+J>>(m{=C0TnNH#ZOne%+C+4?~(ExT-DBNoS5^r?zbo_lO#iWQ`Y#MZIY~@b8}CBJmkzJFxin zVKL*bW79=8FJDymZDzn%C~C-!o3+GT;3a+9*jEBt?Gcf`qaEUK5k|9am=_Nh6hkU0 z!&A}lJq2eLr2B}WMB(G#mKIn3z!e>%?FyrZ)B~#S^>XskVaEDomAc^9_6et$yn+P* z-&$EsF8Q4bU;2H8&(w;{bDX?jxK3pD7{r(W6T``A!wU<%fc531lR`W><#&J=)m_)c zeT!-^afG_D8%1=;UhwcMfml6Mz z$`bh}EqH6vHhqqL%ugLX{^el8CDT$Yu{ zpB$@h#%d1itY+oU!o1iH-f(V6HH8OWVdW3PX0f`J4@@UVA8~hZxu|_&_Wn zQ#twaAmw@DRK0%hC3be2i!m*Kq`EM_d9$Pv^E?%p0sa$aUd1CsI0!zH_A5O^{})GQ zBnLeGbi&ICk(%GZKP&$%e9;g7`WR@$vG8Rg@Fje)UCGrkxxcdv`9_1cy-Vejs9a)3 zZ(mc0nLBHA zt^F{334Eb@8o7yT&a6WfYtmap8 zt@RPO4F}u4ktil8|CA`k=HgrOFb8f!?PFHQMcR*Z6Mm(s5)_NIw<-}IEE* z7|Inr^=&CK^`Yr4(b;EqQ!T#naR!pdtxA@31^Z_l^vE_(IQWY4a%HMV*l^I!LFVuP z=j69$Nmn7qCPPk5mmHp?B36DX+})ysE=gx&<&ABTx&98vt||JwiIuCv)JkJ+(PPX9 zMzkJqxsU2vDIa*f?~p-$`k!PF%v1O}Z2rHKL0I`g!2I>P>3$-Cg(|x5E#WfYhkGLF zsp0$0>L9tXeJ8l3HSG=pDID6l+&D`B)Tg>|A!uEG^Hb7t*uc_gZc=BT z6v?d$n904;I}us#yW9}{N>}5q$ZA06&`s<7yU$OhlpDx0bhiE}B?5<_UGU^WT+$qo2GheS1mKUOk}nY=Zw1nGSx-aVy-!o$}i)4Q!=E-2|9 zX|bN^oFvU^IbcscH%ZEFc{wem__ALw#)-1OL1GJ{sf3bjlSN%3ULZl#Z`;Qf$FqmqS|MYKOkA&mS$zQz~D2F+}Wv*BT z8u*J5UcA3$!ZBjF;wP2?UmWz#0dF|CaFm$8@_p%_D=tN@d81bBB*ygqB_gokSHAR5 z_f){n*(g=HdZcT9yf1jo)#aZfK`!v+K+>V5z6ad@R12Bz1rHe;&@-&;2agZ_BK+Te zVv6ROKKhlvgYL$9NUd>X7onUfDABetN@T$NUl=C)c<>g~(pTo8HEAG6G!EbIS|>HS zjz~SO-}uY0L)4+vV#=q{+EB}uXf0d7n~*>mYYm$-}`HW=AT=?fnFD@}I*Dc#j)t zlGtpUyxW~RP+fYmpSwNPYtWR+iCSmd?*dvbSIjaP4Eso#qUzQTaZ3CU*MD=bHo?)G zz&RF`_KI3gFiTuEH>B-1^m1fvFPFd|?dT<(#kJPU57=_ik2_a;(Yrh2+gJlJ^hsn$ zD<|}FoZfNK^$z4xoll@`#(byE_87D`9XTC~il#7T=NZ&jftuD9p+4K%LT}?$_v&*2 z!a4flxlTpfPW!=_6MEwlV6Td&y^J4H46jSGiKWJ*uQmUXJJA zB#Dp;4i~89cy))O&GXnaL+Were&D9SLqxkOs$HWPP^o8)Kk{?N6@Fq|=BE;FE%^3d z`WeFuet2{ES)tX>3CH{b+W1QZCw(4SyY{AVFtaUuIl9&fXS8&!txG&!vh5 z2q`P+F6OzJ5-*P^%pOoV;0SSa9Iem8%bG!h<788wCl(f&9M5eJ=19qFVcmj-!Xjw` z)nwAz2u6dv_xlJ>LG}5RZ-VZ(Dju{iN!-^$=|)g_rQ(&U!yabR#R{XWVPeuMD~SBL z(zlHm;0d#&uRg!kQPpU_?1ha)q1qR}?*i5!Y`x--S*UFms3!RawjN&o!=NDPVby09 zIvz%345XQSO0AHv`7A|%56lR6&WiXCzXBORR&Mbwl1FOWaTFnXjU+u z9`yC(rG(sy3TkW6%&M>AMT}eZq{mTp(4O$giK-ltfPR7FQZ7_+Vot$@ij`H1(^ppL z!OIdM1c?p$FT*79`e?$JspTzh;WTh_TSv^Ge9SlfoITdhYV=b**3WA2dFQ{e-&A8g z)Z#cXRTMn$ZDVAP2?t*aPcJZwS+a&NPyf@UgzrC$6-fuxtRC|PiYX>L$-a6!bNZj2 zKinq-K0jpFl`-#~0mwzve`iPY$;tJHXU$C|KJ~!+52zk2Z_xv?ZCCyw?7#94Lq!E< zb4+Ufu+3K0VagWw2RgX!Dt&?B!O>ue(oIT)zg|+hgfi^G){2zBF(^DUh~xHf>>Jpo1L0 zl$K&}b(kiJBS9uCNL-);J}b#3f^F!>Z(dgtnn;t$U!u#H@YqftOIu@Zd=B z(x|XDnqOT)+okzw%fi~vBlL~J&{8sW`I2$KwkW{^E%l=LV{hwRb@c7S(>$k@7hUw5`{6oQjss<^pEsqsDCZ=% zzSnPOjdCJmLr-G(nD`_|i=WNbwxNxcC;Ugy6VKJ|wRnc7;z_{F=%w)2jy3hlVR+~{ z*3i24tgJ4)o<39A-rtTd;LX=`D6c`fpE}&39JRIw45Z#3@6EJyC~q0O_j2&aiEYD9 zRgM~PjoITUzZjX(r@lL*X{$?Gmao38<+SoLY8?vcfZd>J`-WqzZe9RbBGaBe+!@L7 zY3O&WI?+4kRr+j(w_IZtyGvND+NE)Re2Ke-$W5VKF-PQ!qxoAxR9{ZoY#Mol` z_2ebp91CS;=F30h_;@0Uzs;RXZiIG0n>F5(^=Y0C?kgePNr90!FB=-32M|Me^Y-Oz3f{$3(vmMHdx_~DIHS4`817u@r8v{OfGg{mw>BJNL z?v%}n8|kjZ%}O2Q(GLetDw_$lf^Qn_@FSnDH$shHrLx$X=amLB5O~)-6_w3mj`w#a(E};^Efpt2DvRvAa+Z^&+g; z#=%GnQHUBIx(-qLG<_T819i1pcZ!45uq$0hbdJUsj&5 zGTsCsWhKpj3i~rv{0QF;;C+``)2S2UR-OXH>dHrh+w_l?|{iCe^v8rck{htc=(F zK#{ZTWz=nvgn={bsQ;}6>$RiophPj~L044&7ujLDbmt!6Z$Lm&TG2@G6vn^9kb->U zxD=Fmo`i!>z$UdD_s4L5k!Yc*c^Iizzzap^Y$?jn-IxGf+ezg$YlpHw@{R7L5`3d~ z68ZMB6>wKZY!?gIrPgNV@n>LxDp*6Zi+pr!lU$J=8SZfIjrJ&c9(uF|HPBux!=3ix z`?yDYQHInG1BKQl80Sxy#CV|NUb4hx7U}yL&Lk<$M#n(&{8YCKdAcj;_#M6TD|WfU z!MjK3w-m`ClO+y$GR8{;%$k(}ly0D-AZ6g}mjNzcCdf(L&=Y8_BS9P5eTBfkU3L!Q zePqvO|{D?2eE_bF1|i5 z+`I5;Q88p0;C5qkT(JcE*7-0IV(!WiVVOvu>$xw(nk$LVDlynKdx2-5;eZbp4-E4G z_|FbplPsv{-5^)3v?> zpM70(`z1DczNB5Kl?-+peAhMD%lfu>LEDxpq`+$yk{6ycglm4n@Wdf4mE29$g$i)1 zO&SM}8czB|b9+Zc&7G#tYT|Fov~b`Q*dgYMu^2rt#2YjrE@g#uyevnmfX#cQR3)8u zJ;HIFIhDYIQc8JFWd-cvYRDhu@XLYM`)t~(dZ7E^m6GSGd*hNyK|aRm+Z?EONqM;x zUlJ#!+2WkJutmqYl-5-@!5_#t5?nJ_0nWKg)6&TpMuI;bWbVA?JL0Ef%p@tJ-QfWy zzj=Qkol{$~&U7^~rueM%V&1}s*eiK$WGX+k;a+`#-pTb5ouh`1fe&#>Cu;IBizU*l zOFywO@|_F=DW|cl9$KE`(3Vh*_nqc(-u;0hj<>L=l{KCA?+@GqpBL4c()<%m@SZkl zgbyL7r-*-w^yM-`^$K!f(n2yVskBti(7q%#i7|a@;6}3FB<`>IQ4Mp83LK_3q`La# zq-D}bFnh!xKDkVnx4SS^Nr)c_-ZiAV`3vg7_Y7&H^=-fWxrGrnzqdo_P9^H>nNrX~^S~?#?K9(axR&N1m(c&SWMk>UJvGW%`(`f$x9VL^+OS z8EM|cVy2Hvi8nGKmFanDy=PfXd(+OE`z5x|$DV3>j!+vQG>KQ;kCaPgWqMI=WpYnJ zx*7ycr*lsGWo<5~i8m&fK>FaA5NCQ$D);QFxl7{uI>4=WHSI+$f{nfEURNT$SQe2B zzQg$t6K1uV@>13)ydHJbWMpA|Sk8&H%cZu)eUiSA&O!Cjf|`tJXidc}REJarpGz-` z)$h0>-%!d#S9OVlDLK6~nji0sv?kWcpr-UneIaS1^+0|QnM!zyc$}47IoIMSCxWxQ zqSjD*qQ6~bXz7;723P+HuHvze;1g0(x4W>S_WsCoek=7-YnNh0w}+FCD);Hgb4Kx3 z5+9h%y;4Z+NWumO@R6{d>crQ|Jh=v)l-$hM792?tS25#DzgTuNKfdD)F6Hi`wgs~L z{+n&N4o7dDgON)ahwNSgeCOy{}gtmBi3Ca))Ufj@qpaUFr{OsC2?~!e6Q_9DEjZ zdwwlj`;oe|*PgtvP3w$tZqcL^Ksp;B$wd)FRpQpJo`H4wJ`~ zt1pmSv&Bn(?&{8Uu(IZAEMNMfntx&lfH!FOv|P7|A!>utSz4NU^Ehi`00ksPUqHQK z-rEr8II%uz2ZG-cVtTaD6pf>r0n7upp}c=S$E~NM0d(KMH%MFLRrvh*9sw4k0J-7Bf!Aj%AMC z_Z)G>M0VLY$F4;}?Fwf3QoGFCm!l3E%Te)|P)jUleN`LOrj`Agl&bZBR;;&%0tO1a9JRQaKr>15^& z`8dOHaOt~rPHf{iVv`L-Ribw4%9AR${7a5P=wYts$#3R>ImU?&kE6B=oE@okLqfk0 z7An(W)1m$`gZ}J@N8w*a1^{VTxf}Sot(E_a`5fA)Gf@i)_`&LCM=dY@U445eSNpx< z70imIlli<(l)izMo~>QXELkc5Q#j-ujwNNeC0y+?hV65t=q0yixO3amubL=)Z7VZG zdbcZVsI?R`CSZ^JO*Yt0ds&WR5ZVjqw!@Ui1WdNx7|JH!)d@%fURw7)?lhgQ33Zxk zV+|9FuQmO9Plkh@5urA@gf*^U4C0=$Xi0YkEorLlM4N0t$1tX?Hrh7r$NP8}4&D={ z@c9m1N8lMP#Wh$H3M*P%aIy#u&6qzf#=;E(16Z+@T=59o%d{sbi18U1CbYj`>HM(wtDK!5+J>C9c+r^`tw4tfV{RfynMsTKgN)Tb$S@HqQCj>@8Ot z{$SUhuBct6R&~JkZjAa6{NbI7+Sk+8_CK9MW>h>Dd%maPpj~rL@5_y7*6A*@VV4| zbV+TBtmP*AQY)S1x3|zIUVZ!$pA-WN2iILzIlo*lE-H`OZmJ;(>G&j(gEi&;uvP4b zMfA`Jl@k*Qji(}HOE|BD7${G53Q#nAA?5dvBNYzbG}24~`rhztVjN#YV??3NPDWIgInIQ5H#4veqDG0?G%&gn*v4!#30sAM zYRDu!Cv0K`0bU)q4BLRsHAUfIC1eNr`;A` zO!pe#*MYs5vZQPn_0hZ$y=-KM(G}GK9w3oL>Zkk1UdxH6)J#V>=xt+b)kTY$q@~dM zBqhO*ZFwz?%U%9h1V^F|{|Q@VLq1FzzHT`W2Rp-xAL}vSv4Q$h%ACPslQ+4^)t!&7 zl|_ci`>RK2iVwIT-90e!Jm!(o{mr;Pk6DhUAGczzu$Jkn^l^>>+Y(_@#ZOaYSE97R7_uI%zKe6>Xi0dcgyTS87QhEQ(3E1Wn)v$rHrM>ms!Zuef|^ zi@6Evv|??l4cPTJ!*?nie0}6uSTQ#aI1e!>Rdk3GSN8KM!g|?1Z9}zYpeWlJD#~i_rXfGaUlE#gK-bP@$Q$V4U6zK_y%op z;EiaD@*CITa%7O0Hx68W!?-ovq$!EDWqRxb>?5X47rulR^pPR|bvhA}!{Hzk2i;S-#7^XuxX#z2-aOv+hbCqx$+5}P>+lXaca-cy ze1uI-t|QZv&u%MWjN9*`Skx?D$D+f*n@2861`i9r%2-dfxTDahitVf~{vd)`(<^C2 z88L1w8V;t7Tu?9Te8M^TAr&lyEdh1n;&ZA2Ik_of?fgYuQ^eZ2A9wf61-|$DW5<&j z^Sz%c?R6Q`)S;NC|EA#=khw+jDw;k zFqymp-J~rpb7)(Dc`h8hHuT%RIN*}chkgMZ!kY5Mhd@Q2M*7JJ{e5yhv*-7a#z2!t zG6XIZ(?GHKTI8WPyv&(lCvs(7ICyq=%xC21XEaQwPD*mE&>Chh^^=>#yZSZraYjIC zZ{eh63TMDd<+HtQhc3Co^koH7tjXfnV-U) zra|u*75tt4I8+4*f%3h2nN8%ptdLVeYtYNu#5iwNWYh-u^H7ZW!x61uihO-cs|hfg zKl*h3MWO(z@rpw0G$5*S6ZaDKF>M7jZ0JKoUr@;R`Z5e86f3LxNbFhkC-&-#Pt0!F ztEjBBPg`+s^V9uLjOGGnM>yzK=r?9JogM0bN^^vRR|jA7pVyGi=!|^+CFQ#)jiR)P z(kY^I6H22#RX(VL);Q)<<>X7Rz$1;>cSiGHomGhQEKWbA=<>mJNQ`NP5?jp<#ax+f zXLnM~j+@K0O$2OnyYjv4z8?>5xsqX=*2}4XL?!b@i1C&f!8OaN#A0?y&fSsuEwhY^ z%*^u83&6M6=XBgRbDFc^IY>VXi`MopNItj$a+V(Rkw9?=BUdx?dlQl%ap`l`A6$Q% zhV9e}wDu4<_W2ldI5;z;i@eEKCv=)9kf^e!&+KYm)@F9(l*nZISUVV-nLn!ex-`zviXi;Wiq`$+mxhwX8(3Lpb-*`=--ya9u%AF)dF9JVcWI5Pz<5CWlY=h|jz_GP zwyRl5hn~A?1I3&ao?iH}Y6ELh{Ehs^tEXR&D*@J$sdVC=MueyYO*wcfL4z*~MR~h~yC7>w+2RV+8kK|oJ?Eo_&zpvW z=&O;=;C+f#ycDrAQM*dC4a;2@C90kNAbexlgcwcOA@h|-4e?_3Bg4TLkur)VaX7d! zG}#$8P|odI6C&zkaK+*55ZukU7vWxnyM()hdjswbxW9t?E4Y7v`v-B*pu51~f$vMj zm4_<>m);DU0iw6gC{-I)0otn8(~)2AGo9O?mng6p#ODh#SqIq13dCby#OE(#LY-TR zY&VSr&y6-f5B^Ey|8Jwu+zlIH_!&fW4m?6_&BMVz4sI@HMNR}C8*f)!>5OQ1jhc?H zXCEb|_z;_#k$c~&N%!-C8WngFTLC!e)zuwM%e;4tC9Aw$u_k3$-HO5JR^pA&;3hMwC!jXW*AmL#_P9oayP&rq_u*ub ze7Xt(AQ#X1^w|+PO@!pb1}0Rj1h>RBt}KSGo}WekwUPh$$iFV~pBnks17{{Gqrs6d z)r{gSlcizfNhNjZ%_S$5yrm~WEoa~?lZ>T$$&gFTM?rmn{|pYr5bscQ_c|1P#xA?; zn~F0R!iKEk44P|tBv%2+Lav3#H66L)w;|U=XKK;jateFPUCS!dN{sTx`Nn|_46gY` zIm{pu(73#Oe97MOI@4Z^^|Mjv&juf*o-MXe@b1W&AaSp0Nj$FDH)6;=uY*^`p3BGm zL-4Q^#;Crco62MK0T#~;3P zZ;`fteNJ!r_vh-dXC>mxI{}u-<%%kh$(2ign53O5fbuZY=*d2f0iDL1&J^hKPhMgs z(z$v`y4%$l&@v818-F06C3m^Hangrf(cZg6(cXSR%5^MpQ6Ea`g{j!k$G4b3B6r~G zfk$Yq)y?6);7o;s=dFPySNA`BAfO|A%XPDLxo66^!vC4Z z_GlC{cKs}1k>5um4ygYpkw0vK%>;498HgoV=z&M6e0Gr8eceZvYG{Xp55i|Q9#KKV zK^AdyfM4q2Cyy!|d@1|S1^ouGHxg&Y!p|nIWh8j|t?I(4-;7GsO7UoWykgH#^|8sI zzvB;93Z6+)lE)y`*;S{Xcb!B`1Lrvh|AjPhA7TLyUv(#HPH{2NtXs$#_~KeuXb1ht z&<94NwO<9U`(1c<#MAG)HtkNuX6$M*x!zZ7^Qp$Xy7eCD#9qc+Q*N#R>3cB4f7X{t zf6}CMe6;k`C03nMaM-2w{7w3kD_O$VcwIpO{+CPeGhkWAa#xy2>-Z>bsno8~b)3G$ z>grrEo-@)1u1S&n+5)|6k;KRh!#EbXCPipx9p;!uP=|x-q32K|UK-fB{=5ApCNFy0 z1&m`e(*Ba^b0JI2@oEASRa50e)gk-LGt`S|Mz|UCGW!&z0&Bu*SZFp^4tq>eqx1)R z_UQ}KE?1oAf^^m;NK4Zb&GDZI1?7`mi|%qwbzL8aRb1{02j_$B03ke<}CR7 zDy>tYA+U>Fq*U2*U>(ZbKLy3i@bw=F*GR zg|V=~E%rDgHG}tJ$G1(Aid>9~bw$6^zBwg_D;6=~(f;XOA=qjh=rQL?X`%j))rHhw zvbxX}0f<&f+LBKuei344>EX?(DQVZEO>TYw z)V`J1iTY+n%g~tY{;^mN#Mp%Y8OxEG{Tuio zP`dyp#X0u2ap+yN%)frw_HSS4Y|&ZG%>Gpykv;$hVxR}2eWN^$6*k~^aJGeEGMPqX z6HS8$KWg;<(6K9+T5lVXCNj; zEq;agAO|oIP8G0xuj_Cm?``mkeOXxzDE~+0QM)FB!;UGJD=RBkrBR5rJoKV{n(vnM z*`iUDu={kNzvIrnpoq{vu#huEaO|&*^3p0hZSmL2=YGE6mb63m zJG_0B%QJe*Qx(RNRt@WJ)RlHOKJ%^?zHf{P{xHTo)I5XI z$T^6d3gnY7;LlZ5j6fm)*^8QBRya>u?ZWY48^?%<51w z7X26EBW#57ZhT-n?k90SGv*ogZX1oK(#`|L1zr9l@JTq>G~5GyIgQ324&IL54Rz^& zpVQw39Wzpz&6u=Srp|$VejZ-elpCRa&qm+rx-s%!MpR-CED6cbA88RuJRF>)a8opA z!@-H8oWxtMdbeBpy({dN7Do8O#dHf>nOtF0HM~1$>DNc_Y)QbbL}?;yqAm8ghJ#&* zlvbfFs@?6!`3S-$U8{WxJ(~u$hdYU75GONmB0Newu?1R0y)f1th;<<*gP2ww)2&mO zg*eB>Nnp*lr7`)yEh65{BbJa4Iu9{TWO9>gNcNCVmqxvy*aBX3PT67CdQ%i86KB|@ zlkA``IV}`?1D-F`7L))E#M*rN61itPaLD`R_2BH?ODN@>ZLj3ABSBghlIUKwS37q=T5}|aU>k+n?#aS_w_t@|Td>n8gepnRXQ^!2lRfV%` z_7HQ>OP^O%(TH80O^@Cyr3siHRIQ3Ahrwsad2rte2i4;PTUXYifxNWRR^2 zdpH!lFcLXiz|40=XY|g2(nHbI#(~9$uvUCoWNrHVG~d70e;eMH@$>2W@!yMRx~b2d zDxlZeuwrkH@KcOkeKo`~*LO2~IVQ+q^{qJN!%D~a%(qXPusj}as%o*UF@wqjihz%( zr-ltHPz_xy-EH*SzQ{Mr8t&{0$qdN4?C*Lg&O=icKp?(X?k=R|Zm#}}_L=`X{wMNX zIISiDd@;@xf+YAucuH(XyvYGbWqOW!&osK6;Cc;}u&)g>IQN4+XTT233mvjw^ij`n z>?B9Mlpu~5@2%tmQzD})9MMdy1s0W9A}m(;6=X)9FAb;Y7-9+(!NvF0b4B91 z@=&mRq+cq*5mwj~J zI)?J8m6c@kfvscNt)@?{EnJ`;^B>3qeZs0eW2u}7?0g3C zE#tCPzBG-hgVM15BbWTK*@M0mIScx}aS^@7FGgaGvLCVc29HSBdXsF^?yLHs->u(W zNHG%Q%M*p}f2}VT^~HABBfNG4piS2m69~_}h?)l?H8Z|g7_I*&$Z_qgX908S zcYQJZL)#Bx4d^__cr6h;_AgKbJVwWwJM>~irlE5NsY*-FKA@0YJgk~BhV4b403?rXU`t6SHpEab``-Jf2>Iad3cn-9G9=2iQ~TfDX_F}c6C-;KKl z_t=PM@Xxz<7wQ6&63=;wnaIC!Khq6JulugQy6I;<&qiS<_FT`irk|yQe(X#8bL3PT z3wVpFZqv`Yk>lv#Y%6I>PLt`5xj{V#wpWa;CwH!5`vFkov;G6yU3dp22v^*k#)jXA@qJW1HA;34i{X7Fb! zwi`siY|s&o`ojFuZ@;2@nCdk*j8?ZmdpConC(w{VeJ5nc`HC|5#DJrOxY z;J4wA{f^2MjF$Dr7CZ+DnevJCm}~xgTn%U8ylJ?YSpk16-fM6na(*f=&J1P^F?nXR{f=i(wj_cKD>8v)sDi(2)&{w z4D7WxZYJk`znPiySHD6}sG0x%v*f13fNUN-`D-~*@aUdk+8*dW(%=l)bEBhqU8B)jT_dUd^4owK?60iB_o6+DyBVT~`Q%dP+MGfLaak2=` zUrrgR!_N5}X9<0;i`p<3iF;ttd#f!rpkY4LZL@C^W6m+Nim;B)L1V$4rTov6qvr0j zh>eUz)YT^n-%kBhm$uz&zgMvsN_)4#bBj;jB^j90EwF{S`M!^6F2jnl&We=H=*;QZD+;<`|{cI>$ zff-2bS||1Ds4w#p>Mh)-8h?lDpp@&eK-)GCeGFr!=~`&{YrvebJUvxP%MbYF=BIE9 z7m@#KScTd79%TL0E;4;w*TI^js6FQF1zi=Q`!wh)t(8x0lyVVc9}502R$WU};9Lc9 z4d}E^qnEU~OB6n1ws_3W9iJdx^XahW25~4j0g-p1;JYId+Q}XK9GZo2@Whx7X*8Jd zFDDEVdBs~{#GE89B=R4iL#Tib0k~xgbhNob9gU_R3JyR^tT{UxyfQ*0-V9BGxgX~U z5;IQm5$<;hb$xywuukRREhDi-+!h8W+(FM&M=6K{Gl7`-h!#O>8x4A)Md0eFPM(&* zc@@wa=tao;mYf!no?#sg-Z88P2QV|IA36e@9>FoULx(dnxdr;b>MQ=4IYVCP6f6VK z<8ZKk{XKkL$G`ay(WXXpm6Q{jAf~w3nufz9XMy)wCBuqy6gcJ;L>}dSjFVQ0yb$v~ z=PdJ^^Ov}L=!ulKC|r$O%ok5X2YobL1nD!5SMSz(MuT5KQqe~6&mEpB2|7cEsWwXK6f-GsSB-5oZHfXL)93E4~zw znLVjyX7-SmYUY$?4sGX_l{P9-=FWbxTZSIQijCU%(UF$Bhzjb z7q*zhwV*3G<%qB6-@n8@rU%sVfr*TR>S_K5Gdq)dz$f}*Ju`DALNohbn5#MF>DfZ< zxSS=`+bB&FNmg993Ex@o^9xj`FML9>Xq_hUw7){SNz4%8(IS3~iwJ+l2;!n~#oUK} zI_F;SdvxA${u=sS>&dIk@T`*JJ^KrJ>;xirK`Vy7<)Ux72Ivd(a7wD~C@;ON(RS8L zD?I6yPEVIKFM?C`h4c)~C|0G=K8Q2e;-NEG=HXtYXQdLzv&>%DYIj2q7CCW^axFs< z`0o7%zJERZPaP>eeN8=O3nEH)i$CfD6v^2k#NFSlKhL~Mb>y+5IIXFR*|%G=Va*v8 zr9O9fiGZ`gtaH1I(f>V)4sz80sqWk3n=10Y=bW6}+CW1KSW1DUX`yXeNH0PWlr&A# zLeV04DWYpiK~q2o7ZoqNq)@ehtCg~Dxu_thh`LJ(-K8KFMO`oJvkAy(LM{3ce?x#VaMBxtv{yP3$AiH&!O}DcXqm0A_Ef^+1<~@VwTyDxx9tu9ntc+E;~|xG97} zx~s~6mUdc@^E;wFa%_DZMpukSR{50s3vfWUI##%c0E=sorxkmip+IS&_v|d9@xIJ2 z$5kXuXEM31X5S{fEtWRV6YE#Rfc~!F_HZu^ZPsqXN#hB{%kj;S8K}jqwtsbje+X!Q z4}qQxoV*dO{A+h&4o9$$2DK)1vSk=~Z_=#LdgNP(T6`By!h&tcX=cc?y<-mtpAReQ z9hl`ET~TeJ{yCxbPN__Ea5~jUH4?39_s|*h zgb!<5mk;kpE)b^LFyT9C=lkrwK{%5$e@hQWEi@?kJ?!Oha3jX5rWNO+dR8ajb{0BH z;b1XN<@{-WPdIoVdYAMo2OqepQN9;6h>`S$TYehf<3j`En`l^Cvka2s?rZsLRE@_R za_?M+7UL}gI3+54ed4hba5jG8Al%ke2TQxhqffu<)Up1SMtfzIQ8vgZNIOO=zGz8U z_gC62ZEqv(Z61A6e3m`2F9^&|gTeWZBcU?e-6}mxQg;gJ-d0Cc)5yx`CSdS6Nyg}1 zXhOXMdgs>lT=rIssH+m5M@yf_rvxgS+VF25p|c5wHuNFq$b4ce(XAeS)qe(F)$`Gojssp*7$< zvO|)acoqG~lKX-}*A?)*E)gxOKw;asZ$0)iEWOz40e+2@Z~6&J% zgGSGXpl&^bw-#d?sM`p%*|7i2qM`feEryQkUK)qO=xD56qwL%(bSmH8<**Mb{`3Mb z4+phqJ5jkbSgkgLe>}_0)xw^XeUGCaqn_(KhcS9Duy*M?cfqH{xA>T2t^<6EX2P0< z%vnen9RQL`G)H_I>d}kaR^r?{hGB zhRIn(cn2{O-j!h6-=za}H|lJ{)3T?xf}#;M9W>xx;2Y@(14RKe$58OOUf!T{%aW2F zPjbXPe${7qJc7eam<`0E6KwOEWDZ#pmy+bjZ`s7mBCubYLAh3Jfy+_1Pfv$?58Oni(?G*R3{A}rvC!{@f&eLt;2S`;S_eyeZezb zgbP8t%RhOZBmE;nCqhm?@L!sdPAJDmSGB8H377^cMlTE?_{}p^; z1#}uhkdri-iIc$9?r?K^x`XGtInaN)gSFkG+y$V=tOE*@;)!lh{D|HUBr$1^0ovjM zI>+UJ?;)75Ls5^u>?UerLFY3#`zw`7Dl<5 z`vdF`^l-r4oNiGf&9tubJ_Y1$Cr=<5lIR02T4YVPQfnh9|zm?O{AwUmi7i^&9RV%+1(f4#s_Yaf&UnN zUm@#gaP17J)B;rB}4b~?Gn(4z%jD)$QI6vYCDtgr(XMe={g8&Uqbx=||M-G0 za78s5(I*e6gn2mmM71l~Y3xN_vJY_+zv~Noy5luVf;HW4JQYfKJN_MLInS^cIh1}* zIi;Y$PEU9D(*KXW2P~UBZwFL-7DioH@WY;spdYg6cYQ{Ox?RRE23H1W6#HT-ABe6T zc%mrZ^r5dn;)Wy?SnQ{Ll+zcmcR>DZAU3kpX`PNgXW1yJ%NHjuX zfz@uZ`QPsizIudovA{(>u_bi*K0oYQsT#Y2XM4?yiC>EqXhm)R zdK7KvOUeoeZ_8OkV^w9#g0(C@Ew>pvhJIO!m;=C$eg|jskwD$8; z7=v{#Ksq;EmbKGm{k(xCt!uOTdBN%zgchF_RF;$Y*9ymd2d=R-O(zZoo{ULHd8=Z^ z;eSz#-kaR%TClsp+NoP`)ORS5j?;0Qd@lI@{7J*b?^i?P%lK9^)pv~TL5tO2BfN)H z<6}-E6${K=hf-JV#+@ZGYVR(2aWiVUU?4}f>W_$VAjbYv3|mEIxfX0dj5CIBPDZ(O zhpnpd?F}qMYhO5ZC{Tg^f3qse|BY;p(d_?Q)t9zcO6G~eHsX@0nzz`f4~lI=oAYgW zuUX)<^tfy< zKB9VC$ceUcTSmAsQbw54GCT>^4*evW`*r zm*(_~7gx#+Tn^QmVQkZB`zDVHs5)`h!S!6qPUsMIq##s5bA1+1lSWy$NBF%dSs04mpx*Dc5#zUXd~XGN$NeL zgVIpyQXAQ!n0*@cdg3!sM)$U>c>y*gDXp*td$4BJJEeY;>O_2RJ@IN`|I@7Ne!qpQYj^8Xb{SOTLeM`6lAH zhNsE5D!uy?DF@*8BVWk8V?~j@`T^RRrTX6Y8NQ82;Xa0AN5f&{uT8aOrHyW;{0+cf z`8|Akj{4E)m~xh%NL)+GvA*cDLZd@}dT1wmklyCd=0g2KAk)x05?UunH9UnQ-WLHD zm8p-sZ6K?slc(`iUQXog+kiwNh;(Flxb>nDB##n|2;EcR`HMsjJ|zf>g#l z?%jV)w`{(bW*cUj`b!%q%G!C5vd20wm!+lowQ2=WwWlLg-k#5mL5)XX{wh4wXEN_B z;Q9fj+ogIp3dku$qZLN}yMa=0o0uh(sxR`;nUHzY z{6o~pu{#0pnvfO;?@hACiX$>i>1O|{uJq2MGt&LqD0(^pv(bzc3DDzFcn(`!9miau z1X%1+g&KCXE7Vd?wtZ>aB}WfMmtJgJ{_5BB<=amhQcv;JQ+$R;_3mOHzis5|dyG+D9>{KdU4bLP zq1?pbJwZ34=j6HR=EAWm*1h_6E5-+|MM#Hpt(=$9S}|Mb%T^x z>%jU!??R6iF*4UFpBOJU@k86r!qhW++6A_w@F1vO3aj-nw{5g_^|>9k+fW*NP!Zr2 zM#s?RGW}|4{+y#SWeFE$F>Rg%=uIgCoD^@=>-5O=!T9D({YBJ-%Axh5zUV7o#puDH z2F&hW*Kr1GXe^}l>x;e^sO{AHBFj0GEr#~{FOtj)u&bU(#Lgndme_2-H;Cr$Fjyq` z_i7U`S(9u9*ysPPOPzkeHbqLMK4Z$>T?jcRmD@Q}h3#@AzfkzAHzcdhK$-;saM~Pf;%XS^CO<>wE388TUSwa(>_> zVBrigDV*-L%TpJ>bXoh9?uzm$#7a-dPqJ=V&%P@~(QmYCQ{2ri+*bzVs&B*{u!pf@ z-<_AV(L6AdfOH~TZ)3HsBgqnQ0c7o&&KMfqc8PcEMU^ig`^jQg^j2rU{j0S zm%M*i*IL^~P#WU;>;B7n3#|k7UT7Vt^(F5vUs(G6xQ4OZvDX%B3Ye>H(i6w>3+nfQ z7LPT17JTOVbocLmFJq?0_24x@>dq$H1KmhJSx@N2*)R=zMj0rLfo?hW>%GAqNUo@H zz9QPsQODxSkqLFcMT~>YZlW#ftg$l57H<`U|Lkjbq*sDNZf&=F?;AQ=4~vJs|6 zUL}_25k|VUk#}JHl^b0-ryvW z?ow=g+nmZNO>{bSf|L6UD0DxZ?(k{x{(8HJ({cyO9(0;gns6_+n`N||ei>zx)bz9P zy}o~5P|V6q&}DMoF%uG7j##iSXucIx>9^YDYB6}e_iANBrK(*n7_D`dtL4J+rofn( zp{Gi1$~Kbs!C4V??>zk#R?S-=n@zQ_KyT!eR>8U(U)5tiS{1rHdfN<}ANeQ+G59|6 zEU{iKzasGyOiew(e}wznW6~ZesJ!aNS*%O9Xntj_1!%aHo5dpSNJxQyd_kGSlIA8< zi$ywcvSD$Nq@HQ4zS-3Vy_DYI>%bX13taJ5Xsob<5h;`5_!@i(J{(WIU?Ph?z_i7a zLD1T>ae}ftke`Y3-`>Lkb2Ds;$C}*kvw*4{kxb|Dj!?ou8h3meq%{2Y!<^(FJxnJ; z=3gsO^q?bi7_=wg6&P2?`FpY3{|FNBupNZnkhMmY@ZePnZAQqKM6BxO9oePqM*NS6 zzupQhq@*jpQJ^g(#}f}!HPdeA{cdR0okZP*R^YT?WXIXHM=G$t40yYJsYs_odKLJ% zzVMEKPF7|q%U2y)i8;ajiKQ&ig@dicrETSIRzMO8|w=1|3cDgB0B~f!NFyWSB1lzDp%t30*7(tU7|sksZRw|sG5*lPy$)<-;3~-1f@TC4hAXZ5+3D9suAAXM zUJZMbaOdD2eg<~9;3mO&;lBCBb2sMkf4g3XXL;07j`s?it!ri5h&mywD{mvoz;N(; z@a>Lvh*gy4DmbIe-%;flEu^xJD^=h8fU|z|;2}eqpr2nH4u<>aXbRz9 zc=vJ6{Ek=|uUG70%9QBo9#zLwin)B}o{{wR#R!PI0$?U(gO33y4 zvQf8ksSh5j8U~9|X8(#R;|P=pITY5hqzYP9YgmV)3bu*&&9&{d4E277Cw?Qf=7Fl@ zCcT7gGTM<~PXSg=iuGN~Ffa9zN;XrHy#x+CxN@dGjF5VkdbFdU3jP*uD~I{TW&hI$ zzBXi+IR7GWJ~;m)VeFudwHC9VN9|gC)N`p)S>vi$$^@Iajpmk!Z!^t@Jh-WFH2;%t zf{m2^vCc9ldzU9p@+e;Z{qz}*kD8vh;q0pey=?G2)dyHxm7aC}M+(+;=E>G|$_m!` zbuumwQW)7YalQfaz#5+yy_iHg7F_mIW+A<`;Z9(Due*5DxK6KdGrf&>EPrpod)}k? zV>sB^OYPOlzCMp#tzQ#X)E|H zxOy5EcDEHy^QM*5Tc&!y5qIyS6onU~qvxXc9`1{zuk0%;oYqcMBORfcHc~bc9Of)wv2*^(z)Xe3v%Y67 z-+PYZd=Q)SbI!5g%*yIsJQvyDCu5AYVT{p!{DI%fKVk66ZYiXDQdK~92bOMV&~%-h zgS`mYKXS*@z9KvN_5yvpBi-Hy>s*l3X-&239HiR>{m?^sM@YtFD#m9I^38*vA+6`a zOdYTrPmm?p9D}r8)BQN`V+{Ca#he~oLV5NDUy;7s^sS|xl)6M`k9YJ0r$DBd_KZ4c zcO4YD)GMG2D1mrHc~BWt-T)oGH>ho<`=d)>1}!F)%rd>)^cBzb(`xi+ zxAcq*Tn}M|%2sF5HpY3t0a;N8jjz({9Q?6fG1v@EIl(pt)?1-F)-NRx-^RgyRfjKH z`r^-A&1J|ve1^)i08%Z(!26x!( zHK1?f(1D#1cIf!0`@dzf)XkF39imywz^@(@(dGbM`V$xF72nZ?6NWvtDF<4p8IT7e zNm=61yBxL1HO@`@tt(B)QSU;_FF+>pf3kw&5jWcpV1ItOyLdnFZ%sRs_;K8nYFyOAdCSbpE~)60SL?7VNqm=#e56}VSlx;R7h@*KxVNUkErMD|5x zGQw&mejQ2bMY9f{Q_}b@bKmJ!L583wcpf_Xv`cEmjBrB#isX-}=7Q}VU?020r?tJo z7l4SnnaLdU&^E&K9k|+#t0R!lm8Q3I^b86X);a?FwPvH!`h1~x6rnC&5n*}sOfb=|=yp_jQ?n*}?rkVZf~7&H+# z6Xvfr&Fyetr9`eD1IKtQBnM4OqG+U2tCe7MA6)^E2{y}#~5tzqNvcOEl#&ByGiphj;NTePDcGDE)K#qBFX zJDCa68nFU#+QPwQ;e~D0b}otPu~|HWl>ARA>ygt1Pc?LlBe88#Ead^+*3>f|;o7s0 z3D;hIl6E)McDK!}kMz$=eNH<|o$7g0RP9rgYbJufmocj3p28EbQX~W}DWHQFWk*_S z*HcKFw_i~{e8x&>ZKLNlM)d7SSB~`U&}$sYo8R4q_Uj((-guSE#wga2UYKg)9fhZ1 zEB1cK(2?fTjv|sjB7PysX}sWju7;`J*~CYaH(nZ9KwA)?r-lOUEhesuI+XjUmrrkhSC6A1+z|W zb2bq|yJjMn^MQqs(=T~B@PmO)t?hxe)P30Fg@dJi@A|MZ$=}AhOKqj`9%CD_+5_yE zA%45&u9_Bc$E@0#f7U$ZowHgog)~9_E@^_uzQ~_kG2;ZzILRKF(dgl@S8aA>U`3nP z!+;=bfYz-rver_7|1K|I6RS&b?X!UXB}=pIX*Su6%YSgKhPFA?m8Gg7Beu9o(WVM~ z%t3Mrb~#z954y1asx(I}R?KT5$fu^6{V%w_ZJ=>CJ$%LILikx1XyZUKPjGU&fB3kx z-+B=;amFVg1N51x-ok?eQEyq{Wf@LrbcOK^LcEr)Qo~I57hhG{0_h26wEveU?!gmx zVQeHikNe&Sr|nMf?A5wkWa+nq&dU3T@|m~pOe^Ytq5%H0I;GBt-R(hfgKn#nJ0@D@Pd{xhWATC)e~wmnfJK5uFv3~=K?57X5bHR6fH{#@g| z0`vwcwnlWB!6WlMoYXm>4jL_Rd`ABfP=IQHyLNa zuHjf=dxE=r|7sc8LRwmf!x4?VUE$Asf3^Jk)cN0QMgAz4UA}l?11Bnuj)2bJx6f=N zT_Bt`sEn_C#`UAE>1Kh zqU*O^ZfGw7mBbaXY%oExYcP+rm*l@|Th=+t&RJz?!4_HCH3>%!xE2W?1L>WmENf%w z%8DemvC?;UZ_)0qQ3 zofG!W;>KUKoUj3w6ZkYuzvTqlH`O8S+W%rdfovx{iy3U{YLqM|Q0}j|;-D7<9Q*PU z&NylJUlb#Y`ev^2>JU6wf-4k5Rz0E z?6?@{{$|)pc?wb`RVH97;XF$xV)}yPG#ug}v0sf*0(p;=Hqw!DLC5PCb}seM@lr!S zaEnC+9WOm}ywnZz5=mLHb=gp+j=UxAXah zxJUY3nGyZ2Un#pBdVZ1TNWZHb&r#XjlxAP~^Kbn0^z@OP(&`7jt44FgUW(zDTD5cC zwdk2RX!5(@lf38vIwitd5l9wfU!n@VwN@+h^YUuga|yVgbQij*&vdq*d#xC~Mtz3a z#jw*C*XeF7U*hV+qpw6 z?7D_X8_=VBKYId2wptTK`g-pBI$Y{6h_ zXiz|_sTS8b-~S77JDvS z)zns0SgyBKREx6O@2iDt3s>%%KcwX23-P(aHS?Tx;_9`>#8p6^ecCd`rkTO~Vi%p~ zdV;R*h{a`=910E&{mFN~m1NA~aPruLJw&`4=QcPs`H-1^#t}V3tN(+z277ptU_9AH z|7#&BCOs3_&BWkkNWq7KKXl8ni=yXf?=GYovHCK9VyY~8EE{$^rFf-}fqy%~cIAF9 z$Lr*?>n+2b;u)4&deJOvY32>}i88~{h6<<7sc4fK1YL!UNK z{Pt5c+tY>)}(!cpQh726=L{bEb24W%2U){x$pt zr!46Ur#UHVc~sJd<(jsE_~Vr|%Qrar{y3I2V>wxe8Hn9f`I$5FG(AbNT+%oAPD@hK z`DDSCXg<%m@OH;0kHg4NsW2}CVV8l^^GT(C_23=O@0YXKZo`|)+nl9-t>(=Ya$U8^ z+U7fxmX|L#tf&^%ZHqx~A9fUSJDTrd!+OW6^N&`G2?#4SZI4xpqg{rTfC*5jsGTbe?YHaQYA7XkK6huLm(Ppljd zH`=`q^LNl`=MgRwr|ZlpPYRu`VgF#hBhJc;Xi++1mz7S z5dW_yC_>^JR3OX>SQtk*7VCAMq_bVK&*O&mIs;eB?NMxw=vDDnXkb`-g1dTmSd^{M zWw2BLuW61Q=S^t+kPcNSSb*830{utWT4x8x3N362JKX!aH0E6QN9!$qE&ov!VP0#& z%R3G(LN|JfV?oGbk{o$1q{t((x|#z~ur#-R-*QO3@q79puNl2JY6}nEW^Zs~k6MzS zBOHB-JK5#;f!hk696LCPw1{firrQ179-pJNbt1~k>k1;bA{C=)ZZv!@(KSj*U zjPdRZuu}D@Q1Hp_B#HCJ%uhEBYhx*weBID{1Md*pY@y&{DR!BknWwsMb{ia!Ov=~` z&0feB+v)U$b++IcSXCWLC8y5vP|0ti4{-C3Ui{VtXk@@i~9 zN;D9SqqfPg+GNywD^@?0D1%g5nQ@etw`uh|P)?$F(9P#+bs2WhLsHdVN+}{`B;8dn zpBwP48y#=Fa*F6(m!Q>r!Iuk4_IaQ|k4^l)S#l5o2J~P4-5#|w|Bs+(7DjpWPi03DFjEA4W$g%vO zzwtQ-X^TS2-@zu_?U_<}tjXLlDCZT+pfioo_!->##{0*)|WlgWr3yK@}if{{QqyI;4(??rhkOBn(U96L$Ixxa#u3s&c2R;u?Gd z{D5yjC+d_Z3z}8ZxB<5?=in6N`411}{C5wx*W97GGor`sX*~i>u^iXmF@sg?bKl?t zk2fmc7d3;r@Km#88Xl?!TRpw&S&wp#bpHJs=)hmMS1xSJ1?%iP7 zY^yxg04@62ZmyfZ`cXi~!R}W;)6Mtf!`kjTv!qj6kOkV9|GAA8^(nGJ{G*GFg}xuCYmxi= zyVqT3<7ap`TKE%d!4vFqRVS3A9-Qt~8_R6-AnhGzeSA~+KdD_T-R$4w+S#t*(2^pw zp^qD@)8ONERT+vKV!p`b4-U!vH5L`x!f_-S${(*mu3x$eY-+RvDgDZjc8K*NXB`}3 zeQy?0N~s-L{P8!TA8^>Evh8jkESN9K%-emR26W2(=A>?A&&-Q5jjmhS$#pBPCKhy2 zPflmJc89uvz)CeyhvKCgs6vBL1HN0)5iQk16$szr^4GX(&_~a>_5^rUxiwOkF26cb zmwXl)-1mZ17mh=p<}Nw@LgAuQd|tWLd{JfI5#l%RY#+?+w0vfJ({|5^Ii3gH`=O~* zj(c3UGMI#V1k7U!&{xaZ*hs(P-OF0c^yc-j81|BxD;Vgp{gFPH7!8}piUO2;{Z)(5 z&395y$YdxzZ^H3cEtx32!n$qbdc6DKb!BLH4n|78A~g8w#{S;LNXZ+1e4}OPDgL%{ z>*oo!i_Dhi8&6WKz!d!cJanATmlVEzys4d6Eoj#a=JIy=Y``kj*)~Iq!0Yqap7QZi z%B|TxlTGcTv10)zgEbSfhPF|yQ_mEGTkvIM6@|KwMOUsE+|+H=iNP1UiAwIu{a9?t z)j|e=nfWqcJLrIl*rfnM@srM0M_B5}fC=BNi_ z5T@^#J|2)W96a!ujY+{-u?#<}I zM$+L^x9CCpA}$5!e>Pe&Lwe=rZ7qdKBS{JqcxnVsLJg z9Cv5--{p(1qAmk@6aMJBtEw7pQ6KhkZAtVtoIuO2xi$Cpf=(xp%WH1UF3Fj3LUiTH zuC0laUHjdfZG4?w3|hLzBiCut|5Rv0T@Myvgk?N(9eeBalI<3Y7yEMDo!T`PdyR~R z*MpO~Qi_3G8Is$Q;pc@6;9C#&ruf5r5~O<6-pk;3D_Uqwv$2H*?^^PjGi++ifgf>h zwm1C-a#`KIlw(}ippqdoGBEcNkgEoG=y5>rcJ}i6SolkDHekuU(9Q1!c8dt^bWJWd z_CxA_Gb>|lfiW~U2HLOOr`)%L<5j!i2Kdu&;QM?Kj&v)_3TU+I{A@N9E`*aUb%b@9{7g-|L z&f?0Rbh#6rj4J-9{Ud&sn8b?RcZwQja?gW3@}mvrP8a3}X}3#r1rp9o)k$qkjqF6? zTBv8oin2^Kq)-^sG$#X#jp^s$WILijUNQnbeG}+Hd6EuK$k&EvsXxINwqf*PUl|Ub zg51gV;42}*b%qudw3(porR@3oH2&o$Wi#%x^MRV|0$87P78$sQ3staNv<1k_>K5)A z8v=ypQ}W^}$4izP$OR14(~dq}1*bbO2=*_BfVY%tg-+7E>%s8{IrO9knq@fnC!{Jvssl(x=TFEU0UI?Kyzho|z>uCs>sHipcFo1ikUFgk z%PL)teBsq7D#W}NH=~EG|R=tm{jES zkN^p2o9#CeBJ(2D<9cv8q(G)iwWt9e4@)fqPAzdQ1;Z^i>W4?d?T*q;=X{O+`vl+{ z^0Lmhig0i~C?ph5Y44YiT`M6IWjYL;6Z9V4y%Rc=k>?`$Meb2M&v$DM6DCD^_y@P* z8oQZdlEVkxf3g5iC1WV|qXMH9gLu^f@C73OISv8*G_)+2>_!b@L}d^_WgvbkNqG-L zE*$DW^qh}e>m2*BXZgUjcZBSkD{d>U54x@gL!c5YY$eKTY}kdAX8&H7&Ze6LUSOZe zkm4T`tO1<==0nC+pl(0p~-i*rTYR6@>}D<;Ah;K##P z!5<1=178bY3tt0&D0~(Cc=!VRMAJY%l=D}8s>2lyHMBQqgdJUW6Ha72`jF!O+=m@- z4oey;h4w&Rf$qWL3eL8{phd#r6JJyXbSgs35ad_r)cjNW+P-YZy{PF{OOAI1t`c!I z-rInycwD7%U%J;uSTSd}rJII9RpR+)C~5!`dmZZh2}_ z80%aXEF;QiQu~6yGfM@x^(qi=Dj;!VjmNhQGL{So=(;3TBkAHRdvuVHVG_pds2Ms~ zN76Rl<=AdX@qE2#7uv%aQh_G|n&j2BLR{0-!^28E^LGH-zd+P!$9OxNpi_}P(z|sL zGz>kmK&n9H{v$jKI|Q^RHw;~9k_=%6$lOB1LS7sW9>vHa9G*SlfG^R`lCSuvUQ6JH z&d6(|8rUcBIRyS1}XZD7Zwp1UyyFI5r=y0&W4)lp?o9@E?HhK>P~0Ot@(X zPuB?SK3p$@({YT=g?|g~-;HMW_cAKfI*hpTBI`swKK}8!;k8ZS0hZ%MfZm_ z{r;eSALFl#32-Vn4V)HkC|o>TBAkvdo3LQvV-r@bdScFM7RF=0{7G#dxarPfs>>$W zD4W1kt#HHO+B0GI0q$1Z9|iZoczg@{e|lVd5!VWLw%=Wt#8h+hnCc}s^<<{n3I9Df zdSnaYF5kjbKO%eqZp*FEK|pvp?4sTM$ihePnm!uHI~y0&ZzXWlZ%g5*-=2k|QT8$% zy}!@k6mS_xO#N7f#8lWmBvQkt&ZYjeBS8IlG?qpvW3Cj&s2{0-!Q>;u81lbGxmx%i zaf~OwTE=ALBO?L6Zl{vTDg1?sDah9jW=i;yE;5BT4`FKf_V0la2j5jannlCkkusKP z;2-@olMRC3_VCSYFnp%ImBql9-qX@Ymn^wqtp0TlQyqpwD(TnUfBoD&Om*i2O!d`W zkk2TK#P{CERORTh+@dR-J-c-FExPCD_1R~S)ePh7EH)5xLt?G zE6bPY7ObdzY~hNZllEt3E3aI#aDi^sGF=67UA0iR%CYdjJ-YC*%8G@z=u#H^{P>(l zD=HSQT=@{X=Ly}4{$eSkUwOR0(c9^ zZ$7u(vnX-^IPQ_;6iR!_?;NNoRZV#2gro;Q8>!V`tJy}!QYj}6DS zPtAF2&q>4e>634LtJB&W^G5b7e|-KQszdWq3YNXQAXV`h4Q2e2&63CFM*Ny%l3)F= zKjuf;nO|_zQh8(J!8+Tuu4xx!rFpk!k1}-?Kfd<9sm&|boGl&p=&Z6_%go2J#%J9; z-t_Q86DKX4KXG#2Z4lzu-_@1OsJb&>d;c+T?ZlEv)4g)5eoE?qd_>nt;MWfRA* zX0e!$Jl@tbSvNC|<9Hc2;itOIF=b@kY@**!w@_UZn{(IgIoZ=9zeu2X(!AWKZ+>94 zQ~^2<@l3f7lY8ITTh#loFqnU^g62T6iFXX9L4eiAJcWaY69C20+Cy>U$!EM-M{)6y zI5RFOZVLH7{W!B9&rvdpGyZg6x{&f5h|9Pk&Xo!^GB_+cAPzA0G_J`pumYzd{1mRq zFRbc=JGz>BlhVjo~z% zqUOeMmR`H##_;56!w=pV=8KsY?}ZKgqNXcSZw$xI(3)=yCzK2?yD^+JlR0k;r{ATh zxiOr5w|2*k;alz*e(;8{v=316X6*85V^Q`#Fl>4-E@&Q*8t6c^27J2Tf;0o+h^}ZD t=1hM6we?S;Pe4&`N@{#W8>7JHGDmE32{T~`zMy~(> literal 0 HcmV?d00001 diff --git a/boards/zeroone/x6/firmware.prototype b/boards/zeroone/x6/firmware.prototype new file mode 100644 index 000000000000..40928ee45027 --- /dev/null +++ b/boards/zeroone/x6/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 53, + "magic": "PX4FWv1", + "description": "Firmware for the ZeroOneX6 board", + "image": "", + "build_time": 0, + "summary": "ZeroOneX6", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/zeroone/x6/init/rc.board_defaults b/boards/zeroone/x6/init/rc.board_defaults new file mode 100644 index 000000000000..cb1eb580a429 --- /dev/null +++ b/boards/zeroone/x6/init/rc.board_defaults @@ -0,0 +1,29 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# By disabling all 3 INA modules, we use the +# i2c_launcher instead. +param set-default SENS_EN_INA238 0 +param set-default SENS_EN_INA228 0 +param set-default SENS_EN_INA226 0 + +if ver hwbasecmp 009 010 011 +then + # Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client + param set-default UXRCE_DDS_PTCFG 2 + param set-default UXRCE_DDS_AG_IP 170461697 + param set-default UXRCE_DDS_CFG 1000 +else + # Mavlink ethernet (CFG 1000) + param set-default MAV_2_CONFIG 1000 + param set-default MAV_2_BROADCAST 1 + param set-default MAV_2_MODE 0 + param set-default MAV_2_RADIO_CTL 0 + param set-default MAV_2_RATE 100000 + param set-default MAV_2_REMOTE_PRT 14550 + param set-default MAV_2_UDP_PRT 14550 +fi + +safety_button start diff --git a/boards/zeroone/x6/init/rc.board_mavlink b/boards/zeroone/x6/init/rc.board_mavlink new file mode 100644 index 000000000000..713d7a41b72b --- /dev/null +++ b/boards/zeroone/x6/init/rc.board_mavlink @@ -0,0 +1,13 @@ +#!/bin/sh +# +# PX4 FMUv6X specific board MAVLink startup script. +#------------------------------------------------------------------------------ + +# if skynode base board is detected start Mavlink on Telem2 +if ver hwbasecmp 009 010 011 +then + mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z + + # Ensure nothing else starts on TEL2 (ttyS4) + set PRT_TEL2_ 1 +fi diff --git a/boards/zeroone/x6/init/rc.board_sensors b/boards/zeroone/x6/init/rc.board_sensors new file mode 100644 index 000000000000..31daf8b8605e --- /dev/null +++ b/boards/zeroone/x6/init/rc.board_sensors @@ -0,0 +1,177 @@ +#!/bin/sh +# +# PX4 FMUv6X specific board sensors init +#------------------------------------------------------------------------------ +set HAVE_PM2 yes +set INA_CONFIGURED no + +if mft query -q -k MFT -s MFT_PM2 -v 0 +then + set HAVE_PM2 no +fi +if param compare -s ADC_ADS1115_EN 1 +then + ads1115 start -X + board_adc start -n +else + board_adc start +fi + + +if param compare SENS_EN_INA226 1 +then + # Start Digital power monitors + ina226 -X -b 1 -t 1 -k start + + if [ $HAVE_PM2 = yes ] + then + ina226 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +if param compare SENS_EN_INA228 1 +then + # Start Digital power monitors + ina228 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina228 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +if param compare SENS_EN_INA238 1 +then + # Start Digital power monitors + ina238 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina238 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +#Start Auterion Power Module selector for Skynode boards +if ver hwbasecmp 009 010 011 +then + pm_selector_auterion start +else + if [ $INA_CONFIGURED = no ] + then + # INA226, INA228, INA238 auto-start + i2c_launcher start -b 1 + if [ $HAVE_PM2 = yes ] + then + i2c_launcher start -b 2 + fi + fi +fi + +# Keep nesting shallow +if ver hwtypecmp V6X006 V6X008 +then + if ver hwtypecmp V6X006 + then + # Internal SPI bus ICM45686 + adis16470 -s -R 0 start + iim42652 -s -R 6 start + icm45686 -s -R 10 start + else + # Internal SPI bus 3x ICM45686 + icm45686 -b 3 -s -R 0 start + icm45686 -b 2 -s -R 0 start + icm45686 -b 1 -s -R 10 start + fi +else + if ver hwtypecmp V6X004 + then + # Internal SPI bus ICM20649 + icm20649 -s -R 6 start + else + # Internal SPI BMI088 + if ver hwbasecmp 009 010 011 + then + bmi088 -A -R 6 -s start + bmi088 -G -R 6 -s start + else + if ver hwtypecmp V6X010 + then + bmi088 -A -R 0 -s start + bmi088 -G -R 0 -s start + else + bmi088 -A -R 4 -s start + bmi088 -G -R 4 -s start + fi + fi + fi + + # Internal SPI bus ICM42688p + if ver hwbasecmp 009 010 011 + then + icm42688p -R 12 -s start + else + if ver hwtypecmp V6X010 + then + icm42688p -R 14 -s start + else + icm45686 -b 1 -s -R 8 start //ZeroOne + fi + fi + + if ver hwtypecmp V6X003 V6X004 + then + # Internal SPI bus ICM-42670-P (hard-mounted) + icm42670p -R 10 -s start + else + if ver hwbasecmp 009 010 011 + then + icm20602 -R 6 -s start + else + # Internal SPI bus ICM-20649 (hard-mounted) + icm45686 -b 2 -s -R 6 start //ZeroOne + fi + fi +fi +rm3100 -I -b 4 start +# Internal magnetometer on I2c +# if ver hwtypecmp V6X001 +# then +# rm3100 -I -b 4 start +# else +# # Internal magnetometer on I2C +# bmm150 -I -R 0 start +# fi + +# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer) +ist8310 -X -b 1 -R 10 start + +# Possible internal Baro +if param compare SENS_INT_BARO_EN 1 +then + icp201xx -I -a 0x64 start + # if ver hwtypecmp V6X001 V6X006 V6X008 + # then + # icp201xx -I -a 0x64 start + # else + # bmp388 -I -a 0x77 start + # fi +fi +icp201xx -X start +#external baro +# if ver hwtypecmp V6X001 +# then +# icp201xx -X start +# else +# bmp388 -X start +# fi + +# Baro on I2C3 +ms5611 -X start + +unset INA_CONFIGURED +unset HAVE_PM2 + diff --git a/boards/zeroone/x6/nuttx-config/Kconfig b/boards/zeroone/x6/nuttx-config/Kconfig new file mode 100644 index 000000000000..bb33d3cfda4d --- /dev/null +++ b/boards/zeroone/x6/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/zeroone/x6/nuttx-config/bootloader/defconfig b/boards/zeroone/x6/nuttx-config/bootloader/defconfig new file mode 100644 index 000000000000..ba219419cf46 --- /dev/null +++ b/boards/zeroone/x6/nuttx-config/bootloader/defconfig @@ -0,0 +1,95 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/zeroone/x6/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="zeroone" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x35 +CONFIG_CDCACM_PRODUCTSTR="ZeroOne BL X6.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="ZeroOne" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_UART5=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART5_RXBUFSIZE=512 +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=512 +CONFIG_UART5_TXDMA=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/zeroone/x6/nuttx-config/include/board.h b/boards/zeroone/x6/nuttx-config/include/board.h new file mode 100644 index 000000000000..d6b2925b795c --- /dev/null +++ b/boards/zeroone/x6/nuttx-config/include/board.h @@ -0,0 +1,560 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6x/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The px4_fmu-v6X board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The PX4 FMUV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +// GPIO_UART5_RTS no remap /* PC8 */ +#undef GPIO_UART5_CTS +#define GPIO_UART5_CTS ((GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9) | GPIO_PULLDOWN) /* PC9 */ + + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is FRAM + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */ +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* The STM32 H7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 H7 BOARD DP83848TSQ/NOPB + * GPIO SIGNAL PIN NAME + * -------- ------------ ------------- + * PA7 ETH_CRS_DV CRS_DV + * PC1 ETH_MDC MDC + * PA2 ETH_MDIO MDIO + * PA1 ETH_REF_CL X1 + * PC4 ETH_RXD0 RX_D0 + * PC5 ETH_RXD1 RX_D1 + * PB11 ETH_TX_EN TX_EN + * PG13 ETH_TXD0 TX_D0 + * PG12 ETH_TXD1 TX_D1 + * + * The PHY address is 1, since COL/PHYAD0 features a pull up. + */ + +#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */ +#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */ +#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/zeroone/x6/nuttx-config/include/board_dma_map.h b/boards/zeroone/x6/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..1f45efc569d1 --- /dev/null +++ b/boards/zeroone/x6/nuttx-config/include/board_dma_map.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ + +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */ +//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ + +//#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA1:81 GPS2 */ +//#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA1:82 GPS2 */ + +// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned +// V + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ diff --git a/boards/zeroone/x6/nuttx-config/nsh/defconfig b/boards/zeroone/x6/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..46df8548b713 --- /dev/null +++ b/boards/zeroone/x6/nuttx-config/nsh/defconfig @@ -0,0 +1,330 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/zeroone/x6/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="zeroone" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x35 +CONFIG_CDCACM_PRODUCTSTR="ZeroOne X6.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="ZeroOne" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_NACTIVESOCKETS=16 +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_TELNET=y +CONFIG_NSH_TELNET_LOGIN=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_ETHMAC=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PHYSR=31 +CONFIG_STM32H7_PHYSR_100MBPS=0x8 +CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10 +CONFIG_STM32H7_PHYSR_MODE=0x10 +CONFIG_STM32H7_PHYSR_SPEED=0x8 +CONFIG_STM32H7_PHY_POLLING=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_DHCPC_RENEW=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=10000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART7_TXDMA=y +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/zeroone/x6/nuttx-config/scripts/bootloader_script.ld b/boards/zeroone/x6/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..2e6eba3607bd --- /dev/null +++ b/boards/zeroone/x6/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The PX4 FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/zeroone/x6/nuttx-config/scripts/script.ld b/boards/zeroone/x6/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..b6b341d4e84b --- /dev/null +++ b/boards/zeroone/x6/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The PX4 FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +EXTERN(board_get_manifest) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/zeroone/x6/src/CMakeLists.txt b/boards/zeroone/x6/src/CMakeLists.txt new file mode 100644 index 000000000000..a120ebe33623 --- /dev/null +++ b/boards/zeroone/x6/src/CMakeLists.txt @@ -0,0 +1,75 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.c + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) +endif() diff --git a/boards/zeroone/x6/src/board_config.h b/boards/zeroone/x6/src/board_config.h new file mode 100644 index 000000000000..f1a00d642b71 --- /dev/null +++ b/boards/zeroone/x6/src/board_config.h @@ -0,0 +1,514 @@ +/**************************************************************************** + * + * Copyright (c) 2016-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * PX4FMU-v6x internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* PX4IO connection configuration */ + +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS5" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks +#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid +#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage +#define BOARD_HAS_NBAT_I 2d // 2 Digital Current + +/* PX4FMU GPIOs ***********************************************************************************/ + +/* Trace Clock and D0-D3 are available on the trace connector + * + * TRACECLK PE2 - Dedicated - Trace Connector Pin 1 + * TRACED0 PE3 - nLED_RED - Trace Connector Pin 3 + * TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5 + * TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7 + * TRACED3 PE6 - nARMED - Trace Connector Pin 8 + + */ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +#if !defined(TRACE_PINS) +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +#else + +# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) +# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) +//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + +# undef BOARD_HAS_CONTROL_STATUS_LEDS +# undef BOARD_OVERLOAD_LED +# undef BOARD_ARMED_STATE_LED + +# define GPIO_nLED_RED GPIO_TRACED0 +# define GPIO_nLED_GREEN GPIO_TRACED1 +# define GPIO_nLED_BLUE GPIO_TRACED2 +# define GPIO_nARMED GPIO_TRACED3 +# define GPIO_nARMED_INIT GPIO_TRACED3 +#endif + + +/* SPI */ + +#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) +#define GPIO_SYNC /* PE9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_100MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/ + +#define PX4_I2C_OBDEV_SE050 0x48 + +#define GPIO_I2C2_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. + * ADC3_6V6 and ADC3_3V3 are mapped back to ADC1 + * To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3 + * respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO + * PA0SO of 0. + * + * 0 Analog switch closed (pads are connected through the analog switch) + * + * So ADC3_INP0 is GPIO_ADC123_INP12 + * ADC3_INP1 is GPIO_ADC12_INP13 + */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16) +#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* PB0 */ ADC1_CH(9) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_ADC3_6V6_CHANNEL /* PC2 */ ADC3_CH(12) +#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13) +#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* PF12 */ ADC1_CH(6) +#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15) + +#define ADC_CHANNELS \ + ((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_ADC3_6V6_CHANNEL) | \ + (1 << ADC_ADC3_3V3_CHANNEL)) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* HW Version and Revision drive signals Default to 1 to detect */ +#define BOARD_HAS_HW_SPLIT_VERSIONING + +#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15 +#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 +#define HW_INFO_INIT_PREFIX "ZeroOneX6" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 +// Base/FMUM +#define ZeroOneX6_0 HW_FMUM_ID(0x0) // ZeroOneX6, Sensor Set Rev 0 +#define ZeroOneX6_1 HW_FMUM_ID(0x1) // ZeroOneX6, Sensor Set Rev 1 + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PE6 is nARMED + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#if !defined(TRACE_PINS) +#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6) +#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) +#endif + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 9 + +/* Power supply control and monitoring GPIOs */ + +#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) +#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */ +#define BOARD_NUMBER_BRICKS 2 +#define BOARD_NUMBER_DIGITAL_BRICKS 2 +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */ + +#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SENSORS4_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8) +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +/* Spare GPIO */ + +#define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) +#define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) +#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true)) + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 14 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2 + +/* RC Serial port */ + +#define RC_SERIAL_PORT "/dev/ttyS5" +#define RC_SERIAL_SINGLEWIRE + +/* Input Capture Channels. */ +#define INPUT_CAP1_TIMER 1 +#define INPUT_CAP1_CHANNEL /* T1C2 */ 2 +#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT + +#define GPIO_SAFETY_SWITCH_IN /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * FMUv6X has a separate RC_IN + * + * GPIO PPM_IN on PI5 T8CH1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7 + * Inversion is possible in the UART and can drive GPIO PPM_IN as an output + */ + +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) + +/* FMUv6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#if !defined(BOARD_HAS_LTC44XX_VALIDS) || BOARD_HAS_LTC44XX_VALIDS == 0 +# define BOARD_ADC_BRICK1_VALID (1) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 1 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 2 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 3 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 4 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +# define BOARD_ADC_BRICK4_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK4_VALID)) +#else +# error Unsupported BOARD_HAS_LTC44XX_VALIDS value +#endif + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_nPOWER_IN_C, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS4_EN, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_PD15, \ + GPIO_SYNC, \ + SPI6_nRESET_EXTERNAL1, \ + GPIO_ETH_POWER_EN, \ + GPIO_NFC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_PG6, \ + GPIO_nARMED_INIT \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_I2C_BUS_MTD 4,5 + + +#define BOARD_NUM_IO_TIMERS 5 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/zeroone/x6/src/bootloader_main.c b/boards/zeroone/x6/src/bootloader_main.c new file mode 100644 index 000000000000..77df9e78bcef --- /dev/null +++ b/boards/zeroone/x6/src/bootloader_main.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2019-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/zeroone/x6/src/can.c b/boards/zeroone/x6/src/can.c new file mode 100644 index 000000000000..1f4e1f28a389 --- /dev/null +++ b/boards/zeroone/x6/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu_can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/zeroone/x6/src/hw_config.h b/boards/zeroone/x6/src/hw_config.h new file mode 100644 index 000000000000..6f6afb584854 --- /dev/null +++ b/boards/zeroone/x6/src/hw_config.h @@ -0,0 +1,128 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 53 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)//1024 + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/zeroone/x6/src/i2c.cpp b/boards/zeroone/x6/src/i2c.cpp new file mode 100644 index 000000000000..8a557078e0fd --- /dev/null +++ b/boards/zeroone/x6/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusExternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/zeroone/x6/src/init.c b/boards/zeroone/x6/src/init.c new file mode 100644 index 000000000000..cd6714af1664 --- /dev/null +++ b/boards/zeroone/x6/src/init.c @@ -0,0 +1,286 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.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 "board_config.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + VDD_3V3_SENSORS4_EN(false); + + bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); + /* Keep Spektum on to discharge rail*/ + VDD_3V3_SPEKTRUM_POWER_EN(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + VDD_3V3_SPEKTRUM_POWER_EN(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_3V3_SENSORS4_EN(true); + VDD_5V_PERIPH_EN(true); + +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); + + VDD_3V3_ETH_POWER_EN(true); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ +#if !defined(BOOTLOADER) + + /* Power on Interfaces */ + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS4_EN(true); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + // Use the default HW_VER_REV(0x0,0x0) for Ramtron + + stm32_spiinitialize(); + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + if (OK == board_determine_hw_info()) { + syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), + board_get_hw_type_name()); + + } else { + syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); + } + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +# if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +# endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +# ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +# endif /* CONFIG_MMCSD */ + +#endif /* !defined(BOOTLOADER) */ + + return OK; +} diff --git a/boards/zeroone/x6/src/led.c b/boards/zeroone/x6/src/led.c new file mode 100644 index 000000000000..bff4b098640f --- /dev/null +++ b/boards/zeroone/x6/src/led.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu2_led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/zeroone/x6/src/mtd.cpp b/boards/zeroone/x6/src/mtd.cpp new file mode 100644 index 000000000000..8e57555eacad --- /dev/null +++ b/boards/zeroone/x6/src/mtd.cpp @@ -0,0 +1,136 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(3, 0x51) +}; +static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(4, 0x50) +}; + + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi5, + .npart = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = (32768 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) + } + }, +}; + +static const px4_mtd_entry_t base_eeprom = { + .device = &i2c3, + .npart = 2, + .partd = { + { + .type = MTD_MFT_VER, + .path = "/fs/mtd_mft_ver", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + + } + }, +}; + +static const px4_mtd_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 3, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 240 + }, + { + .type = MTD_MFT_REV, + .path = "/fs/mtd_mft_rev", + .nblocks = 8 + }, + { + .type = MTD_ID, + .path = "/fs/mtd_id", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 3, + .entries = { + &fmum_fram, + &base_eeprom, + &imu_eeprom + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_entry_s mft_mft = { + .type = MFT, + .pmft = (void *) system_query_manifest, +}; + +static const px4_mft_s mft = { + .nmft = 2, + .mfts = { + &mtd_mft, + &mft_mft, + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/zeroone/x6/src/sdio.c b/boards/zeroone/x6/src/sdio.c new file mode 100644 index 000000000000..869d757756a0 --- /dev/null +++ b/boards/zeroone/x6/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/zeroone/x6/src/spi.cpp b/boards/zeroone/x6/src/spi.cpp new file mode 100644 index 000000000000..ae655b1d6e09 --- /dev/null +++ b/boards/zeroone/x6/src/spi.cpp @@ -0,0 +1,89 @@ +/**************************************************************************** + * + * Copyright (C) 2020, 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { + initSPIFmumID(ZeroOneX6_0, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + + initSPIFmumID(ZeroOneX6_1, { // Placeholder + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw); diff --git a/boards/zeroone/x6/src/timer_config.cpp b/boards/zeroone/x6/src/timer_config.cpp new file mode 100644 index 000000000000..fa5a2cae8280 --- /dev/null +++ b/boards/zeroone/x6/src/timer_config.cpp @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH2 T FMU_CAP1 < Capture + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + * TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer1), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PeortE, GPIO::Pin11}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/zeroone/x6/src/usb.c b/boards/zeroone/x6/src/usb.c new file mode 100644 index 000000000000..6d42476b714f --- /dev/null +++ b/boards/zeroone/x6/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu_usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +}