From cac0c2fcf59556b08fabf03d4477d6b45c549b1f Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Wed, 8 Oct 2025 15:58:21 +0200 Subject: [PATCH 1/5] boards: add auterion v6x target --- Makefile | 2 + .../init.d/airframes/4017_nxp_hovergames | 1 + .../airframes/4020_holybro_px4vision_v1_5 | 1 + .../init.d/airframes/4041_beta75x | 1 + .../init.d/airframes/4061_atl_mantis_edu | 1 + ROMFS/px4fmu_common/init.d/airframes/4071_ifo | 1 + .../px4fmu_common/init.d/airframes/4073_ifo-s | 1 + .../init.d/airframes/4601_droneblocks_dexi_5 | 1 + .../init.d/airframes/4901_crazyflie21 | 1 + .../extras/auterion_fmu-v6s_bootloader.bin | Bin 32944 -> 32888 bytes boards/auterion/fmu-v6x/bootloader.px4board | 3 + boards/auterion/fmu-v6x/cmake/upload.cmake | 49 ++ boards/auterion/fmu-v6x/default.px4board | 101 ++++ .../extras/auterion_fmu-v6x_bootloader.bin | Bin 0 -> 46892 bytes .../fmu-v6x/extras/px4_io-v2_default.bin | Bin 0 -> 40160 bytes boards/auterion/fmu-v6x/firmware.prototype | 13 + .../auterion/fmu-v6x/flash-analysis.px4board | 1 + .../auterion/fmu-v6x/init/rc.board_defaults | 31 + boards/auterion/fmu-v6x/init/rc.board_mavlink | 10 + boards/auterion/fmu-v6x/init/rc.board_sensors | 93 +++ boards/auterion/fmu-v6x/multicopter.px4board | 13 + boards/auterion/fmu-v6x/nuttx-config/Kconfig | 17 + .../fmu-v6x/nuttx-config/bootloader/defconfig | 95 +++ .../fmu-v6x/nuttx-config/include/board.h | 566 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 87 +++ .../fmu-v6x/nuttx-config/nsh/defconfig | 332 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 +++++++ .../scripts/flash-analysis-script.ld | 6 + .../fmu-v6x/nuttx-config/scripts/script.ld | 229 +++++++ .../fmu-v6x/performance-test.px4board | 31 + boards/auterion/fmu-v6x/rover.px4board | 17 + boards/auterion/fmu-v6x/spacecraft.px4board | 21 + boards/auterion/fmu-v6x/src/CMakeLists.txt | 76 +++ boards/auterion/fmu-v6x/src/board_config.h | 520 ++++++++++++++++ boards/auterion/fmu-v6x/src/bootloader_main.c | 62 ++ boards/auterion/fmu-v6x/src/can.c | 142 +++++ boards/auterion/fmu-v6x/src/hw_config.h | 128 ++++ boards/auterion/fmu-v6x/src/i2c.cpp | 41 ++ boards/auterion/fmu-v6x/src/init.cpp | 299 +++++++++ boards/auterion/fmu-v6x/src/led.c | 235 ++++++++ boards/auterion/fmu-v6x/src/mtd.cpp | 136 +++++ boards/auterion/fmu-v6x/src/sdio.c | 177 ++++++ boards/auterion/fmu-v6x/src/spi.cpp | 62 ++ boards/auterion/fmu-v6x/src/timer_config.cpp | 80 +++ boards/auterion/fmu-v6x/src/usb.c | 105 ++++ boards/auterion/fmu-v6x/uuv.px4board | 23 + boards/auterion/fmu-v6x/zenoh.px4board | 4 + boards/px4/fmu-v6x/default.px4board | 2 - boards/px4/fmu-v6x/init/rc.board_defaults | 38 +- boards/px4/fmu-v6x/init/rc.board_mavlink | 13 - boards/px4/fmu-v6x/init/rc.board_sensors | 55 +- boards/px4/fmu-v6x/nuttx-config/nsh/defconfig | 1 - boards/px4/fmu-v6x/src/CMakeLists.txt | 1 - boards/px4/fmu-v6x/src/board_config.h | 5 - boards/px4/fmu-v6x/src/init.cpp | 8 - boards/px4/fmu-v6xrt/default.px4board | 1 - boards/px4/fmu-v6xrt/init/rc.board_sensors | 16 +- 57 files changed, 4058 insertions(+), 112 deletions(-) create mode 100644 boards/auterion/fmu-v6x/bootloader.px4board create mode 100644 boards/auterion/fmu-v6x/cmake/upload.cmake create mode 100644 boards/auterion/fmu-v6x/default.px4board create mode 100755 boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin create mode 100755 boards/auterion/fmu-v6x/extras/px4_io-v2_default.bin create mode 100644 boards/auterion/fmu-v6x/firmware.prototype create mode 100644 boards/auterion/fmu-v6x/flash-analysis.px4board create mode 100644 boards/auterion/fmu-v6x/init/rc.board_defaults create mode 100644 boards/auterion/fmu-v6x/init/rc.board_mavlink create mode 100644 boards/auterion/fmu-v6x/init/rc.board_sensors create mode 100644 boards/auterion/fmu-v6x/multicopter.px4board create mode 100644 boards/auterion/fmu-v6x/nuttx-config/Kconfig create mode 100644 boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig create mode 100644 boards/auterion/fmu-v6x/nuttx-config/include/board.h create mode 100644 boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h create mode 100644 boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig create mode 100644 boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld create mode 100644 boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld create mode 100644 boards/auterion/fmu-v6x/performance-test.px4board create mode 100644 boards/auterion/fmu-v6x/rover.px4board create mode 100644 boards/auterion/fmu-v6x/spacecraft.px4board create mode 100644 boards/auterion/fmu-v6x/src/CMakeLists.txt create mode 100644 boards/auterion/fmu-v6x/src/board_config.h create mode 100644 boards/auterion/fmu-v6x/src/bootloader_main.c create mode 100644 boards/auterion/fmu-v6x/src/can.c create mode 100644 boards/auterion/fmu-v6x/src/hw_config.h create mode 100644 boards/auterion/fmu-v6x/src/i2c.cpp create mode 100644 boards/auterion/fmu-v6x/src/init.cpp create mode 100644 boards/auterion/fmu-v6x/src/led.c create mode 100644 boards/auterion/fmu-v6x/src/mtd.cpp create mode 100644 boards/auterion/fmu-v6x/src/sdio.c create mode 100644 boards/auterion/fmu-v6x/src/spi.cpp create mode 100644 boards/auterion/fmu-v6x/src/timer_config.cpp create mode 100644 boards/auterion/fmu-v6x/src/usb.c create mode 100644 boards/auterion/fmu-v6x/uuv.px4board create mode 100644 boards/auterion/fmu-v6x/zenoh.px4board delete mode 100644 boards/px4/fmu-v6x/init/rc.board_mavlink diff --git a/Makefile b/Makefile index 996ffd47e5a5..80e0ee1f64b5 100644 --- a/Makefile +++ b/Makefile @@ -325,6 +325,8 @@ bootloaders_update: \ ark_fmu-v6x_bootloader \ ark_fpv_bootloader \ ark_pi6x_bootloader \ + auterion_fmu-v6s_bootloader \ + auterion_fmu-v6x_bootloader \ cuav_nora_bootloader \ cuav_x7pro_bootloader \ cuav_7-nano_bootloader \ diff --git a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames index 150c7410d11f..7830e5487e35 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames +++ b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames @@ -9,6 +9,7 @@ # @board px4_fmu-v5x exclude # @board auterion_fmu-v6s exclude # @board ark_fmu-v6x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 b/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 index c1b3c9a9baeb..bc9ff446792a 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 @@ -7,6 +7,7 @@ # # @board px4_fmu-v2 exclude # @board bitcraze_crazyflie exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x index 0e9b9df654ae..5dbd5ea3eef4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x +++ b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x @@ -15,6 +15,7 @@ # @board px4_fmu-v5x exclude # @board auterion_fmu-v6s exclude # @board ark_fmu-v6x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board px4_fmu-v6xrt exclude # @board bitcraze_crazyflie exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index fe40b95aa034..0d8ddaf2d861 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -10,6 +10,7 @@ # @board cuav_x7pro exclude # @board px4_fmu-v4pro exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index 141ca861c422..25353b2a4c98 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -12,6 +12,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board cuav_x7pro exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s index 276e1b45db27..ecc7ed50789b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s +++ b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s @@ -10,6 +10,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board cuav_x7pro exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 index 38ffa06896aa..1d5b47608de1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 @@ -14,6 +14,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board diatone_mamba-f405-mk2 exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 index 85b045e84a2a..3a69a846afed 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 +++ b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 @@ -13,6 +13,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board diatone_mamba-f405-mk2 exclude # diff --git a/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin b/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin index ab4a99d348b866fbab23f634dc01159b2422e2ea..2c79c4b1bab5367e36ca229181ada79f098e7877 100755 GIT binary patch delta 21450 zcmajH30PBC`Y?XZy*CR1AqdJ2SwI5;je?4MNZ^8i1-F*gTBE4FN~=t@EnTJwVy9Ny z(R$k%lrFZ~j;&n?N`IoI*xKnf?M&h_1EQ5y+gm~Hjexl%kbLh6Iy1lj^Z%YN&vSCm zJ^S*WcR#neo{}6Ce$R=!D9rKQl+m78inNJkyk)|fgtEla#05Jo>1U9r9YW#?9}=G! z>gcc7)zQCcSB2Q4KO^m)tP?SH3Z7@Amv6^ko_wba68|=g#BosX+^|(*lFkT=B_%v5FB=-B=Jr5(yh&>C6uQhaOkZAj@-{7UQ>p7+=PtuMUvA*Gv~+~ zbAf8EEyhiF_HV-KvNKYAx^AF$wN8wpETR&I6rX-ZN`|za)fUkV@5%ppA8@Q5eTOvm zd?4KoomgOjKMQphZ`cEca!PgDXxkY{4P#fp*l8#UacD%HPKo(ceAbZrjInsCy$JEgTs31ZCkrW^mLJf|E2FCtZ zgHZN%W1<<#Ri;meeMM%fN}BuYzz{gmV(}EfwNL4G(tnk zPAGE$@-D#hEIiM`vj_4VORVA>klzFEze4)2@Vo}kYw#2ypY$R^{0gL9f#*P8>KE{* zZXcZma-c;I{uby(D2Qu|gV#()c}LFpJ#uDsTv_}A*k42Vc51-!Xq^-1HnoI19(DfB ziSz{eue5CIkKTUD$!JWUAhGh;awndBT?pTfj5l1$GFbLU0A>tW|EqvsY^Ke`BJq}#$&qKhKei3&vpJ(p!`8yAhiR1l zTYqeWRb=Rf{@CrKr#uf%Hi6kZ=wUnbPzxZpJ%_AFltFE8&AGVWqh`{wl^1A_%}Nih zvWDBR{(w2g7S=OAJM2PAxhX%nFapwOKm}?W(x}^4W-}M!%PT|aHw8PqjW4eaz4ZyN zWT#$;Dc>D>yCRG&WAejo;fC1GOTQvf9u^UE`xjLK_~ARjUNL}jzY*X?|D~WTBVB(k zRER;-cLMVx>QO?7fS`tuejT1YsE5o-yMUBYw=U;sF^aw~nfB!CSLHUL0>DmtEq*sC zldu3FGo?awOo8*70w@E5CS?hZEghZc8mmQO)+F&z9Hpzvq8Ef~bZoK>i68lNY~%u3 zgT(iI(2(x5lss22+O1Zx$ND+MMLpTW)gKc;bHKm=1uD@M)I*m4$1tRHLWpT~=<$2& zS%wXI7xIh3V)!{>v3MrLQX)pTB|GPgWSGnUU>L9ZK#NO|ICV&R;>hb^_fZe3RY<9U zplrqB&m$NH!bnJ?Y(*k1k$-KFVMpII00paua;}O6NKBMuEZ}1?NvaUBa`Kb%6s3>p zPqQdpcT4HW;FNhH=p|CRiFP&?<2)w&H-1G#oIS#a4DWYPjYuPFULi65{8rM6hQ)bu z@l!t*pB`3bd)+99>6UBSf6X^z@vooex0BUZwg$bw2E(*eN&Bx#vs~PJ0(G2x5-I1D zWBr_kyLF6bi@c!~X*H~|7Es#=t&i8uSYTrHkIyKZQSrr9S*~1vc~%1@J~c9Jfrg!D zqr@ltxn=lWj?KL**+%J&wOC9UzIYX3N?bq0=yPqk95xnRG;t0@iO=wp$0Xqo`LZ#3 zdz&x0EZm92okt;7 z2n-9k+;Y?cC{W3u^hO9*U@~E2U~eIQ7J>`Hs}S}>I0)g1B&3{~fs{k#DP+SDAn*+% zvNH3nCoOBV=w$}>bk?wjrJ4z#y!{ALs-ZzrPF4m`zdCTcOu@g)Oo@bj=VwMvoUn34 z$12K|Ww%F~R>2J=WP;pr%S{NIO3#r)O?_C*fqKjUUPcW|#*R2)AqDpi(m zro?6Zs;G(hH~#r3BYui+jnZl>eE9%wCr0Ai@VogeC9d`nN{-JX!%Y_f#ACcSY8pPv z=ctPll3HT6A>*L?Hvx-FhCKr5jGT|J`4`nzDC1U7v?mQQHW*r-hE=!6mFBm`a=-OQ zKZ|q@?Qi|+t&ewxBmGsA1`5Q#(F{#7&YlnPJr~%;H0oxO_;ecIT9_ydb`3Xa~tcF zM#@c6PWer2`>$gCCNW(8tstETD3A{V6c7l!vjRKE!GQ$uM`D#<T)Qabt85qa)01XGoVOKGprD2!{;4)D><0+?QJb-Hh?96kIe7pmO^&EieQ7P3C z4{X{>UxUQ#QMt%)vG`p8H_)`&$El(Wci!}Zh71uS9germwt=fD&d zHn(zRy)xO_HKgulPVR}o%s$go_Qqo9Zadus9X5=1*Z>{U`~vp!P7_PkMn8ZyUv8*= zXob0`PmP{ z&t#{vG#}AK@!?IFS2ZDiHq@G?lVosC$i|!DZZ&rjVXK_E2l5ClTw2(4S7KKhzOup96PWkE03kyl2R2xZ20Y-bx; z1@H^w*a9|Qx5b3T6G1ckob&?l2_FX87|mG^DKSiG12K0a;ME5N-t3k!h5 zsDzz;B)GKjZ$(LNq$!n{h!foM^$*xaCt|*d6P5wzf($Mfo(?2B$WKVnr9T*Suz0VA zReG=zi-p0$LKlGFedrtkLUdX%J%yC~?&NqHiyHp9gk`dV5lJ}9|Co@1_wd1l0w6vG ziBqBs!BLVBuVnxj?0kJ_-i3{In_1*&*LY7O&d|h&zfONr{X2v+sR)H^X~C;x(z` zXaB+X_U(l0K+3A1x>-g|RNgglGtlxp(!`^oDpGqk(3*4z$q+)Am;YVrG@QWyC3RZl zgT9_NH878A0G3t9L&8~_JZZ6y2w#S_c<64Mq;vw+cvRg^Fn2nyP0OGHL%eIODPzGg z)N!Zbd?4(|Q!XQzVvMh{4KQ^muHauw%a}1RWN6a>lYs$W#J9mBihmip31n!)(11`| zEGtvDCIclO7ox*;L!)FM_1IZ{C@t*)0wc;+2WJ4tehfI}vmGG+YLvimgq5mW$4a?o zs_zuuW?|eVbtkPz#6UW5Zn)9o#+o5m{5b%O`B1+UkZVFIl&^&H%)6FY_ZseK8<}#v z!E^=a<>b(;VU2o7^&j283jE2+@v#Qeb;ykH5&BAKJ86;syC!j=+E>GEc22It?;_pz zQpE0j_WP?iAM24gVQ406g2@U)I8Qk(Ji8Z;mW*JAhS9;u*nAKu>fsOq3j)B4#r^y= zZCcXu4uYD+f(W1qjewky;Vu`-DtDpGQht**#lBKXTY&R6+9J8XN)e9KHnP}mDZR%8 z^aAN$;+DtbbJ5(CwgZ-k3(;I=+m*za1=j>MAb(NV&e4UVv6r|%Sq}7J`d}Z;yxGU# zmuxC`*aFg4tMtBY6nP>LG{kzkG!s&rfrTMF+~8axFT}QtDc5sW=ROY3+pK*yJs0C_ z;*b$tBzzAR+a*1h1iAH`s&Jpp$`#p8a*f4(0$;AP;C=iqUEI8F(#=qd9wCVf{y-W< zdWywb!X3r~H}n;pC><-;VhtsJb~{c%{DhB4zI>%FF^je{vuR^^CldQ4Mz07lo(LA> z4m+yQBJmlYR|sAsh{#SaAUljC0@p+oAZLQ`7jf*e(lo=fL}RvJ28`x;Nx7TpBC`$c z*RHO%Otu6tz@LFn3bwuMoXFwHQ{A)JOtunI*8~*ot`qZ|CN|6ykCAvIXoA%CAOiLg z0R)AEtn`B`=$&N`Aj5h08DX?qX21lnh;?6Gg=yHjzTF`;CoZ>JxLUjjF?6Q*}b+TQ$tlMKkjPTPXS zKLj7Q*{iuDwgX(htwpE=$h!)&IqAI3I&B~2WVQn*gFKa#iM^MNo&Nn*3gCEsklIH# z{mC-m?hffpNDaJ?0;Y?|287`vvOyJ4X(T=uq?+XHXt@qJcI4QSRVLz%g8yrJlKt7B zPY^*Ql9f?*b?Xvos+yqv-9eBe9w&Q3@{qW+jVg`daBhr^sBz{%3+mQzj(U2zGx_P4 zE%MX%aVM{$sXN-LY)YG=CyBc$lybC9*JibSb`>EE@L{p3Z6%;184}dCDw_`wOz;|0 zmc&1p5p5rM0x4;E_}P>F^jLY>5=p1Y0s<3-us+(^VCGlV7OPD@82!tDGypz|)uKZV zM5v#RH;Y}4jZni-iE@y5#(@URutHIaBZFu%6930>WY7%HR(Lulo5drJll=%7u5W@E zB&q1FNbev51V54yWq->NJ5XEkML#_+)}>ceh*4o>9e?pC>Dg?$Mx$v$m6Ggan2#Qc z^wIsp5VMsJveGiCv>sy<3Y5Eb$vW&-c;mzXV9@8I+C+}Ve-SA+!t|+ltVBu zwin4k3xYnhA)i95;ih!HBb$7Vw%T!KjV;!7SvK|@BStVCC<=&obD=_vP@I*Nd2ME; zPa)}hFHP_g!Ln1%Hp~BwurJME{WURhBOQ#E(?To1R8_VUIYRmA*|%M5Y#VcquA($u+0ui z^!R3i@`|98d4VycK1i8S=`u7i8g|+jhxa`ixM_L9CT4{ zA0usk4S}=|l59-`kd$b)sf~zd-}nzzAF65Q4;Yq&zwXy_@tcrHNoRSSnS;yu$(iGD z17DP>PatiO`UEvQYBbKvJG&Wt4v7_fedf57?^7CT7&b#x$ewaqYYtl?yH3?)u}B*a zJ#_L%GIN#NMu>Rp9pZ0f>VWNw&WfQv+sRMJ%2=xlTY&bUrUnZ>6S70>!A(0YbQfyE zxro0hfL$UN^8>JlA8f|x^Atxb(bjKmj$zS9PqfWUX|otQX0lpQfx{BDB8{U9Wu-fT z2~f^xXC3Xh&?A7E#K<>iO^>$LoYkGI$z;#YjxW?ah{WmqP}YoG)IpGex^?SDh7D(Z zZAqnLxviFDcVfAgi*6%(8ejaT=PdgCYT}f$I*o0_yNF+9oD3}DOU9(IJL~c@-)fva zfxM|(3pe6{&dvL!aS{psPjjhmHpUom~ef2)6uF}DlnW(=T$l~asY@%Q9Z*k=YuiLG9A;6b6GX8Fd>^(XsJ zs%wk$Tj3zGP27t0AYa7nwY*;=b2$g=?MbdpVm!)k-*@C?X|aiS-j}+>vZUZXsshya zFT-dPt(M;Uu@=!pZMD7mFlcN>kVX&^fw?*D+{00#i8dL>xyM3j#x<53K=z0ZN{{v1 zps@z-RKFu;o3zw~#7QIj*BanZ4F@iT@Whvbx^-L4%hLU5#Jh0>=}0U(q>C8w4s_(V zK3gMSkj1_d%D)CYTYTGS{2>r8^4r_^Hz#T1{yKD2y33R(m!CT-m79{})H%WmZR5Kp z>8B=_?X%EswJxb-#CyrVe`C;lx4#Gem-tt0glU-!Y$>(1o+3P(v^zff@~a3$R^ofM|XW z*W9;J1${Ga6&qHf){c0e^{?I-!|BB_bc~IR;}VRc{nuL1xtu?7ryqN3_yP`&Z}c!Q z*b57j*=1mNoauZZ*_6w%FG^vsfK!9HAUP_tJ#MDCw%rP3`zT;bLS|JgX6X{57hfz< zW$`xP(mU>YlAmgtglqX#rtx;PiaVU3%+L^$JAptI7(Nu|lcEdNv%a{Bk=ChSAwk2{;On$o{nKp6kXf;*5F%P zNQ)H%Z#@!G2pCA4!d^+F2j6-OiL9Rn=|n^Ew@j1feA5Q#9F&L2oQy4Z0{1SSAHt1y z1Ph`z40xX%MurH`Oa#0JVrJ^bnwua*g6L(N5})R2uPq+MsWMi{5%twL$&xJVqsGem z(740=pQrpyzEn~s$8$V4^{)JxZZvtCOW}!=Wr$I-k1Ufr2};iiwhlU?rk*B{xG^a2 zL+Wkohn;%vu;l=kdFCgMxAEfC2@9tMt2t%J(pM-kb4bN>5Jsi;3{DG_AsgPygP#av zHQx)#?B9j_)-jOs1_4qh!NW+5@ev>mUQ@P?cwgn$=GIMN5od5xT%wI?yU&L7H1Js} z4wi>o>@0DX0ty7WO36FQY|$*{5^R)>kIXAwnBQuJnaVh2X;<9OerifQt0+^Ho{WdW zbb$w9T0H630MkX}BlPXQ+4C(?$P8f&h%%#=l1LxX3GFW)@&1EgESW%s&?==Bnwk{!SrePX$ytwpwL~E$gUud1KPbrA zYrJz>T--tFA=s1~>yKI#Zj%3rbZvdj`YZgUY2(sn4DA^z*-1fAyiWstgeM>UT>Zt>;#?%o zkr>Z5^o6v&5~vi!T@XK8No+oVwvG`QJI^%YHS@1c&jmvAKS2UKM}{v00wZem5pOm0 z=j&Dj0M9xBr%+3*4p^r&;d-kr==}ktkUOKvg3*x01BrZC#$M(c0Y&L|;9UJyqF+(U zP0-q$5js_IKIn}F^($i>biH8gcP+Od<8?RI|E#iI4RwpffAA}3#8nM}XfA`P5)E#D zJD#oI3Os#Qp-U~|D4Lz+!n0@zC*iD_U1DoNFV1*f@j*+ri<+gEsO5B4Lf8EYS)Ys@ z-w~S@%L3)DIm+r-rjL%~znhVL&xd`KLOBcMqAxECbk?~}QNUSWxf5!ESIhFdYl|(Z z(Gs3bNq9ao4#9gkt8QK079(LJ$!B^XR)!$NwpAtKe9#Zf8gx^&H~5wL)9j|!h%%IM z<|?x606X2A7P$*gQ|6}S47wvg59L_gz=Ty3GuER1(~ZR*p(FyO*MX-72?$J<@RS4M zq{Km9J2PkYdC)Ks#YV+I_aoE-3bgx5P_Ya{XG;LdlIC zCT##5&hMQ0D1MK}vu4GqDq-(-fX-}VH_8BsF&sC&X0e^-H_V!4|3Mf7-VHGW4tsou zN(bCk&ddv)lG22X3tXU~R7ZKZtA?Eg-sT+c(TcLe}-Pds|7cEp?MCn?DA#$D%8jUS5V0EZblJ^`C=t|kI@UN2n3@UT6pn-c}z1$NEx}_0sfL}hl2p{3! zoITT?FGrpd+1(OT@wBs=dyAV5sO5mI4A8q~ebC!5Ol&*U1>8>D4g+bIZ_uy+WjVt6 zQH@Y!1+=677Q9eb*LZaVt5^Gq+N*+@Dz`r0!~Ar5e4A&G8lFe`_oSS3!|VE z&8Jx65*faQ# zEEBPv|Cc3`3SQe|jZLW~&SN0#s#{}OC2R%~_W*ODZdU>@KFd$Brr37`6)fj`yUw8r zcy|Yir3_TthUXrrJ8Y3%%!g8s1vZJ}k<@+<}PY z@71C7`-=K6C_NM=gDHo>v~|~TDi5Q=`zm_>#w?LkCU9KZUBi*seE?77`NrteZu-IY z7TCd&UIu!Ba2pa|8J4r66Xm3JH`KNEor+32KkTiBH5l8ynd?={KoU2xpw=?ceX?I@2`RXxE>&J`LW=&{MM*)B)$XtS`GXNR9`+6ZbE7yP@O~FS9Af}>#Ly4^1>j`>}aMgV%H z>&Y3m!sMI%qa2D7lr``1lUXf};}@|r#_s~!S`LI6=?Q@u&u(vyu~BvW>ufwO<^PAx z#2x&P>=HXwN3+N2l~o#R%36TL4+7PIyIGgs zW++SG^c=~xxKYL=wxCVLZUQu*TlK|NH06t{)LN;1$r0>{Ln~9&68;Au?a7}2G|Syv zp{Gb!DbS~A_OhV62VN=H%SE@&^mQREX+p(b5Xdqg2?BpySLOWnc?x_tX&A;1ZVX`X zpFlKDV84cc5|HMvu;t5D!$PE_1-pN1-x5E{(~Gb}YJ;X=9oAh+3? zpPO9Bc+x}G)OEJ%Rr=Kjr9#ISSLON$5YJh=2~9S`@_?!+WCO2}Mxk-$Wp~<~2q@QgQgmMjN40i{-A3$e@Hevu5VRl${T?q5!0UI>zjTn}} z;nx7B+UfsE=#n&3%ACozO7Dj&j%jc6Ixy=P95jQ7G0Gv%bdptpcCh$E|iogWp8Bs~Zk|1Ta|<2x<7~ zr6o~sg1tVWn|fnWX!Ixf7fTZo7J>A_u+is{KA$~o3wmD+${RUn!23PlQEE*&>=R%e zWDGIuj$?iTV#Kh2XeP28z&4*&rVU>(%%oE1sY5~UO1`WtjS3s)A1c$~3Vv5voPDWF zo3*&>)blj3%wVK()9Y1WFTdmc~SSAUgXSe}-vb{p3x)mYn5Izi4K z1WW)9HvlMV+lgCFV==?t6!vpU*rhjMLjvBOp{x9x<<{Ici|7j|yT5yj%_A7s6Sy$k zo*t+Q@_rK-_BY{8%khp6xL6k0>q=1h@No-M!a7|9e(nmK<>xLeGG+~NwlO7NUZrG2 z#v&v{Y>xm!`^XRtkb`%FmzwPm*9f~K<3Cua4fpw(R23*Cg5Ea1YvJT*W1G620=;k} zhn(4_+Tyc(!d+>ZydO-E8vWy{9yz!ti~!(+DF@IctXXq=zfcs>wTL@)6=@f> zEwN$E_{V9T(U$mlB0HNEgt1(&5N=yyqjZD95-{$K8iKy&f4nPhI_VXIHk=rCNL<+} z0~f&&Z<>F^`xmhK62we_{$Oqf5q5|_c})y_Ik^HCuNTSyU$d0zt#CNH-ebmks&zYRGoi<|kNtkpfhfJNHvM5Ed4&0Q3 z*Jkp|7G>HG2J+3|J>kvmat)c za@2K|8vBwh+Sw)9BQ)RIblmHf#6q2IQrE4-H{;)_)N^HED<_g-uGMPGhgs1<@-GEe z6wM!a^rJ(d3C(1ySiiT(|1dFqshq+-wwnD=&;jzZ6k4IC4o)hWJ830`48-(_FxqAe zwD~WAwC4&e(!t`5c&ma9;9oF*pyZ=WmNf47CipW$Ill$w@^MS8_#nT0X@)&v*jz&l zU?Ax|vfF>NpYq3`a2r)tWhFM&+G3*QQ?gT>C8^l(0#KcCpqYCXba|0S=~ntZU<{Lp zbyy}*#I?DPZmumBTVHIB1prX6)FG0$0UT{JA&$g2N%lIPP9&z|aQ19Y%ucnla>ytc z!TT~pF}XCyHU{t{Fm+(4RkVT$36$VObfG0W@m;$sFKd(9%Ixjml~cWny7r& zagRP~HvDHrRk`Cqcd{JRI;Ads@8!o8J;yycQCW~@iZZ!N!0DT60%g--iYI&D>3+{s zL{mm|^Un_c{IX>G>kd4nWWZ7KO$*Y!(NiK)$`X-Lb_pe-Qu$B#S1Zp5#|Du-{q%bt z6W!esW<1tOI;;>?l&Ygdbih6-W>9|lbTF|S{}M_`WgoDVh})GP3&%Z^qRirB4Wx!y ze5wI@syhs+Pew(-0JlU%#KL0(u$G1a2bTukiX{UYu8Du@?iBn2zxVDG?eC#*ZB#wv zYi{SGI+b{dUSc$hU(|Q8Z}C^}PO&?N6>L<`d!Ds0GyAO#A078pM_qDvv3TMbk4AMb ztj&v(#uP6qVKBSuo7q47c-*rt%096ABNbaRfJ&mY;T}bJRHpKfQB;H(I-;~~*QjtL z=J{U(*Z7N)rkNJQD4dn=iWjMU(D1{ZK^= zbW~HO>_`LpvyV*#rAI;AZ%HHZ@Ag!PIjV2rtQb{a3CExoc4=mQ(?TGiv3Lplt8l92 z*r1~V^NFVuS>?O3-0(uYH^B+pm%_`dN=y3_kv?7wi%N5+vfvZ67ei(I(zjrlT$%cV zfF=U>Evlp9J8-TbXaF@bJf63^m}$~+XwofrN+E#&nY)E8>EU-*jkkMTH0YqJ&KrCC zo_xx3xKBkvg(j6JIE&f4&oaG3dDt}ZOg!bmRDQ?GCu)*+6wv^!6V8)Pc$%J@3B;qZcm_-Tgy)$;HS`>sJxOve zD{L1?rfg4RF==tT&kCYFBgisBEue&$ZKKtTm z?^s7o+Y@sC({p&*q9T=gnR5hZ9C$!aBJo3hN}0Y}!r$Q zExQCVx0L_CxruV1QdLnfEPt`}#^y%gx}mVMMOjP5%Is0i5qfT2Df|=uNLQgR}TPRT8l+%g5bkr?=%!&lNAdvHUr~2nb-V1*L zhM~CVSO?Ol6cU`mxN%cTVdO7(+8F|bxsmT_*u}nvo5cHE&yAJh;Ux45c>W#WM3W`= zw8Fo!R1xaWr2NByf1lt8`08`le-I(nmcH0@%c$S^&SHm~OBjW0uKv1jKmQ0k*H zux842>M6|)1(g2sDbfPdjePWQGt^yM2=_=&kMDWo`qY}d|4V7vIpnjC7Js`hLWXDG zI6c*w(fjjeoSRtqC(EIZ@$AGhy6;PxzmA?V-B5(TaXk&X`YJRCrn}_^^Aw)ufOLh2 z3BM$5*$rX;qHAg(9+5%dM(OP=+TEQ*F1s!-eBEOA+CM5~m$0ajs1Gg&Or}LF8owu8 z!cmRj)u+-S@ZjnU)U!L-U-&62)2htRAmw%lb%6VjB|7E?j>l@n!Hh ziDgl?>LOaNW8({b-c2KYT-JJ|)fe{J+)Ig}RRIRR7bS&y45%TAr^hHu!oR;VIjnjm zQci>L8Sh@1WPg*yAP^RcTm%{Mvcni`dqv>Ps|G6p@Yx{B=C^}eWTCoshb4xkUCDKL zD$17J@rhu;$^;d%IOhZrB9!2plmrTAs*7+%%Jx$VA9(0EK;3n#n<~S)#M%L29o!XO z3jzF?%5648EKa|(CE1rkQY8d(kxU5g_h{%UOI3lgeKWA{_(PPjMicaQ2SM-Fji<>a z9L|7Q3=|(4y$yVJfGea!9h0Ffg`uDh(v7+`8XQD%Zi;I)7X|(Y30+ZTO&sk()$}0B z-DinDjYWk7K6F837vsQl@nR6Xl|nAo<3m<`;*5Om7?=+cr3?nK@*t@7)Sv?mFJCI@ zH99Bx$FmB_KiE(P+;SL1ZrcG)-$sGM@;+&*{s4H}pbj#*H4vz>PTP47WetO6kfad~ z@uRX`%_zezXD>-7x2Dw6uUwM8ehWl(GZME1Bc0z$$aYEkWDhLpjBi1Je;$1GF*JU^ zG{Fg15WrrB#0R$`Se=DIW;X+b{U-PbU}C^+(#}pZ{@RJ(S}f^B)X}~gDbGNd2Eo4S zKVd~R#7Tl5BCTtX@-hVdTBJMxp$Nie2zVV3-~Ug=|8C^}6`u`lqYMg$sfJAi9(gO> zM8i3ufuS3z$9iBaQ8=Z6*@0WfCD?|NU=U}4h9 z)mErsrg>NyGu^bJbhOEsI=G`eA*Ss<*p8Umf}3M$N-IC~ffNtM?&|@YK!))>C>N1< zvYu`t0t;>DFTuUjCqapG7_?+3Zyv2Dg-(PDeOS+>G6r<>y?SzOl@5=Ljzx^Nuq5dH zDnP1J^d*7O7L?oy{rAJaxkMC_L5avrLt<=@(aLwrK|j?T$j%vX|198)r-UjHG{QkG z53ag_9fF1}1JNLeO=fXXJ(KsMFcms~Ff@?b`f+eC+$=s+Z%lx>t9M$^&2{zQv0+Cy zSJz*XUTwaYeGgp7zlIuXLc_g>cUH&Q$-tEKj?kpw;tg0mrUw8%z`Nw+&AIhVBi@Vl zVK_&4>OTb_q-x@d*9@v3U+H@1^+Wp!e1YnYfy^M}m-f3VbqUhh%)v`!CSgo5jx^WK+L^IAM@vjR0kVJDYQU z{bv(=PeDu^Mo03dmSSE88st_}Du_Bug+)k<#Eh_CcuhBT#y+OQV~$ zATC3GXvAAP1mzFOUI}{ZZ-7DD-j-S)q>q~?@%k`XP2gd$hPfU6dX zUyU??5%V;}J|CG_)>JgpJ)x}8GTnViYHTJYih9Gt?*$n6U}UuXMTuEmxELoMglj4JN8%TdCSD&h zftSteK%A`LC=>9O`{>k|?y(Ekvql@tZ-{ErvK*@)IJVgeZg>q;&Clv!f=E)Xz!wLBjpnTK{@kfv`_5&n0z*DVkWy&?&h_`@W@!&GNgFo`1 z73>ocEPi(!P{rrqNc_h-@k7WuLF`I5Zrde>y?_5Ny9AJU@PR_dHbedKEZ)8Q2)Pk@ z1#Wt#)aB%0moaB7KtATDhO8Y(%#d<&qTJ0MRH5t|_P#r!)6;N07L7N9bvWaiFa-9d zrEPEl9z0!!z5Do`T+&KH2Z5kipKT_N1VA-+BSVFYbn^~$lUA2A8M>LA5b6f*SiFnG zBDlsE1NAqJp!D(3!DC0}J2BB3WFNOM9W*eJgn`Mm>3Yz_pLx7K#aKg52y;Vu4ba%?y3yjl zxv9MCLPKi2u{XqRToqKhpZSjU%OAK0e5WM$1gIRmhD!lsgX;=6N^J|sB}Z_hcV@7e zb=jbQaXZZbV2M!UmOHa(9gJhW0~B<3EQ4TidZxR%5JcP{*%`DVnTkl%yB)!hyjnOw(rpypJfZ-mIB zkGCp5!0&>hu?D>|;ynlk5ILC1;HDLr$#(r4{6zjt&CDFaj9k8L|G4I6;C2lHo`)z- z$DyAA>URUA6Sj}2xTo+lADV&x#sBW1n50e8MTzOT2)8f5wGwn|tNIEsGA4DyCkFU8 z9@64P{AUj(VJm;}q0H15+CK0oBOboW{2hsg|5Yz|?ejgn=3&+z39BB(B4erhW%h-l z7T?yJwl0hFb71rSY}SC!dxVb~PP4vjuINp^E6w-9t^e@{Jo<=8fAr(lUWFC=2d@u=|GM#75NdMQX$V&W2c3NazW1R4YkygnL3P*em9+b(tk65TP zTY=^dI<_UQ>!T^GiDSu!KA>drPXfv^i@f7a(AdJji(%jatUcoQ-ctC-oAhvB0$C$N zL$@nKW0!++fI8g>&AA*bJ34N!sJK1uNIwd^Q$$LRj+;9DP7%8Ku_K;6*cZu|d*$Z0 zh0i=1#ZI%%rx-5pr6c4%9MJd_0~36T{=(i!2KlfA1A$eHU2w!N2FOYxe`@XmdoN8! zGPJjd^5L7|p}|CgK&_hL57lQ9h*uj=Izu1rbF?$Pp!wTupVvY_9 zFoKCY{f=c_7d3lLp|v*>)^Wd|`sJu)Gq?dQK2zaZ;XDRww5BhNVSEa&&WHQctlydc zdex4$AZ@t-`;9e_NOpUI4}1P(&b8iIIHy0f65|sh3VP)Q$RBy@j~2#94Un!ehJDP> zIsHeAv5U%IRrq{TQwx+Q%N%X(#a6jL(zDm{pEZs>z1K3fi<$?@^+dS+Q83*O+NSHj zz>O|JEc)Q|r+pN?t}jB4^PTKF0?S?#Xtq%>vuA{Vvd;(vMv4U`J4PT4R)BzuA z&_|Xd9zL1Cqo%Kn;a#|KjSe+cTJO^>u{K&>4xNAUaR&`3#=rBc0gn=NK6;1XXMyKx zBke9hl(-e-mXZ+&zb`O=Fc{gl+1PP~)Jw|0Qy0Es&`B!_Q8JXzb#RarqEf$ue) z3)!ULa|>;#gD_mgwcre-p8z*K5WC@@*sPGa3ml50LSHK)#sF~UfUo_a^u-GQIq1s{ zUlk&+I{3_yZa@v4gIVw2A3xF!I6^5fTNnuWOpdY@2#yW3;y#e{!HJM`u;w`FdcZ%L zQ~F;yg~#E;Bqzw%OyEN+V`__|ZsSBVQ(J6JjWnuT?F<{%sSUXd5p(j>P+<+YYJ!(W zJMutBgM{_Je4;@ibN}Z(=+@$G!7LChdzlkA|>av6ql3fL%cV)+Y>6TPHH=I=! z@|L*M<0QPPD*2hV?2N6Jlv>=?n0$Y&IZF0!d)2|9u>4I=~Iv8?UaN~UFXCWR8 ztYkn(VOs!5E79OCwM!axLdOQoQZC9sgL4K|Li@e#{KJo=;Scy1A4$`^=5v6BNC6sn zvb28hD{Zn8zjse4m4a0MyGP91>-jdn*FH2E8hCnW68t|g1XoVIKLB84KRo0;Ka^GWss-FW(n;!>p$VXQ&0ag? z{rgZx2@)6hWo$Y;i~Q-p3r4y##2}>uX*tY&-40Boyc1w?Gn%l%`o1N1nXDwX18bF9N@S=68>1caKGR0>$mfBGzZWhU@;(X&hrGjwPqYkN3mEb~ zG(=iMx_zt2;Ujs}?XoNXU6vwsDepb}`YkD|K9_Lbpr9}$bVerKV+tOO)?KZs2lJ50(j zN_b;B$toV>FKro@D=Q7R#=t7R3nu2#FYEY)7oa>@Ck%cPa1+c;gt;!zQVe8aUnptl6L=hPS9X6(#lDOBPut9&|*%WN8EhHF}Ov#}!x{7g?aA5v-Yu zW)oRWA-T;zrE_Xdd@x#~0;bRaWmuU-n$>mA&cMATQPR`YWon_>@MlUkz;kiU*$D|%UW zRp=(egV6er_kECe7KcXgJopSELnR2IL2q%8(a&PZ)HVkDxC;2bT!i*=qJd4K=z*T< zptm~c2<4NqD?;w<8$kC^cYQ;k7JOXmM!x3I6mG#8GHs5FL>Z z22JQ@P#yGYf?qosJu`1isi%s`#Z$mQlgC>mH_DFafN%boHi--(K5z`v1?<@9{}?n# z;^?Np!07OnR`5znli#a^LRY|mjCnPN8nORS>4+NU1()x zZYd&%f{*3JSU-~@=8_!@0Mr39{>Y=4j{s|HQgL%<~y zT^E8|FB+Y))yxIGK|kCM1n42A*VIytm`1BxmvXOKB3)-U9I%W5m$&5>S~Soxg(p|{ zZ)M8b@|@(8QGnF-a8pG;0AKxbt=^x^Tda~so#_6q4OHz}VPAMU`m%(uho^J>LB_!L<3S@9E^WQv?wESfMR-{T_WMTXi6)hSt<)J8W zHLO&)6b705{&>$euUY%pojLnlXHly_$*P)H8 zHloU^JWKgwQzlKBKFRdpn%vdZYu4qjUNwVncxE1Nelp)qt~_Fd5OGV8{nzslyu&LZ zUt=Ko$8Ntj-+s>7xM}06hu6+Sz&?}wxf-MdR2h2Gx1Vyz&_cQb-pNx5?`iN<-Odlg zC@EAS{B{C3VTInugr2d*+d!}8!?Th>sO5H? aWQDS|XfZ-+WoYJ(+iCDIMacg5BK{w?3Jvf8 delta 21505 zcmajH3s@6Z+5mjc%p@5|BtcN_kP9dfkRVvWOAQGONVItAh1PbBqU|WH(%P=}njm&- zYr9payG7{5*0yVFyCo>QprzRReK*nC4@E1jZKs0TiC{A%K>qgx-Tl7*dH(0m^PJ3? znR9v1Iq!MzXJj|k)=1&Md+T zWy%O;B1oMs#FG5Z-%$Upj;(FUym8p=GTMgSGn1V+SL5Bd1?8flm)*D(nXN;6+{>z$ zFN98q8|qAwmbObQbgqW`{yMv4rPbH+!|pn@lK|HMWvoy}_)lJN+8yQ9*>hV~+pCl7 z?A0xG)D<){d5x|5)aqp3ChcG5N_HmmyYc9WWL^jV#W2b}X!OKfxY{KpG*;?>g2Pr@ zq#QGP;<|;={7$&ef~!rUsAy+#B!?jfEy0^YhtZhqv_L(hq@rvRO_92kR6-@@27TtL zylNT-VO?$?M$2gzfqdAy32rvUIj1?2c*AgiS=q3AX_7ONH$c8H$r;NVBzP{lm&Q6V zl(EK^4Wn30o)23KW1$11WL=i*q}m!Pllfirf-85ti(BxV8%0!3)yf6CP$FDYA!S4Q z(CI`U(5$L}a$&rU?LnFCrMBwmP3Mf-qb%3oSovBTAjkjZl{Oc4{Y(^!dUm@?GJbkdyt8|{i%K1 zQ0(>t9!76@4@r*Bg&tgbQAD}FdF{jQP0H#xCpHa;C|~rN;GTl}A4SW14V3^^mC&M0 zO;s)=IO^V{b|M4gNOB)epuLIttJ1_3N07yy(-k-)X0>tg@?NV04ff zj&~w`YX5>fwl{T=r6jdn6M2p#o%6D|GLPv^T(l(ebVzi;-IPTQk-H1xU-GDvHB#83 z>yBNtGxF?5QRiT?)lS-1GwgL(DkGKGzV!sZK19sg{OfW+?GoFOH8YZT2UELnjN-~FTs(pFmX|mvqpjq zv&!JyvuZh>Qav%eHFg_NCIL#tI$`=_7pnEiP9z-+BBOR8tw++|gC?LFF1uaox0{@j ziLBY`f9PO(8R*Aq8uqaNy7V4i8{IpN!N|!L9^K;J#_H4kXbs`8R}B9Rx3EnPA20k^J*g8IqD@1qaktN|tLR%oaSP zOw-I_gUnEdP3gT^&P0ixo8(Lj?P;#W#Y~=Gcv+L+niNFYZ}(8mNUvzSLuNuH9i$CC zhl`ccSO`l`ji(6rDy9E9f_khE zA$Hy(Y?`-tr;+jBuQWF_bs&SDqokY0Xj7tb_CnKU3pd*_yXNEbiX!Da)43)}dVXxy zLOplAlah9YiX8Y&o-4W`)k&Gm4Op5!3iF65$u+{5ikw9}Hdman@NPs&&j}kRrQl9s z$0U>MhhVBh?LkuicnVyx^kFDDa!r)6GyuamIz~yKjWMREDsuypJ|9;=+ej*vm65A` z1WQfhqhb-i0<{AgvJA@H4`~ey<_isC5#&1|9fkB7q(hMQLMlx`tRf4sU5nBP8lX%{ z+C8RlSbu-Ww#I;-V_52v`CDjYBXs6?g!WUXI7KAHWgW;}V35TR3V~Jh(%@SDBhk}G#<5MX6vR4mp{vpiP z&4LxVM^~BD+8(zJnXmYM6R~v1s9z+VkzMn)@Quz6WnyEePc9l^V8e!s^_;G|q+_Zh zl^1pzr@DGQ^!Ai?WTv;%{%}!BJMC7SL3;g~i|voY43u;ulYWf?aH?(_mNtbBjTjNi zmb_NmC6Ua`V5BP@j9U*I@~beN7WC@6b%3j%gqd{ZsWmoAx+F(B26Bb;qoUlAz$H19 zoCanp9GD}Vi!F2Ig!P=8Bswe|Y5e1D;Q$l9`|fNQ zyk-0+J7cAv%j^mVqM^0|=rg?^Ne!|+6>~Z--bwGLqz6Xu9#T3^W;lxnr;+?dnM~dc znTE;y*%uBBj$@_%Ea^yieX=3#{gq}oun2k)T?ts4vnhTh*OQ7Cd3 z0vcNLL>mLJP+{5yTgDy5_!mWEf$`tS0+LxM;kTjKCi>;yhICKd_m3w5v?qpi+kf0a zKYzA;@-VtD+WQ1N!_v8N+)6vC*1Bz~HURk9C7fb6mZpXkEo2HVcz@WT*bVaAy+1US zL1*8Me=C=_b?}Y>g<|a*(!wTQ>33iiesZGJ{)W>k&oM&cY zNj=7JUJo*S+C=Zt?4fq4_uyU8d(OZ+G-p>1R4S4c>55Zid43tq=9Fy>-Foh4Sj-1U z0ieWLML-_*Q9SsfQVq{8!4fl=k@2N?yqhSV!UR($B!Z+tpaU6$?fYxC`2=mVm zRsPAfol|hTxI!+2J0oZBMbeoOCVfsH^dZqoBpHKDx~A_5&oZtQkQPhNz*_~pMN%i^ z;!fS-A^D3VhW?q{(nyJa$V~dBQwQpi+3zjnvdP3|j9d`atqZy6YAF0yByENwKlW)_ z%Af+0UWL29NRuCr5DEZTpk&+7UQCmGCKMe zm&-q8Q=iV}k0LD9jy7?>c1?(lFe7MkKQ`y`ojuru=OkNimyJj>xHYD#>t8Z*{?tC? z{9HyBB4T#`DnE;haAB`#hPGEAv-1?Zf%XwSczly*uujYLVV9IN`h|?zdc-BN0pUU@ zqW_4;bKIm|Cxce9g@>=^51oCKl@kae#YOD~17 zMYuD`n7JeD=I|ap$NDjgC1<$2+zV)U8#+Od5gilH0ml=(sfjd}a)r;5Zc^MjCX1bd zAvq1dBP>WR1FqAUT&SHHCInp9k!WB55uOx2NKPp0JJQghtk12RYLkB-M>iumGh0QOx8A37}c>^TfpbkV<}6R zpPrz3H~2c-Tj4%_L~y20o%_;%9?&BUR}0mx3Tirg!}LwS#EVH2&qPYd-5TIL@sLs> zMd+~LNuPxa1u=bAj4RmRr30x^2gvf^Vc2U4`l_FRldKPt&5_-e2pzV_tOvNr1G;WP z$>W7p8ClfSprDJhWUcH(J=dBp0Y;Dfixh-TWCfRW0kw|gGlVl4S+h04>@GdX7g$mS z6T4s?OY^`L{A*y_o!l8wNVslkuv+AT-zNW!S05*Mk>ejnC1R9*m7Ea`ZhzYP@2WKtS6 z+L9ur75;2=JO5r6Au!40hK##1GH#R^*H4=G-Y1Gg5SmOz^k43ddM-R9#2Atn=LYNf zO`d`+_)TQ|M%L^sA>_9Nn~;<{Qp#Ciu;CG0%+6Bh4Z!A7kS*0T0g!?#0bSyG*oGi` z0QzF7Q+U9Tk#cWO_yVCH8g43VYtR6)OT8#}wio5h65chWxmL*;3vuxVXAJ*|tZ}Dz zk;y(U=k;5-nH)0h;#VZ%6R~_@*FIbP=~zCe>!;+ng%?B}7tKlHcAhSu$i-CWK)o}v zuAgA&oA?xX-^fRow>a%Q=RC?cR}R8fAoT^kDOq^K zn0Z?p&{3!JnlzcnrSRuPrix(P<;dRgiz$5gdr}3NR2>wDcVa^#$WDVnFjAS62CS!~ zpJDgm7NvoL{MjJVPsk9^MP|xHnK7v%;wh4jUzN^Ex>W`w{YhA9GP&Yqg5*RcAX|ip z9aFfQt2446Z#xFWUIiq)PiFTrC&?s57Vp`zu2OCZ5Cj1j_S&wgN09!qh|I%2HE2VA zZ#b|JM6QdzU&K43pDuTM1xO4gUG*x(sQ?R@x|YqrvSMh3{x$1>vOhY--KvG>QDl1 zg<9M1`v>WAJLGDCrZ)e}(%$V``XXgHNaA%rrMT+fGtVgu|^g@bbGI+n{b zb%YnZ8b&75X0kHm9g=SD0uv99!FoZ=C-a~UU5A>d9y#bqedIZt^4M+s>aL^b(ac&W z>x}D9;V+BiPUoxwD~hInB46v2#cCeq`h9R;^uc+AuwI9|g{QL;U764erK}my#c94J zW({TaGTEe`3A{&(uqnwygAsP;s)kCPWkf80n207)r6LNr(-567MPe0J>9~8nW4S!t ziDn?_8#fxZ!aQl&gI7=ilG@z|uUO&Q23L21RrCX$x~Lqh z^rAa{xS{6bA=;AQHK}SOZIq*Dzn`V;T#b~esgd-WR&=|p?2ii4BPd7@%@~M^u@A)1 zi)5vxW}qsHHhm|femaK^M!`EeX5#>@!H_3qikut0%&@fxU|4Xs7a&`p>4DXR8k&A6 z?;6q!#6%h!a=N=Bokw5mJX5dNx1uG`adf0pnr>Q({o(81_hap(UTAb}#}%}(+}m-* zy3y`^{fc}2DL+zF3`Q#s@`_;86|5&EH2@3>vQou>M$zHi#9Mk_SIjs;+i}h&XS~;S zPBHleBWakLf$g+b&-mNQX-PwWE3@&7(iHU|5#>=kF^t2j}W9MC_}AC8*UbJ zIIywm9~F`5c@dlbB2rl&h;&wuXc|EDzaqp$jI7+z_HZBti0s5_>msYolGS!umV1)d zO)NNBZk;W@Cy@g!zcP|~$g;B?l=Myr>_1?4VLRArt)6wT3&DhCyv;ctm=jVuR7NeB zw1^dEJn)asf1gpJcraYOIUTXYdPb~BPmW>f2}qBRO>!jiiCr2nK&9}Tx)eyyNKHav zcE%l>KxHJXmhim*NJFuU@vZ_eUB`y-9$*+i3g(PYBGo*UloHb0KW;DfM1yTM*E8p? zTz>M#WGCGwb(?vWzX2s}j7V};B)#5A+Iw5@WGCPg!WY@Ms^1Tp_{5D!qU25?KPNw- z_6Ttd{PzAk--Cq>m2^Ze%7R|^3HRoh9HcIRiKz4LdcEh|jy?vTK+=lPxgB6T@{+#2ZP2!r7c6);&g);Dn%%oNJtV zt?`DArg|keiHqkuK2D74Simh$+31s~1;TeIx~Dd8;kWmkj(b zu8T-1Y~?=xx9G$3$#LHrlQ_L|EKn&tV=ll2Lbo|3>e|4%gdfavbI6^pqkID%?%lLk zUZlek#zt_z^xhW-)=t|7;xWN=l6{x3ATQ1JeRx8f(RE85TkC;NY(pkD&pck@?q%^{CH91V_piw*I*AKS!^paj)kB%(8xoz%H=K0tmY3-= z95{!Doss9W4i%HJMjIq8wnBGNOq3?c{+USSuszUN-M__l=+bkgeB1ZL^ZM+kU?#?OBPyi zzH$%v(#DYf2Qi7eAYS$eV86Dwuq7wS7YEhjym7ULjwb`)mu8e;#!du;M5sLDjsO#8P|D1d~8VlS!hKwW^3p$$4Iu`i82c*t=<-%O< zFOm1(0Ygsgn#kV>dPzz5>oY(}>YS0D&^vNSzQK~LRGv5_FS4X4sS`v@eqOjZ!(>Tu zwAg5$&X`;^7Wg8xcSAU^DAW)C3qz|nkZ~>tCqda!-Vl8)ObAqkF=-M*AdIQoE z*BJtD&LnU;VAE^zBD76jVu6X%VJq>;(C>$fXzAGUn&DUPOXM0lzD`DlG>*RV>K~D`SfC4M-Skyg_<{~B zwyC^=TjT-hUOGJj_Wi4h2l4le2R4qPYz^2g#sfMTW#c|fL_rCS&>#j6oeqe4ZXja$ zqJU7VyT${3!ZU>lDx^~kQj?p61BG8HllU6}OyQB4H_VyiLj~7)RsIA;mZVj@YqRtc zDxV+jxZ>6p9V3{xA*>ukx^3&2gGPQI|CTNH_>a5*lB7TtO{*ym*YRwz9f(J{%*-QI zO%bbU7HLBZHH8#>DQ7>)u{ z3hVeefvq|hqAFC?`a~#BR}5lIgA>34LRkZdcIeBNxeIJsWQC*xwgOhc-AGCgf}26N zw{k4-PoblDy$ify*iZ9ndrJ=u6^Sg~P??eQGVIieH#`2%8)Tv*ux8}E*aHq;s0&mU zP1I_DPAp*bJSt;@J`GI+`xfLF{}P0xv`Fp+$R*0(%D*nj>LTXLgR;p228Ry0+|sI2 zoxlcSv0~-x2K3789wnC#I=+&-D0I(C$lovDy>8TVY26{4%127|$QRbFTel{eSg+0N zU$9N{U6(SGGjKc)TBd-ni&GyMXZSTXQub9LzH^Dv~;B@K{@M#%{j{+N63vRSK!+~B< zY3Nf#q6r5w-)FnYBw{Hvs^HG?&9=#2#?LA((29PHPFF$ulgDYEF<1QW)^_!l;MW(F{VE!l7PmjXAImSl@#3IvH(&af2p-zK#uYk^o_J64x&oylY9U#~4 z)k#=ObERH92OMoFIJe}a)KNBovtClY({A=sb4)U|g3e7mdAq7&K*3GziO-1VAoQW$ z$kBt0MwKgkH#^t$_8_HV=X`b^-FZ%=bHD4AM4bD1Z&Cy9N4X(iL!~V}R>pHF881NQ z5x6Iy?)F5NtGPrD7YRUzK`CjVxv2g)8EY6Bt5LS!SDTDWblqwWo|#EIzl$`N4CQ0D zpq!vjm)uZEmE%&H(+L|((p)j%_Ox^yKaXyF+7{*eWK|P!QZFa;D9PRk=xynK(?W#s+}cfjA4o)`T7y)3=&w5xw?8_NV{6sgS&DM$_{wRead=bs?`Y(mOg+Rh2Ki&6hu`47OVnO z-K0L01%6L8Zhg_FJ|3xTXkFJ_Sp~E*XC#}OFf9t!Idfdc#7Vg$g#Wq{d!mgX#^rzQ z>y=pxGGFiQmC=$Zl2tL!2b}3CH&JrI+E27gV(njDp99FdGWb+*_qv^xtDbrFnW*;3 z?YnHrzSZ@xySe}Sl=40W^;$*7p9ox#Y8wk&4#Ja??I?Q}cr<9mE|CRy2uZ#+&#*tW)~q!K5`7_*ST#TY;Yxo|#)3Jx@uDUN_5(L-5XxpLFji@x)Q5 z_3Oq1w+Q~ZX$1{IRr>rslwS>7Wgdl05SFt7<Gy9&Y;wHDJw71yOdp3c{g6T9nVL53YGX8L&6>PoZ0ah*nxkGNk zMU43ch`P zcpOoOkw29sR&Of+{)F(ueEYn$BXuBJfKh$Do@=gzSdCK?LImuA{0x2%7jue~%?(G) z+E3IBKLjS6cyqyQyjJ*O!B};q@h(+WQX>U4I1k{W-50tS#nFJdK6QZuWoJV=gnXhlB^Js4}BwXYdqe1jg z=_PQVqAZ3h0Eg7y+f7eTV2#fAwceXQL?*H_OD*k z(|T^z`jqz7^3#)>pzk(>D>t+EF9pgZzXLZ=b<99jVXh3=yobCzWbSIb*4m{o| z1ATgY3!bk!=H$l%9Kb|IH5z#K{dZBrv^u``R!h0=dI;1APW9`wzx(Q3@Mt_RbNpx6 z)p8ASdTr+txHJx2f>P{QBR3j2JkF$F-*?!Lv`e`?GG*!PiT11T7rGs`9bD9DTv!FD zwhJuz^eM7Q9i!R(VC|rzLF+szGe>FAHEVlrx7{wA^)&-KFg3_b7I-~A-u0o3+{~cs zD^g6qyp}Fs>4cnR1>|1(Pp*nP13IJu{1-5eXODAzA}-d=Wb@AW)P5XIz(JYID=wc_ z`zcHSSqy+2=_Bpb41CEfmvb#2K{w={7hPWbGW>}Ou9tZC&lIlT57!AaO{1D%V@+S2i*m4M37v@w9r;EOUC>ta#683R9Kx@9?mb>s4ngg4* zrO;E5Bm3ewJTqxaK~B(1L~Xf)2HhihOF=H{on9SpnZ6LlF2u-{dYNWrY}ynlbeZev{}i>^Qjo`fzJAZ|MSH6sTYh5W~67 z+5KgJ0nf`i&qhh37!s)&U?|*KbY>9{m3C;M?O>F@IC=@-A0Ab}PSpcp`D^H`cv9B8 z3I{!@&L!Lzvc7CA@Fh5%#{=ib8Gj~CT(NgL>sFaozb2QvKR&NCX}}i1Szh*_ta+eZ zPdKN)kW7^Ohh=KhmAD3kA4g9DS_cM z!ksIs58_KQPd!OgSR2G|esrE$d#W)UC;;L`b^(#xmw3VfIx_ZsPvW9|@Kz6Udr7x~ z3q|Di&*A+Lpm3<~(1^z3=sNdgpHh7y9GDa#fI83sLS1++iQU=PD4m%QsKed5?vI{~ zn+_|k_0sDe_I#Y`qp2GYn5`E!MZIdEu z{NIIGhe2IE%A`}LsQuxFJALFlA2gDI?EX_~@>bb?Pn#?m!|KeVec2 z4>;pIEl=W^EijD%psYlx@ro)l_C=X~5^1UX7?Qf9F-2Pxw@( zW5V1;8M9)1=5;Cc`#dCmr@4}W|8U@M;}$@lUO=LT?!7z{A=VAXxkTr zXBOFSoz8VtFsJ8nD9_(_zws!z{Tif}*&y%XcF z2KK=pMrgnzh)&E@IQR3-uu@pqv)G`PLri)!ST4eWBf=+(3t|(xblt>C(aa-Ho~5C( zQ&8NHk+U%beoQ@a!YCmQVJvW0h%)Itw9&ZP$j5CS5>1;YLdo717T=I`S3h{+vN_Xc zFfV0Yi8y+sj<|(jgjz&Rqo*5rHJ{R@b~>C=_hi1^Bgnd=QyzJ{LOyvDe;h(NK01%G z=67NJa_7{|CTGUxWUh|;MKn8?JJUDI;&Si-qMou zZBO+aO-6caIg-pm+LC%xY!DlM1^GxV)8NB0Jq_~QHkg(OsALe}Jr$lcCM*~YJOLiJ zi|uO9G`Dx*G(%GzH=) z(w3&FI0$?WUzj75EzNN~G+ttbfUN-D+2+CfM+5K681#hE059izC=PUw1u(7Pe^fp= z8rUim$F2ns1|;I9B7WbRE?^QxULrjpLwXg^L>9){e>Cx|yya+0b=ly#dy(lvC~p}B7KUCwK~tHl+!lk zYv>*eoEX0%QjTZU0siArb5vfu(3ULl?2f$~9wwk)Fw2V}X`%Vn21&%J!BG zT|VS~1w1H;`Q*m}X#FLYj-yb)S*-8&^U{^%h3x@A}x0E9tg#!LyDZDBZ zQRWIkb)y~c792NbxulS_p7_x~@4Ihj=<*O1ibHBA<*?h4-r;PhBvwI|D}=azDyO(- zqxASyBVNoQx`TcT5IF^dwNL@dJc%Hr!8g><@#nU9@E$2SW5)@S(V2m`XBN_}NPXrZ2LNjWf zCBkji8QIw;$Y?K76Og3ZcG#b#h49ECN-*(DVQ%rPlfWeMeh_55wl9leMBX6<}$JY4nKx!%KmllFR891Gpo9%ZiSO$4*Zv5xj)#dr0wiG zP;Q2{H&V_jZEAwfx9k(|Iqbh%tA>XNOg{iC|KFz3mgk@fA9?HEcG#C|MA^u4tlN98q|JOls1RmpChTFvU{|Kt_zeJK@{wZBtl<`qHwOwnOK{uM{HcK=c%@>*ft>MPL)PZXM1Wl5Yv-8$Xn%N)1t@cK zrHLn{Nco#NkXg;QoH7p#ZffCZA?Cn}^0>JQ;lN-tjaweH3ATAXUxF5_Xd$)pdMu{n zx35oqs)E^VY5HRo(|v6}}nJ4Hf{j7jf&6ifG@9a+ZEp zZgQ^za+&(cP>$^>G#PpDtiq1kS$Q2e@ATZx%ESKf0)_8DDyh%Fjsr33#V)bXbY5KY zC}OK1ErNuOhQrXJPR|wQ2+muly5^suW`SignpA79yrsg#n@#}+t|apw-&0{&YiO<{ zbIJ70Bmh|Ylrv6z{L$(!+P&gQ4o{y1 zoA*}OPtVAD3t5yYzBW$L&-%k9&}{_p%8J18_kne&=;9vm&2S&V#Fz9S)0Fb`azHuu z!wT%1U*7x+0W%rU4=g(~hQ0Xu8JA(_tkJT=`Z@|Qcb#^#@8A{v##LZiP(=~^ANiHS zC>wU-ihH3+;r`okbLE#JU}90sTY7F;u<7#3U=u|8O_mc=n=3!L2IPX~%KV?R zIW3VYpCz&wc-9|Oaoa%!Ozkm&lODEUR4R8Sp#&n9jhq=Ut34c*dzkwO;+VICiOn+e zK!pfqBN@xb#h0pGoR;B(;Jaoyb_FvKkssAYltJ8qkcIoKD zFJCOLKXi$EIP&~Vxx_Hvi!Wa+d-%|$&mv{-IAL4JnzUJ1|MJD_>vvt$2`m1P=3+|^ z0y!D<&Gcjq{JaSlC71uzw!dd8H`756eo6}$(ZiNYD)q}3&HrhK>1)5lJd9_#;knAM zU?DhtFQm4m7j(coW`sAw8Neqww6iY-;#FGh-CqEFr?4w$&i>ni1`|AyTqy2mgBh-U|;a< z6Y$E6B0bn(YJukU61wO9^tH#Hp&^1t!5!u6*QF#25C#LW|K?OK`iyyK1BnZnbE=Njj;d& z>NGh_0Cuc$UB^>4uwwZVlXcyxTOd9s?{}Xp;v6tsLnuvnWlF}=U_<-8k8)sRa>KB= z6h!q}IGL>LU>CtjSZPcsb*8v(hbK3}n~5`Rd;NO4)>d1_cGHd&FprbA?mt2_KT=!Q zF&P4Ja8bIK99LD$ZLuYt)H+&u+K=k!E2yZ&7JCd!=`xZogyD2w2uZ)g^(YARSjvY` zV`3M<(uGcNGWH-u!D%zf#l8j>Y)v&X5eqiNh3O0)@{dbxn4CN0iY;Huk#ed8IFPrkvs#lAh_sGZ{5{~vi=SS8qUh!zPcTJTZ+HD z$0ORG%Rv2~D^*CF=#RsT&7T)mH5gV=vVN?ME92OtF? zJrC&7FoSV0W@$O_Ij*@`rsti#Urk{sUMak@RDuqLr3tFmYO?(~Z~!(wmynKS}0O zIs~|o7A9e;1)#H39f>>#)3nqXCO*i0w&}eJFw~I)y->lb5MWuX*P6pX<>AEkw3My| zAf%;iiEAjkJej5p?EZIvZ^Jp`af67m4vV#*f`H{7$O0Yy0)j%2GzCskSf!1POz~IZ zOaOFqWJdnnI0X)cSS8m}jpiii9=r|c^0r0@0CAzq?#8q73vIV@Z`tB~pF@@VBV&7@ zF|*4+&g0I^fOFhg;Kj@;f7>?2N9K&BIgv~_1ne5Z;1&Ulf%ui9msd0@o9R7N3kL5s zp81^!d=A7TBz;1xR&X41g-d44J8f1;5AgMhWFoJRbhe-oWgXzk`pNDfSndXTvmf$r zLn52FR);dlmLwRD^5^;)_VlD>Aisa6uDc*FRu9J`Yk$vzuX{=b^q8)@pF|DR305ozjg&{B)a zD(!Q#W^{S4o3y(5KdrtH0oY34{|lMpXCgKJ><0XgAHRmrJ0eBgbX}y#BT(c~FZ*V^ z9wJa6LYy(EcB%mDw~P_>6>x%-h6C@5BBj?t={vo8W9h<#tVx3u8Vgj9K#l#Xzk~xT zuhv)*sev{X{jvr?xDIM8?)${mo}ORbOJFL82Nm9$VQ&MH-XCiM-{~>Pb&XAPv{sb* zvK-B}>wIVB=h{e#iUGCyRv6!FV-w}y7^|&VFnsslVNb+u{$*n4r;bUUhf^o{$Ub5B zQ-+Csk~Bs-Uq2QbkrouKb7(1rPBBOMN+I@^=%noI&BJ&{EF2545&PTL_iBcJC{`@)gRS)g z><-jJJRi?O+6%j28(ej42eU}e1BVnQ-E|Y@g}S@!F5(lR-z2t&yZ(~A5P3cEj7sMcVxMY#Iu|@;yg}Ho+i-fWPf3iQ` z76bM&=p=iImvr(5bds?pzW}-@NQ`uW-y{TrgL8#sGZ`6via+zTD0%AFpnSf|f(Lg-O;l#i5@q2xrllp!Bg>=&ET6U~<* zUro3GzV!2AF;J^tgnQSmsJ#(F`()oVsEn(DfP} zm?l%+^jKk*ra-OVeK}hSKp`xRJkgLRUT|DB6mUw+1$zP?4L2yR+ykG3LmcA zHX8U;c(%SYe=o1^`teB$d{T7oMIQsFf55CI6JO30^fRFPE3KmWI^G)+DO$EMGK z4HKe2D~0~MITyn{4brJqYH~kiOW-O`wgrp0z;_tFPZ?z6!&2!e8frKiP z=Dm>odq(hyaW*vd1N#8BD?>5*toQNPeyTU`UqO zkglkFfG$U&nDI9%qE60BLZHXEB}L;K6;{_}s*x(0S8g3pT3;KCVbHWR&$m`&0&l9l z5Tr!u392jnJpl^kF7bVp0$|(#0LXaS!O-}qK@$^7Eh-zJ%h-@+XopR8^1(z6074xj zJp8zIIP&T#5UEf-j=*-kj7XKGnl{M3uPC*F2c;w`XK%L z^Hv{O5zDAh72;`9w zq7Zv^gfM;cHo*w*JxP_6mVcEDbH{BFKlST1bWk~L3~Gi_?fRf5fP>1Rnt}Km3_*=Q z!#z)Qx)9FH~mzUq5PG>Xx#Ik z39KBzl>mm^2@@!iRVOSG6}pJy}!nDYuYIKAzyc!*g&jhPrDI zt5iYF=w<67uucT5FjLdfw8*Two|pmNI5os_p8qA08~epx@$<3HK`Le)oQ1=8S>R$oe(3575!O#1X;LYC|GkfYk2FBiHCG_g zq1#Q4%xVcfO~Y^r+dmpoqnr5@&6I~aZD#NDPj=cAKCIVdDMHA2Ge6~_vdh5gZF;Zm zGKOoq3o_(Es<$lifbF?0YjwJsyFWd;T(Bh^iQkypc>2CXS8?^M zD!C($FTP>oyFx{dV)&jCeZ>_=UwLeKDEAs(l@O00}bTF$HJ4XV~jZCXTQbkC?Wx=&9M8v!pUzQZ6Oc3@T<+}*tp|TfH zu&x13udu&uE9oKO&& z^fk;VIafucD;$a{O%H3p21;V6Bqw7S30S+xdve|ilasYoBZ1klImkVHdBs3iu^l6U z86y-#;wC%UZt^^lv~{(t;Xh?5QkM!O3HkR!)S8TouZXJbslAgH;z1N=ImF=Fhj>rg zLwUyNDk`M7?5?$V*jx3U6%ZnIwB0)FhEG>bU}z#Y0%Nndz&ZniVX`OKXk0IusckZy z9|cMrLYkgTDU6X}xtwK5vMU@(Fn14tueyYIq>Pr3_%T!_6N4f80#2g&NC4bPuw{${ z+Q72$lQ49DmP74mfdfi(FLlK|d8;kDmyO)BSMQ&`dZLX)7)7>Ej~8a@CrJ83lQ=6M z3z5s&<={_SF%sA+tbAaKOSPz;PgxfSF>NX@0rznk&%5G-@KRLLoyd)fR>vYRGeIN) zeC1$?XC&~^7z6P-L~Ys|4hGghgjfkgh)rgKA}O^WO4UNCHYlZtl==jsKZAiK|EpXZ z98bhBzUX5J#(=CCw4*S+&dq<3j0VeetbqSmIG05I!E2{BuV%o?t&W_QSOblZ1n!Bb zF$93^5N8M7Dn!{;e!tN0^{&9+Hb=V!bC+}_t5W<0VU;U| zL4?qe5IJIqocO1B#)9=T6MJy+06dz6h}WAz7b4M!N^n_Efu;jO*5-_qAvj^OwvQN& zW5RA2idA~ct>^T!!-3C*m75RZVj*tJ>n3KQ!V%3=!~Lt{;NxNB+iByX2DTA{f{JWo z*boZL70zx+ay1ae9Bf<&j>qVYY=@N(2Na|FY%pR(&NHS}>!l1@*Ks5Nf-TGY?fQMT zOdmF7Lzok7Iy$tKiR+qoWQxPPdT**=v&(v2hHtnFOxw9BzLxdiTlLcZY=*%4@9+`` zEhVyiIM4yu2}In~C!%zStWi{j1Moc(j)v?0uwP7dqRdMo0jycr^I*z~>`dqgMH`q9 zRg6Ov^@5G^QxpUrE>U__*$k)y;lN+Qde22W357z&U%;LM3NU=z2G}pO^7nX@x$3@q z{y01To&vb8ici6-hVuC z6|@f(ubj7GX=()dIw7ujcdZaPAorsh4*3nzgAQYZJ8n!D7VTu?VrPj*0jCAn$S@-G4e+ zx8Y8-Vbz9%8y`)=DNAaLZHxX`IHT~o8J4@&7S)v$78cf(tU|CR!q$hbpAOKIPE>8G zHVXd9iG^u%qTo7laE+{hb+D-x~hiDiZ2 z*a}C+cf$Dz$dhTEGM%0P6n%)%EO@AY@sN_7Rg1bm3Pm?WAq|+(8%SB%mAW{a*wnB7 q!tk4S?FOz;Kk|D6i1Px-EnyHkcr{O6MP9=v93eZ=hOpS3@c#f(gN3yK diff --git a/boards/auterion/fmu-v6x/bootloader.px4board b/boards/auterion/fmu-v6x/bootloader.px4board new file mode 100644 index 000000000000..19b6e662be69 --- /dev/null +++ b/boards/auterion/fmu-v6x/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/auterion/fmu-v6x/cmake/upload.cmake b/boards/auterion/fmu-v6x/cmake/upload.cmake new file mode 100644 index 000000000000..7319b46df3b5 --- /dev/null +++ b/boards/auterion/fmu-v6x/cmake/upload.cmake @@ -0,0 +1,49 @@ +############################################################################ +# +# Copyright (c) 2023 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.px4) + +add_custom_target(upload_skynode_usb + COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} + DEPENDS ${PX4_FW_NAME} + COMMENT "Uploading PX4" + USES_TERMINAL +) + +add_custom_target(upload_skynode_wifi + COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} --wifi + DEPENDS ${PX4_FW_NAME} + COMMENT "Uploading PX4" + USES_TERMINAL +) diff --git a/boards/auterion/fmu-v6x/default.px4board b/boards/auterion/fmu-v6x/default.px4board new file mode 100644 index 000000000000..dc58fb1c88b7 --- /dev/null +++ b/boards/auterion/fmu-v6x/default.px4board @@ -0,0 +1,101 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPIO_MCP23009=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=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_INPUT=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_HARDFAULT_STREAM=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_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_NUM_MISSION_ITMES_SUPPORTED=1000 +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=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/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin b/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..c48956fc9e34e53237080061365a4f7f60335131 GIT binary patch literal 46892 zcmeFZdw5jU**CoQVGcP!CI?_h0?f<~I7v7R1T=`&VJ7Sx22B8cieT-8pxq%n5IJb9 zG)xF;1Z=_BHnZUjKIv{{I65Wb`k5`RJY>{Y>@2*L^D2 zWSLK3yIcw$9ZTQ&-!USXY_9UrjQ!EvZGsnChsvO*=W!ky?~mxYL$#lE^a# zh+IBM_26rh#O0 z=jodUj_;s%{5iI%GM{N+7JTiO948fhhN-`Dl}S!uZL$_U(r27h(($Zol})zdKKQZRPM&O ztxIkF1bw?3eOpfNH{gE5G2~AwC3IeFwtg4hmt4O$;eJl^9_3}cm+5<2K2l#2zE6tQ zhkLaCZ9aE2A87}5jJ6?L@qI}~7S@_r+2zWtXGoION*1u3W){mZb=o#U3}mUU#k`mp z7}F`Nu3cuh<47|c#}uvcxT50)2cBmnTkWzg^2Xpeu1udx%TgGjWsfUPp2%C2aIkCS zlyVw%kTSc>q4a5#JBRn@ke)(%YHlKG>&i&BA6L5Y>>{3BM0y$NWu!7v8R-S27m)TN z?Vqb_jrO0o$daFYJ<>x+mFYjS?S{9u0h4O`bafO1COGtk zfC6(|9oz5PT;*nR8k*x=o82F~i9p|9Xx@&}$K1TZ@-C4}-d^cu7JTWCt0UQ8d9@C# z#s)x^nGr7f$&AmvCfswF6=MF>Z+W*eKiVgXv*^J#^uQSHLCt6nG=)BeIak9(Mgoi_IT{;NN&yyORV<}meF{Y>O3bAEO1=cCWA zMV=kHx^64e8Jm0l-%8$}&75a)|Nc$MKWt>kb&5i%4lx0$KyOlJ03rcxDKoCWt<0}% ziM>-T#*5ifoF`q(bXr6rUsEzAn*J)3;vvFxDcflfE3u|8MdmK0)-Lm0ZC^@Vl%mZA z6{8qB7cJDGg-XD7-3+?c31(f(jPv^gI)2J@?Kv*sv~yQW?Qu>Ke zVoPp%UOb+0pn5tdG3Z)22V&PVul34io!9kk`6{$e?7`HP?bC+X7SipQnH zmGLFgF49HEWGtj*bS*0-PEO!fq;r8>p){v~ECd~X-WKxFG7}4dZeRxnC>L<2ZJVYY$0bLa{D0aF`ZD-Zx`gPcDvkV zKZ?98Q0Q6p7R4bK`UP6AB^O8+o%?|pqWuV0a*In~eqS!~VmNqb*x*T+e*O}f&7Pm= zWSexYsgkLOVN;!oKe>f`Q*QnZ%Ej7Kodf>Ld~Hi~C8y6gshDr4`y%-se*VG86cG95 zfs)sW_Rs5>ENzR{%Vx!TQ$43l+V$A86k^b}#;)faw9eS|iO!<+3g{T^_w{{P|7qQ) zpQt~1c+1K7lV`S_Nt#Ynu?Z;?CktlMcCZiBqJ=q3WL{z3C9TnWKFirjWNvI}U+vhR zI!<03E7RxKuSA7eKyV!hFzkQI&$uK{F=uHy-4~T9`*9rzm|1gH@a(6`3;!(c*%SAV zi*fQ2gqU7Aiyen#fpE88?;&&Rf4+;3`~S=M%vtj~=@`-G6obMpDDFwNukM>-FYZan zd!TPhUUAR3MGy8(SybFJUi?Yl6tTExLcY{DCBL{wUr^pRrJ%THV&R&;DTT#7sYMli zQ;Ldv(j061rZ{N-i+j=+qt1_`bN0zuIvzgjSDkdeuD3-9v}k!Qd36Jm)aS}QJX3nK@I8Q=;}p{oUupwQo(FfT^$44_h*1~C4G zL{3#yB6uS?O(~Wc?W~`wCus-yz9}}X_rH`3Vs@(n@!T>c!@{}u<}-8o>0kRWo*G&Y zs}M=sI;91B>T5)vJV?xMw6S}MLDlplg%9Pn(0UCbGdD(FF~rC}ABveC^pP2S=W0Xi z#at^RpLs90mEus?5)NJrXBbrlG4d_o4wa{J5 z%g+tYD>R5daPo4!lH*`rlf<06(w(f3UCGFkhCmM(POcr{g&b#&#AGizZ;@PtllP8f zIrMnKI}HUdZYA;`MjEBb1uM&c>}2Goku+d<{YWZ)KfrU9DRl!eO#wc0sFlcf52)lX zm2^j(o5)=wX-FCQ-B4;I)hmqL6=LMKhI#qjL0*U{pkI7AqKbSuUr|R=`v4<9HZtVT zkyess(1s?^2CIf-G+|!u97D9P;(iP6t8nGvD!{cES8E#4{%k7I-aeVqK9a%9+Xqz+ z>$RWSRvXE)Jo zY0$hUK=Z!C5u|&I&2iywh6QIyo!`AikI1<7*?o1%s?da#r zW^GIS>6oIWip8?h&GxplOQpT}YDcPs%c*T8CY9rwKUJjP(DK*EO25}qzTyUS_h!)D zaPX%iwdn6y$1N?qI7tGeSe+HOZ}- zQbr(wcn$Mf?L)aDCqEZvM2oxZ(QY^WCLBBzp3ueYBUx9^j-AWQF`z_wI2Sb>8PA`&Jyz#FU9${723k?N${fNlBj6 zUCf-+?G)ok8=V8XA0<0L6+e!9S-`9RdzGo=lzg}-;WR4RY@mQluV9CqF``x`eIdIl&w#NH=saD!&x81*mJ|u&c$}CbBiXj$Ey~qy17F?cX6urgNfukj2Eucanpv0n zJQ0M|#PDS^(mcsn3kqdU-$~>C^{Efl4T$81hd6mfP6?-}`#LI}xtDL-fBnq)f6k^@XB>Lq# zz&&Jlg+klszHqQ-gfV;?S(DtB+UqlH0OyYxc8$(3F{H1#&24&ghb_j(1q@7qo0H!h zj?S(@%xyJ@8PZpNEui@M;Xc2vg?p?v3Ul9)fWQ^XcMnJ5OxMb0$NMN`exDOl754a< z>@Tr<>42ZVJwn>vjVBq0anYTM$)Ka+Q+*ohk|?xsXTbJ~>8=sp7@VLwOcX z=0_N_My#goQ0n)c{s>#IHLJ6ee3?~zpa6Tvm%~nXwqy{yAE=Oo2Z_+Qnvti4BD8Q? zdlyY#k}|7M7nQB(96`FHb3~;(VNJ4I|7e{}>pRg*CB7VYmbAjTM%w4>@~26%|G$7^ zA@@B6oU9o(ct7x=aD6Ms19AI_}WF9B|b)#CC)cFA#w$P3W^a_>g8-z;r&_DKzD z{#0faBkZ&$+iRWK(lPXlE4^`xd|)v{+x+h#0edtf-!VE%;o#9>d{OuPkqBGW*;?Os zXZMl89}m_kb@Yo_<9xzaRW|42fvH5c4GCK{*(zUll{TC8(I>}37Eo-tX1yGz{ z3;a-D1%6O^cO5?dHjZd@*aL{XJY)dvr4SSj_P@7YW{Iv9&{6zk6A#$Y3~|_FT(NxM z?ii*X6v4vQV@#Z?9=)%{%09W_tsUsqlUUiq%4C-wdXgUx)++p-STF4@Cw~!Q8aOB0 zP_|vugkJqZwU?7qhtwi5f93sbXQ4+fbu_#-;E=mAKnbCyp1VV1y}yyx0Y;!hZBVQ=B7m_3;gCeOv=mAKO6c7vQUT ziVC!i?nPe>m_?qBqQ)S84k+0&a1GQaPSxk1(xQHW?1>dWxx~yR!bDKVkHb8;kSQ&i z7uaXjFMM)|%uN zD+lHjfsZ!ZeBtINu{xMRa&s3mBT;(0jhV{K&$KR6j7>)ZBw?n{t{AQ1=FgpfMs2h# z({Qc%*NVk(ugDpuZF+DMxZwHSJ6H8F93RMI1=-1U*M@_~!QX9H(wi9BF%S+8hb92` zK;uHZAUqNds)m+hAE2!hoRQX-D88B>4kisSmO9(lKE|N<89*dpW>AUjy}FiT zJ9#lpHSW}{9+zZx+keV{>dnP$zA;E?-;~I%{ZQoBGuXY;-cQQ9Yju#xh}^9Zw+qsp z%AuFQS8e688DG0Zc`7P*eaqVr`PInxM*LE`NaRO6ya+8_%Y|mnVHEY?FOGnhAhJ0e z<%je}yq9aj26rRoo{MO%=v;;T85Sa+Ia1kz)$HF>$;#&;ueO69oF7t6=0Q_f`FPk2 zjT#@AP7XtY+lWzc&_Oj1aNB!SCW*=-X7u(AXimAaR-3kUJa{@{81(0Y2mD-`;h}w`(m^=* z`*+M@i86LUw-Y+jK}gsn9Na%>Mr+H$m%sm){6?hvA#ohkt|RW z%0qa&W>#ADpeCX}t#2cSk0X2}R@yM&r?^USmySb!s9kEJ94X~izN5>HcaW)R z60?A_#uX6Bst6@fJ#b@1vYXEF<`K#XL!*XqemX)7;Gx@Sy%AdQA8-UR+Q_#!LdAD!=v;h92IjzZsC~@Z zxJdhPE+TNNqq9Mw5#Mabn$Y>fT2d~It|hxwl@;Stt<9=qAaP{5h-u+=7X3;XodL>= zDv;03j?BB9hGUmVp4mZvZyNpmBl7ef_L&itSl}iBr)K(Qv#6gp8#8`1e9#v3ISs6w zIl_y}>01?h(}cTj+H4T@b7={8_zje>qJ)05gjGdu(%p5_Mo3GM68pn1kCxDUQ-Zxo z`!6Ma5vfCIJq5n{FSw55y3R)t;g*(d5<|J6$GTRo&B<-ekgh^@O@eHiCfVJI1uSSwmq!Qvk zkF`bS`g>furr<&|E3XYx%ZS;d$C!UJtaXF4-K=Y+yx;Y{L+<$5f08>ePvPsZ`TtJt zVC6Ev{PnsiK9Rs;6~+6T!X=;&cSrKZaIOc^$DHGr5`iP(U~BkGaNF;M%pF=4$2xFr8>;0nsE8R&;@T7~&Y2kjjfq0UtUQJ!`3+mr@tThx#nIwN}x z-4TdkBzOh-!ja(R;pltp78X|C9VX^epal#x)I^9W(zPThIaap!7_;5R`wFVs?F6zn zB>SAW>;U$k0pN=EO`^?haY;qs5+@d+ddKG!vzIJQ^-{_K;;ROZ%wPC-g`H%KI#oTs}aEC27XAf@4LjTD==&uNzyIoqM5 z>mB`;r@PDz)=GBUrEa&*K@5O5ccU%A7p>*RNG;3Vv4yOB7}_YOGm87Ut$Hy{y5#49 z#lIQ866s$6l5Y4Pw2wr9cFssODteKZLkba0qT0w9c=_sRo<;s^=)85U6t`~NCvGdh zfXjwuQSMcEK@-v75ZR|(?}5fhCrdWcft4B2AFOK}c zZ4qMvdWMy?kisbL6KGNh@F5QR=zn;_!COa&`K<4xKl)YXhy|F&nErGLvm+dFp7hUj zZwsV9T<#nMwGCh9K~Xv9v4CzFca;cnk-8T{_uSsc zC2O-|POG8a77SUy_5{KRiSAl!eJOO4mO+fq37R?Ml43{M39!)2B3C+H>m19Jn@Y$G zB6qk*zZLWGvGmPq(x#gt?~g^N`GbX z@jmVcDPBQSEGK9kZLb8hT#lGwFc=z0iK1%P4sy!aL9TClk2c=k6VKU~6!(bnoY0{V z7njKm#`l?fIPLl#jxfmEd$e4(v&zf&TXWEpJ2rb8uaex;0m9jPwcJY50a`}CAw60x zE!*pS4^nEfFVcF<_125!jIqVCVQd4rUs1VY&^p@S?ow11CJ_F?djTfFaT+a@VeIP* zycqfVe6-_|uD8>nXd|uAl4yz8dk6z7trn}5qfpOPuH`(8GCPA_%hZsi4(P1V^3=fmw>}wj=h9h z$C+{#V~w+=wCTi%mfcX9PruW)@N(M#wFy)DqjkW-oIy;Q!m`o?!-3L~;KGnbNH7Sc zbjKM9{{HRoQVp48rr&Y$iy`PWas4_p22z{e6Aze7lQw#YK?8o9V%+!l-Vr~wvuWhN zy%*JaQCy??PBknQiFeYK=jEx`DX|NJ8vS5o46W16%d-Y}`-SG)+_A9I%yECHR2s6R zr1hyzy1!&g+CU|lxE^`f7k?MwIjD}G@>S3WSHxp)OcWbDbYJOKUM+jIqRGunyjW(G zHB3xuc^Q!}D7`z0!QSs$)?1s~YOiRtU50nrJqp#z_uDF}vPSio+g|ayZS0w26M=8N=(7q= z%*y+$Y*oe5v{hw#%IgRrNOaJQ877L?M-#qGt#NUSr-9qsHVmDcocT>Z=ZyBV68%(< z_OlYQ^%=*MbfaVRstre zZ%#}h*+Uv?ZOqAUJ#n}*1U@*V{>rE~O+V-w^`|*H$<;!AxVAMVi{#*=p81nJHgns2 zF}l`9w3nEtD%uHtQhQ6Q=xSy10)F`IWnabjbp9!A&21r5-u% zz4Dc?|H@Z}vNFu(s8sz?o4w+csl6goJhecdXZQ&#-xcbvD6KH9kIPGTmX({<3o^qU zRkmBO_iYf?!{5fRULMa1>-VjaP4xaRCBpg@&or{F)5R3u2plRVNZJ)`Eq zQzmBp`w!Bu3_lqTP7Mp|qvh2_v}IbJwk@o`5YgRG7@9Gi!rmB2tg`U=x~P9k<2r*F z(eT~?=80ey8y^e@pBjnonR1JL9k2s(b-6cKFX+^QtdZk*&WX|{5`rB94D_cuqX0TrE zjGKM09fCjEQk2uh($da)#iiRU722luTkm1|$&yU_Ly=nQl^W-3lCj_V&@}f+&rHhAyj;29I!2252B8*q)<=O|AZnb8~A3sct?c~-2w)pJsL3AJ7e=|J6} zYy5_*tZZ2XSR&J&XzGZR=nTEGx&ysqUZeMBc&{~9u=T=PRlUaX$tCV)BEK2R5wk?T zFj~GPq;9GNTw3`=vS=pJeyp~%q=-*889VCNCaq1*TeY@v^;!2R)Cm6lwNsHgRePBF zZqyo2Yn%t4+ECeAlNeh_-yXlDo0kop%u^u^q;1;QRge^^)xiS#u;ZI{a$7i2CpJhw zDu*62`FY#gbt

YRy(7?6G?2S4dW#_gSUd@Q!=gcLE;)DhJX5##a{oML-i6TTUbk$(MPh`v!|3744=7^QNsjp zGWPBGHdbJS?Mk(!Ryx+_O5U!xkn2p?uGBz29T+&SY$wzbzGI{V_4P#d-@{ZgTlcI| zM}~vyVPc}W#E67896ZpLi*-;JW{J;5-tU8kQSXW7`C%$eCR!-or--(7d(itN5A|Tt zwQ}nkpm!j~z4<{ugI{WoybeJGwwNdc=~MM>lt0w9>`|I5DPoRWhracMbg0~YN|oUmbwWo}?x#;v)oS|GlBQ-OPd|i|s%xcfeC?(1FxHg1st1|_V#-^$UD*OX zU}BAHYBJR$!qP~kXlfrq$&!~)ceW(-pT=tGz}wMhuS=9>zV3|b10xuvOLIIAdX05X zOf47=CSm-$4aq1shD*jb&q9~!!n3_dw;+9iXrZ}z1i4o&%K)Ji>+Tzjrb*Df9arA4 zoKp5j-cj7S3-4&kN8Y_;0gROp>%}~Fxuu19^vNcbn758(7W(MeCORWMGW@`?FWRG| z+t8zrPy_A7JxFOUmLQGxVli^Nb!HLpX(^Ic+D!dFTgvs5Wyy929j#%eBTJvsWwTYG?R>*8x3+PYDaPY^2 z45VExaF@>Co8S;B-oiI`bZ)r!;M<~N$UkQh?bepKLJ1Hz0a9_yo#`U16>0O`_orKO zB=Kn_2AK09XbZF+(*r&pRHXrX-FEPvbg$L5*rbJ3$VxiVh?J+(?>#Ggx?bVhUAsj{j&O#iHkziCP~Y^fYO$XqcNKHH`> z#2YjrE_tPNv?NO^gYA2jR3V*oZs53%ta4C3DY-POybN}6H6)QzDOQ3H`W)J>y1(n8 zRg(LvYwNOdK|aFi+w7=!S!t;hUlb>$TH_o!uu8`{mDbfa!7s=-9DHM-3>M zO9JU-b+#%NTo0Zn?rqa%6v28U=#EvLfk)dN3O&Wp9@X6u_*yCt_-bE|}`1Jh5#bjDyaj~4PeNk){ zV|vw~kz~I~++X#hD&}StI7@9vb@j1{_e#S-0Tk}Bdv$a7=BFrQ!H1Zf=cQ72LltZ; z64!fz>ulaf7Ab<2z3SRnB)w1)kq5rV@emW{wKD2q9)a1zwyN|Dp4LlODTmr18zg-` zorB85i>lJ6@r&u~sY9x~3(`ws<-5+vJ9||+ohJQ#=&EEX7>IWkC zxvkV=tzC*0U2aY~tlY07<sDOMGAw_i8@1F9}=hpi06fsw-bF^W+-zRdNeoecPdA zaW#`t{Q12z`EjS-$^9++v(v12c`GjcIwmtD*3{lwnA#9n>WCCJ6xMEk;r z*=hzd5ukC7Pf0JRw+i<6mGoS>)hG&Lho8i0twiYy!>!sXx9nE*?J0K^_bi_9?!8m_ z38xyl#5--HwHLJI$*$E?t=VXA7ieU(tt0=|7C~F;qFO64z>ixWM?JXF5{aR07zG_d1DwfvZyu1xW3fBYbKZMH4oo!X;TU1%QOMD>8_Mu*+xcIN2w)iHnrlC008-ZAfQiL)Qu6txgh-v$sy*fDuEe#vb%VxUPJ4+0a-qnW<)mep% z3HY45%?cZ556e-Uro9LUe;Ki$06to8yyEH5{_we=6B|E3O7m%&P=~2H)-b;CTJyj6 zWGFawM5sqgZO+2V~T$3Dx=>Tt2@xDZuSlhm^o&H~-Wu|CaIR^e}B z74AOd7vU;n74|+>VQxznFHzXXcXErWdP?zsGrjk6GO_PD^vAlpC(q409JxSg3f;Vx~Py(e#D?~+B;e6>pERI3?gM&rF&UlQg-yZlSl-QXlZ*T4e`vdhlR z0R-Cj=o*)B)v$DMTma9mGQu|OkJ!&L{^nnz7_5vX-FeloqvISMtI{&2Tm#(rkteR& zg0-g*O;%BeejtJsN^5Ujn#Te7wsMY#v!3d$+h^0BEUhk3t4_h5ZjAZ`{N>$-)K!3e zL=&;A9%j#fQTH2L()r1vu{zyR#GG7yCB32fQ15|+#IqBN7~zC6SGyCKbX1v}`&a*E zU)G~1G#5KoRofz8cl)!Snj>anH=39i4*n$kEp7>($F`^U@rv4oX5&v33o(iiRYQ#wDvJwB5 zP3ZyR*0Mn{BY3MPS|`=RIT2sLgn3ih7D^e)Hc|ZzaJP+^5`nK@waqOe2FgpF0Ibeg zOu2pda|1s6hPxy^_Ftpe2|jH^n10ucVlovRPb~PYnC?x&=9rMGz#{$$92bRbqz9OJ z;ozm=y~?8&b>KLOz`MMdGu)DXa~+=61ZA(8N$u#FW2czNUwSwX=y1>s;g1YQmv zL7Us6<2NLd3>PknTX{*8A4$5C7ylDh#}`tZ23*^L^U2FfhJp)*XxWG!HiE|#8nmFa zR6lkdS8dgtctXvb3J1MyY_+;zDU-Myx|+m9__M75RB7224@cGmefUpQF%$A(^3Zil zdN|k-R^S6;-$H#VWzLXomEUlYt9v%Dmqmt3`}2osjt@8?+vN;Di&^~L&*+|iSefAL z`q_5eKa06OtW4BJpQahM;~q1Il}%Hnjj{JzmkHa-ewHjd6I5P4Fb*^;927$9C-({#&#EG8UYdi=a0atVg8*G~yO`PlbakMnJ{0xAxzAkil2~b&wNR_3_EV zCfR?}mMYEGt6L6|tgZcz9*owVgt~9{MQfgan%0Yvey84(BPaYTk1#ViU%sr<+_dRq zKRZ+KecT*(Bqp|T3p1b3q_KKD z0E1c>p?EL<5Oi5zSQTQ0j){4HZ&t526%RB4Sg0iK3CKLZz=FaHDr3y z**!&!anGHUI-14n)Nv?i9lj_TKpj_>$GJ11lQybiJDw{1FhViY%4xJ1F+N@}6r4W% znfl(28potHDmfv>6Hq5CJ+11OlbR#e%-_{CN35A{q^?{11jw3S`dOuZ8*Q8HV zhhm=iyE6A70z2o=YJREQ_ToE`F|G2(n!hWShaSUP$(#=Ttf;ZhcwN*4CXrX$ie+ou zl);?=<{9YTLNE8mfl8bX{Ss7xHRXzHu(Lja{9}>5;IU22^S^_16%PJsI9=dEF?EzW zQ|d}-^M5(gZA5;w27AQNsBg$GFh3HVv+>rO&!~_btrR@zaySRm(xR7RL1KyXS>`tWZe)_};P6Rdwg}zxRY70yT%swT_fU^>`n1Qj> z_CVxHV(l5LJBDXFP;v*}&%vx~O?C%uu@Cy%`4JzE@gbe*2a#tM=xDhHhlg#LFWy>2 zdw6RBc&_D;4?-@}yhs_QfqD(6-?CE6)Yte5zlhGb&o^J3g_V&9|Kg{+-A@PIU*tYD zQnx_5IaQzcrtQ_Xnc|eeCzOSecdw>}gXMz@p4yxDJ6OVB{=!hSG_v|S(3{`B8Rd%T zDHJ68S6`$SXt7ex!QBHyw?8nBJ6cCF)ty=H6nTT zVfe6js0uE)fAzsYfFcka@IiqM2hk`YsNsh3Aa%|U{5y>8dD-Nf3AT=W`Kw5xQ zLMkDxLt2OQRiv*X{SfJganPJQ!P$Y|OTjf4S2`}e89shWIQXhkv1K)Ovx-f0JlFe7 z=XGb10!u-Bt{{_*;L|o9MV{W@%Y-@}FR9_M)ZPWW4A&x>vws7% zDHHjRL#{$rYxS5dodd1a$gRN3t#g4KAonaOEaGD_1en(THZWuZ$k7+p%d zalbM)QT7qj>O#8W-PqqaL_;E+sPS1K^F2f;uSlY+k-x# zJi@D#{?KvHVpI7EP}ZpAPNs%}UyU?Yq)`8WoW`<|V2dJ1a}0L5ofA+SW(Sg)%iirA z!Cd0pj{9+jM=qUnp}&0@?sMtAJ#uab$%R!*C|d>Iifdd|2z@+1oBnDezwwb@UF0_< z@~fXcf=J~N*kh>P6Q_nO5992Rl;yLEjsv%kWAB`SQ$y01>m@@DjfN(G6zH-PL%dzl z-Dg+y>Gd|*H`ReC7Q@uSbXsaUO5rpXZ5~Q3Mycs26~7au^p2E*eWeuARygl1Pc1Ua zTNfJpfvWvm78>O+gLpsViqdgK`$}s}`!Lr2k#KO|z-H>RVhsgRanG7!wa2$s~hyF!1ds@}J&@|K-2jr+NPUzH;;)vM!)*JYaBzq6$nQrPAvYwNnk$8)_Qm z&T!g==4@JGp6=G;mzW7w%+`z2UC#XhEn`)*(;EX?_D<(#PP?MLuSC(_W)MGi6oG#q~uVxy{qfyMj^4Xvozl%f~P`^(if8>E(1hJCoh#^?)h9{|fc7WM? z-8YtMV26Sg@Rf~66wpv`EMnvU!GSH_)zwp3;GSPPEwmb3;&ro&v5X6->%G$ z`opM1twdwX#woURRWF;Q>Lue|FBjYsr9`(us7aQ1ZytK z+E+MJMOw$lsmrByjqcRRORTQO8RI@Jedt8#biJg_(>s?)3_J-K`x56w#HoaXHJIbp zi_{-wQ=5XQj|58jZ_r<2@}j4m&F$zn?Jt==-$!Q6^J)SUR8!>y)j`{=)6_d@Mz{s@ zGUo)XdtF%FOLW`Ihunhnx~);lJo%Ya?~HSQCY^N(((<$fbNm@0uXLhw$(_!r&gY>qMCXFmoBl75~Xx!KWU&YA3?{*RUU)Gx9!-wPkfIi5IYj;9E7=Q&(UK};PZBgdqQ3CGWgZ+2R+2<4yIsuk@94Yw!5nfttqiy|Gx!~vXZca^b zlbN5Nt0S^Q06Xq%8tp{!{?Jf2 zwC^1V?@Aj%L^&gTj?*1ztBibU7~f@&1ytJtDvwexvYt2?$fAxRpR)zlqo49{NpMPW1r%Cxv`q8CdArqvvOHN z-u5>BR$7M1V$VctVBHfd<<>WQS&jBqc!dA4+s|cnoR}>}w6cQkbb9n%DPFXT7n=sAS?a_Y&Ch@ncf~RDUbmfYBU2l9 zr8U29i}9B2n$dh<4W(YNXt*BO4i4uR9>}zj=(ioPBO;QV`sdR~^5{1vUw2jV5%98= z!n(AIICvcG%@@{z28j*m2Omf!q2QAv!a6muv!Q~%{qf+ALF#wkT~+2GGv7z#J4gQP zC(~%u#a8v#_>Cn;X`Zwp4m?;~D`_w?W)IFo+Z_{_9$O-Yg7=T`ljnC*{uN_rcmdw? z&qE$2SvlT#55DBFpWnb&?u_CzoLCdtW*C7+N**{H2wGcd`qOy*GKrD$HqpY{#W_woSpD6rkFrF zc}ig+2Q?4VNPJ@EJEQY?M}NsdGJR|R4-ZD~x8fe_#orZKpNoE4`d{10#q$#W4!VZ? zZCE{dVJ$rPQ~|x#idCx}<|i9Fd#gzHeBVrXiHw)S>RWJ*h=q>x$?u+Lk^N}6xx$mZ z&J6wnkOUe?eL$>O1*-dv_r2I1 zJ%*S(MR4-HwOoO?u{0F4443UXJTMJ-#^mgyup%7TmDIe?mgOrD5eXbK6#QVY05g_8 z{MpmO&kMw)<}|#W+_n)^f#D|Ehk`AG-Bm~2i)6hjYW@9HSdI8KKKmGU0NANC8%ya- z9T?1|QcCS+NhR|tFV0!)^M2vq2wC@Q?@@pj*_V@7^O97+=!QEZ;x*Kz) znhL8x;{Y*VL&T~ff_DdoRFhLXyQ?_JfjbXTjCg49l0SlN!gtqC)2r6Ly+}P86*~`n z74`TL$|nHwPeY3}CR620)liEfVvvU~`D1|#$#O;l=N%K#&-`*Y)+qbw*#vITv0B-x z71n*&=h9QULTM7?nWe*Pi&(>-99B)%b;bn3^Dm<2{z%P?FV^_A-zG-u ze;6gMopmo_PQ20^qgu7A5i3AvIR=#T`;?51H8k)-M3$m+25C-9&sd;vJpr>a`9DP3 zMdnIHvS)#|(m8G19*u}I6q6bMtB~EZ&(d}JE6%Kl%nm#yncX*PJrukU64oKMZ`go zA4peIyJi{gETEX-;QgazCZo*qL1N6s&i8bP7%fPj3JHLS=w61AFGPG%YcBS(2sZ<5 z;jEFyss(P!&7_mYO3J^$F6f~?tGvkL{gjci(f6sOZ1jCL-XpGH6fd!g<#9*ey8851 z-PyOU?%3LXrOoxq)g2pE+2qPQu1_x}%Uj5A$lLh;JvmI?x@y~cv)6hhCg(S{yO3&- z#zuUNpYPh6uM12}IO8Q|aI3Cox&ZGr-;Zc9{k;3>Cwenw^EB)u4XJ;QoS%~o zK4Np1>E~T2ad=>kg)}Fn$`o&IP|tx~WuuVDoh#dQ06X(p|AAdjJOjnRm;d|^-+c=W z>a&fzR^dC^KC__JziQY1Z@x}S?Wf=0z|&?PYAH)st&ifX8xi8~XzKb|Bs2gYV2&KJJS!o3*)TiEVoM0-HS0Hkt*SX3c z4HmxqFP4GL9Ewi>582$l5y zau^(3D=|`BGgi`lCtF&HQ;2|#rF5n)(6fYY;9V2p*|3WVkEVHOo@$q)+zI{ak;vHv zFNZ$?pKpgJP%`t#Gc&LIaf&-pj`gHJ zZ4Jrp^fD$q(@{u;Ud%fIqd=6=Ftx*|y$i+t&=fuunL!?B_fVd}wySm&yE42ryKK8+ znrqikes9~ZgtOe>w!Ydj`>t)HxWla`!m%>@YHr=iH5G1sKHguc*|n`KrWstcVQFgn zrGzHKsm^Eu^cWqnC4A%D5R6K9f9gg+Y?m{UYizkOdfqo{Gf;p>&Z&v%I#2jvQ zsyll6%&%H$O1XZX#?Ha6*&s!1nBew@;L9123J@1SwKF*H5BeaSlOhfWAMoH*DUZ@p zi_^iziaTw>iH}J*+jROVV#S!>32Q{j{c@EHvGorR=POf5rH8q_vFdf3>U=I@$M1tD z!+4^!{t$0Q;9CxfY~GtT|LLDNU#TR39`Hy6r{#hAj|3lsjtntSRm|<06HaL)_yc(J zMs>ZlZyzL;)5@gN_geCFKY+$zaC|_QaLq@bj0CfWKacS5=M~HTr^LzN;Bm5!oG`2c zt~BB7qB}aNO?8R*`>MCwVgnlHBi#;LofvbDnN8*CJdMiD_7>#2VOMK53bA4ZNSD`Ct7@p6~sT z|GP5;dHOmpe_H%sKQmW1TRZ)X50qH%dJ^>g{VmY_ZA0^{U3*?tGnMG-NWW?YJHNY{z^n@U@NQ2eB?%KIoTQ9>=*~ zIIn()&SfmL4Jn;u`k2nws}7^~n6sbhDiAfOK`&{YeDXeN4r2R5!3M0lmZ-qLri$xC z4w`SBq@4pkHGQu5j*UA$O}ysQVa@e`kT0Rt2qCUdLOZt%Tmbcno*zh0GaL#2HF|zv zZxC%tL{~~VqVZx~Q?iq-B3X;PPb=vboZrAPuOgx;=M$XjO5`HU`@FNv zZ_i)i?xv?--mGv{E-_a;2_5+1Z~^4dI9|P1>mCWd40%Nxp+2{}D`=FrU2^85*JSEv z{>I4tekc5>gU@4@y1nzhDT9+Go#($P5ya~2czV9mIR5W`wu%!OORReq&coM33&K{> zanaZYXodSb=(*ilTS$8jPx zwEYh#t;-HEfeGZtlXVL7H}LASsCT{Ew+$_g^%jA*N))^OCfu>!XBS;N*?WckzRzMf_1Gph-4{5a&O0;Wi<(9dlZ<>b-wS<9w?tq=lT8no7Zd2+H0@NUVH6z{aoH3`(9TT z-mnrHw5Yd=jc;}{(=?mcJKF%s=dHc|Dj?t`QJ+$YXfsarlQ+bdfiqdBzX4?^E)XKf z%Fb`R=RvLdX@%j$5vqk zYBCZOl|hZ%p)B;^fd6rXLQpT3aA6ZkB3Qv~fuv;Vg^GYb74v3rEhW0?9Q1as7dTms z`!{jv`w<`8OPqGhOlV7`@G;_j7`CNBF}X0M$C|5_4IvdbzC8;K>wzYOrZn6 ze`EDF;GnSN1@1wjIs(*xHFuDE9vbhvao%`H{X$edvZ^e07DGa>8Oqs%ATfqNJK)u6`F@B^Y zw5e+o$#5xB^qy&DvG$Bw^^U!=9-ln+pGpQ6!CZk#*_(F}h@c@z6@xcvaTB%Tthd+y ze1{j`Mx`Vqw;{@JYMB9?qX86%z$5e+fzsGRfNcKC3MceEDxwF4l6DK5Bw3wikPIW->Vr+oQ{tx*FxY+%$EH29k6NafC8vq|r2-spS;A z?4h+dx77j#&=K%|(fy{q#D3Ve8OX3AGzB1|2^^6S6OdX=USJ@62MmPEUX|%UO@v*Xx@_AjomJ6eAEIw@r_%d+uhXl;M1*NnIQ0^D2&G*0MC zD1~d@y|R?X%V@`5|3}glqLO3-nWTD?Fic=$@;z=~Oym#>;hg?b4W510unQ?=yO*WZ zt`MJ48U!7U^9|F1BuJ(1%T-)tsn;9V*nHlUG8$(|eXRzbZN|@DNS}E3Sx?lzWgjdw zNZL68{~g@}T>Ek(AP1#&e2hCoT!%5j4r7EZ>t^E{+%!)A(E9~;F82euh8q)BpJS(f z^FC->PvCn+2>o>%?nx;#9l5x4@R0?}6i2v2)B}}qI*jiTHtt0_mH(x~ZX1yQ(G^}r zdRp9;N8k%)%IB{+E(>yW2KM6L--lz=>mPU=IJ%%f?XWXf zs@akEDDV>^fF~7$741le0rcI_OVN)i9^D0sM(E5g|H2+S3tQ%=R;i{7Krv^T{B{%H+t#+WD8E>tfXX6Y*A5_Gr*rFed z7N!Ya?;v}#S7)1N+=bx#pH^zS9dx^O9(jUn7QcvIPCgKPMNN?$5cRs z=<>I8cllRCrkZv;Ex-$|NF@3`X|r@f=IZxP!YLc0l_6iG0EasKT=1mZNt75mk)~e1 z#7&p?e^NqCvp3aw6>A~pH(_Yw$mC%So&FincvZ$5gfeJpvN_L4ocS40gSjf~+kiqv z@zf(o-|J3ghdej6)6PCSLdKe!=C;~LLJxLwKPvlg&?di<7H_o+?KS6t>Cx+dse^dc zw5xnu())A~Nug9mrwkc1#iWw`lpT)~D-FMKgmXhl%%e zQjYKCnq0=-A@IqrX++D?9J9N$uQ@fX zk$?YO-|2r0y!oGM_PY3WVL;VM)A#!KN~HHpr|vYg>$2XjHxu5lf}@jnr+;%j#mY#R zbwNC#|BivluTzf+^;oV2;`d5-8`i`-r9T>2JinyNpYa~)(@r5wQ_NWdfKeMuSS1_( zlVYWTz6B%&q)ZFYdHvkhy)N!xr~hat2g*+;sCOe=*`UO1urITzAL@iWAkopyeP1cv zzJD=MVbj3*P=Y>~ppBaar21j_W=+nhucY!*F|&y0ezhwMm{Lsv6J&aZ%_3^)p$@E0 z#xB3Mhe9Jdw?oE@nMNk>Upx@f6j%i%rwjLNZ0tww%lCs4w0xQEeXkmA2KlRQS|LN# zv`Iv6hekq{1Hm-``7v6pp{01-aah8B1Lyvj-pk(Gabi=pXhR4e z1Fdf^j=rGDx6iI;qagEQJFQUz2kEwYSVuaAr-YT{EXaM}?9trAxT`(0C-?R<`&+^k zw5y-zIV_B7ddb>#W_L`D;JLyZ*4si|AKTrwJ-LMDCY%qoX9{PcvvWdiCP-({E^v_z zPXzuJEY@Uyf~y|?g&uI6b##`GanB=7V0Iq+k>_m#UBvtP)D~}l$r_y#ZyR^MJ$hf% zYjaHY0$aAs$4Jl4wq@d-YJ2Ga?VfvbXSA+;=OARRl7%9n!~f6j`$0Qop)T((p+tDw z8;`w!HHWCv@tBqA&50WlN%b(l>kXC}i88`AKtq`U`aDt^WRApsO%2^ z{_bQs=GC5?yyDR?yH3D38D3`pL^J%0sQKrv@WYaFY9U4Rll^ns2>Z^c*!gcoC+563 zXO=D6mSf*tqy%&v5( z25fCu#{dT3K?WUt)l1wYGur2mnB#3O4l|M(_viO;yOQNAwKUx}0Q&%(!GRX0ImWiJ zc(N@)R$YQKDRxDL&k-de@seb#9u7V{6Io?qvc`?`Xq5@G3pepR_C8lGS4rI7U9l&8 zi4pv^Yi>6BX5qMS+&3d4zu|;0C1R>u58n`x=|15zMNGs0n1~`z6!@YGz)_#&HZ@;< zP}6k6H#TAn;>;0dPd+Th@Vjy5Kg?HA&uj1;^5sH%f?fNwGZeh4{8m;(d}b;`Tdy8{ z!dDv6QDYHba&i;$Tb=oz)Uf!MoAO0on=dN0=e_x&R{Jmf>$PXS$J^MtgfoYHW@vba zq#SRcG77~|;Iib4PA%W1nap>oC)GpmyES=Qqw2uTHdVZ_Hz8mrPMdcQZQdq9;Wuu*6$LiR&#{Gz(B$m zoxsFTyEQ^Y(;;6e+HGC?(sxeyN+Q1UoENy!1JHuVIqexBKSzmLywh_P)xwispYSb- zSl7DfolpVw%#SeYd>UOuvi4w#s0m4`k1*E$$m^Jx(e)y%_FR$-)e13$=f-5ZqeMO; z(*xdJXkqiL=twav;%2l2gMCJYNohKQeKS4fwHAe1>zOQ|-(ao>U3f-^XJQT;MJbhT zll@k#O5DU9c~rU<-}k=4NaR{ppsgQ?z1J=w8hpj9+Mi>3qTXmK6vu{sin${t^zUAx z1#@o0luv4?NAAd*C;Z?&U30w6S;$pIpNSTZ9BIo!_SF7&4n=Hz5|j87Sn(pZ(7 zeBmVW(!285EAP%txS)d`1GoFDn264e*I}=*>M!*v%`K}{CN7<7$2yLoG#a(BF) zjcfOe$e|Kdo*E&)DNgup8&G@s+zN1}i!PuB4?ki(+!D&8gx#UOz*ObVUDiqU+Qa72 zXQOx^3T4(Wd}vwh)42+a$x&!)J!s=6e1RDX&p5fI6)&F64fVVzC7LIuBsHjTm0*rU zDsBCQ(cDCn9U2>Gx5)zk4R^Cy&S63wCC}|SbzX{7ZQGGY<*9aQJcnbcOw~4e7G&>t zDPBD4oiMu5y9KtTEUF%*KOQHt?A7`LnaCx#L0+!^?8F>Fc(p~V3T@G7)lF0$^+MPXa&b3*klXILDW?Quba8~X z)lkBt&C4Pl@f>M0tSIr&*ul8bofjGONMYvy_V7=c1DUnWm2IXu-o#v<-_j%htLYmBH5rQFf-*spO$ zLsm@fe#vUN{*m)~w4z0;xn8p%1{Nf`UTQjzd4;XRY@sV`Zd$pAX6+R_-MF_xS8us~ zY69FqR%5Ao&P(q-;`iQLRAcv06hUvA=RV|Hp}0^JGG1M{Sy?9zlCq1o%^EhkTyr*iu^d^ZzwV@`=k#f5!+{38d_;GG(wZ&e3 zcTD*mDWM+d?_iC}wny7F+cMsP;jk@s+u*7S+@xNwsU^4<705 z?_8%c(1U0$)3vCu%DiN4yZDmzANB3gY!rPLAZ6Nv zaY&tv$f4O$=>a7mC;WSE;#un9>EVYA!raac*T_bQ$vz0$13U6y!)8W*&u8N$%*>w& z{BGs9w7Sh`ef3RR-`2H0_vXvrCJ7Nl`FM`ilavh5v>uAZ{whL!l+~!`k7r0SLfRlpe7Gm4`Mh_g{S3?z zvJ_0xVfw3EXAu>1u*h;^>s?nZIxgWD{(V>VokKl1B|uyzN92_u(PqP^Q7>3wBP#La za0Us5yH-wLd6O+D%>{ly#LwQNefjt=bHHb5_P+d6)+0x+=E-I8mvTgOM&8mK*zY|vwCUxa(w1fXm(;3r z{i$DV2~%;?uAWJAB{qMznoEz)c>#J?Lxs@=ik6QQRX?#u%vUwKmwy_GC;eTngR-&a zs`3$Tq7(NuKBW%&m0RKV-uk0n$BQ?2pam2g1-7*@hHMNkfK`cg{&nxn66OhPM;2N> zvcqh?Rbbn6Xn`F-2@Z`1p0B9ws1Tlp6|tb5$AJ9%c^zXJquQ2*Wiw~fbl~x46b!U`> zb>E3zT>vRoo4UYSoNZGTY>?%`6%%w0qN|*K6uQ)K#>bfUG|+cX+aRM}0J(QL9fepu zhd7F-eK==iWj+2UYUzxJb6XkFe6v6iQ9vqzgG6m+U5~#I+7-$a(M`6?LQqygS&7R9 z$!N_iAjqxLU`G-u^w$DXsRd+Lb8O!;65$h_tOs@%ILI8o3_N>1^jLfRkIK^fK$_0c zAA8ywDJa~rj4pcixEio|{wa~~ z-nBxmzJ5AJ`|B-At>pivr={#rnJFhDr^?z=9CqfoZ)8N|d8;fh-s`^!nk@fnROTFr zIS2GxDzy&J`0>I&ycsw*w8%R;(QOp0!VhJw!zKSol$H&t@$Y4hgBkDmc>kLKK{31R zva1JLe}<)t%C=e~-IvR@OL_VjNUDE$MHA2B=SNpcc?R&hLE|CGZ0eo2cQiqBrpFIz zzu^+}Y1r|g6v|Mn6Q6@i$J6_o9pG)k1}<{>L5l}|g7V~574N9n~+i-DfUE!cs{`Q zW#T%tjiNEMfCn#A*^~ka6#hItDYI_BrW5f$Bfh;6T2k>>y=hS_VFDcRd}rHiy!cmW z`JF@Um5soqL2r(<>FY|sf$(`cy#}OkaJn85BjSBiD3mR+}Aa~mh*>k!_=h}A)o~vewYS@=QwSI&{@u#n(k6!^L9#0-8 zg}XkLnC&a+-EC<3$)AEYzX^0x4rLGR80CUZCD-VMloJMj&8sfbn#*xzGG z_j=?Q#*2F-w2OJawX^}}kp#j-LJo_f3hiQ1?7nAKu*Ar6SkWC7S$h}0MWiF^+8_mQ zR3Cgxih{<**S$6`)#80{WnpKzLb02uCyJ`CWJyNoIDx-->e|r?O7o7K=Isi5oHB`B zJ5=%252&{;eBfZFH0I>P=1(u><`rLgmBy_6cKQE0{w?{UHx}Giq@Du%#DutmJD zB4s$OK z9HmjURfXR2Ob=1UpxaETfsFB%oO%gTm%0t{Q)doKR3Gg2zl&1wPJhDO)t7#yoSv=z z)AuxsW+MG9jeo0&8#}9k>LVbW>n?0{LuR)Ew93NPGq`%RcXYw-+$o+>1v{*hJYPvW zswqWovrac3-|ODqVEVG&BG61{zm4$}dB^u8_Z#rX^@y%VVh4C=jHwUu#^4wm-?P{t z@5>7V{-^3_oX03)z=NIwSqxx90=tzHt-ViKFS{FXrWlm|>*yQ=-mRkQx$lCz`dHAl zH{%T7ZzG&xCysTh0Mb86+Io@z+1fQ=roo0c=!B+?D~k3LX}VjojZyY7Hqx1fK2l?n z&0r_(t8V|W6Pa}+`;mb@xgUNe{8V{9SI#y7JMuJHrA;@<^EKU%1mDJlH7nvmcmb8! z>)#@;+O!6eb-s`SgDuM5?QiMe;%S#?fd1LvBrfSHC;=Mwlb6b%XVCNd>GeH+Wj)=G zD}cnL{1zM0PgA>MW~$NFQP{C&9*F`%Atw&%G#}xxX9gZK_9eakKR`DtvT@KYWkL$x zcv>gF8yatdsr5MY>J*n;z9~E$G~Ao0{2#aKTf;@Z>N;sE=ZN7mVllU(vsYs5QSc` zHl*+l)Squj843H17s%un}rs) zwB2?Td-4}M^N#?9*Ss&DAI(jx#8s9ZxUCLD{L3rvaG=Two4b0lK&;;4wQ7o zU1?)|u}yL;l>zFB4+mjC{+g^H@_EwcPmtZjl+h<#^!^V=PyI+&E)#~D~Np}E! zU_`+kxo2%ZLHp)MH8kBqZAdGlTO)1e5q0sNeTO;5r60upN1HvJBdt3iei#LZ0b{E>ABTmkX_~0uPH<`aaZ9&z&ag zgM1lK#Z7NS*bGiJT7Q}le4o#7-;Db^%xSmH22kOY#z4$%bTvSU1qClP%(Q=lL3X10nFU z*NN~JC-u`u4bcwH;P!I3v%yJWZp`BtVILc|=kjhYZF}y6z{Fnbp`2%dS@$S*k%TM2 z41e)fB$s(82OCrRzj7=fHavY2riaN%MQ)*&dLd zHoqjP&6Uy?%p<@iPdVadh8=m;$Q#>NqbN^s4t4gWc*V^benNa$U%6WNl=B5Q4{ZMx zqJb^K{~y^x>@0N^ZuF6v_R||bb5dJJK`sJw8zj6iW`0K=g82@FH(R4T@y`yzUA2dF6*x%Ra8qzT>==q!w;O!wzglA&NUOCt5Y**+CGfHL zuhwtRfB%eL;!kmD#mgquaFY7eaA*sD{lsq4Ai}AGp7A+wGvji`RiJLDXSLfT@UuRK zK5K{HFTLUY4E-B+Z|rxMkzNxpOU0j@gD#S86J5XIbV26{NGeW}ir8sQlkF?qO*&7i zh^7^-b4osoQl$7B_OVWGyY5vtOBvQktMV?*z%R0~F3YttL;kD_T6M6*c|cl^(9gYu zsQ-i+R+bX4!`c$v-7Zy{A8}D$;6LGPNvBg<)dT+XT^ywRE740Jhmm{IXkoAiSwAOmPLgZDIur1?rJ?zSLQJWd? z?fP5oX0#f$8Acb&tizRIV(pDzWE^Cc=`4H|+F(C=Zj3Q@A@!VZAS)m99@*B_mZ7e{ zqf_PT2sKCgmV@KIxmHnu(aUxDABP?Vuqb=_?d{QuL3@M8&23(icmm=H^k8I-a~ThY zR$QPHk~G^5mg3yf4(D-6ZLp2WthdFpZH?HStUL0UJ&E>Rn~=6LXjQHfy4uWmQi?zI zY|Tk2!4T28rF&2f&B<){5$lKs#OUdMP}^MPX_RaRW-Jo6LC0#Ss|fSL(_ITYH+5{n zTywSdMa-78dIz}`$Y*Pmk_?k-w%udBjY>J$G0H}^TVJpqMo4iHy9))b%-n=Jug-Ur zbpfw*H+BHDf8nNX#uey;&hf=#Rzil=FbLZ3ENQ3vGjEp5viw&KDb5Z3vwGTf4-op= z`geAgwA*N}>GJdEL)BfFJ-7D`@ae-UrFD*Xe~4fae+&Na`9Z-xFvZP!0)D0Rlv!)iL;8?boWjog&3789ioI_q^qPA+IAnk7K5sq<~`-8m$wRwt>1gV>Ru~E#AttS3v*Tljqb}r@Z@nS6d;{0y zy?QsepAr`ftm^x|qLI%q*6QEGv)bS;!TlYM<%1?&!?avdq?=C~>9(KLm~;-6slYL> zEPrJQ5Mwtx6sFG{7MyxQO`BJ0a6;=(akgyZ%FPbGFBVuqSQYx?s>(ig1anhPisK-? zP3Jv2c@SO~(SM$D;@gf&7>$0R)nat|0!|ZW?sRs>3eB>h|6>->_9vJ;#@q;Un({L&xr&2O9?}IDKDkYN>5sa*Z*EBUcLQl8O|`wn}L%Qjdch4`)7ADNSHkQC>Py zq#-r~IVU1!lD<-!jMz+eu*?SJi%Mw<+*CuQGz}@HBgIYno3Vn56{H(Ow!wx7H@ha4 zjf0DGRb%uHxZtSc#^T&PHq@O69g-oi%&^EFnZr_~#uA&&PPiI(vL7M&8zyjX3_-tr z8@tS3bzsiQIxwW=b+u1VpbNaZemw!`T_080D`BBTa}HLlp=Y!E|IoAPf5Kz`>k0q< zohKZ+;R(bQ>-IN7W*qb(j0xC8N4V`5nemO)ZWrXGP25)Qpn7{yBa6?0_C`*(zp`hq zRnrJP2x|#&rsmmj5`~@+XnmvJ^w)k zA$#k=*>fQ+Y1wg%?63x9(K8^49+Wc;I~oe>cblqLLRyYL*y}&tp*s}1lO*eU{42Uc zWT`u{Oh<8_cZgo_Qo*HT$5*4xhYH-*tw)F>`mF?Rd->S0oI7RgAkb2|D#A$uuA7)B zjU5}|srIo#?Rj87bjHivIMC9YSmKY~4rt8XR;zC!JfANA06BJr$Sl)c6I~`dWS3G8 zK_?jU$udU+*&2d5F0tR123Qe|+E#Netf;f(V+ zFnD~RkMQ6lh1n0*n##>737(SjC9w)fwH2i(J$mC_JY$4psLc?x@p>WE=BVQ{^zpEW zniS%p^sPuAO#QQm&-lr^AucMVS>})dVIuxJU_pdl9G?_-Y5ar=YfR%_Ncn*;<06}^ z3CWQcDIAh={k$znb?FYI2t|rJ6+d|`2v0(oM|iU0JDe?|pan-fL6vnwh><+R#jYyLUMU3QhQv$t`(z^zTJ~tJ|1_b$aeEyQh_%uC-hnkp7}|z{O+G847QFwJmFH$kA`wh5>>Bpy`%zwJ6r}=8eHN4k(*1kxm)UNy)IZzNF3Vvd`B~z@(z}1+ z(${JoGIAU!Ms47hbu=nrotWmSK@xEmFZXE|{peB7q`Ml4B-Mv7^p*N=u$I#77KSzZ z)z0F$lqhgappTj)L_0DGmnx;*`$+AoT9*7Cz6SPgS?VTm%aURt2h6gFo{Q5|?OQ%= z*!@?O|HG0)8d*woBgs}=l9WxD^-LrMY_XEO7)yyk%%U4&g7@cIOIorOj=Z1`{_KCG z_%$y3hPeKG^J-_Ie!*IyMiYXy+VX3y#H1T?QOkX>?d6|z%d&nP26+|Tg3(vi%ig{E z(X!)Lg@OZDb06ux`u9hMUe!krySg=$=GS+wGbfXO;!S;i7RFAV_Qi0F9YUX*<=HN5 z$*qA7zU{o#^#M54f3_H4(JHKy?;e@G-BQ>b`-hR8TiXBH)$22bg?9~nFuPfk&2_28 z9oEqEu`LP(PMDLO;*g3RR?D?P75tQvoS5hXHAlL7#qchDdQP(qGl5nV6#!TOx?-#8ag$tqdGO$bDG1Itdo;a547RnnMbLKWopnX-%xMnEfqibY zWUx+HKg{+suUVIz=cg^s$!-ouEAH*$zdveSEx3faXA9l;xQ?TR7Po{bm7N-Yd?$B( zWcEKSXsI>KINOVF%^7fyzVxV0&i4XrO7*uI7I^ zTYvfMj9}Aua ztEc_2{#b}1WVYll=)|}#$u)c^IWr`GPG^om@@I7t#oU?kq12E;@(6^R3mgao@EbbR zkT-nT(P%HqX5#A|82=qXoVYq*z7ao{WJS*5ejOxKnD`3*gYnM;Gd6L0~iGf zbUjzob&lceqL)MQ;=#G`t$Ku^*9R*mslmIgPWcXMj(RW#!HQ$3vyF-Oq3#?I?g*!D z$q9OLdsi@K_6;$@2_~vf!fvz)*wh1{xzM+^Sd`%7#D%AjHgHIT5i~F2Sisgj(k}rw z377+Q%!lW+L2g3)?&JoI%JXY@F4;xX9YD)`{KPCY1WmK z?^$CXPI14y={>6ow&21NRb9&Td+f0fXI)b$b^&q3dX0l02cN>R?kqX1t-mY58pqwF z6G9=2H0;a}iCa+=`*>|?;(F@{2X}r)?A;Dav{=Uy&Uxo2T=5nqc)fQdK<`ulBH?}C zd844WN%hIWH$iWk!`hzHyQQE_LoSKOxk>3p{f&IS@*IdEJO_K`@T zKnjXatmS?auRTWbI=8ki1o1n< zdA-=LHN_XUGP46H-WzYqxFx&Q0ZTI*Z%QjjpLJGpW-8j&MJn1JpSPQ@vPu4SX&g$u zF8_-XXK44&K<`SuzuiBrV@$ywE06;c=x#>GDC{XxOWXb9I}-DOhX6WS0(_y%1fF%c zCs7RW@sREb0RmXuSak#X^J+Hgp6oZRnf0kc2>Sn99V)?A`$tG;wf9hox{d(_181dz zix-VjmB49_1giM59^NHSl0Q@8GTOY_q~Q$_GYgwpEZ4#Y&3SmQEArv6e1_4O z8Xn%IxPGcA({-y9#tg1`IE9_6v9vl3(D>=1QR2vp5=h?AjC1=bIAv0B=MmXJEgU5& z#)d!=g|V>u1Yo!^<2;;aRkL*2k!bM{(1J2$eV;CGEb>yjf=?`<7h)d?YA0k*+Wm!H zO#G$;+E&nd3bminbboOH|EhC}S$ElZ-^R3TSj2SXnYep%c_B1^1F(T{8fbGyR#`(E zH2D?w=dG#+uFW~{dFu}Bc7kJ@)vrMt+o+w7hQT)HK=7OlIe4dnc7NP)4lNso=lfuX zkKU&Kdf{{G*~{!vWqQb@0KpS)W`xD9Hpu%zv$M`pFdO=vGXDrX;&%T-z#UY|8p#Jh z?u`OPyDc#@M}8YUeBQUEA$L&b21BLPoEDc z%AEFZqghLiUfEm&$;JcWiCLM`I2_8!Tx3e^H{3d7k3RNLN$+%z}!iTdj+o|`Wjrhg0` z(|jowz7l>Ed@cOJ@WbHi;p^dt!5<7?3qK0J5`L_?zZ@$0lV0t~5_<^H8)M2M#ZxPW z;cUjEH7V{esFtvN8$VbM9e~a}-Gc=goYnmP@4;uU15Z`!GicwT7ExWLQ}ZwBxAdmj z??g>^S<^kMa21QIah@7nMd2#ha}8I6ah2dnE4vdl-en!>S%s@GTt$0oaHYl75YIJS zDRHIul-LcEgS8Cx7$*HO_wSw?pLbjD5xEvbp;vYfkcia3Tqx@Fc}cs4e{Dz zq|@KiWq!W*K19Nq_7%`yOk!`-`RftpkAfv%snllN6CTr>?J87Sv{drbC!k z%mmzeQ>%ASfqT(jSSx^40)4dSAGOfW7&FwfYblqeb1QsFN~#COCw38dzYO3v1R&{` z51BFab{_t#fiJzWwlBO?H#=PBvB3qX1+M}|!SmK=_xYtyqusc8Je`Fm+-ijlR(_zE z#1RD*cu8|KZcUQPb9WRy2X+iyKV{3DuK4f4#R38%hBoxaQSRe0ETMSS{SQnYd;fU& z3+=_L7B4AYd*7OIC2Y}(6>IKWQM|Zx)x!IW%a*e&hr_z6Z27&nJ6PGOmE++Su3cVQ z?kFu;Q@Xfp^(tf;zqs^)@oUyRG_Rc9et+rx!SM36_ua=5SC3Cz%~qGLDp|37>QqDS z+_{Bwry8>ETUA=T_#p#sE|-f5?N4HuTY7KV>NTbGKtpy;_V}#qTMWovR(zjf@v5>1 zN>}}ww68Fsxa_{t#fCL23?(RaO{rmxz4Sk_mOfBcQaaU;xcJxX^VXJ>l&)UA1l4@V zu&VE|RM78a?|X9D@+E9}@p3k&D8oAYfeGU#Od4mtcX9fnlEq6h7Zp!tslT=a0CV~p z1#ghJm}RY{ms)}5?7J{n(JODc-SEJqqH*QSy7st%;w#8 zOM2Rj;4c`+pS&RB(TVqzvw)RT;^-O1lyG{ufpGC~Cb+xdR>Q4CV!JmULC9(I#+xo&qeg5?2E0!1EUwSi&`hfCR z7?_st^A&x*8WE+quR)l6Ey5-6L;K=G5UxO2*B1ur$Ko39ZwT*$Yr}Pao?2X&!L5c{+wUeb zZ3|ptCUgzqCcDsEM!`8l&`kWpT87)Z9C+M;OIW6b=nbq*Az~o$t{_BFIJQDOR>w-R;+2;?o?Al4c+8K`wemn2$hbw1{&5mvPW>WNwsawq7Jo`}Y z&F^k%_;byfJ=4=)KX}g6K6A=Vueav(M7)~z;-9ztQ+r}TV)lwR7bmGdrcaGuf<^Y& z{Gh+_wCq=Y`RAH8v=Qcx{0G7Zv zy%BvM?j5)a$YQlU7i`DGZ9#uwpC5eIum2{brO*-N<2EyG^3(Wc&p=mT6J&OA?`OC{ z=w3V;_lXG;8OL$Ff(y!l4!9v@~8R?KtuoZ!sWl1Y8{4NJ>Y)s9;(P zT_f!@^8f3PvxumJoE2$P{%blpLasx9+SLCe?ckQcy8i0?AIbWo_#c3G(-+`>2><1} zKmNb^2VjEjzjqT|pntIrRH@DKY=jElj# z$y*Q#{z78aNsPAy1Na{}0{w`$;41hV9yhdz@s?l!|HhHb!FUUBjJ&SpdwqAwIfbXwi+~_}R>HV|dJM z>Ww#s({9)Ay)iuXj-khI3%Pq(-6MU}V?CjbA>zr6Nn zc?)**w3z+gTK!99Urb}#x^!UTzDU1#}?DZ&30_e%l4cY*VNQ8mg!9I2fCHVNIo z5Apr?gL8k*VH$Nly70p!tFUqbi2N5ijt#^4BtpkUj>U~-#r7}`?c)<2M;?> Awg3PC literal 0 HcmV?d00001 diff --git a/boards/auterion/fmu-v6x/extras/px4_io-v2_default.bin b/boards/auterion/fmu-v6x/extras/px4_io-v2_default.bin new file mode 100755 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/auterion/fmu-v6x/firmware.prototype b/boards/auterion/fmu-v6x/firmware.prototype new file mode 100644 index 000000000000..644953a9e1ed --- /dev/null +++ b/boards/auterion/fmu-v6x/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 53, + "magic": "AutFWv1", + "description": "Firmware for the AutFMUv6X board", + "image": "", + "build_time": 0, + "summary": "AutFMUv6X", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/auterion/fmu-v6x/flash-analysis.px4board b/boards/auterion/fmu-v6x/flash-analysis.px4board new file mode 100644 index 000000000000..30717ad93ca7 --- /dev/null +++ b/boards/auterion/fmu-v6x/flash-analysis.px4board @@ -0,0 +1 @@ +CONFIG_BOARD_LINKER_PREFIX="flash-analysis" diff --git a/boards/auterion/fmu-v6x/init/rc.board_defaults b/boards/auterion/fmu-v6x/init/rc.board_defaults new file mode 100644 index 000000000000..f371bbee78e1 --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_defaults @@ -0,0 +1,31 @@ +#!/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 + +# 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 + +# The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). +param set-default CBRK_BUZZER 782097 + +safety_button start + +# GPIO Expander driver on external I2C3 +if ver hwbasecmp 009 010 011 +then + # No USB + mcp23009 start -b 3 -X -D 0xf0 -O 0xf0 -P 0x0f -U 10 +fi +if ver hwbasecmp 00a 008 +then + mcp23009 start -b 3 -X -D 0xf1 -O 0xf0 -P 0x0f -U 10 +fi diff --git a/boards/auterion/fmu-v6x/init/rc.board_mavlink b/boards/auterion/fmu-v6x/init/rc.board_mavlink new file mode 100644 index 000000000000..4952825bc4f5 --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_mavlink @@ -0,0 +1,10 @@ +#!/bin/sh +# +# Auterion FMUv6X specific board MAVLink startup script. +#------------------------------------------------------------------------------ + +# start Mavlink on Telem2 +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 diff --git a/boards/auterion/fmu-v6x/init/rc.board_sensors b/boards/auterion/fmu-v6x/init/rc.board_sensors new file mode 100644 index 000000000000..162a0615aecf --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_sensors @@ -0,0 +1,93 @@ +#!/bin/sh +# +# Auterion 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 +pm_selector_auterion start + +# Auterion's INA238 uses a shunt value of 0.0003 instead of 0.0005. +param set-default INA238_SHUNT 0.0003 + +# Internal SPI BMI088 +bmi088 -A -R 6 -s start +bmi088 -G -R 6 -s start + +# Internal SPI bus ICM42688p +icm42688p -R 12 -s start + +# Internal SPI bus ICM20602 +icm20602 -R 6 -s start + +# Internal magnetometer on I2C +bmm150 -I -R 0 start + +# 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 + bmp388 -I -a 0x77 start +fi + +#external baro +bmp388 -X start + +# Don't try to start external baro on I2C3 as it can conflict with the MS5525DSO airspeed sensor. +#ms5611 -X start + +unset INA_CONFIGURED +unset HAVE_PM2 diff --git a/boards/auterion/fmu-v6x/multicopter.px4board b/boards/auterion/fmu-v6x/multicopter.px4board new file mode 100644 index 000000000000..147297d55e79 --- /dev/null +++ b/boards/auterion/fmu-v6x/multicopter.px4board @@ -0,0 +1,13 @@ +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=n +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_COMMON_RC=y +# CONFIG_EKF2_SIDESLIP is not set +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set diff --git a/boards/auterion/fmu-v6x/nuttx-config/Kconfig b/boards/auterion/fmu-v6x/nuttx-config/Kconfig new file mode 100644 index 000000000000..bb33d3cfda4d --- /dev/null +++ b/boards/auterion/fmu-v6x/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/auterion/fmu-v6x/nuttx-config/bootloader/defconfig b/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig new file mode 100644 index 000000000000..2c0231e2940f --- /dev/null +++ b/boards/auterion/fmu-v6x/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/auterion/fmu-v6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="auterion" +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=0x0035 +CONFIG_CDCACM_PRODUCTSTR="Auterion BL FMU v6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="Auterion" +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/auterion/fmu-v6x/nuttx-config/include/board.h b/boards/auterion/fmu-v6x/nuttx-config/include/board.h new file mode 100644 index 000000000000..7907eafad194 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/include/board.h @@ -0,0 +1,566 @@ +/************************************************************************************ + * 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 + +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The PX4 FMUV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +// GPIO_UART5_RTS no remap /* PC8 */ +#undef GPIO_UART5_CTS +#define GPIO_UART5_CTS ((GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9) | GPIO_PULLDOWN) /* PC9 */ + + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is FRAM + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */ +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* The STM32 H7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 H7 BOARD DP83848TSQ/NOPB + * GPIO SIGNAL PIN NAME + * -------- ------------ ------------- + * PA7 ETH_CRS_DV CRS_DV + * PC1 ETH_MDC MDC + * PA2 ETH_MDIO MDIO + * PA1 ETH_REF_CL X1 + * PC4 ETH_RXD0 RX_D0 + * PC5 ETH_RXD1 RX_D1 + * PB11 ETH_TX_EN TX_EN + * PG13 ETH_TXD0 TX_D0 + * PG12 ETH_TXD1 TX_D1 + * + * The PHY address is 1, since COL/PHYAD0 features a pull up. + */ + +#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */ +#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */ +#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h b/boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h new file mode 100644 index 000000000000..1f45efc569d1 --- /dev/null +++ b/boards/auterion/fmu-v6x/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/auterion/fmu-v6x/nuttx-config/nsh/defconfig b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig new file mode 100644 index 000000000000..4fbc7a3b94f1 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig @@ -0,0 +1,332 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/auterion/fmu-v6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="auterion" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0035 +CONFIG_CDCACM_PRODUCTSTR="Auterion FMU v6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="Auterion" +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_GPIO=y +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DEV_URANDOM=y +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_NACTIVESOCKETS=16 +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_TELNET=y +CONFIG_NSH_TELNET_LOGIN=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_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/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 000000000000..037356efd3b1 --- /dev/null +++ b/boards/auterion/fmu-v6x/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 Auterion 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 Auterion 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/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld new file mode 100644 index 000000000000..5df2f5180a59 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld @@ -0,0 +1,6 @@ +INCLUDE "script.ld" + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 10080K +} diff --git a/boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld new file mode 100644 index 000000000000..860eb2ddd960 --- /dev/null +++ b/boards/auterion/fmu-v6x/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 Auterion 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 Auterion 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/auterion/fmu-v6x/performance-test.px4board b/boards/auterion/fmu-v6x/performance-test.px4board new file mode 100644 index 000000000000..5e69dd7ae311 --- /dev/null +++ b/boards/auterion/fmu-v6x/performance-test.px4board @@ -0,0 +1,31 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_BOARD_ROMFSROOT="performance-test" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_MFT_CFG=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/auterion/fmu-v6x/rover.px4board b/boards/auterion/fmu-v6x/rover.px4board new file mode 100644 index 000000000000..cd49a241b545 --- /dev/null +++ b/boards/auterion/fmu-v6x/rover.px4board @@ -0,0 +1,17 @@ +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y +CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/auterion/fmu-v6x/spacecraft.px4board b/boards/auterion/fmu-v6x/spacecraft.px4board new file mode 100644 index 000000000000..997a9054a221 --- /dev/null +++ b/boards/auterion/fmu-v6x/spacecraft.px4board @@ -0,0 +1,21 @@ +CONFIG_BOARD_PWM_FREQ=100000 +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_LAND_DETECTOR=n +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_MODULES_ROVER_ACKERMANN=n +CONFIG_MODULES_ROVER_DIFFERENTIAL=n +CONFIG_MODULES_ROVER_MECANUM=n +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_SPACECRAFT=y diff --git a/boards/auterion/fmu-v6x/src/CMakeLists.txt b/boards/auterion/fmu-v6x/src/CMakeLists.txt new file mode 100644 index 000000000000..39ec808e1e9a --- /dev/null +++ b/boards/auterion/fmu-v6x/src/CMakeLists.txt @@ -0,0 +1,76 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.cpp + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.cpp + led.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + platform_gpio_mcp23009 + ) +endif() diff --git a/boards/auterion/fmu-v6x/src/board_config.h b/boards/auterion/fmu-v6x/src/board_config.h new file mode 100644 index 000000000000..c50f0705f258 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/board_config.h @@ -0,0 +1,520 @@ +/**************************************************************************** + * + * 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 + * + * AuterionFMU-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 "V6X" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 1 +// Base/FMUM +#define V6X_16 HW_FMUM_ID(0x10) // FMUV6X, Auterion Sensor Set Rev 16 from EEPROM + +#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) + +/* MCP23009 GPIO expander */ +#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpio4" +#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpio5" + + +/* 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 + +/* Some RC protocols are bi-directional, therefore we need a half-duplex UART */ +#define RC_SERIAL_SINGLEWIRE +/* The STM32 UART by default wires half-duplex mode to the TX pin, but our + * signal in routed to the RX pin, so we need to swap the pins */ +#define RC_SERIAL_SWAP_RXTX + +/* Input Capture Channels. */ +#define INPUT_CAP1_TIMER 1 +#define INPUT_CAP1_CHANNEL /* T1C2 */ 2 +#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT + +#define GPIO_SAFETY_SWITCH_IN /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * FMUv6X has a separate RC_IN + * + * GPIO PPM_IN on PI5 T8CH1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7 + * Inversion is possible in the UART and can drive GPIO PPM_IN as an output + */ + +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) + +/* FMUv6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#if !defined(BOARD_HAS_LTC44XX_VALIDS) || BOARD_HAS_LTC44XX_VALIDS == 0 +# define BOARD_ADC_BRICK1_VALID (1) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 1 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 2 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 3 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 4 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +# define BOARD_ADC_BRICK4_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK4_VALID)) +#else +# error Unsupported BOARD_HAS_LTC44XX_VALIDS value +#endif + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_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/auterion/fmu-v6x/src/bootloader_main.c b/boards/auterion/fmu-v6x/src/bootloader_main.c new file mode 100644 index 000000000000..77df9e78bcef --- /dev/null +++ b/boards/auterion/fmu-v6x/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/auterion/fmu-v6x/src/can.c b/boards/auterion/fmu-v6x/src/can.c new file mode 100644 index 000000000000..cdebe7a3ad61 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/auterion/fmu-v6x/src/hw_config.h b/boards/auterion/fmu-v6x/src/hw_config.h new file mode 100644 index 000000000000..4ad1049fed94 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/hw_config.h @@ -0,0 +1,128 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 53 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/auterion/fmu-v6x/src/i2c.cpp b/boards/auterion/fmu-v6x/src/i2c.cpp new file mode 100644 index 000000000000..8a557078e0fd --- /dev/null +++ b/boards/auterion/fmu-v6x/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/auterion/fmu-v6x/src/init.cpp b/boards/auterion/fmu-v6x/src/init.cpp new file mode 100644 index 000000000000..88fe88126cd6 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/init.cpp @@ -0,0 +1,299 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.cpp + * + * AuterionFMU-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 +#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)); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +extern "C" __EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); + + VDD_3V3_ETH_POWER_EN(true); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ +#if !defined(BOOTLOADER) + + /* Power on Interfaces */ + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_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 */ + + ret = mcp23009_register_gpios(3, 0x25); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +#endif /* !defined(BOOTLOADER) */ + + return OK; +} diff --git a/boards/auterion/fmu-v6x/src/led.c b/boards/auterion/fmu-v6x/src/led.c new file mode 100644 index 000000000000..1e33dd1299b3 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/led.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/auterion/fmu-v6x/src/mtd.cpp b/boards/auterion/fmu-v6x/src/mtd.cpp new file mode 100644 index 000000000000..8e57555eacad --- /dev/null +++ b/boards/auterion/fmu-v6x/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/auterion/fmu-v6x/src/sdio.c b/boards/auterion/fmu-v6x/src/sdio.c new file mode 100644 index 000000000000..869d757756a0 --- /dev/null +++ b/boards/auterion/fmu-v6x/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/auterion/fmu-v6x/src/spi.cpp b/boards/auterion/fmu-v6x/src/spi.cpp new file mode 100644 index 000000000000..b1100edacfba --- /dev/null +++ b/boards/auterion/fmu-v6x/src/spi.cpp @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * 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_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_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); diff --git a/boards/auterion/fmu-v6x/src/timer_config.cpp b/boards/auterion/fmu-v6x/src/timer_config.cpp new file mode 100644 index 000000000000..928f4916f0b8 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/timer_config.cpp @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH2 T FMU_CAP1 < Capture + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + * TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer1), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/auterion/fmu-v6x/src/usb.c b/boards/auterion/fmu-v6x/src/usb.c new file mode 100644 index 000000000000..70eebc6fe0e1 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/boards/auterion/fmu-v6x/uuv.px4board b/boards/auterion/fmu-v6x/uuv.px4board new file mode 100644 index 000000000000..3a7b00f13de4 --- /dev/null +++ b/boards/auterion/fmu-v6x/uuv.px4board @@ -0,0 +1,23 @@ +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_LAND_DETECTOR=n +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_MODULES_ROVER_ACKERMANN=n +CONFIG_MODULES_ROVER_DIFFERENTIAL=n +CONFIG_MODULES_ROVER_MECANUM=n +CONFIG_MODULES_SPACECRAFT=n +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_UUV_ATT_CONTROL=y +CONFIG_MODULES_UUV_POS_CONTROL=y diff --git a/boards/auterion/fmu-v6x/zenoh.px4board b/boards/auterion/fmu-v6x/zenoh.px4board new file mode 100644 index 000000000000..cb14fde93580 --- /dev/null +++ b/boards/auterion/fmu-v6x/zenoh.px4board @@ -0,0 +1,4 @@ +# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set +CONFIG_DRIVERS_UAVCAN=n +CONFIG_MODULES_UXRCE_DDS_CLIENT=n +CONFIG_MODULES_ZENOH=y diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 45030adde4ea..4a20430f10f4 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -21,7 +21,6 @@ CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GNSS_SEPTENTRIO=y -CONFIG_DRIVERS_GPIO_MCP23009=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y @@ -39,7 +38,6 @@ 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_INPUT=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y diff --git a/boards/px4/fmu-v6x/init/rc.board_defaults b/boards/px4/fmu-v6x/init/rc.board_defaults index 2d9a6ea49a31..7dfe7b546a64 100644 --- a/boards/px4/fmu-v6x/init/rc.board_defaults +++ b/boards/px4/fmu-v6x/init/rc.board_defaults @@ -9,35 +9,13 @@ 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 - - # The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). - param set-default CBRK_BUZZER 782097 -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 +# 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 safety_button start - -# GPIO Expander driver on external I2C3 -if ver hwbasecmp 009 -then - # No USB - mcp23009 start -b 3 -X -D 0xf0 -O 0xf0 -P 0x0f -U 10 -fi -if ver hwbasecmp 00a 008 -then - mcp23009 start -b 3 -X -D 0xf1 -O 0xf0 -P 0x0f -U 10 -fi diff --git a/boards/px4/fmu-v6x/init/rc.board_mavlink b/boards/px4/fmu-v6x/init/rc.board_mavlink deleted file mode 100644 index 713d7a41b72b..000000000000 --- a/boards/px4/fmu-v6x/init/rc.board_mavlink +++ /dev/null @@ -1,13 +0,0 @@ -#!/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/px4/fmu-v6x/init/rc.board_sensors b/boards/px4/fmu-v6x/init/rc.board_sensors index 100c67410813..75eaba3d1c3e 100644 --- a/boards/px4/fmu-v6x/init/rc.board_sensors +++ b/boards/px4/fmu-v6x/init/rc.board_sensors @@ -55,22 +55,13 @@ then set INA_CONFIGURED yes fi -#Start Auterion Power Module selector for Skynode boards -if ver hwbasecmp 009 010 011 +if [ $INA_CONFIGURED = no ] then - pm_selector_auterion start - - # Auterion's INA238 uses a shunt value of 0.0003 instead of 0.0005. - param set-default INA238_SHUNT 0.0003 -else - if [ $INA_CONFIGURED = no ] + # INA226, INA228, INA238 auto-start + i2c_launcher start -b 1 + if [ $HAVE_PM2 = yes ] then - # INA226, INA228, INA238 auto-start - i2c_launcher start -b 1 - if [ $HAVE_PM2 = yes ] - then - i2c_launcher start -b 2 - fi + i2c_launcher start -b 2 fi fi @@ -96,33 +87,22 @@ else icm20649 -s -R 6 start else # Internal SPI BMI088 - if ver hwbasecmp 009 010 011 + if ver hwtypecmp V6X010 then - bmi088 -A -R 6 -s start - bmi088 -G -R 6 -s start + bmi088 -A -R 0 -s start + bmi088 -G -R 0 -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 + bmi088 -A -R 4 -s start + bmi088 -G -R 4 -s start fi fi # Internal SPI bus ICM42688p - if ver hwbasecmp 009 010 011 + if ver hwtypecmp V6X010 then - icm42688p -R 12 -s start + icm42688p -R 14 -s start else - if ver hwtypecmp V6X010 - then - icm42688p -R 14 -s start - else - icm42688p -R 6 -s start - fi + icm42688p -R 6 -s start fi if ver hwtypecmp V6X003 V6X004 @@ -130,13 +110,8 @@ else # 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) - icm20649 -R 14 -s start - fi + # Internal SPI bus ICM-20649 (hard-mounted) + icm20649 -R 14 -s start fi fi diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index f0a8d6ae8653..ec6b1c7e2b0e 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -91,7 +91,6 @@ CONFIG_DEBUG_SYMBOLS=y CONFIG_DEBUG_TCBINFO=y CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 -CONFIG_DEV_GPIO=y CONFIG_DEV_PIPE_MAXSIZE=1024 CONFIG_DEV_PIPE_SIZE=70 CONFIG_DEV_URANDOM=y diff --git a/boards/px4/fmu-v6x/src/CMakeLists.txt b/boards/px4/fmu-v6x/src/CMakeLists.txt index 39ec808e1e9a..605cf16ac948 100644 --- a/boards/px4/fmu-v6x/src/CMakeLists.txt +++ b/boards/px4/fmu-v6x/src/CMakeLists.txt @@ -71,6 +71,5 @@ else() nuttx_arch # sdio nuttx_drivers # sdio px4_layer - platform_gpio_mcp23009 ) endif() diff --git a/boards/px4/fmu-v6x/src/board_config.h b/boards/px4/fmu-v6x/src/board_config.h index a57610545ccf..3259c421d57d 100644 --- a/boards/px4/fmu-v6x/src/board_config.h +++ b/boards/px4/fmu-v6x/src/board_config.h @@ -270,11 +270,6 @@ #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) -/* MCP23009 GPIO expander */ -#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpio4" -#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpio5" - - /* Spare GPIO */ #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) diff --git a/boards/px4/fmu-v6x/src/init.cpp b/boards/px4/fmu-v6x/src/init.cpp index d914b754975e..5d2a61420672 100644 --- a/boards/px4/fmu-v6x/src/init.cpp +++ b/boards/px4/fmu-v6x/src/init.cpp @@ -74,7 +74,6 @@ #include #include #include -#include /**************************************************************************** * Pre-Processor Definitions @@ -286,13 +285,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) # endif /* CONFIG_MMCSD */ - ret = mcp23009_register_gpios(3, 0x25); - - if (ret != OK) { - led_on(LED_RED); - return ret; - } - #endif /* !defined(BOOTLOADER) */ return OK; diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 84e76cd888e5..f64b7801e410 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -40,7 +40,6 @@ 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_COMMON_RC=y diff --git a/boards/px4/fmu-v6xrt/init/rc.board_sensors b/boards/px4/fmu-v6xrt/init/rc.board_sensors index ae60e13536ce..99248dde7285 100644 --- a/boards/px4/fmu-v6xrt/init/rc.board_sensors +++ b/boards/px4/fmu-v6xrt/init/rc.board_sensors @@ -69,19 +69,13 @@ then set INA_CONFIGURED yes fi -#Start Auterion Power Module selector for Skynode boards -if ver hwbasecmp 009 010 +if [ $INA_CONFIGURED = no ] then - pm_selector_auterion start -else - if [ $INA_CONFIGURED = no ] + # INA226, INA228, INA238 auto-start + i2c_launcher start -b 1 + if [ $HAVE_PM2 = yes ] then - # INA226, INA228, INA238 auto-start - i2c_launcher start -b 1 - if [ $HAVE_PM2 = yes ] - then - i2c_launcher start -b 2 - fi + i2c_launcher start -b 2 fi fi From 7f5b503a198fed81f11e11455590f2302a1bbc6a Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Fri, 10 Oct 2025 14:16:00 +0200 Subject: [PATCH 2/5] boards: remove USB device from Auterion FMUv6x --- .../extras/auterion_fmu-v6s_bootloader.bin | Bin 32888 -> 35108 bytes boards/auterion/fmu-v6x/default.px4board | 1 - .../extras/auterion_fmu-v6x_bootloader.bin | Bin 46892 -> 35416 bytes .../fmu-v6x/nuttx-config/bootloader/defconfig | 12 -- .../fmu-v6x/nuttx-config/nsh/defconfig | 12 -- boards/auterion/fmu-v6x/src/CMakeLists.txt | 2 - boards/auterion/fmu-v6x/src/board_config.h | 4 + boards/auterion/fmu-v6x/src/bootloader_main.c | 3 - boards/auterion/fmu-v6x/src/hw_config.h | 15 ++- boards/auterion/fmu-v6x/src/init.cpp | 4 - boards/auterion/fmu-v6x/src/usb.c | 105 ------------------ 11 files changed, 11 insertions(+), 147 deletions(-) delete mode 100644 boards/auterion/fmu-v6x/src/usb.c diff --git a/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin b/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin index 2c79c4b1bab5367e36ca229181ada79f098e7877..233552b39789f86ffa3ef04330d8fcaa538d0de5 100755 GIT binary patch delta 10502 zcmaia33yaRws2M5?#|6Z(phMlB!t^bu(J>v5+H2Sbi&PsBoJg!K$}Ip5S9p{5plX9 zIHE+w6!U%r$6-dsCnGAI5PzeDpfEEoGfsjq14MiX&TA3D8wlLn`#aTv8NN6F_x<<# zs%tr?wo_-TQ>}W){#K$}H5^&BoHzLe@`}LI-NcC-X&=d*>Cqu8-;q<3Q+Y1?8_=H7R=~GmO`n(C5Vk(sC%2P{al*mh(k@P{nOJ+`vbI=fxztSLj_CL*LA=*RF1db`?vwVCH$d7gNJayCj&4Y57A z6E-NsA!`U$bzlhMw?lmq)E7XqLb5?Bgfu)G@n>@p|7s56(>sur$or$(8po|o&gCYw zOH+yD$ss``hx9NPn9$mxM#~ zR*I0;8!82qkHW@Ie4tb$@^>L>)0gYm=-YI3y?$=OU=dmC;^>!pCxKDYQb&8GhptmaHBCFg^5bDAv%OS2md!K-c0-bmdph^1YEXqB${c$fzV>9sV0 z90^c;dQmo!<2q6IYe~qu3sPx^R>W2lES|_e57GzI&17|u{ye>q+#jR|)0ZX@d0jy0 zoL5QYh5*gXuq6=L6kv0F?}hl%8Pg#Iw>aX?zF(xt`{ zvM54#8?%!ckJuqG9uvx?;F6ipan5dqn)IAoBf~2YUI-%X@t5P6h zQJR@mo_sFCKqFPw>3WE+&dQ0aJIYx40DUE^f_xOB=dxOLOnj_ybba>hCa@oJy}t z!160WdT)*)X?XY`G&rEa6Qr&j!&E-}yW0)xf*NrF^mk~XhH zm{J$yz1YHS)ORr!92|?T7%31>2xP%N>WdFi_njF^J2WEdpQU97^>V1LQ`0{$R(?K2 zzZq#wdLm@&6iOH!9}CfBA)g)2WFcGsewdvo-vQ@n$FdrtD}-@m-WIw?C?(zyJtY(- zzZAM7lc*aY$)-%w8lw3oVb;nJF5$-~7XHwS1TAC!=6S$DOeRZV^;|$B+P&;lv22EO zS-qsRi}6{|r|&3VDToo}1f2XJ1O5HZ zxZn-o)1m05??@7zZ8m354_c%w?;dH3lu*9MRVK}J9g}ufTmdk$Qo)i*-!xn2W(Ser zat-R0(k`QzC0+JuDj99B$42Y-Wl7O*SQlggHE7ZU9gVmg56tuTJc1Ylh*veW;rq2jiU5jwCUzMl05lxdgDeDfXq=FI;FK=mrM7L+oQ zJycMH}Ipb9c1lKH&Q*w;xYYnL*Kmq{Vj0H%{TPh zPpU2U5mK&;NkZ=`If}PVPE>!>P5%DclU0I!lw4R8aP@kL2;) zFzm9=eQhwU_vVFlP?tURUjV~KE=Paj);6ne=^HD!wO_%;UR~N);l5Kjv+~%DV*mnb zuRW#iM@YUAJf$AAAL|!Tvoon@WWg!*kkGS;>&GOa8(B`M2L(uW;9();V_J=4G<+7B zV>H}4NW-l_!*dPQotdjAcYdY52BUr&)B|&1IX4`Wb@%qtuEq}ST2P9kesSn@4CS5R zish$aefR*Y+lnz=)%ghlnA%oM-+)owNo>gRNd8&Svf3;rR59?0 z%PHdvfPohV;||%u!@+V8{5j?}*d0;jg?~;|+QEr>aj&#^rQvfxy7B` zvraam(yrgP?@~9}_j(`9sdv`Tc#zZ%csA^UBhD;y{;(y@Dci|bx9gPZ(IeR&MZ$mk zGR2>K=e(^T19r|{VCYSQ4w{~{0pw2VCKhbj2E#Q=$8UJjx2c=$NFEzKp?Z)F1an{H zo0ytB0ZLo5c9*&hg_Ua|WM-w*nDP!QN4i1fuhmuMi@%J)4@Whk+t@i+`4M(l+BMXU z_=|OQR}Yi^5Y>BQ)B#Ru5x!cvw=G>xPT8+MVaGkm zmh`0zA6QnOA$|d{-$HwzF7CA6lDPCFaG2hUOi{P;x9DL2?AE29KCC`2yrN4v&4xS~ zWUZMx9c#5`=}4^g6)+O|E;h+eJ?uP_&6!Jo0Omtx&Dw2hlK>33#gm&Z4hk_dhfIh8 zvu;0(T_9No&TJ@?^;`i^y`}DL$s)Tk_qOYcm{yMoh2B{6s*~&0n}$_}l_9Zxr32a! zE*-k;L{a4(Xxjz(0m%2+>w&G9tjq^Wu{;U%`U!Qv{gk>p24fsw2{4vN{0#P*9sC|W zcF5&qfxYA7rA^Nr(u$h3D6g!S?P$0wwhUoP%^tQ4^JG}Y=P&@9dOPH7>TQs>=z)>! zHnCb-=rj*JGnX4c_333bY+piAO{$dWU<+;$cBxO%Ib+h@JHo7%E|tlszDyng+d&qf ziJkFO6I(8-1J`en9~OuJ6M4WL;O$}MS(s}dGPWb|pP@Y_LDpi}BEl3Df}MZ?*V2^R zLUf4XAcr|mcYw+0SxAu9|Lm5=<}{02~4I?_Z=E=N2A3^i_t&EAl}`PSS5kn ztqar07y}sHFV$jjlKH~^UJXe2Lb#Uw8O&W{Mf68~hf|u-lrD|Tv&bX4mhL1gZ%ubi zw|vqxqbW(C4z3zZFGfLZo-4gkr|&w9nISoLnWW8-_*uLpI2|%3x?WU})SY2TvZR+K zx(I<1?}dLhKMgooOCvB>ZxT-)6L&DCEYW!fRp1m62R9@ zRlB-*AxVe}a_I}DPwMieWzrtkQmH}u%C(;3PUo*oFJCI9FUeoIOnT6z8*mgakrE{H zfMXn+ST}Itv89strpH~s(jtGv89`~saqjvhOQfXgL@CpeSX1m^h-%mJdypBM!b+Qe z8CdeZxX#m92rD1^@$_50?LM~4ktjWKAv%Ef^=EOq0)0pBnZ7n`PO@fKji}@bG(mFx zg+-a=E#26HEa(c+JDcFDMxZ@)cQ_*M=v;;&%vND;5Nd{c9P}T4U#KVHml%&Mtq=NxrU?qs4I-Mq+~+ckD<%N*URUtpoRe*2awe1KF89Nv14}gIe>Ds$WXa zc>nA+wl*DWTPrPZB3Dk4lWn_@sG5-^X>NMfBWp(8r$)I87oYSYA#m4DolWUAKu~P& zNU~~zxcF6RiFa=kvfd|gS59($ZF|s6)#4yGJsYZ}*Xm%w&HrvOkr^o4xR$w^_Cd}) z>}<-mYS_T+q>2}-nwq_mv4T;d@$k&1>`|IojDWhJw){J3zu0)h6@!&EWt$m`)|cVx zuNDmA!$>ABHWG%BvQ`=^!104|sNJ41VFid7N`;6<4Hk_OlK=DpNa|hnEbtQVt~bW& zbd&uTny~V1fNI7rn7{>)Eve5YhLtzN$cFo{aNP&mPvs<3aN}#mCx}1zm|sW0lT7T4 zDC<6Itbiy|>)2B`JFL9xXLcz1Bi|8LG6TFf!_If1%8*Z!+P<}z2Zp3ON=7FA(LWZh zy89}^iq_x$en~aP&rm#J4!Inl^CrwAM+5Zt6U3x%VI_e+eOE;J-~$?(V9OpG){2*; z-Jn@5FW_R!R(84Nb#_?lhXLxCXe~?)1E3(e7g+#+EL$1NTyjN}CskzAo?~~QsB)tV zPqA#(cTu6V5_AeF2Zw&rPN%jfRmIbhil?9gr8g}TnL^5=aB%{}meLYZxRriVIzixp znEN0O#}dTkVtHc)k)J%mf@E96)HuoN4lDb>9e{mXY6tq(lPUuDpjJ2uYct{-;Dj1M z9}N*Ntr5h%4Iq^^f6t{gd7>a@HFSO7=rC4{zO2;#0j~as{AT-hadca)>`ADVaUyQT z+?>JU?@++{W$%(|`{ZmVf=Bgz_7DCP}HX1F!1+$ql<5-1m;#`#!5K z5-P=q1KZWsl{+ig64+AW+tS)zaf-bR+PW&iTM4^mWo)Vx{~eF?Y=_bIfP#$gH=^fN z0($#zDr-Zwm(QU>z8k2c0h&MS{&$UV_Y{M7v;&l#7^&JHssyQSOTQ3 z)0|`k*ZdU-F3)HNk5${B!8@SeFI7#>$i5=bzy>+08{dPA#^PRjXqaKym8NK0L+6z> zHn@w!(dNXRV+xh^se!rJeV@Vh#$Z?0aOW0EHeiMyeS3i|Sm_F|1;AJCu3-I&8oz}V z4AXq$Q#w*00^-u4{zm%6l;IEV4l#BkUkfY4N=D>e=MTNyA-QYxWwoqXN*0HTi&kp- zGh=HVt;Xfd>_elgdo=wnf-G}Y&BJK)xL(bbW-`23)1Ms=C2szTN^!#y;2@RWJ2l4| zR?dejVbLY((ih)&u~JNH%WB)>%<0}BaWdvcl!cYQK%8l6HYl*JFx@vbGldzeX2}B= zV1u}LWf}cqYH^{%4;*d#u2wP))cO12v8!bd_k8?8-f2!-P26?Bl??Z!zRb~Tv@}!=wI|=V#LnV z8h#n93e%HpIjBFI*NDlY1E!uH)#gm>V@Kphxggf@Aaw~BcUW2mcV+-(0Mfbh-=&kS z+ZesHMhmjJ5M&cn$LNda2IVuQ7LES9igqTSV+VXbWMc>XT5C~Hx#w~soahGaWmxBlB)aL|BDWs=Ed;?q8+fS+x62t&)&!BcRMhkvb*Vsx zZ~&R@5G9BzYG4pQ6L78vkf{_r|B*ptvO}H~v;bWP6(Fo-29lrZDhCA!*Aoc;M3w5u z8%%r8;wjghsP>wj<7q2M$`bpax6 zI~o>LM%mJh;H8#DF_f~QbZ@L=gVLlZa3R7bHW8A?b+b{lG2YAo0}@iaVM`M((47U_ z(8vr*EnHRLQfj)ihOV7qAR{Amr`eDkBOgf2rKYS-fc$>O>T#FWum=xz?C-Q)1%1j? zcvNv8{g-<8^;lX2amlKzwu@^%Ta?y7E1e|-djH&MG`t6*7*!@l2~*r#4y%P8d;mZP zolf^BJGk2{VeP>!pX`WlD_g}B7HLU2#|5_DC|h=X2LU^f*0wkE_%dW^UdAmyz9wr` zgV$IA@awq6xh%d7Y=|&7^VsF&amROLwO#c!R?Jw%wK!MfK=X|m4X--&hZB0a7QoUI zXlW1j58z-%aaJ2Qd>gVHyR0uhzAV$r{FSKkw=R}9R?ursL(TxW96%w6H)M!BFawfX zW5$w)c;l~*P;;5hGCNYC=Ay<c zcaf&;hv*BU6F<}b7tw+f7{l+ zY>hYDRVRL?3Nu1VDjZ=%+0|ZKwFKiG)LUJKSJIo+kCHzH=|eSU@&^bS*32SrhG|dD z>-ZpDH!BOjPIt_@gw1r_eZ#PwK6jsq@Era9ebs4~KhSqEA91&YyoL703Wy%+X6NMp zRmB!0Se{I{po3??u<|FBSP+nsGn=0@OX;zo>R?oo&Yo@5AA%dXO|(EP7UkZAXA%0u z?76X6A$$CqZJ5ANF$70h+?AF24sA`M7j7VGNVybYVakZobOd#u&t-m>R!kCu%Goe` zlcM(8w8EhBRX8T-g*VRQsW#x8#E`Y^2VbG*nr~u`YL3FHG0g8hN{_ zff1ncQf)PUf}X9-BeI`r>Iw9|3GT5>4$IEYwdPZ zxlA+xr8IBApQE`S-Mg1H;7yVEpm<0Wk6AHpbxsL$tVMT(>0gaI2v$GFff1>5~(@kItRCb zP;X-eNVvFUt^2fu_$!d^gY6ECn0fs$!d_2Twzz zZ}#F687A1YG2nx)n;xBjU#8wiO?Vgm>d`8^j*gHBVt-H*r9SEPEJNdF-PiOtY{ zapf*N{9s6vqwC8T;l*}$RC)QfJq;=E)0Z0_NPY{}$PPaVw99+p_FD}`4bl6lzA+~` zLme#yl~lD1ev?%?wXqZqyZwpAR!mAcny_8~X~NyKXni&m`j67t>$5Wh%C}JuJmSPv ze%8iRe?U2VR9hK<7&YCtzIsAHIUX4U)nkz&`0av!xv0vy2oeg{sLJ0W`8BUOoxNa9 zp!KhjQJ^9VA5oRhBUH1&nWifL8A+~5t1bkeHWQlnMd*SJC5-)E+K@wj@1gH*Fs!Nr zl9C*4jkYqQ8=H6&ku_wvOJh=%O-C6_e*s;Hz0+2z%46{F8CGZEKusmzp(;|OR=!|C z<~>W8PrzV=z3Bq(!hhnDSiSxzEqXi?wygv8_jsl8Q{bw~XA!Tl4bn3G4BNxuFg^Hq zX1=QY4lG=07chW5=sOIk$blBX>5A~|*b5 zW{N^NbNf`~!!GLDXf9IWnuVv{>|H0Pz!Qn1W){dgd-d0fbzZ+x5!B>pAb1p2_D2KC zf2;J+MnhT&G-_jwe~Q|~fO1l$XEr`TZ<#mkp3UovSa-MZ-sH+#y& z5SL;0M|)RphdNXd`;!8LJ8suYZ|76ju3Nig%_H}s=#QT;_;~^Gbo+vNie#Ge*Hg-u8Nc;_Jed^z}m zGX~2us}Ro;>o@*(e!3p<8|EUuW6ogv|Aq3abJ|xtlSZ_=uSVUNZgHDw&(oSz@+o_` zANtjuB{l2>!CQUbdaCer}Q++EMCF)X;dZk~l2@2=<1(`~=IK5q8?`h9mdOrCG};O_e1#B*a=>@bMq zadu_kp#pfUtY^S^WWi=A-==dq(E5L;6g_5`JaG^<&;qgmkhAU2j{|-x2Ht|a3({3c sY(Vz?zhG<{9 delta 8556 zcmahud0bOxw%>Pi6GA`;pcoeMCIK5Zjfxr-+Ys=wgbIRMM_U^~Z4|{+ZR=KpqSjX1 zT0T3^Y8P7VjMgp&%si<@>~yBv>$6bnJgZ%7Z71$tD)!#2_ni-LmiN!g?|1So=UdM? z-`VcL7Dj4fRBsJMnM#Ex?iuCYp&iJW=gf6*ysHy+g%s^qqii_ly?}v_D_3wxc#BMm z&W{ekseX(`Y7bcv?PjEP=+KYu>!Wbs865`ZeBq${Mua`+6 zb}e%I{?0&Ajo6N%l!q zf4QO@uQFb0W`qsl3FRDruY(cR1;^X*VJAO+M!JJB=DM&jBJ|xAgc)I}pEZtmjCbPP z>ED^1O^6XT`E%?#=wTgP+3Rj3yhBFDjbSNRRfgWk{G3;&|q$76|#~ zDx}t~C%?sIsK&+tdDfHE_)+*_QWS4gMaLucw=7u}KRWSSSoZE#v|H^Zr=yd}sdyE; zE0VjOd>)@SbW?=kF>m6LurSQ=SU4T}nk5?TL}vDJV$;?z8v^9_S}w6FV1Xeg!nzK8 z*upbHU4VS5Em6_cLkg0ZP@@^BqRdZO(wJalV3oFnQB0bjoKILrTYMtNd@T`Y;#%7J zDbd2r_mlJ_Q$H@rtlJ~qXxnx>VF$-sIypYmdDEwcecTdxE{S8NNaSeJ=yWV>JBhl6 zYEWh@fW@oiai$&)&j=xj1d(Y*0SH)u<)V09lDU|Y>$@1!mnYX8&=0+p;jiFhHZ(XvUzvIox@06awgzz zM99SCd-JgHMFj6xIGFwQTceJ4UKXBL?!^L2B~orV7x^p(%N0jY^=gpMpqRuASR9~BQQ z6on-p<+0ZL(N306Qx5xjN=K8^(g6Q^!>cdlEe`+;{NJKoCTi8z_TKaBVHYPs{h2Y*d?*BbqCu!tG^xwHNpZ{Chk=RQhpD;RZ5AZ(+s+$QpfKTx{U(qeNYRc~_sxXanSPJy+@T z;{x@Bn7pe!h*MJOZ!QE0qL0!7N_sO$quE2biiK9-%kqVmPAX?XpVnKll;b1fUu2G_ zBtXLaE;7+j!SqOEi=o2cmELy9ZBNlR$-%0d6&2ZV@T1agkkeu4j;}yNZW;{fos!X+ z=Go`m?9`O(a}+zLJ5D+GmRYeS51J2uyHeWT6GJ(B#N@n(} z_zP{#uv!-wR>}=3ITmj$A7xkawbEFv;@V#nY3nXTDb6Bcq?Gpr2)M9K4)_GHCrUfx z)_QBDaav%%uv{T&=!^0OdWmOVH2)u7R-TZsfl z0#QDlZ7{rd8#U2Qkx+Sp`XjeazVki!C&=Q}RAxCDp*cVja}23;X}TD<@8N2)Os&%BIUTW!%irmC-L^&TKWYO(F==0uxdX0|w9Ux9@DFyef^R9^6X_hI@F2;zBTVb(g=SR1jlD0~-%t#m=Ze45w*$zd1=vOo!gWB8L zut$0jg~i4&GSFH=zxoS{eO(sswgy#s4*z05{yL~mUB^IuIaohSXUAyp_q;=ScTMA& zrTg3Vst!ss%t>dDfoMIgia$#g`(ORXpf6RWqP^xc71Q6l6*RB5Gf9YxzttUQOsc!? zldoIgAV{y|>l;%XlwaxgeKtjp){s^f7Jmq~Hp=3h;6?ba4K8d1ikMA&g>$~m(D!7G z!rg~zlZx$*y2b>1f-}aN1hqZVOf7L5`!3cS1*|B(T2xOQvbZ@?*NC_zXR&~4i-jSI zBnLJglq%6ysoG3UG}2xV`WQgGhgn!GR@N@ic!0ho6 zH}%wxz?n60X0}JeN0({!VR2iqt})4J?B9l-{|7jK=Vg~w7SEr!yOG-)Q|<))kq|=0 z==;<8*$~xC_AE#@k9YFVO3}cwaq@WZoz!`~J?v3eXECVIW1t3IrSf$Rc*u$}2sVm@ z8i@gqUkx{y0RybD;HTR$uX7^d6EMgB+D_~E_qMCQO)@5K2UWrc$)SmJW4DEnDfWU1 zjG;*)v6FO(R5dZ63}ZSXVsEFb6oR0MlfK63NJt7$L6EPjyjGBP$UFczG(*3z)}Ww3qTlnRWek~gQ$WE#RmnmUWIhRKXVKDIuLOo0p9 z&WJeW1ZgcarQZrE`Ag2dAO^-~@Oa}E>Yk}pWr{-AxLnm1Qy|crrXfFR?{+CrG$TAz?ep6MKja z^=Lb3%kLwt(+U`NBl+93iCh^_b1j6E6hL$Lm#$JqxO0NWc~Xev-J9u-i0473;qJz& zz6-0Eat5rq8b}}7h}5;f5*H};A$)xU$M0XZw-lND-SrLGJjbUkqY|Mj&A%d6{S_S8 zqke<=X+FQLN@$9y60ioh;0Z@;=ekgqVOL_?TQ*JirJeb0b;}T!)&}wH?q8Y})W>l@ zkM|e1gOu(73EjTxPdlNu9n|x{q?Dez1`M(0RtdM(EZbem_9nx7e=Atm5XB>X%`%SP zUHWifhqMD`p)sGIUnwXM1l0HRfsW9i(>{8*W@i&0$K#d zSmSkFLkxI=O2WC{`-bHBdy@K^+`2A}q0fi%Cx3fRQkzk3dG|R9X%hr1F71H}J`ERq zYT$xT!3FDpq7Mh2cKchF?k-*U>>JNU!}c%O?isxCzxOiTPs0rl`!K}cI`oDsEM^C3 z4>G-W9_6dM;ND8gBCOxPbZ==j$bYY7;`<5wJRMixPeqD*3Mf;pyiDn%`~~P^5Q>_e z3zn*Shk}0_79#;RgS#+(EjT%X95uEZkIC;LyN4yaZ?C0vZs=IuU{tG2OM?}KFlqZ#pV#+k8+uBxup?>xLG30i_*>e0#O;$FQEL2ZnoFL zAS0wv9!B}&df02tO#FDZH$56^ioeyD@v9exMQ?x{FUrtF#0selZufeCTr5gv;h92o zTa*r!9EqgbQj_KD;7yfMNr~r^c`$LHGLCrqHa&kM z%x3&{-ZLG4^@nTG?A4vQ@I=zuKm~U<0H;j+e0XY9QeTw!_^1k_r$fEzY8E8f3jH3x zGGp8YQmsoSO~p#L2Hr*VPdkl+t0ce^z58nDO7!Z_`|H6XApLxJGw_V_edh;4g19P_ z|34Di9e19tJ4-fEPCixDw;u8|H>9b~1J|Mz?Kag{RJtzoD*&PU3h;2X@`{goz*KP& zZHdXP3Jye^CM1h!us#&(fdDdCco17v0ubRgw9Mdp%Hqwy!1z=cb2)(Y7O=Tzpfp4I zWxxnj9neQ`oFecVI@6z|CYuEjm&MtU18b*xsP5FE11_p9!(+u?PHH>p02T&JkJJwi zNJjMo1H`j{cX^wgar`j;!KL*L?UzexFm54J`G&cn2o08X2nk{YLoFR@zxLNmP`eRf zds7kC4+K|#KS@_n!WwMv(0-ksEg9G1T-7(Au3c2ee*!KJr04YY4J5)RGg%R0HYUgQ zQxIOqrL}1tfSFRdd|W;F4O~C7-)Xzyp^u2#Sog_)YFl5oaTmugT$a{W*YMeciOa~j z(gFr%$Cc@l>mwY{agxkXJ-Ydrl-Gn01FEphrlV$!rNM+p;oR?3c!1-e;$4W0E>C5) zog@|IrU!RNN~J91>cGMFw3$zdd8ozj40%~tti>F0><#0yCxp17$%aS!D{^v<@x;!11kZa{>%+C>`uE=55 zgh)Zf9HuNpc2#U->LWyBHyQeZ94|o>t6>AMw3-!tf_K|d8hR}S0~&%rhRm{?m@gq} zvYRxr80Dur>Q6y()SiqllTYkpqWi$~MxBp{Ul7@z!mLFkwK83IG&o>I)z*mk)=4~7 zv6(s;fSgg8%nT2cC6yDCp9kAk2?i1wX&{x%?>L&|VAhhhN*nHKzf)<%8am>k{!zp* zV;5dS-kb6CeeVQW-qZnsw^D#3W91EBbZ-GDg^(BBXMKxo^(ew z|Cz)Ug~hXeiuqgn6IBZ_{%`V4bum6dM$CMKi4KwNGYw2tguFGgk}*e!H1pLFH(|7^ zlV;*T)AGOiTAgZ-EWQR5j))gYd(EYk9KX{sr0nA>j8YbdLciju&>71`#8u?IT0OHB zk*{hi5_3DWoz(l;>qMSBv#S(ByV0{UYDf?p5odftb5R93+Ay4#F(T8QZiT_{gu$8A zAMxG|87ciF{G*@7nGulz9!-OUtqU?9u|UvQB$`wt zb7v=3hQ$AX!~?vkyxZU5LK7grjAXW5_2o6)^iA@z8AJHw3nR0Kp9_hrB~S|nj$aB+ zD5`!|!scfshQlNz_Cex|;>n+8SK#9W&&g)S1xVhUJf=`X=FOSKg~bU0tiKGdXN;tP zz~8tF9`sh~To2rgoSu_$uP4m%H`-b~j62p&^8^v`eLqd;(1$z@)_*PZ<4zhrC@_7@ zA+f8IVpj?ba&-#pNzMbQ99@lZt8z3w)?Z~qtMnkZ#?T}!;E;h?5*C+yKo&hPI_F@- zVg-vU;@zztd?+MdmM}P7A+bdo;VFg>0L{(@hiY9&d{-hLJTS%C7&d}WJ-osSL%xSR zkP5u`!XQ=YGbIR(w8%Iz`@o`vb7l~rBmO22^f^%e$K97!;emZlUdg=LBq^c;s1zbga2aUs| zs)(3yd|XFZY$Jc1J7PqYJX=!l`e?f59Q)NgUeD9)_Yuj$AAwC5lON~4z+}o~&F`$K z3fTf(QsklO_w_yY-l1MKlg-cNgW~icIsLmrV|QdG%ngfkE(;s@Y@RuUgyE9%RXmX@>Gy$=4i5&Vsi428eZ>4L z7&o;?J+y++xWLvt0x!RQefy?|hqAbpkowv6$vr?5tQb)uFl=C7a0=nu`8~9tROeg2J_9RnAdKMBpr*=hOF8BgS4h~ z=5=ih65_~@i<08qqWirHzLrOOi-53~2wpra?p$Ou{|x_k;33WB5N@$fW8H+*I{?-` zNoZ+0LfZK1B$2l4O#lWL)#D{eTyqqOW<49;snAk8Ks&9)#?PYYDopNB!Qe-v0Rsvb@NTa*64yn%oOaO2%{3kqAKTr=s>0N}>mjH~5k@^6@bb!?W zcnKuj|IfUCUE}|&PpwDocIP+PFmMNyNlA4Oa$ko4-Ug`FqRfG_xAV*9V#ehstqtF* zszLr6){`yEt+-haVI%X7dNYGIxO zXoa<#p#=A(l5>W|BAL2XMo4L)u2w|Gt;k`ZSg;~p_l$&1Y&V{U^6&KE0s&T9|5(5W z$d(lo@l)ip6?%M{Tw75-@^IK-R5+>xWK~>5S=W93ZmVrphxQ^hj3IF!scoE%SCYex zwRk!SHwGDJLVIB49t`j1`A3Iif&B5&-^J~QBT-&cWjr?09=A%zGG7FV>G6!X?m#{l z6#qL=4F8`8$gIaLz}xoc9&f?!V{jSND_5gC&uhD-fq);IFwb-|CPg>IpJhR@vjgjK zS-_VMAM=Uz#=`xztaI}?tjBW_7q0MbgMg~0sjh^7L23HK5L_zjzwH zo~^Sb`awU&*%K@B!1$&@_d!2#tt+6C`-gQIsVzVfYTxD-R|yx5oZz<3T}YqD7l?en zF4^rDH+6gg_Xj#(>`&E~`NhW|PeI$rfb}dSJ^bQwKb?#W`xa8SgyI;Q)`zhV|6?rE z-+o}Q?eeNXvw{%X&;?iL94QmN?FPj^OSs^UFUpj1F220#DoV#>_4>)SRuEdw4aYPM z@Gj{bz2|XBksoabc|fsUnSzXwzE;XID=T7(li-qv!Ma*HLFmju->yyM=6W4-ElAWG zW~KiOx9O%gIu^@Yoe6v@&y_qRv39?B@;F($!NB^(4<+*IhE$6p!e+3Ldy&P1azK0o zTs!)KA`x6Wi&qxkmX+{*$1e&H`6&BGeFCvYKzuGpgbj}~Z-n@eniImKl3JypZJyB+j{@fGW-Sy|D&M&)lZT??=Zx@ T2~X)h+GG)GTTg!7G46i>y&-Sy diff --git a/boards/auterion/fmu-v6x/default.px4board b/boards/auterion/fmu-v6x/default.px4board index dc58fb1c88b7..f714280cdb67 100644 --- a/boards/auterion/fmu-v6x/default.px4board +++ b/boards/auterion/fmu-v6x/default.px4board @@ -13,7 +13,6 @@ CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y CONFIG_COMMON_DISTANCE_SENSOR=y diff --git a/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin b/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin index c48956fc9e34e53237080061365a4f7f60335131..c619569917b47376eb4de82beb40a24653d88545 100755 GIT binary patch delta 12380 zcmaia3s_Xu+VEO?_6!3E3>T4`I2W)%E{=eTX*mwM0ntRUqSP8iYY@4ZSya}Hf@z6I zb9uf8<>aX}j~y);kbX%KJ6fIU)L}|a3SCU9QAyn>y7yf7|E>Y6=R5!N{PR3(_Pf@4 z*ZsY(b>up8emA379gkAvGJE)|%xh{TX<|%x1LQMvV>z0UiE0k<7P4j30&A2T>5p_VO-LVe4j+(!jlT0^Lw2+mL;gw ziMn>e&Z>h@N)t@GCk!dKLVhXa%OIsd(nHFCG$#ou<>Qg^qhzFvZbvB$e^4SD!s8Uz z>X5R`M)rm$D}3QdX|a)0;p1@_`8ixC?}J+q$one-tS*$Bh?WZ z(FQ-mVNMUnvfKxo&wuG%O5Tl_4AZ^v0r@4O1OUlP?o}nnF#OlvJit5Qi|fGe6_VGD=8fWIkR>9*j(dKK|+b4{0%;kSz?^cE ze~mLF1b3jWzl=gDyCG2m!YLY93&YzyWM8y8gyE|_SRcf_;bR#7VUO9K zZc%gnt12zJCy;LcO3bGaS2C4By~Va7cf>`_i@|&NPIcx&#EtxybC;MbL7Zi|ma}W-AkRnd2B9J(_^dQ*S z!3=cF%E{33}wmS|Ej{I`BusR0Rv`5`Z9NlXsnPEp3`Aw7w7 zYdgIpIcb-ivSbQrPs)#92Q4IF8gz>JA}>Y_hy}r3v#JeB|udHNd))k|$a*|CUG27246DIVfYjo{O72 z2?ojV9W@CKvl@dAV7W3{D`)N*^T0jp)m&UI#YprW0SqHxY#PBZ%F#Wl2ku#?=2QWU z5Z~J)7;AsSVD3@=0mJ1z5(_9|=P_WaBajY23eYpToty(3@w$&>jLTMGe!zRNLj}TD z1;Y2|lf)byn;KO3Q!D2G<81(D(RakbM3f$-9qVN4Rh^VC0{xM9#*Kr1HhF=Ev-Ft% z;sexmcc8p>IMKm*a!L}fc}qIj!Nmc1o0n+S+HlO*dG#IYT)OA$ykwDj0?@;Y>M^l? zA6EN?79XVxWjhd#0rPGz`MWxs;Wv`+)l*==HZO_OOvu3ePVZgug1UGRy_r||{Fg02 zQ1ch?Ot5~+8{Fm=1B|fSOR6==S(vZ%;#}qA(2T1Ns;+=->uED8aq?h^ayQEv?3AiN zl6c7nnj{$PhYr%KDFom_4;im5)L|gYBW9^}3l$@v(fEzBxoI#)E{HWs6}O!y$!l6o zBIaj#be2T>Udu*H$n3r5e9Ij3X-iYV0Mvh>oe3Q#dx%OGGlOpJ%|O#ZXQD;={v;d| z(t$MBs9+D{fS9-YkWR}fG#Dh-mJyf%c%zS)bt}U#-{7X_qyoA8L{}RKOT)JmUNZ}@GdocV$Khf&- z8P&(7MM3Co{cvH9$ncXOO%%h5<1BF{n||#^d?}fh zmcEGLSNe69xEjPWBJCM-U{bZCAEKj9=b z`)-_i_xn}3lr%%;rCJ!i$VWa%(cmsiU^}hlzl1XR68fufq^-5< zl(K;WS)1q1t(EE1F5sNhAv9}=QUiFQ7ZkgmdK0-DNhE8M?N2TX~=w#BAUC?d$XUE}S){wvZA zS#`a5NL5=PtNt1mwr53c!Cm-##pzq8p$0a-`kZ(GA^x`KoS1dQaC%UU>P@4%$EBYW zTh!f4WrLUr=|Z}*;t@3@1Mq^{>!i|9R!#mC8EfsWoZFGG=H8C4#lJu=pLtY3VVJ+i zH>_XsI&0hI)gU^@zueLjz&Pr8Vr37^2ERk|`W#HkD;d&XDJMb2UtEz*L7*aXxCtCv zG>rd>N6|uk03#cTIf! zEz2s5H*xeHQ%1GC+kShaHL1IXk3)H#e{b6@K5wu#+aFCXHI>eKlvyxjTelmIG$G$~ zbz_u?H!z#b=R}(d@!1km|Kd#GZa91GyMX!)GDCW-BMR`@?x-PT9o5C?u&x2RtGArF zWs7bQHy99~Bb^m(NDu7&hX4D3Ks^hFCR@E*Y(PHYCoj?hWJQr2)pS1LWEaT&YDLim z?#}^)V-iT)j$!x`tT3;0mH{b$Kkz&5b8w#YyyFt$y0BW+scPRP9x}vmId&BcdR0={ z1G@u+(Ww5qqPaDi505w?K4ZY$;kxJ*6#px+qEQvYeGZjxK}DY;s7Iv>UGWuAl**1Y zlJFnt7?d|DqI-^sPpe;3MD)-u&v|HRflEW4qk7b9=p9e&HfZA2@#d}Pw1I{Ee zuFxkifki|EUYINz+U!J$v|nUj;;WefJ9#6f+-`wL^d!9lm?$r2SdMs z;@UtXxS%}1Kq)z}YJ>@}zkwlYot%V^Fws%hIV&_aYSTES0c1gmPbhO^(BwhDS9HtX zbs;t7sk=KOJ0;~HIYyB{ch>gMA`5U`4e0ye`AOV^pem->A4@XiSh($CFjz%jiaB7z zD>DWiEHL~w8&a+T9a>u;{iWqgpVG#}6Xx-71sfqXG}%mcJ01l&_uA&nj^ z5*cu|l|Tyr1CvIP;070CF3y7ZPmTk5{2`wR%KVS{+CZM%ocl8C6E3*PhT@09{Q`yv z#HcEt0OsQaSGHsk04LoKYSU51T@| z`?qDbu2_xKiLHz%v;ABzqn7yU9k>~#XLaAW6}jccE!E3Uz5goc@t1F@whlK-cJx;@ zh`6P1bts70rh@(|46&dkFco$%7Ua9db*XA2hct^S)!fd4Vf(ye5JjBrt>I1bss6i=(ajkP@I6&c!C5zPa0mQee8FxcM)p+OImq40VS%L8WR9Zry0obYBn+ zDx4j>G^(}3m4$ZFrD)#)oC~5-9W`{(D(?aTc{lJ1IRCZ6ZMDj+wn%Ey4ZCR==KT3<79jtk;a z^{&++_Ci<+4xGgf+QA1THHXr_cZ#I@DJ*70`BBwLij)#<1Tzh4u*WHq8n&SSx=> zWEX6(ms{SlOgBd7?>86Q@jL1YNoew7D^M8ot-1oZ-~XQJszcVocV=D@^Xo0)+-PoT z1v{7!SWvnclsu;oWzOwp2h9x9EfU$sQD(M-9jIsGbJ)S8V1Q%~JyFQ5TMjfN_HR4p z(gHc-oV}DfblS$K*1e{C9EBV^s1NoDeZE3iVzy{mv3>vcLN2N`5vr5B)>&krl*Z=! zgwK7;?39-zp;=N~#5rvGM<5hx_=uo&%jxc%@a4hoi1q6&a-Nlc?Oa!Z(rqA|K@5VLSEVNp+dRs&o9*N`1pz=$uM%%o|<6CHkKn^1&qF0IzTa zA{Tt$c@Y_kI6KI;dfuoUsQTwETO8#r%0cmtTyFZs0m~Sm>+?afp0G5zBOyqBj#^qh zzJEDGfYPJ+ln7aO7#xlSiwV*2&H%o3q(KNY2svkh?j_-0J~mm^7d$9U>xQO7fu`6I zqPgKTal;*)0E|1m_Br^gg9E|r)otmpopi^7y9cT$`~OY}bc&R6wZ0u-!c)0VcLNP3 zDOoO@Gjc&*;XX;8Je4eaWQ-N1f;b8WX%TX1n{K4bSP)_$Rd)WjRH1tlEA>}FG+VO- zWD1D9%uBt)awTE`%KSz|JHvbF;q-a+fxTTY^gINa?{!VL>>mi0wV4!OQDNB^5SD!R z6)Vu{I{6it=UMRZsi>!XRBV=WpVy7z((R!Y`9KY!%jLSy&BKwcBm|QUk_44!IIjom zCu9VU0hsk5Z61(VoFWqT)#pZ91Gub`Ai9U~69DI?8)@>ugdFFwA`Oj&Bzkmk48tNG zC}I}kpX>YyL_8R}APOX5u77{sbUW2ZacF<-u&G>mk{Yip$3p$R{_>IfSX4ezzXa-Q z+wXEwe^p||t&aC^Z?}f^zJL2w>*<^C+Ya7-HFBLi9o@9sez+{-pZoLCqi-H2NlOx< z$i=1t)nI(Yx7|pO_&v657s<{gVWp7e`|XpNX6!a&ssr{Y)uCZU32lR z?PkC@=E@?kEE%iOHui5D#+QBDzfB8@rq`)$ya;8$nFiGQBiXTJjPCbySM=%{FKrv{ z6;JPUUfQMxiU3@Km#P=Zu%mqY{>}J4oXMW=-=^kt4U$kK-D#z<xR~!9E z|3BSy@-v63kIF8hOa_$AXjI!-Zb9j;-c{x;pmwC3a&tYgE{(VDH&x$Q^0iKs z`9t@9xUlKBRGM`a17-_#Re;oD!I3GHXk0T6EW~^X1C#{N{Q*c1&@>6e6v7&MG~gn#1iVI*i)Ea<1=YyL74xy$$9;i`MOND2;Wr>142lTp}E@PaZ z*p|hn2Z$9UZ+~542Zfgad^dg%Mt>kk`nL21%u_}_To#SXNzXE!_4h4}bo>sppseXt z4du^wTd#q_rZ$2kSWnTOn*%K2?AA4^x#g=9TQ608x-_bCXMwJficy?Hd0p3lz8&9y zCx7Xz1rdE~)|~BVe2Xi~z=CBlmAh+E^jj&1!HQ}-Vqp+TnCYKtpT?QNmOL7m@KlMR z#>K{CVulUBLkEuleY*r&VC{BMhQbDAn6|S@hvo!v-*lI6$5UPxWvawhZRPu|j>YM% zcyjq>pfba-3G=b@AKPRjvLmG%H(LL(Ex0v*HC5S6V??jaz3End`I&7D5FjPkGv!EE zUoKmDrYdoDr9G|y>TlvkQ+aSJSV`(d38$}wXP*HwyymPen6+BgXj+5a^|xkK?lGy3 zg*ar5fTd!fq|Gxpggr5^GqMJxJAFl!bEZ7O4#A|E#o#k`0#Hm1e`PyM<70N2rP(60 zgTw-JZU}5|Ab61ara+Nhm!o0?BT!!}kS!Ww!W**nkQbjb35! z#8Ff`zT9&D5yNcN{RnPfVh2?bcO10DFED;mYmQ^RLb8`Mn)P4~!zILV^I`xtxrl1{ z^HBA=hx}>zcqqw&s^v*gQs*J(10}&O!mQA1y+WBtZGK*)ZqiiOPe7QGaAqV9?-vgG z$-EUA2S`f17ue88h49TI)&E*b283bc&p%_cNo}OHOK` zzuZEd74R)d=aa?ECms@F(c+Itre!`pNM5k~l{w-fNfimqJ{QTWxRjuESatrqw>HwL}Nvz<0x{dF}ZYmRr&xv&ghKHQ`w`1gs#=4?zPxr+XIS z0;#v1ONpkkbkW@wER3kL$5~q3Hr^OqTY!Ox1EEwPaT-mgu(F*7Pkq88qF4CQPXnla zp$@K(gW--90%_bR&Le!|3tSq0TNyRaBRG5kVVH62J3K=V!ZO&K(t6dIVY}{}+Ri4! z*7c1`8*|)bo#E3+`DEj^NgFkyasMQ$k8?N zqca0ni@yX8qaW0~^y%K|XUTVK9vtTtYCwEn2B{P(${;|lYXsrkK!YKH#gc_pV}WZ1 z;QHZO>l=2)I;xlk)L|(udcQ#hX*SIDg6l_6MVOaiDonkC>jPR_!!w|84s0avRVBb3 z%BNL{z%_4lkjqsW8D8OgPo5Dx3<2+a!;TMm1g#%~CFlVoY^*&W)K5LAAH{PX;j)hy ztMlN#>It6?9Q84CjWA#w1OpTrpYV)GbK88o#ic5w8<)0!W#oASkYk0*W`{B}%KRA2 zsC2Wgy3+iiQvuWU2}?yvn;{Aw{$+}5upM-%cOB~I9tM9D9BdjFofD_7Q`(Q1kRxwQ zC(iW=a^D>%Q%vIpG$z0tN0FquCRX|HuIvtTzvzZmANZDE~>k;O=$V+Rdkn?LN=vMf&TpGt5Li`v}z7J2Knzat@Db02a zhogYF-bUBS4nE#m1aCM2%`DUSlTAGWo<{7e+fBECr?e|diKBasfx)gPad8w{G+ zJj1#LgBPWqh(}<$J-T+r+WXAI4%o5l#?Zm*DmU}ZY+lJ;bN=<3@r7g83x>=aI%mH{>WNNW&;A0uNhF&mS4+{P3wPf=73yId+ zoj-`RZ!G*(6$;cS!QsfZa%g8?A||+b$?ScmP2bJsN;%Xt3xvpzeuH5lhjxXEIHHLw z<>2i&LLFGb>-Y86J~BGQuVx+s6l9+Ac$R z?PtJDnLVcBr-a=meOC;JGD5yX6Of_2A{ao-1^U87*;yat?m_U7 z0O{}aL7YjOP&?!t507h7A*tGx^UP+58|UHl$OU8$DHOxxHfSzuH;kHs(#)HObqylhLEi1{E9?q?*R8+h;Y z9em#oTr|hR1vRzcFy8~x6(L3`Nm!{T7i{TT%_Zm>%67nczZ8+btoP2Pi{hLNtiFO zJ6Z66Z}!pp86w-PnLaN4@_GE$B2mYqE_nq~CPI4Af|Q>;`FnaB%4j}+HB$N@rB@MDLC;vaV9tJ_F3`|o+5;u)YM*I)3SA|j;kl`Z`nMe93 z9gG?l2Nv)piIi;6}r^p+1v*kI%rZe(+}JF}seC&{e(Nq8k$ zS3l7@#SeSeg!HFx-nWr$!h6tOEJA22`#;V;5vgeF7SNuEZ}Tq^+4P+zBhNrT=L7T0 z0yhEinvE#+FqePvF6~kN(8En%1|$O{)o7G*_prk{o=ckH&_jRQ{I3)%b}k{BhE>)( zK3Ox3;fFi(xHC?qlOK{33Dg_X8~K0O=(;}z81W}<@+R0i|J_yh`o8()F81jF_Td0_ zYXJLgz}^&OdsH(YhpR|Xnk-g~odMnymL3w6^aVSfHIll5TkiljDzQB(}{0$ zA~4owFcT2J)wjje-+kT*I5~_)acCGP8B7Bi+3|A(bu4zM!18MYIWPVCk6p`Nlz)Wa zn_OJmj`Yf|IBsi;B<%Ah7AfE;54hl!L0eoA?RlTe0G9~+K#t`@$iy!!cFU5Z`=aJo zaNyjo;6HIO%^J?a>4uKOt&Ks(5TCG2Tn+A_-h%i}mw{8l;M4|q{^Ww8A9LmN`<(Q9 z9%M2#GyelA1!(GX_<~zGPi=t!n?zkvT|lU$kPo*+$0L5Oi1n=FbukFZ0&n-I#B@1R z$h9qrNq%7$t?kD5q0HM3oXf)q&#!koX}@GfQ#Q!q9YEM@-vmy>;U-D=UXsCG1~tO3 zj~L-zVYiPpL#Ob}1LD%PduD(gU*jV!dlCRJ`^cAj76CBXM^g5d01)aUb$fq_eHg58 z(J|g!3z2#}7hW4e5LzGG_EhsO8pA*0Ws?;!C_IyaL3jK%)cYQye!VRGJS>^&icw&( z9QC!m{Q6ay6<*ru!sj7^2_mTZll0IFxM`&pHJ9W+sx8fLGVSg{YIs}GqJrB^j}Y!s z*>N+5i&g~xi2UpfMhsGb4pO!Ut35)LI0ybC#M$saN|Y5N?HSRQaz;F#LY)O&v#3<%8IVr=C5o;XD2laF0QGp9bN-hVm0|5rp_R;D5M&2l@HU()87C zh*z11OIChBafdt*#Wusa{h?;|2k=yrl)sgJ&jx^2!j;1v2Plp~z`G67pYK0WA0&7D zo*zrv-})QQBg^({9(4=SDR}Hs=yuKtWzlR%SdTfTo6*a<;hLb(E!;ST|5rUc(t!HV zZe?dM)c+va;8H)R@Y7a0Pq*;RDLIs$lgRn~DbbS)YvIOo>wUTN^M`6>{{Se5L>`Eq z;}$;jPXx46{w(-E0k2I(;Y&YKXH<#8XZ{Jre=(UH@MHo?&-llKxtg&`1l-g@xKM=G zR4MSC<4GYE2XqgE6ADts-0_&*FSG{wY4(Q~N6pQE5LW`U+6~W2V+#GkJP^))VbBj8 z4){nfI5Hr=$A1fWduuKp|6$;akr9=li-Y6zzkt7}Q}b41*>bAb zOUT%_$5=(7`cw%O+ZWMA8g0XcqOj@|>Y{n1g{Tc&b&0}KKW&S&dzVw%pmod$?tYG?N8XhzN<* z4^w>fdAetZe6q~oVjvVWsw;(;Fw&HYsRsGn(EMoFkv$;U@;WJ_dz_0mldOZWtV_7Z zMG6ltmRn#wi^-b@qghdSuag`Y0g8KmA;(0cDUMkHjXHE}oy0J#+Yn0-3_8OL8|%URH;Q`rQLo`ZNfG@j<;9`5(UY z1tw$>eF#YFjU)NIk?)M^n(F0MtL{gjAZUHC1}T}5uWaP2fQoBsqzr;Q{VE|p0AG07 z7{Cw4C@}zpjuea<`Gy6)D!J0uMxAroFBL%I!c1v~`-?7%M* z;P0T^3F%58wIv^AuoY&htblYEuWAIoU_?rJ0T_KVk#d!3xISzSj5li-USEWiG|_ge zM!xdJNV$IzQvSSfxZDZwrz0@M(^s!wvnCBmDBvo7EQjJf$v3n^6{~yun%Y#7q2@dTx3JIgT5&gPVb+QrY-Z*@4av|prIZtWicPePJUz^o zQl2t>t0m(!kw*6rsoGDZjp8(Jtf?bNBt2qs(5k3XPy6O5s#t_#Py0ygj%1Rtk0Tj` zkc?N45bY*}kL==19J5dSNHZC~Ow^AFzY7d%CdNERuALX0Eu{6;BaGI{#D3&A2m_~c zJdsX_715)kU&WAmqKWoXabvWLo%N=ui5bJZdSrY|0Xx!ltl%DV(8KmqkmrVfq6UM$eVCT+*V<1MiVm{%xXN zNmPXJ&Qhj~k*bjv9mf)9Y53Zd8H{nt%pC?*LDyPMeG}31LatLK&GB=_WW#OKO@i^! z+ibU0oVu(o&=@b&tEA`sWhf*b5v??zFE=4maVX-M!+J zfho*k@!o-Ym0J2<5o-qWDwXt}U)(n^&GkfY&{yDCNE)#whXF=&6v;S@LCzdNvv*%ToZ42=O&0a`mno)YVk3pt4J6w2Z;C?vNM^eDaJ*4HGoEN0#OLG34roAsx5hA2 z^v3H|kN4KUDc+3FOIqH`3XG72RjUkPZKS^kYsB%o@hVPQ*&?pc&6>bT&xaYo zf=7>nVfjdSXeYCWU<-=`&D92mkrs;Qh7C{Tq(ecK;3+8v8JLC6wgp9P%E)p~ z5`#}H)0F()GUN-UaK^MQ?@CESF8geXs^V@%H9{*e&v8;+&@C`8@Pf9B(Q?xL!IF|T z-%4o#X~%CY`N9{(mJ>}G$s8jYL@~uWG_i*`;=77{Vl&3 zmud!b%}gyAK(SNTl&n_)n04azRDBUEeFds^!b7Bq0d>0SJT{tiDx3ups_M!kM?o;w z_$jY*7&-Y@I~19w9R-Vt;-UU$B#q1ABGQEWUrlPrR-jn zFpuV{*-=C99JP)Yk_%}GPxvjAFr!3re+jdijMCjXY7H;wA|>{PU+XUs^>Yb!l=fF8 zo(;b>1VxmVGuVKCgF6Km!F}<`5d{E!fg&Cqk*{N=x^QQ+4y0XYW~C=uMLRzvGpg*n zMpjxLZUA~`H78>rzYl3WjFDTXYoU86(w;bu9|0I9hq2>LBdY+ZTip~jVF|ltsIxGa zQQ=w5s;;{tVSQNq6K@#EN&~}L&3qvRa&%Zc&*zMxORsIx*is!GTd~_YCYSXRzE}PU z2VJjxE!3Cqc4V1YX-8Ph*XOg^gW`kw2^hfiu((g3lgCOU!?y?%Y1JMi+R>LK>r)Qk z)XWNrjn0~|PuO_agg$e^;!S<}ovg%!nL_RO*t{#~OHH?YJ*`HmRS~AV7rVsdp@_vw z?*bQ=R~EHUBoFv>O(oU5&?}z;p7g)0rR$qnC^;xMBg75)_xZ#NFneiOL1;tb;f(cTSg8}_ZYwgsRyG~J-xJ-H%$S7nYguVu@KJk} z6+#$`8pM#@uwg$8Xu(tp?O5QtC=lNaxeu+c4sMR{Z1S_av?k8O>yy3URBX%$|t?)*h7L_TB-s zvPUJ2?Gf+H&a(aS7@d|Aj#e&es$Ui-sD%V!Z!^W_3(A421IrG3m|>Ty^imWPol;#z zr0BCjYxNkA7tm=qmsVpF*=f05{Xr4%Zvcdu8Dk2xixK* zw)})qJDr(q0oxhyYHYEfg!4i~S`_T##L8PK>-ppRZ~uFGAw}Gn8JP~1)TD^F=NM9G zb99gtFWk#`&xNfWDyE&49#X`|bH-rhq=5KVPQG?SC<|DVt%w(M4E_AVfZVTi*M)M=Gxrbx7t#Zb;Xa@6Wqk$*8g~2w_)`= zb-;xU*L9mtD?9kXj!cPR)Dojgu%A{M;I=teYuT%%Y-8Z&Pm6Pk&oTL#-K2PqR*!P1 zF)JHocFekBA6Xt_7L{5ZlReRE={~VYR9v&7N3(6((G$FH9I?2%-E&Y-7ekBNMa8XK z=a_EE>^9%cbd%ZH)>V;aM5WIDhC|D!)7(+=^CC24gn|*Ayw$;+@Ui6{w2!`Rg(YX?F$vx*J(7gBZ1K}U7E9#ZQ zI%lbM1#RqwMb6S&;j`5zuAe{-XvT^&%3B0CiQpOKsOdx(PwFjkZ6k8eD98A=`?xNK zjcFyuQ_4{u&V*gT2Yr;1TE%f=hPqOgmp3n1KB@V%@+#W68PEaYaCR%V=!3Iq+6qwJ zkxw0NkCf;LyuP>{V`1K)@vH(y+`o(!jmy7?^QZm5-oKw=aOL5im?|SB@FR&~qp37EryI1eRGACJgDRsQ{N?nrm z%7<&Ll8LLgpHUicrZIlPf8$FMuKMzihz?FNv8Eiom*leN&nPeQ-+GeJ!qB#)ZsLk- zWsQunL8&#>J5FAACp9Q;ggW9IlscR>Jw2zC1_F-TC2#3%M}t=)r1vO20#@u&Hj$95 z2@wMgB}9&bko-z(5tc$TJx6#xlD`KWOmcHySOxyRs3pNfv^oISvSKHOpV&-qWV#k^ z#op>c9-`k}D*G7xUXS$AhcYDKx`i{zDaox2uWQjY?Nkn%1_=co9q81Ru+BpXP<|K- z#GkI-+n6K`jDJ;m+{CmEG$t*g<-fod86)uYvy}(R#x2qX-=^%>_o%O?98Y&rkHzE%cV@jIz%a$)vmG zPGnMF70Gr~Wp1vU^PQj2qMGJHo zcf+T{m<_*g7&8#sq0170kEU|RLW`mM$vIp%nVV#F+30-vF}4IpteMVZ2fs^sQYQi) zomCVD)+@zTq8*KfXkL=TDv`NXX*lLgjDVbpqGb)837G}De;-isRf3Yl4VFY}3dt^X zeSjn%!32Ad9@&=}1(-cyL=Y91i4}RHT8!`CoQG*4Vm4$8S`#SDtdRVGp8=3oqIEUJPImyqhJvGro|z`#N{~9ybAOttz#(i`qOn&# z0X+dfmDlA}fs*WfQ-!PVL9sD^0`s1DIsfyaZ}n8+819H_ZfE$Ae7uLb+JJ zf@jt5FUO%Dcn>!t(#(w=ISM|texSy8S?JljVT@r~GwcG~E ze8LeUxILWXsB*uKJg0XFFF90Q!?^>cB#S$5tg&K^jcYl8bfu&sH+|u2Qj@B7%8?{t zF*B&*Kl8_^2A?^|CEi)qI!$sf8DlQ6f|OYqse-Xe?zz@(V!bfiTKl2fC{=L7ti_M8 zwG6lc?7Mugl2#^~jn)s8v?8fRFBpY(ABlBo%|y8#CXf?JO*@q26NB!oxH4ntd-F3@ zL(lBz5@uTZn=flEk=%CSQXGbEl2{fw zHB;=?TBD@ptdCIX5zvh`8cQWhE>3C!1JOYA?o2Qcb*tZ@9DN-ah^Lc7HKIq8JMb){ zf5Dt>p6Gcdssiv$IrE~x6h!4}yx%ptC|e8gbY=@b`r`cD&2g5lw#+LU^>>Y-wKOkH zZ?hUa_JZURsf8Wc<>PMbT%&-@p71n#(Cr3dbZ4O3`ql5y()H-pRvQgmAW6w3jB%^^ zgPK_D$+f2=giF^FzQ)>4D_ZS|>jUUCh<2HotEs$R%yDb!y!spD`x>OY1#M7U)~2Y6 ziakb&uH9rkt0jH%th33O@mjZv@&Blm~gvSYw=ABKpTD1@-ER2df zW2j!xY^+TwTgVKXS1ggrVY8}g7hT@~oOiZ(Hw^=q5tf(qUiDqrlz8WY^n?;attW83 zYYtpo0N7MmVX<$pklFG zBFmSC>xQZb`+Utu@M$Q`_pYUMX2~b@sGc zRjpd$)QcHr^#1u;Zz7iBC8`tei1^p%iMjVq<)$6c+v6cg>sg*cVZk+85PYBDF90 zayRD-*$x*k3@ZuC4~2i(E5_z0YSfXP^2FNQ&FLjqH@(w%#4@Jtt+Q3N^EGdrd53}- zGfVEDU2-|)o=-To*dtWa5TTm5c2TNHuU!jj6D2J>%safgymDsqg4&apRSC1BwC#ld zuCc*|LPaeLs%KZuue|9SCY%Oq7nU7i$rqOY75W~GZaldfAxN9UYMZ9~q@v3`t&m*0 z!B4`EkZvGUGSS-U9n%h#0TWgks%q#~uUbnbBiM_r#E^jf_d{!8IpJ~BF8u-sn?J)S zxft$41gZG6(~*p0R4;Tmc9-@V^X?p7K{BC(h^dg$qA#p9u8R(+%S^&w6ta)vH~d$a z@nQLLXt(m1Nz-+TM6h0(!ST1HP1uCAu-t*XspFzX8`BwbXLL7aHbFSZ-@&Yc*wan1p$_qb4NGBK!iNmX=-cNMuPc2ukQ& z*>y*GY$>8J*@bYCToofS22m>bIsCQZgOMix|Nc^P@TfW5Dlri?BH(;Lc0L8 zKR!v1>7&X}d*_o4i0=Yuk1E4-eW|H@1LA-a&YM(q>HurEd9HCo)ssn*Jzm|Wa&-*` zr3%YJU}0z6*pX-Bf6~U?r;L(F>sNOW?ek`${T}}J{r=WsqCMB|zJVWtdlvcB%|#i$ zrZh^`&gQV*5gO7y(sPTu8r{iBBOop;ZDVue+DPtCUXm?&PvFRQow#l$FF$I&VkP!R z2X|8DLX&&p?8&Pqxfl%uf^5Z=dTvImy?}B7#*&4U=i{m#h5q4DFmaKgZ|^nMbVLnl z-vwqoOL(M@e1MHvFpENhE)j(Q@B!uen7y!E)k~T8`%Q|g<-tc^fApM>j{HD7$$8yN zN6O|7^^!5J?p22{Afm~-ngN^A9no zbl+j~(i3I}vS9_4c*wns}BrjJf_#!>4<{@GU&f zjN!bck}hi0+RuFK7^C;I#@OT0G5c$niK^^DXTQD#t}b>!d;(!WjyP`rS~^3X`_RW4 zZu&Sww@+pG$p<-!&nU(B=Tc_(s&6s|m4ArweeKe?y2l)fvAVi*54pzNaWm^sRSk#2 zZ0;T1hC>cM0j2^D~QB;g*6(s7`mN{43dgXvKlwk_!xBcZ?qP5 z=${w)8Z$az4|O0OJ~$Aq2M;oUK+nNXkXMSl?t^EM*LBcEyZ+&zsviy2P=&g>haEC( zx!I_(C7IJb)^2ux#S0`Ic_; zYJ)k>Y>+N5GIVzuaMN3DkQnw;We`uKm)xT`()D}ygIrSk*UH+R=Uhs1(K!&9B=g=z zMkLs7lj_h^QCR ze=4R`PhhzuPKSXmt22*&Q;6ysP7btINaolP{;gfibC5a&Ub`9#YH>F3TTlnqP$VqH znfesMPt+`O;ShLYE%U-3aXAXhe+i`-xj^(LN|h;5r8M~-TbhMPkJaID2=)u$p9O>* z6lz1v6XFJX``|URJT;C0YvvyMDvD{>ITGv(wS4{!-`5HtIO+gMm=tAhFR@izDNR|R za5^kn7IVeLa_6ELF}M{=as4Yhpum6H^Qgk zL`lV{y2>RN~UL%-%gwTsv#Xi?qS)O^u3eUs^+3;X#ZtaT+WLX$_f?+()!g zT}+g=D^2^3H|V-JQQ(pNwn7_DpH91Z8GD;{6_zvnfAO)9GO{^;_nuXBI-GQ|#m%vS zsD*oxUx~6?;h*r)6f@Y6u)JBJImLpujP4AYi{sXR$agl1wD&>epBHcOc=SMW5uKY* zMvtCI&WZ|&X#dz{k74$nk6P2t=+EKAJEs)RtGH5@%J{X{b1kgsuqD$A8oN;8>_f~$ zfQ+0txsBb+7&5PLYP;=Il(zwrdz1wJ7%=7D2sCHq=)Ci$zZ^L?N&|b8$N0HXQD-1A zyMRan?*JILz~6&eZqf{DpJmfaJhMkh&%h^z3`w@3~mCxp&iK$ApyRl7p55tz(1{{->1U zNZx_euw3n*ym@!Y9~G_pwTpcDoCpT!KzROeu#YElQ@$bhcNbI2v{)Fse}}7w==OCD z=04m+vNat!o&_}w)-@_|!P<=%7u2wN#kXJOy5W604wp!hz4CetOW8v-k`1_ILE5|; zu*f=(d$V&6gx+(`+u!}qEhd8!D!Rtw;fk7KXLQ>20teyB?ou`Gio|%qo+Y@7TGru0 zHKT`t{Y6;btxzuJI`}zS(FuMHEaOJ^NMh`}pwf#1y`YBW+(4g9dEiXkUmV%OLNps; zFaM|HIxvwzS=&SO6oL*#D_piyUV}=J(Z>LEk~{N~gUaeY2}dqGL~j7hZOS@6PRL#z zl)pttFBpWNTo)K_3-gpgyV-bB(MH3?o>a2nXTdLnUk2X+-vNIU{7vu=z&`;06ZoIR zLVRck9|!hs5L_W#8eDQ#SbkRt%LkNYuA0R-%9gFAQ|%vQ28HC-as|TCxFVxO*5J;u z=0k*Od_EIs-&kfI6_UT~ZGaH)T;%tkz4douH-_tB1k$~l=#wGi{y6BK&I%lqM%c%3 z7R8=wvG*E2T+6N_hPVJ*oK|rE;{7FL;U3tUuq#6r4~pD$`6+xhIrC#cqYyyOlWoK4oBnxDgXqF4MtGmA%I52(waoukG#`hUzas zQ~Pe;Br_oY(7S)xAgZe>*k9EvHz`I(K5vyya7Hu-_)uYy^@6<@;5?;}`_JIqreHUA zpO}ky5sh1+zNKME^Nm%Dz+7?r7fpv$QZ>#+J?%L98yET2MScfGev`-b!r-VEQfOcS zO6cZ=^{13U^Tw8+!j?XTgLAa)l#(_t*})f3qb34ufecFFbp zmFO2#4ldtQS!dXT*>?AadTn%7}pq)j3jtc?+p z9Yp%eF(|Ts6;Eyc@3=D(7w??#l!{0~Ks-C)o`FGmS(s$Sb!1^z4Gf4=Zc9#}N*Alj36#Rz`%KpTbKgl25P;b)tE3qgCY)^nvr)ogpAyQz<6X3;|7WW7wkd# z>k!FO1Fz{l@_Gw1*|AugU;mcf=V6QMb35-m|}2?|reDU6N4noYD2FSIF$ z_4vfLsf8?mNYvau!KDKrUxa}kbp*>3@%2>FcCdw&UVoo1MSL&Ss{$~`s6aA?|2|)WyA|0qFN^GtS+@HqhfOpxaNceurx7p9bCTt7Gt9Sf6wp z8_#K6k-97vI-%XA#ufAgaP7rNR9z_~AV1w}T%iF^v3D8Ge!#!QzXgq4SYOpl#(Z#o zrNoiH`p8IXWZ=^Lh~F6UAq|sOm^aB4^^PdajoEox8MGt1D=%i25RmWhRi#htpqmYo z*!!YI^Ti7|vq?@tTU;}0sxVyF#{a7oKBw6EFP6r5%7h)IeP<3$Vf1Cf&gvbd&B_>E zvtr_-8xtF!vqXUzwDW_P4)+j485HgZN@oFq{J11>5o0Y{lGe~QMmN@3^ljj6bWDEq zeTj|DJ^5sZB^H1+yn#aJlsNH&JBGPl_6^AH@g{b=UCFI6`feY|d*#b_9VF+zwuz1e z$;>SDV$_=eBbPvB3Y`AKJeYqJ?jw3b9LW)s4wn99LuA+GqN0)e6;khJ1Ro@EY%%!$y8IY zSWpQNlC%F^7W7fNv2}7i?=C(FwjETwde0}C2 zxhFx!AUca$Q%PabTxyAk-l6BLIIYhSFD?xR7O2>uu9FD22N9Z0{<-aT*(hn7% zv1nWxZ{I!|4{}X)X2$BF3X^&kjP!tPwKpY-$~43BzR+b~43Ixb%82LM21NM7--crJ zlJBfSOdimwddaLcuK47-JDHLVN^=-J*MUd$OwM7sWTNS&_hh*oulCtecA zS(6~!49kxo@#cBYH0F!fuSTmEZQBnBQz%Ba{V#E%ozSTSdS3L=(~5$Gbn#l1Fi@bV zI~0>n@1R%;70v(PX#^B%k~FSUK_bFGxts6Pg?{T$hag!?oJkA5KPish{9_t?EkCP+@8nVkQv5uzY`inRJwy=O_9ioM+nu#HBYOusL7^ z9`qeiz=mQX{kf$GM--LTGPtFT?cKkAGOi0~mh5-Za~7h=W@;;-5>&_^(OcD@pF*no z^K+5!Y`V4gu#nZU$KScJ-K9JK&W$au6F;@OU%#5bke!GIT=efBviHD=%MHQ5+`&<%Kr7aKQC}l99QoX!1wb8KR)BENu+flkdLj0KmN{;q7kS||vV8;L5=ft^kz4)W;WYpoFe3J@% z*)ic3PX-1K+#F6bk~Ow%A$ZRp2t zZZR>Qtg#x@> zd%>bR8sn|shEh6qK9Y_Ey1JRbAb_pDff!F*PAK3Or+8qiXba1~YoR{nm{rv360*y^ zj)mbR!>^cEdnEGs>#+0A$du&_&Dxs?}noUhv&8RZrJ-i5-L?PiL;rR zx_|wf7WG#}u(iDp+KC}VX}K3Uy)c=Pe9ZWR7T?*2?5{fsPnp%BuK{700Qmb+?0f@=VUs8u2%G4WAp39|$oD1t@L_oeb#2QJ~jW*6;c+}uXikK5q^Hgf1ThwHAsDy>hoP#qknJJI*Fn8>g&-M@_ zWbKbayOw#wS0jFY*W5X`YN#UYSF+=<-z}M=@wN%~K$^z@r>S<0hP6#1b17NHDlr)Q*?oOQHr^hv=iFwz*Vx~~c*sEkTUh(C*fAGPI zD1Cr1q+>+((6fH|4%nxu47^Yciz+f}yTX{Z<6gjsz#Z74(|qyb-R11>d&K;EvY2FX z;XT6!|Hep8{kL7JV6{;lJUcu_w#ms4efbWPZKY^A(08d`NE`z2ezrJIdcoXC_wO34>zk@v=5?`HfPH7GmA?;x3H`DIuUU%p~ zmzK>I<_SIWKZ0WK{3#hvg=V92NFLZ*k5^82beA2<7HFX!d4DiFlJisdVyQ+rZF%pM+SBb=`qEk%#Uz2}piT;vg9v?;-;RUOvteR@?lLJ8T6aS;{=nv-D zt{-%M_FpBS*jIdi_`djwqd%1PrF~T*sZ^avyM5WwA3lzx4LWm&xN31Om%pqK{!sCq z#fF4YHty=jocKL?!t_H_>>s`#AzogbI%n+;X!rKbzNU+1rQ3TjDsGcNc66jNBC~fP z9#6Ss*P(J@u0VDd!&)+_$7Gr{`l3}?HqA7J%wXt2$i-73}CeqlrA)CaMu*-wPu+h|t3{mFCh0sY%yH_*Z>% zt0y ztnuu776?yUr$Eo~$Ezx>B7YmYTK%VLV@Y9&Xt`P$_r$t~#Q+WEiv3WZ~^XQwQo)TS3K!lml&VTybltyxR1R$c_}tP)I^WNl!PQN_D9zym0Drlz|xLr!**~JlG~25>$ym@#*fK zP9ODW!yx!8ACbthzRSiCu%DlUiDBuCP0kkj&RB<9atATOph>Vh(3T0$41~V0q zChZKnot6F!HBdXouj+v1VdR;SuB8h1u`aLQ$D>?YviQn_lX9F*(RWf@D_GCw(lO2s z6rdlqmx_7l8AzmK$Eo@#KUw_Y!Hlu2^nt=k+tK#AFf08I;f2_zpj`N+q>z=K#g&;5 zRvQj8+Cs7TplDB|IVl5rLe z=^5!ckHd%L66v80gb&NbVbu;5L}Nd7Fgz>WR8)KQlSkxUI?KE=M}elM^`#9&djxJU z+yiyLxT*Dh;STuEH-I+4aT`H%;WFXo!hHj`=9hY||7zgZjs5?^sc4*JvKXcc0LK&c z4cuP(u8)H?L8y)~LK_{+@|!UsR(b&-W0iT7S}NeGvmWwBatJHEsGL=_ru`Q2W5=Y? z-}Ksjw80N>x5j(X2Y5n)UiT%3G zv7>q{lOx719kGCsmg3&RNDqe>DyrNa7PG{n^x4R`43Tl^>qzFCg0=G&?opavh&NhA za8uyYhLVh1D?Xt4v9u}PEVMT*EH*4%%3KkDTsnC2XSffTr4QY7A}t6L={>i4HzTn> zPvh^Qe_bR-^#QdQmhnmurQeK{eqFp{*1I9U8sV$wYq zsX#6)r-vkuIA?jHYiwvSA5ZVe6=C`57K(eRTxxDKwEhG$y919`7|GK6wBomg~iZILbv70JILke%tYR-i@Y*xe|76bzqYPVwt+D!7$6ZETQ zw5N9iUCuVEsHlU=*j#POF8fjNRWJF=j^Lq@>16{uikaMiP_ZM{k>cbHe^|A^Nep|O z=bb657OXnI3a{s!3s#R<9b?p1nuO2Xj4^gqfg=^dEaaHJZ=@8PzJsGTJ}Lo;B|rI` zO#@)&FwZmFqs7HODE}5F0`z3;Cm3@{@Raw2Q!+4Prm~ zfa+H0MTF=XxzLeZO2x`?!bV5Gr3mGG=7Y%!%l`-y-u6?CZ^hc8QHMWl`NS=cW6m`a!JaX7-Vh*nQ2`%EJt zR5#%%3DN#j(IsT#IoXROtd|?YA1k`LxC!rDuH#wQi~rNmi>AmZRb5B5c$epVy17rR zim9RXTRomqb~}l&s$oC$wo)C{L7eC*c987RX`>Fx2$kN9W-dUVg~t zFza8m({Z-1?nw20D;k%9kk0{#ng*)h7&{6_9_gWQ(GgAMkn%N- z^VBqbYoD%~s+p;-8gRqA@}R8l0R;F5{9CUx`M^`2z8u$1xO3WhZ!T7u;yM)~QT(Tx zZ{VNm8Q%+=i1r^liFV>H;?mMbSc4%^Oo7OR7>N`J8XY+Zr{cNR?o!JCQ?N?KefT&~ z*lL;H2K84j88Z!fPa6zqR9&Z{C~i)UXjA?bR;N$tK->h`1r}hk&^MvakZwZyZd1N6 zPUuU2k+|rGAJpj?$at|IkG@uBxL>qWO!`2Hb5qd4EDQTdEo^Gug*T>g6PSYcE%deN zH7^6<1RnV5VCN7fnGx+&9mU_-y$Yoy>Kh=Ebf#3-iMQ$N8yvqE5+r-{+)cpZSvwWZ z<=(NrQBj@v=cXsUbJlAnsdLCrr=fGf<9x4W(h}RTE;fE-+p#V#J`cYP3_DM`^BhE4 z5+q$Z)+o%v6TTf5`bnc6FS{v`PjNqGp>L`n18CIj#2Qc6#aXE8fyv$02*nG>&*)wPr(~Hx};6KGj@wtu^`%z^JzXyZZ#_w76 zv`?Qs$s0AMsJ~pH_kCQiV%z==#`Ki(l<9p%WqMWFV*0(JF*PXLKtAxwGWSRu;dhrF z_PO-gY5ikLhH*EgmG1r`ue34z_h>w>zhNzWTJ^VWEZ!xr#M7ol_`RPz;3LM^x;Eg+ zbjQg}pSdZxlko{9AT5Na*g2d2uU?FFy&7Ex8O~`}&n{&n8l8*x(e>~vuo2&jIitKc zYjiWUQK04lAU#hnb>wc=IfiadE`g4L52rvUQPA4Bw^4+dBX*5J|IBY;G_lo^>@_@- zh*XW2>LM5jBAJP}ZS)KQxedxsh5l?wJxi@UD#LvmZ`Ui~Pkev2e0T2RcAdhWVDc-M zO=x5k&52=9s(-U_FV)QHwnjSn9B*FIOUBe;a2V*}Hlx6ne*!y?9$8l2@O=g>$EOq= z_u&b6bOBx*N#DB@zcl|86$!uL_S~?zU=8J_a<~^P`H|=0_qDBbLH8ctxw3m!)o00E zu6*|8o9t{hn~NB)M-56Pr|_zlZY+pAbMO@gY{#ceNp$^9B3*xzxavnA&G{E%Zsc6T zEda+|b*zvK6PJkBth*q7izcD_Fc+WU6+UH3Qzg6i!iR@t8t8tzDCDMx`o7A zH>Nu*j$-Q-calz^{E&zW8+3Rcw??$1bL{lNJ@5Ep1z)7w7u`uv^38P^D^EkmCt{y$ z;2W==cD>d{a))-%6L?Ql!Wn8#7a10KQ#kEHRW=~@IjSF>4`BVb*+exYunn) z)nT_W0l60HAv^);|14Hf3nlaPP_H%Jzz2_L-bE;@B9>EhL)X)T67K=16$4&s(Ib(* z)M`_9yN@Xv-kwv`YB!Lb9bhY5N1k+KIZ$Ua$~K@ZwQ6WUVWK~-7*0IXcwEWggvOn}vD`&lIo>nU&g3UH{?_s)V)M8!!544{nwW7dzSyp#uqG=A?Zwee zIS*#iR)iSC5ALy*Ijdkw!Y9Ivi)6jf_L;BPV_xx#%93e=(zlf|zypK`aH*=Das@XV z1M=U45x%H^a;}u)YXZ=Xc!x^)y|6sD)!9NnG6xD-@$BIYLlpRD^#KCaz_DJu>d~qo zTj20;jES!3E}!+eqH}A+&o67=`22FrmVg`=Pzgm~m15NzPa$}zzFVI4r?t5-nZVhm zUI6;Gt9L+`F0MgwIp4b!PvSr7`+e~eM?N&Bmv4mMpge8T8g+UH_R}^~MfZ?3*kk*u zo&x8D(54+#RhFBbRSgQa<3fY##*#Jr7bVzET~01k-7wFsSJrPhsjM}eRB9}fg}8De zDLwQO^ z0a09g5B;r!1|m|Y>s6x2_}C3%Tl{LULbM)bu~k{QAdy5G%;|@ZAcJSp60Tn2GQN^F zOsKc8T`W7O!%R3MYpQadXyl!mPR^*}ZO&+;*16UBiPPB&!^n(LzzwYyTe2(cHZpqFP$5MR+~>ToiX{47#@APMIx8ey-0Q2= zc-lrf7dZ{9Dpwg-Hz?7a%OKkve4;|q#9dfTjQiGJT-TtaARZOh`ACD3?l!KeT=UAB zZ`bJ8R;~5n#p28BMm@6Vkx`FUKDrV$`4jOa4T_%l9$i`8pcvg1QjGQ?$raV0WP-04 z>26RAPM3L9gEFeKLCJ77C|ULusFq_Ih-$eQOdg74+Z&Y8C_V;mES%{?gEEf%fCdXt zA|JVhs5u@v6LbyAZOAPm2deG3fi@@;;U@77%4C$7f)Z18w@1E81r-Anq_JS4Z+Cen zRF8p6_Z-Ha9dO>+!i>hvcXUi!CQQ)=le3d}fxd1Elh z%0Y01s*W6pv6iFt1YpHU~@yvyG;?!kQpxLd32KORlv|30}RC`4G zPdI|;t8jh>Fa8m_j!-x6GyI?Vt{?2-w@F|5HqZV zGOzi1+RT=_nsuGj@Hrq4@QV#A=D@Vz+aB@!idhI8>k-GSyg29{2!RyuNIMn@1cZZ~ z_>|-$InJF7AeiqLPple*vWpe*?5cSKzs2^W0F1*vf6ag7_SIK77u{XDrf5ETh9cYi zAnH}q_*06zP?1agCA=aRN4}KeE&NHczwBfLu_jd<^)xua?kdJqDen_i5l3*~M=94`Imczu-G`%8R;_{O7uWJ<)@ z>-7s1d3-ZIn^5NWO^a2L5;!Ics{;bWwP7X76gjh*`Ja4k6U~op)3!t-e=y7d7$&Oh z(?&W@MIO+sMrw>-{M-5rS4B55Iq`C2)6~M5)@~>K_(PHredy!h$GZGv_-jbX0*q+QXB9(*T z%YZKgjF5#6^kzz7)_@PwM8nK8U3~blguA1$Sa0{J1$*=T(DU33(N@Mk6pHPSjTrtN z&_;%%77_ET6;h{>mt5v~l@#Ic69+s#)OAz-_p$r1;K0^SYIwtx-IUvbiZo6PuqDIu zhMV%=6j~Qzr%GzpLi5=EvaLUtWg~U}+#h!~X`p@~8BmjVI9u*fGVr}0MJ`g9!W%wq z*08hj(<`o!GkgRZ{qw(IGkhsBqzaPZ$u;E8^duNS<_4 zehenmDo`M362OfogMXx-1WbfsP!VXyTVXW>V>jgoQHs(jyn2Kokc`)8B44u>?HEGh z?wS=US$@_p#ysgp${&N`Gf(~%DHnUh`)WTK=a(-X*EOkUP_|Kq>0K7V%ZD&)tAaq- z3<)lQ8i{mi8Q!36GDA8P67P0Bt)V%NWbs?qJ&|B-s(8EmVb_`^tE*P7m^6u>HfK)7 zoJoA~^3_W!7eB@$amA9VwM!Pqkp3e4oFxxcuUWffb@hsecx#DuY_WAFkG$&2<^1B+ z)sHM${Y%mQ#)Qi1Nj+8bGU^4b@ z!sOu&!PV`;q@V3;AQN&0TJZt+V&zkVij2sl2}l0lfC?GA88|e%fUfHW&UbbKr+9#3 z?}1o|k%0*qSq`m+rVNaXj7-do|KDs5X>DL+6?y%?o^kTQ4lO~Z7obx&A%N)xAA<@| zRD)v)aPJpTOa*9_=;Y9Lc{z{*Cs4!#fg_ZL@PMS?=Dv0@MwuGm(nt;tpgtBR2M}8T zq#%STq6NqXn%Y0vzf;#>t`P&rUSr@=A|Sp9WHSP3m_gX&CJVN!vI0x8hz*mkb;=3k gfEJZN!G9o_)Fr{kvKAOYK(PQ8pi|aPR_ihX0LX5z3IG5A diff --git a/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig b/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig index 2c0231e2940f..fcbf56afd9da 100644 --- a/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig +++ b/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig @@ -30,14 +30,6 @@ 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=0x0035 -CONFIG_CDCACM_PRODUCTSTR="Auterion BL FMU v6X.x" -CONFIG_CDCACM_RXBUFSIZE=600 -CONFIG_CDCACM_TXBUFSIZE=12000 -CONFIG_CDCACM_VENDORID=0x3185 -CONFIG_CDCACM_VENDORSTR="Auterion" CONFIG_DEBUG_FULLOPT=y CONFIG_DEBUG_SYMBOLS=y CONFIG_DEBUG_TCBINFO=y @@ -80,7 +72,6 @@ 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 @@ -89,7 +80,4 @@ 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/auterion/fmu-v6x/nuttx-config/nsh/defconfig b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig index 4fbc7a3b94f1..328a033bbf0e 100644 --- a/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig @@ -76,14 +76,6 @@ CONFIG_BOARD_CRASHDUMP=y CONFIG_BOARD_LOOPSPERMSEC=95751 CONFIG_BOARD_RESET_ON_ASSERT=2 CONFIG_BUILTIN=y -CONFIG_CDCACM=y -CONFIG_CDCACM_IFLOWCONTROL=y -CONFIG_CDCACM_PRODUCTID=0x0035 -CONFIG_CDCACM_PRODUCTSTR="Auterion FMU v6X.x" -CONFIG_CDCACM_RXBUFSIZE=600 -CONFIG_CDCACM_TXBUFSIZE=12000 -CONFIG_CDCACM_VENDORID=0x3185 -CONFIG_CDCACM_VENDORSTR="Auterion" CONFIG_DEBUG_FULLOPT=y CONFIG_DEBUG_HARDFAULT_ALERT=y CONFIG_DEBUG_MEMFAULT=y @@ -284,7 +276,6 @@ 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 @@ -325,8 +316,5 @@ 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/auterion/fmu-v6x/src/CMakeLists.txt b/boards/auterion/fmu-v6x/src/CMakeLists.txt index 39ec808e1e9a..d0f1b0b1a743 100644 --- a/boards/auterion/fmu-v6x/src/CMakeLists.txt +++ b/boards/auterion/fmu-v6x/src/CMakeLists.txt @@ -35,7 +35,6 @@ if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") add_library(drivers_board bootloader_main.c init.cpp - usb.c timer_config.cpp ) target_link_libraries(drivers_board @@ -58,7 +57,6 @@ else() sdio.c spi.cpp timer_config.cpp - usb.c ) add_dependencies(drivers_board arch_board_hw_info) diff --git a/boards/auterion/fmu-v6x/src/board_config.h b/boards/auterion/fmu-v6x/src/board_config.h index c50f0705f258..c304153abfe3 100644 --- a/boards/auterion/fmu-v6x/src/board_config.h +++ b/boards/auterion/fmu-v6x/src/board_config.h @@ -473,6 +473,10 @@ #define BOARD_NUM_IO_TIMERS 5 +/* No CDCACM driver for this board, so this is manually defined for version.c + * so that the px4_board_version reports the correct board id to the companion */ +#define CONFIG_CDCACM_PRODUCTID 53 + __BEGIN_DECLS /**************************************************************************************************** diff --git a/boards/auterion/fmu-v6x/src/bootloader_main.c b/boards/auterion/fmu-v6x/src/bootloader_main.c index 77df9e78bcef..ccb9a8326bd5 100644 --- a/boards/auterion/fmu-v6x/src/bootloader_main.c +++ b/boards/auterion/fmu-v6x/src/bootloader_main.c @@ -48,11 +48,8 @@ #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); diff --git a/boards/auterion/fmu-v6x/src/hw_config.h b/boards/auterion/fmu-v6x/src/hw_config.h index 4ad1049fed94..949a9284a5bd 100644 --- a/boards/auterion/fmu-v6x/src/hw_config.h +++ b/boards/auterion/fmu-v6x/src/hw_config.h @@ -57,17 +57,12 @@ */ /* 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_USB 0 #define INTERFACE_USART 1 #define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" #define BOOT_DELAY_ADDRESS 0x000001a0 @@ -85,6 +80,10 @@ #define SERIAL_BREAK_DETECT_DISABLED 1 +// Connected to VBUS on the Auterion FMU v6x +#define BOARD_FORCE_BL_PIN (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN9) +#define BOARD_FORCE_BL_STATE 1 + /* * Uncommenting this allows to force the bootloader through * a PWM output pin. As this can accidentally initialize @@ -118,11 +117,11 @@ #endif #ifndef BOOT_DEVICES_SELECTION -# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +# define BOOT_DEVICES_SELECTION SERIAL0_DEV|SERIAL1_DEV #endif #ifndef BOOT_DEVICES_FILTER_ONUSB -# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +# define BOOT_DEVICES_FILTER_ONUSB SERIAL0_DEV|SERIAL1_DEV #endif #endif /* HW_CONFIG_H_ */ diff --git a/boards/auterion/fmu-v6x/src/init.cpp b/boards/auterion/fmu-v6x/src/init.cpp index 88fe88126cd6..7e35a407c434 100644 --- a/boards/auterion/fmu-v6x/src/init.cpp +++ b/boards/auterion/fmu-v6x/src/init.cpp @@ -179,10 +179,6 @@ stm32_boardinitialize(void) 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); } diff --git a/boards/auterion/fmu-v6x/src/usb.c b/boards/auterion/fmu-v6x/src/usb.c deleted file mode 100644 index 70eebc6fe0e1..000000000000 --- a/boards/auterion/fmu-v6x/src/usb.c +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file usb.c - * - * Board-specific USB functions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include - -#include -#include -#include -#include -#include "board_config.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: stm32_usbinitialize - * - * Description: - * Called to setup USB-related GPIO pins for the PX4FMU board. - * - ************************************************************************************/ - -__EXPORT void stm32_usbinitialize(void) -{ - /* The OTG FS has an internal soft pull-up */ - - /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ - -#ifdef CONFIG_STM32H7_OTGFS - stm32_configgpio(GPIO_OTGFS_VBUS); -#endif -} - -/************************************************************************************ - * Name: stm32_usbsuspend - * - * Description: - * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is - * used. This function is called whenever the USB enters or leaves suspend mode. - * This is an opportunity for the board logic to shutdown clocks, power, etc. - * while the USB is suspended. - * - ************************************************************************************/ - -__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) -{ - uinfo("resume: %d\n", resume); -} From 692748a51329b008e2de7b8544bde6c77910d104 Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Fri, 10 Oct 2025 16:49:09 +0200 Subject: [PATCH 3/5] tools: Ignore known_hosts file for uploading via SSH --- Tools/auterion/remote_update_fmu.sh | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Tools/auterion/remote_update_fmu.sh b/Tools/auterion/remote_update_fmu.sh index 2eeb66b99976..d3777aebafcb 100755 --- a/Tools/auterion/remote_update_fmu.sh +++ b/Tools/auterion/remote_update_fmu.sh @@ -7,6 +7,7 @@ fi ssh_port=22 ssh_user=root +ssh_opts="-o UserKnownHostsFile=/dev/null -o StrictHostKeyChecking=no" while getopts ":f:c:d:p:u:r" opt; do case ${opt} in @@ -67,7 +68,7 @@ target_file_name="update-dev.tar" if [ "$revert" == true ]; then # revert to the release version which was originally deployed cmd="cp $target_dir/update.tar $target_dir/$target_file_name" - ssh -t -p $ssh_port $ssh_user@$device "$cmd" + ssh $ssh_opts -t -p $ssh_port $ssh_user@$device "$cmd" else # create custom update-dev.tar tmp_dir="$(mktemp -d)" @@ -105,11 +106,11 @@ else $tar_name -C "$tmp_dir" --sort=name --owner=root:0 --group=root:0 --mtime='2019-01-01 00:00:00' -cvf $target_file_name $firmware_path $config_path # send it to the target to start flashing - scp -P $ssh_port "$target_file_name" $ssh_user@"$device":$target_dir + scp $ssh_opts -P $ssh_port "$target_file_name" $ssh_user@"$device":$target_dir popd &>/dev/null rm -rf "$tmp_dir" fi # grab status output for flashing progress cmd="tail --follow=name $target_dir/update_status 2>/dev/null || true" -ssh -t -p $ssh_port $ssh_user@$device "$cmd" +ssh $ssh_opts -t -p $ssh_port $ssh_user@$device "$cmd" From 88377ad6d260826b1a5ed4f966a7b792d4fcf73a Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Tue, 14 Oct 2025 15:36:09 +0200 Subject: [PATCH 4/5] boards: align auterion v6x with APX4 --- boards/auterion/fmu-v6x/default.px4board | 10 ++++++---- boards/auterion/fmu-v6x/init/rc.board_defaults | 3 +++ boards/auterion/fmu-v6x/init/rc.board_mavlink | 12 ++++++++++-- boards/auterion/fmu-v6x/multicopter.px4board | 1 - boards/auterion/fmu-v6x/nuttx-config/include/board.h | 6 +++++- boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig | 9 +-------- 6 files changed, 25 insertions(+), 16 deletions(-) diff --git a/boards/auterion/fmu-v6x/default.px4board b/boards/auterion/fmu-v6x/default.px4board index f714280cdb67..dece24a26f34 100644 --- a/boards/auterion/fmu-v6x/default.px4board +++ b/boards/auterion/fmu-v6x/default.px4board @@ -20,13 +20,11 @@ CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPIO_MCP23009=y CONFIG_DRIVERS_GPS=y -CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_BOSCH_BMI088=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=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 @@ -34,6 +32,7 @@ CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y CONFIG_DRIVERS_PWM_INPUT=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_RPM_CAPTURE=y CONFIG_COMMON_RC=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_TONE_ALARM=y @@ -53,10 +52,12 @@ CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_FIGURE_OF_EIGHT=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_HARDFAULT_STREAM=y +CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y @@ -64,7 +65,6 @@ 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 @@ -74,8 +74,9 @@ CONFIG_MODULES_NAVIGATOR=y CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_MECANUM=y CONFIG_MODULES_SENSORS=y -CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y @@ -92,6 +93,7 @@ CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y CONFIG_SYSTEMCMDS_TUNE_CONTROL=y diff --git a/boards/auterion/fmu-v6x/init/rc.board_defaults b/boards/auterion/fmu-v6x/init/rc.board_defaults index f371bbee78e1..1a6fc9673c39 100644 --- a/boards/auterion/fmu-v6x/init/rc.board_defaults +++ b/boards/auterion/fmu-v6x/init/rc.board_defaults @@ -17,6 +17,9 @@ param set-default UXRCE_DDS_CFG 1000 # The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). param set-default CBRK_BUZZER 782097 +# Update default IP config if needed +netman update_default -i eth0 + safety_button start # GPIO Expander driver on external I2C3 diff --git a/boards/auterion/fmu-v6x/init/rc.board_mavlink b/boards/auterion/fmu-v6x/init/rc.board_mavlink index 4952825bc4f5..88cdd87c66aa 100644 --- a/boards/auterion/fmu-v6x/init/rc.board_mavlink +++ b/boards/auterion/fmu-v6x/init/rc.board_mavlink @@ -3,8 +3,16 @@ # Auterion FMUv6X specific board MAVLink startup script. #------------------------------------------------------------------------------ -# start Mavlink on Telem2 -mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z +if param compare MAV_S_FORWARD 1 +then + set S_FORWARD "-f" +else + set S_FORWARD "" +fi + +mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m p:MAV_S_MODE -x -z $S_FORWARD + +unset S_FORWARD # Ensure nothing else starts on TEL2 (ttyS4) set PRT_TEL2_ 1 diff --git a/boards/auterion/fmu-v6x/multicopter.px4board b/boards/auterion/fmu-v6x/multicopter.px4board index 147297d55e79..4f1b9ef0330c 100644 --- a/boards/auterion/fmu-v6x/multicopter.px4board +++ b/boards/auterion/fmu-v6x/multicopter.px4board @@ -9,5 +9,4 @@ CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_COMMON_RC=y # CONFIG_EKF2_SIDESLIP is not set -CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y # CONFIG_SENSORS_VEHICLE_AIRSPEED is not set diff --git a/boards/auterion/fmu-v6x/nuttx-config/include/board.h b/boards/auterion/fmu-v6x/nuttx-config/include/board.h index 7907eafad194..964976318acf 100644 --- a/boards/auterion/fmu-v6x/nuttx-config/include/board.h +++ b/boards/auterion/fmu-v6x/nuttx-config/include/board.h @@ -377,7 +377,11 @@ #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 */ +#ifdef PX4_RESTRICTED_BUILD +# define GPIO_USART3_RX 0 /* PD9 */ +#else +# define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#endif /* PX4_RESTRICTED_BUILD */ #define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ #define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ diff --git a/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig index 328a033bbf0e..6070e6696ee1 100644 --- a/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig @@ -139,14 +139,13 @@ 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_IPADDR=0xA290A02 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 @@ -155,10 +154,6 @@ 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 @@ -174,8 +169,6 @@ 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 From 8a3899749c4c2d85e0f8c68da2938413799f23d4 Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Tue, 14 Oct 2025 18:11:55 +0200 Subject: [PATCH 5/5] mavlink: add som/fmu config params --- src/modules/mavlink/module.yaml | 37 +++++++++++++++++++++++++++++++++ 1 file changed, 37 insertions(+) diff --git a/src/modules/mavlink/module.yaml b/src/modules/mavlink/module.yaml index fa2fe38834cb..a8eee0d09378 100644 --- a/src/modules/mavlink/module.yaml +++ b/src/modules/mavlink/module.yaml @@ -201,3 +201,40 @@ parameters: num_instances: *max_num_config_instances default: [0.015, 0.015, 0.015] reboot_required: true + + MAV_S_MODE: + description: + short: MAVLink Mode for SOM to FMU communication channel + long: | + The MAVLink Mode defines the set of streamed messages (for example the + vehicle's attitude) and their sending rates. + + type: enum + values: + 0: Normal + #1: Custom + 2: Onboard + #3: OSD + #4: Magic + 5: Config + #6: Iridium + 7: Minimal + #8: External Vision + #9: External Vision Minimal + #10: Gimbal + 11: Onboard Low Bandwidth + #12: uAvionix + 13: Low Bandwidth + # We shadow the modes that can block the FMU to SOM connection + reboot_required: true + default: 11 + + MAV_S_FORWARD: + description: + short: Enable MAVLink forwarding on TELEM2 + long : | + TELEM2 on Skynode only. + + type: boolean + reboot_required: true + default: false