From 25cfb4f790555e0cf2d4fead725233e7774b6c82 Mon Sep 17 00:00:00 2001 From: CUAV Chen Date: Sat, 28 Feb 2026 04:39:32 +0800 Subject: [PATCH] boards: Add CUAV X25-SUPER board --- .vscode/cmake-variants.yaml | 5 + Makefile | 1 + boards/cuav/x25-super/CMakeLists.txt | 35 ++ boards/cuav/x25-super/bootloader.px4board | 3 + boards/cuav/x25-super/cmake/upload.cmake | 49 ++ .../cuav/x25-super/core_heater/CMakeLists.txt | 39 ++ .../x25-super/core_heater/core_heater.cpp | 261 ++++++++ .../cuav/x25-super/core_heater/core_heater.h | 159 +++++ .../core_heater/core_heater_params.c | 94 +++ boards/cuav/x25-super/default.px4board | 91 +++ .../extras/cuav_x25-super_bootloader.bin | Bin 0 -> 47164 bytes boards/cuav/x25-super/firmware.prototype | 13 + boards/cuav/x25-super/init/rc.board_defaults | 40 ++ boards/cuav/x25-super/init/rc.board_sensors | 65 ++ boards/cuav/x25-super/nuttx-config/Kconfig | 17 + .../nuttx-config/bootloader/defconfig | 95 +++ .../x25-super/nuttx-config/include/board.h | 565 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 72 +++ .../cuav/x25-super/nuttx-config/nsh/defconfig | 333 +++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 +++++++ .../x25-super/nuttx-config/scripts/script.ld | 229 +++++++ .../cuav/x25-super/pwm_voltage/CMakeLists.txt | 42 ++ .../cuav/x25-super/pwm_voltage/parameters.c | 43 ++ .../x25-super/pwm_voltage/pwm_voltage.cpp | 56 ++ boards/cuav/x25-super/src/CMakeLists.txt | 75 +++ boards/cuav/x25-super/src/board_config.h | 509 ++++++++++++++++ boards/cuav/x25-super/src/bootloader_main.c | 62 ++ boards/cuav/x25-super/src/can.c | 123 ++++ boards/cuav/x25-super/src/hw_config.h | 128 ++++ boards/cuav/x25-super/src/i2c.cpp | 41 ++ boards/cuav/x25-super/src/init.c | 277 +++++++++ boards/cuav/x25-super/src/led.c | 236 ++++++++ boards/cuav/x25-super/src/mtd.cpp | 102 ++++ boards/cuav/x25-super/src/sdio.c | 177 ++++++ boards/cuav/x25-super/src/spi.cpp | 58 ++ boards/cuav/x25-super/src/timer_config.cpp | 90 +++ boards/cuav/x25-super/src/usb.c | 105 ++++ .../cuav_x25-super/x25-super.png | Bin 0 -> 100165 bytes .../cuav_x25-super/x25-super_pinouts_01.png | Bin 0 -> 26772 bytes .../cuav_x25-super/x25-super_pinouts_02.png | Bin 0 -> 35123 bytes .../cuav_x25-super/x25-super_size.png | Bin 0 -> 24265 bytes docs/en/SUMMARY.md | 1 + .../autopilot_manufacturer_supported.md | 1 + docs/en/flight_controller/cuav_x25-super.md | 172 ++++++ 44 files changed, 4679 insertions(+) create mode 100644 boards/cuav/x25-super/CMakeLists.txt create mode 100644 boards/cuav/x25-super/bootloader.px4board create mode 100644 boards/cuav/x25-super/cmake/upload.cmake create mode 100644 boards/cuav/x25-super/core_heater/CMakeLists.txt create mode 100644 boards/cuav/x25-super/core_heater/core_heater.cpp create mode 100644 boards/cuav/x25-super/core_heater/core_heater.h create mode 100644 boards/cuav/x25-super/core_heater/core_heater_params.c create mode 100644 boards/cuav/x25-super/default.px4board create mode 100755 boards/cuav/x25-super/extras/cuav_x25-super_bootloader.bin create mode 100644 boards/cuav/x25-super/firmware.prototype create mode 100644 boards/cuav/x25-super/init/rc.board_defaults create mode 100644 boards/cuav/x25-super/init/rc.board_sensors create mode 100644 boards/cuav/x25-super/nuttx-config/Kconfig create mode 100644 boards/cuav/x25-super/nuttx-config/bootloader/defconfig create mode 100644 boards/cuav/x25-super/nuttx-config/include/board.h create mode 100644 boards/cuav/x25-super/nuttx-config/include/board_dma_map.h create mode 100644 boards/cuav/x25-super/nuttx-config/nsh/defconfig create mode 100644 boards/cuav/x25-super/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/cuav/x25-super/nuttx-config/scripts/script.ld create mode 100644 boards/cuav/x25-super/pwm_voltage/CMakeLists.txt create mode 100644 boards/cuav/x25-super/pwm_voltage/parameters.c create mode 100644 boards/cuav/x25-super/pwm_voltage/pwm_voltage.cpp create mode 100644 boards/cuav/x25-super/src/CMakeLists.txt create mode 100644 boards/cuav/x25-super/src/board_config.h create mode 100644 boards/cuav/x25-super/src/bootloader_main.c create mode 100644 boards/cuav/x25-super/src/can.c create mode 100644 boards/cuav/x25-super/src/hw_config.h create mode 100644 boards/cuav/x25-super/src/i2c.cpp create mode 100644 boards/cuav/x25-super/src/init.c create mode 100644 boards/cuav/x25-super/src/led.c create mode 100644 boards/cuav/x25-super/src/mtd.cpp create mode 100644 boards/cuav/x25-super/src/sdio.c create mode 100644 boards/cuav/x25-super/src/spi.cpp create mode 100644 boards/cuav/x25-super/src/timer_config.cpp create mode 100644 boards/cuav/x25-super/src/usb.c create mode 100644 docs/assets/flight_controller/cuav_x25-super/x25-super.png create mode 100644 docs/assets/flight_controller/cuav_x25-super/x25-super_pinouts_01.png create mode 100644 docs/assets/flight_controller/cuav_x25-super/x25-super_pinouts_02.png create mode 100644 docs/assets/flight_controller/cuav_x25-super/x25-super_size.png create mode 100644 docs/en/flight_controller/cuav_x25-super.md diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index 461ce2d95b..f41c0af8cb 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -336,6 +336,11 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: cuav_x25-evo_default + cuav_x25-super_default: + short: cuav_x25-super + buildType: MinSizeRel + settings: + CONFIG: cuav_x25-super_default cubepilot_cubeorange_test: short: cubepilot_cubeorange buildType: MinSizeRel diff --git a/Makefile b/Makefile index 3cbe67acc9..55d910d7c5 100644 --- a/Makefile +++ b/Makefile @@ -332,6 +332,7 @@ bootloaders_update: \ cuav_7-nano_bootloader \ cuav_fmu-v6x_bootloader \ cuav_x25-evo_bootloader \ + cuav_x25-super_bootloader \ cubepilot_cubeorange_bootloader \ cubepilot_cubeorangeplus_bootloader \ hkust_nxt-dual_bootloader \ diff --git a/boards/cuav/x25-super/CMakeLists.txt b/boards/cuav/x25-super/CMakeLists.txt new file mode 100644 index 0000000000..133046a2b7 --- /dev/null +++ b/boards/cuav/x25-super/CMakeLists.txt @@ -0,0 +1,35 @@ +############################################################################ +# +# Copyright (c) 2026 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(core_heater) +add_subdirectory(pwm_voltage) diff --git a/boards/cuav/x25-super/bootloader.px4board b/boards/cuav/x25-super/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/cuav/x25-super/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/cuav/x25-super/cmake/upload.cmake b/boards/cuav/x25-super/cmake/upload.cmake new file mode 100644 index 0000000000..71d0a62541 --- /dev/null +++ b/boards/cuav/x25-super/cmake/upload.cmake @@ -0,0 +1,49 @@ +############################################################################ +# +# Copyright (c) 2025 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/cuav/x25-super/core_heater/CMakeLists.txt b/boards/cuav/x25-super/core_heater/CMakeLists.txt new file mode 100644 index 0000000000..35c06ea37c --- /dev/null +++ b/boards/cuav/x25-super/core_heater/CMakeLists.txt @@ -0,0 +1,39 @@ +############################################################################ +# +# Copyright (c) 2026 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. +# +############################################################################ +px4_add_module( + MODULE drivers__core_heater + MAIN core_heater + COMPILE_FLAGS + SRCS + core_heater.cpp + ) diff --git a/boards/cuav/x25-super/core_heater/core_heater.cpp b/boards/cuav/x25-super/core_heater/core_heater.cpp new file mode 100644 index 0000000000..89e0cc5696 --- /dev/null +++ b/boards/cuav/x25-super/core_heater/core_heater.cpp @@ -0,0 +1,261 @@ +/**************************************************************************** + * + * Copyright (c) 2026 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 core_heater.cpp + * + */ + +#include "core_heater.h" + +#include +#include +#include +#include + +# ifndef GPIO_CORE_HEATER_OUTPUT +# error "To use the heater driver, the board_config.h must define and initialize GPIO_CORE_HEATER_OUTPUT" +# endif + +Core_Heater::Core_Heater() : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default) +{ + _heater_status_pub.advertise(); +} + +Core_Heater::~Core_Heater() +{ + disable_core_heater(); +} + +int Core_Heater::custom_command(int argc, char *argv[]) +{ + // Check if the driver is running. + if (!is_running()) { + PX4_INFO("not running"); + return PX4_ERROR; + } + + return print_usage("Unrecognized command."); +} + +void Core_Heater::disable_core_heater() +{ + // Reset heater to off state. + px4_arch_unconfiggpio(GPIO_CORE_HEATER_OUTPUT); +} + +void Core_Heater::initialize_core_heater_io() +{ + // Initialize heater to off state. + px4_arch_configgpio(GPIO_CORE_HEATER_OUTPUT); +} + +void Core_Heater::core_heater_off() +{ + CORE_HEATER_OUTPUT_EN(false); +} + +void Core_Heater::core_heater_on() +{ + CORE_HEATER_OUTPUT_EN(true); +} + +bool Core_Heater::initialize_topics() +{ + for (uint8_t i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) { + uORB::SubscriptionData sensor_accel_sub{ORB_ID(sensor_accel), i}; + + if (sensor_accel_sub.get().timestamp != 0 && + sensor_accel_sub.get().device_id != 0 && + PX4_ISFINITE(sensor_accel_sub.get().temperature)) { + + // If the correct ID is found, exit the for-loop with _sensor_accel_sub pointing to the correct instance. + if (sensor_accel_sub.get().device_id == (uint32_t)_param_core_temp_id.get()) { + _sensor_accel_sub.ChangeInstance(i); + _sensor_device_id = sensor_accel_sub.get().device_id; + initialize_core_heater_io(); + return true; + } + } + } + + return false; +} + +void Core_Heater::Run() +{ + if (should_exit()) { + exit_and_cleanup(); + return; + } + + update_params(); + + if (_sensor_device_id == 0) { + if (!initialize_topics()) { + // if sensor still not found try again in 1 second + ScheduleDelayed(1_s); + return; + } + } + + sensor_accel_s sensor_accel; + float temperature_delta {0.f}; + + if (_core_heater_on) { + // Turn the heater off. + _core_heater_on = false; + core_heater_off(); + ScheduleDelayed(_controller_period_usec - _controller_time_on_usec); + + } else if (_sensor_accel_sub.update(&sensor_accel)) { + // Update the current IMU sensor temperature if valid. + if (PX4_ISFINITE(sensor_accel.temperature)) { + temperature_delta = _param_core_imu_temp.get() - sensor_accel.temperature; + _temperature_last = sensor_accel.temperature; + } + + _proportional_value = temperature_delta * _param_core_imu_temp_p.get(); + _integrator_value += temperature_delta * _param_core_imu_temp_i.get(); + + _integrator_value = math::constrain(_integrator_value, -0.25f, 0.25f); + + _controller_time_on_usec = static_cast((_param_core_imu_temp_ff.get() + _proportional_value + + _integrator_value) * static_cast(_controller_period_usec)); + + _controller_time_on_usec = math::constrain(_controller_time_on_usec, 0, _controller_period_usec); + + if (fabsf(temperature_delta) < TEMPERATURE_TARGET_THRESHOLD) { + _temperature_target_met = true; + + } else { + + _temperature_target_met = false; + } + + _core_heater_on = true; + core_heater_on(); + ScheduleDelayed(_controller_time_on_usec); + } + + publish_status(); +} + +void Core_Heater::publish_status() +{ + heater_status_s status{}; + status.device_id = _sensor_device_id; + status.heater_on = _core_heater_on; + status.temperature_sensor = _temperature_last; + status.temperature_target = _param_core_imu_temp.get(); + status.temperature_target_met = _temperature_target_met; + status.controller_period_usec = _controller_period_usec; + status.controller_time_on_usec = _controller_time_on_usec; + status.proportional_value = _proportional_value; + status.integrator_value = _integrator_value; + status.feed_forward_value = _param_core_imu_temp_ff.get(); + + status.mode = heater_status_s::MODE_GPIO; + + status.timestamp = hrt_absolute_time(); + _heater_status_pub.publish(status); +} + +int Core_Heater::start() +{ + // Exit the driver if the sensor ID does not match the desired sensor. + if (_param_core_temp_id.get() == 0) { + PX4_ERR("Valid CORE_TEMP_ID required"); + request_stop(); + return PX4_ERROR; + } + + update_params(true); + ScheduleNow(); + return PX4_OK; +} + +int Core_Heater::task_spawn(int argc, char *argv[]) +{ + Core_Heater *core_heater = new Core_Heater(); + + if (!core_heater) { + PX4_ERR("driver allocation failed"); + return PX4_ERROR; + } + + _object.store(core_heater); + _task_id = task_id_is_work_queue; + + core_heater->start(); + return 0; +} + +void Core_Heater::update_params(const bool force) +{ + if (_parameter_update_sub.updated() || force) { + // clear update + parameter_update_s param_update; + _parameter_update_sub.copy(¶m_update); + + // update parameters from storage + ModuleParams::updateParams(); + } +} + +int Core_Heater::print_usage(const char *reason) +{ + if (reason) { + printf("%s\n\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +Background process running periodically on the LP work queue to regulate IMU temperature at a setpoint. + +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("core_heater", "system"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +extern "C" __EXPORT int core_heater_main(int argc, char *argv[]) +{ + return Core_Heater::main(argc, argv); +} diff --git a/boards/cuav/x25-super/core_heater/core_heater.h b/boards/cuav/x25-super/core_heater/core_heater.h new file mode 100644 index 0000000000..942d80c1a9 --- /dev/null +++ b/boards/cuav/x25-super/core_heater/core_heater.h @@ -0,0 +1,159 @@ +/**************************************************************************** + * + * Copyright (c) 2026 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 core_heater.h + * + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace time_literals; + +#define CONTROLLER_PERIOD_DEFAULT 10000 +#define TEMPERATURE_TARGET_THRESHOLD 2.5f + +class Core_Heater : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + Core_Heater(); + + virtual ~Core_Heater(); + + /** + * @see ModuleBase::custom_command(). + * @brief main Main entry point to the module that should be + * called directly from the module's main method. + * @param argc The input argument count. + * @param argv Pointer to the input argument array. + * @return Returns 0 iff successful, -1 otherwise. + */ + static int custom_command(int argc, char *argv[]); + + /** + * @see ModuleBase::print_usage(). + * @brief Prints the module usage to the nuttshell console. + * @param reason The requested reason for printing to console. + */ + static int print_usage(const char *reason = nullptr); + + /** + * @see ModuleBase::task_spawn(). + * @brief Initializes the class in the same context as the work queue + * and starts the background listener. + * @param argv Pointer to the input argument array. + * @return Returns 0 iff successful, -1 otherwise. + */ + static int task_spawn(int argc, char *argv[]); + + /** + * @brief Initiates the heater driver work queue, starts a new background task, + * and fails if it is already running. + * @return Returns 1 iff start was successful. + */ + int start(); + +private: + + /** Disables the heater (either by GPIO). */ + void disable_core_heater(); + + /** Turns the heater on (either by GPIO). */ + void core_heater_on(); + + /** Turns the heater off (either by GPIO). */ + void core_heater_off(); + + void initialize(); + + /** Enables / configures the heater (either by GPIO). */ + void initialize_core_heater_io(); + + /** @brief Called once to initialize uORB topics. */ + bool initialize_topics(); + + void publish_status(); + + /** @brief Calculates the heater element on/off time and schedules the next cycle. */ + void Run() override; + + /** + * @brief Updates and checks for updated uORB parameters. + * @param force Boolean to determine if an update check should be forced. + */ + void update_params(const bool force = false); + + /** Work queue struct for the scheduler. */ + static struct work_s _work; + + bool _core_heater_initialized = false; + bool _core_heater_on = false; + bool _temperature_target_met = false; + + int _controller_period_usec = CONTROLLER_PERIOD_DEFAULT; + int _controller_time_on_usec = 0; + + float _integrator_value = 0.0f; + float _proportional_value = 0.0f; + + uORB::Publication _heater_status_pub{ORB_ID(heater_status)}; + + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + + uORB::Subscription _sensor_accel_sub{ORB_ID(sensor_accel)}; + + uint32_t _sensor_device_id{0}; + + float _temperature_last{NAN}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_core_imu_temp_ff, + (ParamFloat) _param_core_imu_temp_i, + (ParamFloat) _param_core_imu_temp_p, + (ParamFloat) _param_core_imu_temp, + (ParamInt) _param_core_temp_id + ) +}; diff --git a/boards/cuav/x25-super/core_heater/core_heater_params.c b/boards/cuav/x25-super/core_heater/core_heater_params.c new file mode 100644 index 0000000000..b46575372b --- /dev/null +++ b/boards/cuav/x25-super/core_heater/core_heater_params.c @@ -0,0 +1,94 @@ +/**************************************************************************** + * + * Copyright (c) 2026 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 core_heater_params.c + * Core Heater parameters. + * + */ + +/** + * Target IMU device ID to regulate temperature. + * + * @category system + * @group Sensors + */ +PARAM_DEFINE_INT32(CORE_TEMP_ID, 0); + +/** + * Target IMU temperature. + * + * @category system + * @group Sensors + * @unit celcius + * @min 0 + * @max 85.0 + * @decimal 3 + */ +PARAM_DEFINE_FLOAT(CORE_IMU_TEMP, 55.0f); + +/** + * IMU heater controller feedforward value. + * + * @category system + * @group Sensors + * @unit % + * @min 0 + * @max 1.0 + * @decimal 3 + */ +PARAM_DEFINE_FLOAT(CORE_IMU_TEMP_FF, 0.05f); + +/** + * IMU heater controller integrator gain value. + * + * @category system + * @group Sensors + * @unit us/C + * @min 0 + * @max 1.0 + * @decimal 3 + */ +PARAM_DEFINE_FLOAT(CORE_IMU_TEMP_I, 0.025f); + +/** + * IMU heater controller proportional gain value. + * + * @category system + * @group Sensors + * @unit us/C + * @min 0 + * @max 2.0 + * @decimal 3 + */ +PARAM_DEFINE_FLOAT(CORE_IMU_TEMP_P, 1.0f); diff --git a/boards/cuav/x25-super/default.px4board b/boards/cuav/x25-super/default.px4board new file mode 100644 index 0000000000..b166d4d442 --- /dev/null +++ b/boards/cuav/x25-super/default.px4board @@ -0,0 +1,91 @@ +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/ttyS1" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP581=y +CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y +CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y +CONFIG_DRIVERS_IMU_MURATA_SCH16T=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_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 +CONFIG_ARCH_CHIP_STM32H7=y diff --git a/boards/cuav/x25-super/extras/cuav_x25-super_bootloader.bin b/boards/cuav/x25-super/extras/cuav_x25-super_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..807da71c0094a99455bd5c69bea55cc3b9133d29 GIT binary patch literal 47164 zcmeFZdwf&%{XhObmt5M0HoX9$Ei}z3m^L7R7A>MPB<1uHv<2LT;9N>kPbnX$fUYVl zDMhV-8@Fv-+=kR`I8;cX&Wg1aaC17h1loO&!tAIT+Uh)^g`8gVeZG^To3h{I_xtbn z$2X71$$6i1-uL(G{kp&2n^Q=JiX+;W+5da}-#PgI4-Am8U+D8wyMFLv)w^HzsoYa! zK92Q%*%wvwytqna0}}gXUwrKpSs$lsnel~w>yBeHx`&I)#g7%Um&h9jk6jrqj(k1# zxqhq7O3Uk7+ir*KZ$G1DY7>}lN3DSO7!duHCq zL*z*#xKM7+2x-}4AQ=ZalCc*ThMe)z38Hl{W$`vL#jTl_H4|!zv#4L&RB|nYxqAmgS|#(pH^%c-^IJ>$WJot^5Mm&ai{4W%uqYM$Kzgr z9+8Y)guc<4?Xnsz=*;M)+1_unqqT5)2S3z)7jp9Eok*Qi`ZJ2JqhdzUqb6G>yfbX1gAI5E4Z0{%N+kNQU zQu@3O&+ASjeNHK%^J2I6yYao`#+_hHOLmk_`4(WjD1Z^OMUCmywRW+Xb!D4lqB1@Erl{yFZS<1XVa z=bL$E0#Vtf|o4)MR*RFegGj>;P zpT3Sl{RHR4BEUs%d>z;CeyqyF%!+p>)IH`ow#%Lv_mGUGEZ#=4#jzv=W_->S@~^GWwGTHlP;(<80djJ2*Q^r0** z^A7GLop(-hpKG8yKNS3Jcr9pIYvWkor$$OYJyx2NgdT?JYKV5QE?UOg9Qu6oF=9$B zJa+BLO)=+*$$m9!(MoeXQqg7u{-kc6?viR9GSAia zCDlbRSPrlj-LE-lp$;un0@CYd&~=V8>l8adm`&ySN%Vn&Yw3dED68u^KZh__=T0>r_cRAo6dezEQhT6 z=J!tXBo^-kU#zX5|h3##+d9PvTlf&VhcGVku^i8#dKCly-SccIUI7Q z;}p`eKw)Ra>)K{F`UD)WC7+N^I`67zqHT{N+Qde;!2G^kCfhhdXlia)WDe3ftBP4Y!Ml3fG-%KXT9&neSqoKwtqQ5s3UwJ%>yX9|d% zJFxl)(Z0Wi$62Tak(oFFoL4-~TiRC} z`=s;Sl~|d+zj4JY%shhYP=I0oTY5&foMz6_ba<{PX$Nr~3Yb}QR`9~d$_xK2?%5Ud zk1H|qB88u4!!@nbbHzXo;z~y<7pYv5ic}R+Rb(Pk3Q`J5peY6^W*kj%NO4-4(jcYb zXeth=xaKQz8VmYEvVgRkZ}gD45^NM>C9V`3N9K}6J zc@OoaZX>ii%wXCGdm2rv6IvYJW z^`381CDTc=hJ2OznnsE@(F=~?I7QmW>!YXoh7naEQHiTRZlb}uoij{QL4hjJTf ztwxc_iIP)?8F|OBetOVHX7C*=jm=kbZH)Z4w{x56o(@?;@!mjDeaVB`wCi_)=#;_W*ZGQyqr>@e|x4QfkeZ6irH0^2MI zae~2gd!g_nt9ZNf_Tn?$s%*8;Rm;m|gL4Xv;&)uU{IZhmWL}oU?0ZvPtYE2RO?^UMcb;Ohg{KBDDBHuTll7VxbF&-j+HkyJvBfmM69KKIc82R!LBfm1j%Re9F zg{T5r;;*BsaLKufI(&BwF!H0L!~Se(IcWf{ItE--q9GaXSBSQI9MK-evkT7>u7$WB zz*T_jp;V$BKaFTVokDRj$>8M&2USkn^(XBs)5#tl{k?10C{kQZS|+_jw0}W;G@r@| zdbDD6EKlB7dE(=U_9F89#$1WD)rraHfrFm`4*mvrlG+psG9xBYvrt=by}_o;v60?) ziQV-K=mplWd96I23}GDIsBa7U`5UvgQFlJ7Xt83oF88p#t?XiHZ@$`@Ea7r#n~6!~ zyzWmHX&IXT##m{2E#+};LI-XG9S8+;M*Zk-tn>CpUYsle(z1z(d6_dZyNN79%K7<7 zx=7?~g%|Z6#uy4t8)ZdCG~?YPBY<4_%rI@M67)$Y{zQ65n(KL9ik4op>wWc2Tbo+D zxokcVONe|*;R8C{-&Txb^OZ^)CqLaBBgTuL`A@mN@Uu-^X|k)^A4D(WQ1^F7NFZ9R z60Jyop`?e~%S9ioP4vy>5xOI|V{)^mlo3ckr(s^MeKc3((=?VNY5tRtFEv*@T0T(uQtuG1C7SntXOG%IZEPHMCfB9*vz2W}o zvECFLeGuX%4|?^@v?uSPC+cud)RCTmHzdYkztT8Soa9tvS51~e!8<~6o{H7;Ty35( zbeqESym{U0l>grh>4UvB-pk#Zb=Yk?l31mKg#T*xf3b8dYH*Hy%tbUAZXSuuwo%N*+;LCUMqut6 zk{EbYdDTb+&h*W!MdzcC`Rx@|754ZU%NL+tdhE}}lcc3hM>76`i&82kgYGF#zID{t z#N-%3sUlF43)zTL$#G&-6)$EU&$DuJ>L_E@h}E|Y{(XIR*zv3%*XRB0`r`{=zlHuYpn0H>t25jJ$n}G zdwCo8i;o);pvj5$K8tspJT$}{;9Ts1vMrip=3(7Iymqnssj;B5(<7kLg_{A@IilN<1@!p;tpf1_+d9c zo0F#w@}k#6(*Ib??bPjKcgE~vc1G{Jgl}YLCdyti^8&j^{lbUcBqvdf7TNSrur>T8v5_Bp zOH9BrAcN05_gKT#5D1eVm?UZt^t0^9UW*_=F~(s5AsuV9nX3ei*vEZ z8Tl!ERpBe>HByNezVD&wzJc`4+2W#bjzbDR{do{qyma$cORN5w7w50m@Nf<(?%i&B;VNqdQp4i?JfJYoCbqc=p>6{IN28 z5SROcLQ077yh5zZoZO;#sm?yGLoc-ggRC9MDFQETUf>Hg&^5;Vk-44BjCkpd7G^3l zH`BI6Nk7K**2JC+khqz?zbeEQYWURkK5C@-nFH4weyLcE_luly+6F4+J-h)N@!YO$ zf?UQWI`}{y+f^G1HiOgKqNE;UwEkq%5QDSq;cd(w>?~&}xUwb3NoS5^Cbc{#?h`d4$rvvdiU!jL;NRa27l_X) z+kwUR4vVSxoSZJQIk}>`cMAi)LQz9*+@dAsJTK|hMjsAnwZ}#Nu2zV{1sKhyVO~6z zR|u)31W)%3-rnI>Hd#=bBZC4osq#jUpua}co4l~xLD%5$uvQIe6 z~_}0p5((QLDeDQY`K20k!J2`pLaE-|9Gm23GCW@1%4KK{|0@jz2b_((2tUm-^ zRDVM!_YJDS$O*~~8kXCb2)?9ij00lBoZHWa>LtdAUd1mjUnVV9j8GWC z@PTMTrgE|}KzW`RRgd4>&CX7CF{WkfD)Vz2w@4~6$5VzG;6GyKm8~Pf5%7_;UnxWM ze{pz5vcS_%C%l{-uK7Luv-1AX6+igvlb{hNL!T3YFX9XBO17TK{;g%uHyXU{Z7QEc zI*1@thDNW5+6qLE+O^VyIfKe!BrxcoEcGsHmVn+ijt$0`y z*6VUl@m7b-a@@L5@DHJn{T#(WHRM~ISagwIa(Rd)wj&C>KXXU2tpvN&;5h}p+t5Oc zAB6czth8~!PxmU_yL23evUAvU~LFJwnVmu$kSAzv1fguZPy9H0-vkd=U zCE%?MVYm$iTfUMgOv=|1#n@bYLmuY9ZK!?B>X>l*F>WGoD9_p)pRE@}&x7b+a?`UYGH7H_0HjTb|9?c9 zKC^Pcs7fsGkbp}w{V}s>m@^AAel~Q}9`w14tUPy=7njnnD)yF%_ulfDQ8eVx9PfmF zgB&*GFpuT1smLw*dv93}$tj%U*jG6wewBm0Mf-0#ejU!CG@k&E{T8k>xNh)NM7X_i zv&2xY=;?1tkx8qjH$`Tj*-N$g=}$0_JRC}fbQSw&9Q4UHPbhd;d8s_fBWyfk=OA-< zfOB%2Go)*fV-p~!rbrG?d;u%(40Sf?p-a-+Sb1AZc&@+2v1Zz(N(>_qT^ifFJG) zr)Pz7n;?nIKGPkKJpvjX`U0Hyn;|)jNl3sD&NU@uZZblqW#vgBLlgFr{PMt68-FV_ib*7ex<8%e|R;ZbLgaX{=?^|Qp!za89G~EONpd~whLa|@r(re za!;|$MwxFrC_a76in+NnR3WYR%&da8()6LC+mTCoPgvl-dD2@i-20n|x+S6}E5x6?;v^}v>80ev!q5E%F-DaAbrPEwNyQdrqTH7w`c8_s5<2%uzp@|d zW!RT`S^mXdp4sR6!lx>vb^q_kE3ODvNuZULYc7W6;c*KE?4SJ-nabR;-z7+io&yqW z^p_}=WM%(|Af@1IjTD`?-{p`NxLTpF>-9&<@|4QlWTj+}L+bLt!ej)zdFt(PzDO-E zhHF{si7sU2Gtf-AT#@z6Z8nH0Qn#PSE`Dv~Y8V3tAoYg+LE9mMrV+Zj9Zb4G)jf*No1LIZz^ zHG@ImmH)=OafK9O%_9_lP+cm;ca(b_FP0RgK~n&0`LS5BL(v}OKcedq;V|bn%@s>P z1Ajikiw`wTI7y6G{lwDmi-F!b;0*;AjuP`1zR&z~#ihtKZ`6vN#F*agCISn727SfiMf1F246iD*?Jz3dTN+JcA;xRzrhCI#1KkJucH?nR>c%~G_1R_8 z3TSo7?4>TPE3q>L^oBm^T?ODwb)Av)QdlgDB$5^I;W_)AZbBGvt<)C51Cw&D(*gYw z?ivwd!fi;fU9|RbiP4tm^J-|g1>lRO-JWpmA1_Hblv4;RZI?dTz##kJPU_uI13kGofU(Yw2KEv%6kdnGcc zm1BE2&fvJ>dJA%?-Y3vDqrTNj+~A~1ydNa^E~P+LrrT7P@ipWzPJ9Gd-cTt z;T*j>u3gc#(ta@J*dARh>{UA2OWmM)_z3h$+2;?cX0g(`=;HJP+M7uJgU85LKsb$lD;OEkp`$_u!ek$QsgKz(Z zpE3T-53deCD>VB#;iO+c8-EGoq))k?0Ld1STeTI=me zEe0{HQwN2F+=MmPHuCa|1Jou>@r%|8OM3<}X$s3qF*^F)OL}W_n;jMP_RqbrktkIA;`d#~8icG@{ZR|GjRMsq-^A9#%dZazk^$Cz zR-xlzM8-%O$;Z?R3HyIhtDr4p=Go!nFyvE*?QkpMskVAJVqsj-LjBafeEZdZbmvf> zC3@jh%)>s#>d|7nCQsHQrto-kn*~V~9xavIh&(GiRys~9`?@QPo~~^jJk!p~&nnQY zU_4#u>zVG@?6NXyYtYQ9t>8tBTlJL3QE|i``_bu&ERleIf#XsxS8!rh-sQ3t6^m0= zlo`Ow5@84u8}whsN#c#sgg&R1x0r>~z|CzPF@y4r`>LO_$NE``eyYd%SqVPx(pUDI zO00)k9497;g6ExWjLb2i;ESQ@d1f&~*6^h%f9#I^?xR?d6j05|F`uBQLb8h-sI@ca zzV-m(J|gh_A-k`RdGYi^E~0)sI~vbSu02NUB1cW)6HRj`H`&cCbLp75Ny!>#I$BK6 z+iK^1y4#z@9nDN$z>ig#cMav~{8Jp7+eoIqBk|(X55N1c>XFhW10dUW^o=q~<@j*ecpgnc~4f8`oK3$TL1N8Z1(}DoQI%Yh&^fU1jB_wE}$2PAOZgplj=d zwea*Yu9YXS!rJ{SWD|Y{86 z$f@q+M5C+CG)Wu@G9f|Y0&VbJNhlJe)5;d3+q4W;CHFeohQ7Jx;WiVq_ML}cL^
    yRpx-xaMey6yM@#VBB&^J+wD30Ef@^!_qgtjnpYaS`53J0b z{}D3_`e0k3)`)y4Vbmkf4x`VtTdCGhEn+g+9>V7O?ES4Pb}O4ml$rHv&2xM&9=F5m zFx&#oPj)MA*L*3x-?k{$11XN0Xn;)V83F6{r2j(G$%3`}HsuYY_W=$bIngcH zsmci>t}%NY4IXpM7-d|;?-wMmRF zq+ic;>*rXYb2%`ifiz9~IvBwS+x*C7sbz=JorOLQd9oJ54 z>>Q5q5bFAQ%_tDE4G8wN)(6Ix*{6D3cAPilb!p3!2tvDDFq|J4+rVU5|M8l zmxwZZNGSLOW@Rt#kKz6T(Lz^KiPT|mLy=i~2xaJg91m^V8RZpgn{v=vhHrE?eIMWG zT@(KHlJ(tgeKyq%!Zu>NlE*H!HZo5<3rkeq8j@Myqhp-p3h#a6UC#ZHekII9ziLnq z?aOy@r+rz3d!#Q5k=kLTP`d=9{qd404|Ls2mblC!eLuq)FU8pCNNAoP>vtnhXBnLZ zN6-AS-L6ouXoP-ClpHcy;*cj})I`ACSs6gC6z)B?}LBk*;z^4W~n$BG# zb`ssqH|B+V8@??nhCBiI-P9OUD8bJ4X^03>_oRxjP^8TDJeX?Dmc-|kD5}i?zJaC# zzFa&o&35pidvQ_vt8cVR^Q#i2v`j%x= zsxQ$uzXjiZheSaCD5h=gW)tR1+J#!lXt%-FU4y-CXweDUmLwq&-n5X!@SG}K_Y;OE z4r!_6Zm7&xfNO2iIC$7_(np#*+sdl$HvO|ocT1Xu1LwdFGFQ_J(G#Q2s2SoCmrJKg zvZONDz*k5W(mB^Uj%&{<2Ue64OS8($U>{dQ9w~*N4!q=N(^l2}osX`NJlEWtmXr(f zNzTyXK)p*!OC?=VjFfDPac09d9ph4(SKb2up!AX8ih(k4(jA(ncE&god~|@h`?~MA zpN=(+B#w55`kCCugMk!IZOJ&_(ZHB=87YOlg&$(C=CqKh{M5P!40#48*Gu${Dmn&! zh>Jg6m5bRdl3rf=k&Th>W*A64^(D2?`kaFHglfR=Hjncj3>0v@g+;Bb>74&y;6C`k zsLmJXo^F6wwMirV8FG7~_{VTxh8e17P#p0K$<+9JZxIiRnqC#~BtT9)Shc*0nM2zy z?r}^~_c{{qmqvo75u^A$K!84HZ+?;zs~ZW_u?s*_zHYW}>2QrIKEnkICr& z?w=bd2XcREvNx`f>E#l2>CBMIv`5-BQP z*wL^bbqa*N=3ZYU?JWsQ4d3F6h^eE&R7p84ieKos!>~-(i)FEP_QV5{A)mgtp2(}> zX}b&g-UUe+iq&AXkV?IXp-_&T_7lYjTtl z!C6{XZLB`s*Qzo$bxLHTtM4>d_V@?z6)CFOn_pJ_Q205wnR>6aO3|X*!$~KU2lZrU zy7)_p4@~9`=TrNVu+ahhBy6C%^0hKgu0vNPH}cha#}mbs%=qF@@4uBF-}V}pcyB?= z0@?l0t+s53qo>Bf$i<99b}s?`b960oRG)GSaxpi_G5>L{ni!)BxqzN!1fP;xu-hg$ z-ceF><>quz5ZkaWBt~l^N?!E7a=g%g|ax9}6&j&SkLNLv={tgqVY z*$#{uY47BJv`4BLL0wd9BSv_c8)B$`d2VMjiK1;}57Rar)m!U2)PJs`QVY`#KdP2c z@OjYl`PFRo2kPP;d&0sNtuxB`oF*|3Qd>VsC``Z$&cg;U$OJNNK3D@@5TO?d&b7Y{U#O`)v8qoRu5F-vYihdF zVe+`L4S8~Nrr7Q0uI*Y6>ua{g@|iDU5g^6@c!pL_(+yi0qBpi?8k!|-3wL-wnrb8{2#CT`;eb$olw zLTFKPJ2blXHiciRGA;o8O@(xE2JMA{T?+0?uQ!A}hagGP_9`2l)zoKnxklG!Dqq$l zR3{fKXC^J3FO$+qC1uqs`ZfdhE1P|FlfX@ff{%>$`n&29?p-z|KF?I`8R`oxW}J>4 z_d9ytal{l7*=6G#yB7)7%b8_M?J{p)hB|1hN7>^-HL+aqRcut7R`h8SD>eXHvEF(L zujb9i)R$m=E9A4IrM-4$*Wg7e)e^ndW^LpkS0_(SN#18C7p;(?Pxoo2vI>7Et8fn> zy#QAktFRBS3Ug;7)*17Naw?}9(PMfG;(#o)ABY~apvLeV8;I7W7gR-wr7CB9`JdHH zJ2P+4#~Fu%1#i zNbZ+ILU{^oJ=AYzz@HiRH2lj*KOhY&cN71&wetTkpFm4>K4Mt`pIF)GsOH6gsPAm& zs=rgXoLRnfGN03q(l^oGv(<~4B})Zh3WvPIv7{ush^xMzVL?|6l3O#}zHR9j4HUk% zl^Dal+Z{4iTM8Kyut)A@8*HjQEJra2?FDq+A!_FYOg7&f$|m2_4oCuCTK_KYG@YUu zYByC!8z&ZCZ}`ui3uxCU!NVMU8eZd6sL75@*@dp{==$FAdlth;YYPTq;3>-}PNqJ#Ps zIeN}Gm|G{_t8H=grw4j==R>_=dCBw|9zhCQ1z!~cV!h|A5IIHAnw_#_VQgU+t+Q5@&&;P09l= z9{PHZ3QbRKRE2lwQyXSK*HVYtE>aF;RG5D6 zjAAks98h$zoEp`&L3k``NL64J{{(*{3U9a{V&;T`lSlU|PgvD~Gb9X!@*lKmb zVkUkmv_bLl@NZjIP2+i&Js!r9=)-@*R+*3*=?Q=U%C=)ABD3kOjloVs!;IpH9lnJfch6xRC1$1%K&c|KVYL_b0 zWzw?GMzl-jBeop(BV+eMJJCKrcKr|ZTUQ!;kQmZWoS&gw|dEt5BC6+cH z$vo?WMJTbg&qiMSk*&u;Tt6D$37!WM%e&`K!)70+hHacJ?y2P#wz#q>&m!b4r@Sav z_9OTx{|MY=cs@>#c>It2=yyN5?x#KfT|3G8jgPj*S|<9)%uW4eM^P(LoA18<;L+CJ zRuT(d%uP_I6>C#z#IC;;K2@RMt0T|Dy1A*}d6Yq^f}@I8!I)Nu03^> zWNqrNIvS}v0d?Qyi_|>#{LSnA%jjAE@{`O=&L_%x^|TEi_}Q6)?}LVzlTp$28=1L$ zX43hOuYg~S85b8%7~mR?tKUH9&&Zwfv!?5Q&eZScO;`OYlk8vn)mO?%_xfj{PqU8p zeRe^;sei`Nk{&g;sXz1RrkQtNpLVotBaO9WEqC`DkD7}9`D5635sN!o=ICJ(Pa!?U zY1*1-qk4tS>xIpm{2izx=IDo?rEe@ot?Hxyz%zIBL0Hc=^@m<#Fz(^k-u}$AaS^@- zU!yJdzZPjxe(eTajtmgibU%EcB*EYAh{vw^K<3S7vF?zYLi#g{9Um=`V`hs=Je?2vKrfr zBcdiSnH+}B(iW38xGli!3*%WFcx3&Uf+BtJc`VcPXlylc7EID4s|+#=r7rj995$wujRi5G|MnFZ+2#6G2xB71mm@(T-gwb1qAwuU*MWUv~0mXoK?1 zPvcJ0pm&T4eo%iHtbl|-`Cfy}#&KR&$SR^W7-Vf+jJF~@Y9su7D8~H$h*mI#zdo+j z1Q^X9e0u*PQ2^CAtk61*h_>9!y@-8GTLBFl{4=65DCB#6sYWssEvtG-^ab=M`q~Rm z&TiVTsI0V4TXApk)BR7<&3Vj@P|&T=Z_HjgJJc_g<_HC^4ZPyNq#^B*8TsTh%6Ada z5K5aUog#WSp)~4a<-HnclcPRX&b)XSo@&g2^P2x@uR#1~Vai!Wp9`)-Vob}G=t_1l z>gsGeyNhag++3P%B4C@_o$F-}{BZEOtEuVJdN}nDoXilr2r=LiBe-Tcm1xW^$+|Z@ zza^G&;h9-B^fTbw8*@7Dt2xcuxD(RP!h*GZ3lffOgq&r-e8f`R!N`@&{GQl&NL+@j z4M#TIp<&y#0BDbw)v@i|0cR6?fWD`F%Ef62Ik4$X8FGhnFbAj) zu{MyZU9M$zKjXXqv&g)k3->N&=x=^n-!BGEeU|&&Xx%*Nwq!%zYxct}w~A?l&nWZ5 z-wvmQg3k=heXcI=cZ$~i`e(+X#T!{!X7#`~$6kxbE3m6TUOD{PqS*y&0aIq2E;=Bpro5}^w^*xcsFARk>v z1Sq8%KT#+@(+8f6maPO2Or;a|G$KSKXv)D;2^xIaP=vROy$7;}lqoJptr0osKXX22 z{G?$x*q{J1QU8OAR_qR2pQybh(uU=pD-zXNzZbf>Y(mma*dgy#W#TQMh7o<_PX)+zW6oz+J*!!o3dnI@}NAei--naDOibdUY2# zJn(%l%;xd?FOF&fDd8K0GNg&V*?~guvFKmaQXA$YyzmD3Vhl583wiL1=CxVaF*%em`Bidb~ zrc)c($B0Qc#3rR?Ke%$zLwul01)ju~2M&65Wm^L?yH%3bp{7FuF6QU{gTMOS>p zR8~k~;4g?L<`BnC{hf1Kez?#r{P3Q7_&QNo>vD0%q2O;ug>pnUb})AZeL}eddtE5~ zp7Xm4P332SX(O^WnK~5QIa*(lL_G|$>&r%idlW&MZFI=3oPgReUrQ)|+vOS!J`24C zc@QU$C|0@Mfi&*)H$I)|cvz@ZpY zciUy(RGi5WGG-K}(p=NSx$>ZMSBwjhYdUi2wjtL zWN^(-mqQF91k;z5jxX9@T4UOevHo)u`m=$@sK<+KDEOW5nISQ+Xo(J2^lMSX@EUkk z?73ms1sDf>rvPJAU(reBF?s=4cjAg3J_Zb|BhYS&Tmg+1Sgf#!m4=sSOAhMLCXx)+ z$-ws?K6P)vKl9(7Q=0zsxpM4T3H$g?fW>l|q6(yOrPA*wX{QRHJj^tDB2axmukofZ zdHUQl-ONNfS1(HUy6OYysG`*!3TVkau1=f;Vpp^eEK#&~UY4>QOI*~ql6q$q28XZ{CX1gWbJq?%J{%Mj4j#EimRvjd=%Ij~>@U^N)@PqD z-3q^G8uO!3%-Hp_fJJ^6jzpk-p+x?36Kp7mH%>*2!9ou_O=0t7_TKQFr5f7d;BxrV z>JTjiJO>yD{8G<9c~s%xW7&5x=r@Wz;rKHa{x>mABf&qtQJEj{r%{PoNr$$_EA~`X zFPi}RJN`(y;F%=FdyGkMKYIL}4+H6)7%5F>c(nmbN&mWzUh-9pa8N7uSs zJK#@%J}?r+{W5UfZ$o>-9)RDrb+;?Fbm+-l?<%(WR99Zvd>?dTFJZ1JHeVF0* z4JFbaHHmE>EIr%JsuS~$xwM|YOMi4FNcgJL=jGvlnFRj>mUS$1C5yC<50aNktr~sX zxo%cp(t3g_468C;7bMrIhsvB)(kOgn2Z$277!6x;wkhZ=Fzz|OVb?k_QU z(bEoK99uf=FPT0Uvcw#(CNNPoRgO~~wa+|Hy_;r)8Zj@k&r&L|CZvX?W=r|7$0XHD zzqe1b2xu7*? zzz0}qo(c_tRh*9Jg`u}F+aLN<#lPaD6Utfsnp&Mb@K{YB3d)FspmA*4#-ZS{kk*rA z#m*@h_Uo`ups94lzzanS|HI0Br(|#q`eWc>$TbzfKd~~O6SeTILbSH02$33$FBJT& zC0Sx!27H58qqxoE_S7PFG+Byv(Hv30$4-2+c&KOXZu_8*$T5H|4pHB<9NT1f5mU0u zAXer_!xp#L;|$jf-isaIGD#|MF)r2>`A+-hlpL;T#EM7yXK)R{X5&DQIagv6^^2^` zr+$=``Cj-?&TfivWj7VUR!Y4lEAtawLH{ybxs47$v`W$zeKhgYA$FDlUY?qwRs-7P z<_BOUl>aqqbVcGr$ou=}-EEH}He4F;0?babi^yjOaB748VE#}rA3m~>42rq42@R~9 zYP_kpEj>5pKi|XGE|?#hfDr&+T7!PGCmqq=(8e`TpUp@a8mrwm7UO}~o6y%W9%-4s zhHnD33vg15V}A>W-bKp%`Z zBAbxn10{sWlf$VOkTNJZ%c^85G~+}*iWvUN=0+vYdO)LTXTZn62SvH9$EY^9sKptG zRZ)vyAa2M34207LEZ^xk7S4MIyk%cfRs+iaRer**3FEMn%ID?f9f$iaLVi~}R4V(y16Hj!W7SS+_bq8W#h{-4>S4MT} z6=osMcX1L}_if2cE^v#8ck_s4$OoN=m@G2c@l_;q(5FwPHhVUY7oAgf*tOn7g-OHN zHYp@C=u1c*3Lb(-47CNtf&;NOp6e#}Z3hl{w-jC>@NT4(bCRP5&~I&i+0OdjDNPpx zerC2dJ1y%9p1?yb>h|9W9-y_nGN0=1qVGXmdQ{CyGfLM3XA!(X_qrbYOWRoF zaY|d^S)@W->o!-SM_WD|?1ltR{cDL(+~2W|Eo5TL$}UMXI%9g(90)2wykjE0@ylHD=PoFn%0u=m$*Pl4__%3HR5 zM#G_16pz4Ws=;41__ zqcv3aIe?zgcK}Ya+M4gUEJ{yzeK|Xne#b^_TdM zCZ}kcv_M}PEUuL_upBYFaH875=)m--0&yr^XIDjgN}#Wa$XfIblU^e3D&LX+rgE$PO~e>SH6%3b1a_g{#;=;} zA*K@0sKfaM*c(#;Phn5tpVFMPguWrFp~jx>g$_Xv$ax^4;mv{B`ki!EO}|H;3yRK| z(BHX9<&8FLd$mFOLCgw%|IP-unq2Im9&=PHg59;(ozBl2Qzs!55lqB2u z`|0@%b#5vt!e@c<0@P=L_A4E67xa99Z}&Sp-0vHs{O{vqz4UAWm!HmCLsN7hm26em zV?)8ekA%-0F!LRe8NIu|_-G`xsekcNtQB7pUYlM&&G+y1-+}if{Cv88{CC2dZt9Dt z3K+CDtk~~I_$lcfy;a0A*LQ0bbK3+tq`n=ee^}`lpZ(?u6qYAK4HZq6HD*wGKoRf} z_1Lgs1y({AOLrUnb|C!CvWB~`TrvZ)KKFO5it*5t1rUhu<$LpKxmzp$N&C$I1OF5G z4xC~W3%(d<4M7t8KBBd^BM#*dq%s3Xy=dxPPH?@(a@f~~8Jq{gUNm9{num_sulT6P zIQ3Vlm14#5;sfP;U`lv&^F}mN?(HBmih)HXmI#X#emR+u<4eZrI>x9xMR4)GwOoO? zzH}(~-I22GCkCcrk1^T%DVzw0wkI^~w@>vIh=|vX8V+6^q%b~z|Bp)|aX}ACpuvuWHB1jGz1H zyuCM=OC^We^^iBOdndadD}~L7o(qy+E4e{sCx|~NF95eLczUajc<5|Rg|@vOI@{|$ zRlpcsf*!p$%uh+i8gh`vwjD1)t-l=X_GA5SVyo5ks!2 zBkpBfrplMBQMFMTc5tNIADubiOO!L9?;97^Yy5m9I$ic7Cg120=~{1=ZQ27B@AbJ2 zd-EwqVthHG(E0E6MWepxHhY-Yt^>5`JE8)ixmQqgf4FAG7oGm4-!4Y#{}FOrzu;NG zoc(QY6u)Zw5v&27=P0iwjK}^Bih#%HSZ^78AuQ9-IfGQCrDq~g$i8b>HD$_wiHPf> zbEP7dnZT@=Q&s(zNTiyvn9TTJh3uGhfv(Nq0F?~nXN5Ie6lTY_u_&GU=wSi=k2i2A znQ@_G#rFEKK412oLyQ4~^E#5F`~1cIPvRu7s)2b@eQy+Z9JrBEf|S+JNaK8;KVlE8 zSN#$CC>lFN={2Qm+g$L;e*z~{!ncQNA)KWuA*PhdgMeRxdNtrQ#v;?FgDZJuENwvg zw}S+lWj>IqrZ(JP#OE@C|8k6>MJP)8xB6wM14(pk;nHbqh({?lS$dw_wVC7;seHZCa6() zU(@T?p5HX?!t2+zZfd>ymixEYwysxM$kji%Kfc1rPaJ4$JoL)z*X)~a^V+UPW&g^4 zFYX%Lqr)D%Frk`{o$BBX2R??7=EYlrxlX?zqFB@A=?qb>YL!ihP{D-!?@DA7lCI9(f z%6$z7>I?PTSD+kipPAR}U$On*SEUn@`)T=`_`}SB6;0#odR}-2bB5D;;;~o3L)^v8 z;Ln$BH;RDSpd%FVh53cwepUY{)oX4Xt!#q!ZU#$FrXd6VdPx2Q7k=YD=Ajzw9WDJU0;Pll?1ujQ4eTWM9S^dR;i-rwj2;LTRs5R$2i(b-~+(Xh5O70+A2B zt`&aDpN^w4@=f|&0~kGB`CO9$uwWP|s}ekv(|D+IIC!5@UuF3Ua)yHol}OJc94kpr zhLvb(h{AO$q>?3wHlq-ZxVms^I#Pw;xTg>Xz6A9A2YU;JDODKP8^9kA1s@v}su+tJ z=Pn49lwXd-nvit5%hD?;&9O+!abghmVJV#{KRx&7CjKZie+MX-@I*>em{&tO!j;fc zPlity_)X|TzoR@6qh-C(c{?E?Q$Dd4bIo6hsp2f0HyIZ*E8vgDdkro`)KBHbnc|A= zuQlAj4|?C%Fv9zUHDruC`xm%1s!a+7m%JVB4KN)sU-8ys)n8nd(qLNi=LZ&7?8vVV z(<^%NzW*0qCDQ_?Qs{l!OeZOWsdEe$My}kk_e~E94oms%U4x+4Egweb#vL~?ePuZ zoQ;cJc$PwIf9SBlIy;1{w+e zvria20Q0G&KUYm2en}?68FKP_eM)}K*Ri5zs44w zqvp;Fh?$H=G}cE7-%5Q{m$p1$e?YMqi+i@gbBj;dEg6|}O|aXz`Q8s`F5{A=T;2~| zNLiO7^{cN^1>z;wP;dd@g32`K#121`qo1vve#sXTV4`VnNXC){S1-l{ScdlF9`xg6 z2d$^L=Y4*Ol4XUR$xWYWI?@77MOvV#ORjq8EQmmL7BMcIr#Y+^We=H=)=^v4*n2uI z<-$-9+~$0CtqpJ5edXEtR0qz*EDT*r~B6R17v!exC0qW(1KE3K7Js+Y2x%*goxR$WU} z;9Lc94d}F9W017jOB6nJws_LcothwC_vx|bMsYA0jflLVV8e)ncCrUPfo35TJUymE z8V$z&+sT7OUj9Z1u_$p1iTr!$5XzuK0B(5>I@)ZZhDO;B;zU$p)?643UL7G4Z-yqp z+=uf8i5aK+2oJf0nqGerV4cdr&y7SEaL+L~`3`!f8cIPNn2A@$v4zSNgZ1klp&L5>f@4IR6xLNzPH2Ld=whqtj*+Yd-shE6E6!Kon8S!j%Ki{1uo8J8 z=6%iu=GT|Hx%=ozmA5Hem0Qde&p`)$B2)nBGlp01)p|yQpF&d6hVjo`o(c&%Lx<$b zN3Y4$%b=F@`JfAa&cS_{r7rKBukyfK+jZ%y9CY>dJUxGDJdZQSt2hy723Ti#W@akB zM3I?2scL5CpqFaqltvD8D!FQAmezYqQIhqRLL&E!R)F81@3pw5I?Yn5#8u6-+~p(F zZWk9enZ&iAD_Nz8yXW8SW*;{I>iED!#zFNof5Xhqq@M6`zG%)w#G`AL1gy`xrq?B;J_& zv!BlS9`Ji~-f=D)`d#hGDNpsRlyshh`8;+4kvpIjL*KH|w`?Qyg*iAqReyq)UeajW zYo+C$lyax1Lz)-HsfK)dwq^vYQfME**=#!K4DR=EFVizr3FKL3KWw#op$7|}#74Q6 z!7zOHd61|Pk9cJrhCO7bO4Iv%pt_%-)gwTyi9fE(W5xUse?JNSF&Nv z85N~IcX^3`GsCQNI}6eOeTp7(lui}!v$y_Ey6yi|_x15j75UzCPEL}OwzPo)mQo;T zT4sXgm3ns zy|TivV7Fwg|L}s!5M!tXKa=h{)WcG7S2M6MsJA`)S1Bp~jBi$o5K^to%l!)NE-L>- zt*?B?R|tJZnn%?5dW=H*&`MeuJ)~W+m)nwur}_#9%-H;vFqch&gM(n?JE|kpKPI%^Y1K)N+!j^ijur;oXnFKMn|@JL%&}1^JBrQ#zf*%; zBk?qy9@=A`@L_K2_Tl{~1;SbzCVV5We4p7j2zzqoZ@YnB3(HD=4|_Qr+7D1$qQ7MVzeL2>Cjlz~XY)r6!gEb?u=IO8`i#3y9qWJ6Xs@C=$_5<; zdBteO7cCj{{tCOL<1OU9-J?%Vm}pPx3l8dK27~i$M`CrhyIsDPwC+^$xvh?#?3;8O2@?aBZxF7dU&MT%C8P zCFZoTdfOr+W`m~%oh_Qi;=1WJ(vN8@8fR-M6wXYyfur5N(*A?bSk3LF6ly8=iC_N-dPyuMa=mL&J1(Ejgj^?+U21eY{F>|_12O;d=YXV z0m2NI5z}gQQ1AH*xLZ%-t;N{}>NWz;Y}kM1;i3EIFM{psUh0R!=xEGcqwL%(v@74< z?XV9j{`dl~3r|Q@X1mR}q9?oq|G|E|p}yc9 z2gz0h{5}VBXPTTvWLF+1<6sH4{oOinccacGKBahSD>xcaGraCUp9MzQR(k z$#(4i=J-39E`An2Hp8J92XvnngT2!3KQhG8q$K^ooA(*g2(Tx7psat^mdi2#1NyVc|24vsghgb!nk{t;fpk0$t zLi@Utm}yne8%XV?SaHv0={_wpj7i_MaBv&#QvXYGxpB_UvOe;hdjuSzC5!AweJZqC zC>Y&KU&<&Iw4GtUa!DSuBu^)~I=$CXOPDwr_5hiVOkn517Q36%QQwWj@txhogQ~Wb zU5|0Ti@t?kZsvZ+`B&WFfX6x0qDGz>-RFHOgws&RZ_u|Aus(ec>(sA6QCPFi1kw7Z zFhRFUbiV`S`Me`s?v3EF?(06jlr)G)ONc*6IzqGyc47S(Yty%o{k~Mz8&tFofi}$U zzJv}waEk)+$LMsny{5-qk8PfEs3K^03W&fwye7$GAUpd}D94ywRypnomVJjwhB{qwGd|jKk`O zHk=*zVkGlVDEJIVRHG4n%77@$$Id6JQ_W6eE%K6mu$$yvpV>1UuUQhU8Fu5TP~uw& zZ^PQT#9ri3`#JTrf&x2T-P23|KlC23Z1TJn5c!Gdb=|?{8ymnsWYO>Vj1Enwf?ouw z4E8AYMRb24y>gI=;{K+;_zGlcNMeD-e%ePReFi@W6wU#XBTJjn<@nP?8*BgBG2-#vmihN>A!tTWFa;|N#FX0r6?3aCh_`MRFyMx|d z^CFVhVg_1X-#;Hk+xgP+0>a^P7ExanZ4=>5i%-vO#fqU{mm=-}Fs0wd-h3p`cpG^C zD;6_HZdtJn$~eH^KzTzf3mkJx{kdVK0;=%yr- z4+!$M@)Jh*i@+{mW6w(V`UY4C(Ja9Ho$C$-QsaPAp2Ig79Wny-q|dSLN&UJ(;&yCJ zqEvoUz=L-yMkN>7thO1Mv)T>?jB&Sn;t}fNrh5(r3~@6&djlp#dy~dk*4Cl?RVyD7 z^Q?ZCz=zb6)g6ZdS#d_>GsSg!saNvbuuFZLZ=gE-!@D<72)*v*ZBdX`S-aR>BxfE9 z*{TSwM3s0bP!)%HEZuE4VBt@vjw*`wm=VYg$em z3OpH?f%~nD8;AdgC1D#$$;8$z zHfn=n+tAj08{X?gNLp^VY%hO(DDYt1ny%meDawZOtZ{lxK&^>O7x$$5)zN9Kar(pG z^U*+v3cW&pbNm{f%dmJ}R~LLaRQA+}_oylJ>ooEHn79HD-Dzm6U;wHZR>6ApA37Ck z&6fvlMu!fvyvCw~0Zx>>w_Djb$|->JKND+TZc<|rl`i02Eh~ZTTimkJnAUpi;NI*M zHJVOQl>k{`bqlSU&He*xZ?~SZ@!LK;U*^x!e1KWPsA=`ZxOG!LZ8FNz-*0`#n$AkP z9bALGl-rtQ843P~_?D0pZRNI%aHFS;Fr{aD5(7fq`1VbOnWw4O(6jSc32!Y-I~|2u za@(-l5Dnxtqv1bWGcI0Sp)_zgRBML5O}p(|JR;C`;;n}*2U^34Y}`=4CN9Z4%?8_~ zEybh%(!{;=S71uP<3?UP&17Pm?;BNdE0=TLM{OZA)E5cxH<*F_-*vRe7~9WV!~pB! z7MsvPvP+ZPdPWE3q1W8dev^12p+Qo* zRwS)2RA4kFo&Fc}_gezt84B-sxkSaQpA|-XUy)Kxw;FYADjcQ2Qb3E|Qs$p1a+8dX z$gU;dN1<{PNnFD-lv~x_{Yg{;@cdCOblx$eC|-RZ&pA;%=i7*HV=V~0Gm#w)hf%&Z z%{DQ8bSsr_03yrt2ac>|h>eHqZzRxjIIB^gp_ZUaho(EES zvO4Z0dZaL`aFEw#Z9dP<__1#n?(S5puAlh9*EK@IS1Zjn0=*WJi3#6%xEbd$au>!4 zUAjshGe~vZ)~Vln75=VyJ0Xr%EHYWXI>WT}rf2blJs@Wv_m@K)L;-L3wwp`RdV$puw!k z+|=Ns=Nn~NDZqj5FwP}onuz6GXf0b&*ZoxzZ9Y>AuEIIku+Qu|IRAM`Htm=Pmmoyv*xa+CgI+gX@)W>2TUb`%~2*Gpx!9_F@AV2b>WL(*EaGfQ ztptA)my4p`=!{Wv)5IzJ zF$;Ejv)!o|zg@xQBwAmFz0z=-2}mm+D;h4b)uzkp=+`b~poG85jEB*4OFCsD^~x+G+RR zMHpr9MFSbIT002xzi_ale{UZCURBCXRoGRfmWl$qvUHuSYps|V?Ia$_*{7KJF6g%3 zF!2}=aF5xcLs|-5aycKxSnDXHQ97-$IX$cH4W4PC{n{X#zM8nW7H~Hd&@vAP5}Zfn$~33!%)TF~9d&*n^&pWlBUXv5d{2LH2% zgBI^K>^!vatc^d*w67DP0*EZ9q0CAvmqP{3M* z##a++zfGl@Hr+cqfH&u(B zO2KGtuw1PWj<*EH#0@=FW>a^Nz7O__sC(DxFEDFPg>E+0!U8``AGHhC-T0~=^UVy;&;K zj)WHYhZoezEO}mHtyH9gBpc|Wr1eaF_08@M*roIaUkC2kS>TPg!(xRUjA)q*$JgL< z$l-Wu1rvGt0oE<941(95jUANTf$~g18@j;(i!*FWz?|Iavw*7|(M;#@j&KKAij-;34$2hf0L(1$`T+oMW($SQ>nBlJrm zUU&13>{9n2J%IGaBi>Mpbcrv*Jb-mX1TiS=c` z+v7_^J{|IlkmLHoI|4dIxurZ`JhB2~g8L&&U8oBO+eu2>&fThlMyil?%?q7Joxu)N z85u)I^DFA5IjeZ^+MzEK%0by3Ov+HtfQavsQZMB-Dp5ZL^<-Hth}Q zn$tOO@yq^H`r6#K z_-xHjRM{WrYMIyyx&+F48uJ>c4D=gN^fOGnHrTQAZ`-E4Tw|72AkA zp=hY+Ak9Ev8$oV&^h$RP<+%#UDEvm%I7SO;?8*-{UwwzYest{Mp-j+M6^Dc2KDwG$ zeB~4L3yQDH|5x!}QSA36rD8vGEANky1ih+Wg|EVQeVJKZUii>XrLsSg%l@cFv5h?Z zD6ltet>FyB-Qjg;Sz!3xBXQsimV*cSU*MIR56kBn51To>7t=1w*fx?x5+)Mzn-vXs zCuYUA+e;$l#jk>A-?8y6Gtdv>o%vUWD0sbU&%06rY%zBACHt^S@ReiiLcb##nylf^ zF!}+Q73NH4|J)iO_iw&z)bc*LHI~;5gHI{5e@TsT1nv!u6n4c?1N*8q?8?F#`ex6w z?X?W`eu69J$N-F&KKXuJgfGs z^FLCst}9Qmu1is{&aYE&dCxIevMvv_ai8p42W{8mIC`{iTDVkBhDQ-IRW z`SXCL%K4}DJ!?7VX~Pa-NX}1VWH4m2iiQ`yjjZrlYYOJfJ?L8lKExT;=H$~98a`Qa=sODZ362bVUl7*CY0CCAyUs!OO*ev7hw_e)p2u|b z%MVd*9>VGJoG#4L0m;!zUSe|$@|;cQ;~|qV;JX!fI<}O`>;{+bdRIa7t! zj>0N7Z-2r}Y9pb?w4Z~|H((}XhtwCmA68KD?L+RUwi)rn#vXnfY|3ngu7j{mH!1jr z8^M#k4?~ufhFa)*OtP%siKo8UQr7i#uJR6We-O4|y-009&u>OOK1K)$sQmnQ-t_#G zrYTi7Lwb+~$*lZ*oPQ>sPLQ82!hNNd==M=w(#^9apkF+yDLVlBNa+ZdtheQ%RbTGI zH6HFZMqlz=Kg~mr_Q=;LAo&oMi?#-fwmIGdDai5$SbddU=MawdNrFS{%QEI%K)?DAWphUe3PwsXKhucCV8qZ*`t_CN8^o+397#fOg)ye9ZDFg9r)M=Pu3= zy)4Hu656XsF_G_4g@SOLNoGgddeQ8P&na7dm%HzDi_jyu5&ReI^l7EkjuGL64HoGj zQ_Th2+rUM3Nl$5egByX8yO}8*^YLti^E+^~9Y;r?qcI-{o}||vV|$u>2mFFAH2NS` zwT^D$X#5>`x!0Q()xKRzGExIP(ixx~OS;UF`(q81UkjXCmN~~mTC;x+XX|=`i(#9& zSvwIvUZIhIdN5ccZYCUHZMxgx2nQQb>W4r$9t-V3lbX1i|B$qU(}8!qorQz7;g2P4 zP0XbCEmwhNy!~h8Y&ZRKt%bk=5y;cdXImojYCJpcHc*2PrA8++RMzf-1)9HxY$RfP z@}XJsEij=83%MjrZ!z))+p%{eSsOi<%eM2OQioZ;-A?uXvJbU}|HI#U%vd=ev!{V0 zy;*A0j&>*v`FZrAI$yATc(i!CBf6Up4k}h~^VP70c z?T}Nc4A{4(o$(0Qo_S2T_UeeO~Hw+F9Ck&zq9CPgM~!2{OLSQKk13 zo`44C?Jb4T`aWOIjB<4EUxZa1D^_dw5v zt6VmEv5suR#7Vy@JPkjx_d$=2tedncCi*r(hPjz!qyp@hL|9T* zLpKjTyl)sB88{vZnQ&tf?LVnaujWU3D`^@FUWWCaEd7Np$F@E;{yMC;ioFbe>pxUb zA0BMu@V!4CR>Cq5aUHMcwrxghMV{PLvkhM50e;M2zdh!zx;AOY?E1QY)UEc;U8R~v)*yeAtw9u@1O{6uCJS@-^~nP_PG#$ z#s&U3FwPU5obK;FF8w!N#7vy=3FrZRVrsPTkU}(CmU~&I6INZ};6HnjuBD^2Fw^~~ zuO@w=d<8Sw|Hl>g;EKD@Hdr*2#x7F1sZPaaD_N-5zeydkKK8Nz@>Mawz1+cmQ1bMgC?Loe6Pt-{pO>Kk= zZanB=y2herT#?jYYJyjQ?I5MrNiH+wWFAg;3F$HY=^{e9a+`_0+ZG-Q{J+RGV$@&*whK=V2OM*A~ zg&{br@{;ud2aOqS3iChIJsdOajo|COf3}QlBTKE8aKtKaSNId(pDq77b^dv+#2@9d zD;7;^;w0745wQFF`sr%j!s=fQlkU{e0JV`={$M{ebkGsll}wZ?IvR-$yB@5py90T3#4sHNaUR zU!QlpM`?d^opZ#)R%b43bxznfOB;UCtHN{es=%km^m|pHbyEZKuKgdr709o`GZ?|+ zyPIXN3RL+IHZdDKYk`Qg=nqj}kLnodY zbhh2nTEzT)gk=9Ta0p4W3qD>9bbd4ZsH}!&NsS5kO4!rVu9&{y*b#>~Xzkacmq6zu zwS(-WT(I-{nGZ}o?7TFv5!_-CVdtfXotLI*e&SzbjPON1{R`hB74OuP)iiVDm48#l zPS|)w${-uBovUOjVU zmpuEy_Nv(&@ugz;xn=D<;XsnN)7i$ET!^}&^LkB0lzg}gTG)(^TDo# zWD4^9Kpx@X!<_Y_ZP9m>(6&5MqwAogGTDuJt#$)zpq0qd{r{ANeeIAlp*HLB-Fg2hy1PS_J7 zIT?8^|G4E9Xsys!IwGxjbK~m|Pioq9zvZsi$+pT)9#UVnyk1L4^h~jXB9y*PBAY47!hr%b_(ftsR@u_J)=Smk&65txnlL9P!Xz+?SF}vKr+c zrVj=KA)s)I0{A)#;Ky>BvaXWZUr1V)s^NpPC zELGMud<91Dj>>1S=E6~3ePyNPdPilgq^LhvD_pBuv1`HL(hn~r>4+Rxnx{(SiM%1oDDR(3^kS z5nZCy|4v$iH9ToCp6sUowa^xmuL<-F-H56pHBW#!N<8r)CKD*H}+$o)5X=NA9indnX(3qq!9Bry}>YS<$g+b7jIyDB- zxxx8~(|JUB$5|ikF_m|mq7l!op{}+jCf0zagYrSF*jaQRLM~0)JjBDNjqx}Rs}0JO zXy+{Foa*9b3;b*N=bVb<&z$DusAW;f&n=7T7)U=}UAOExC*PmOl1rA6=a_-iP1T<` zBUjUvl*%Q4h3~YiDV=vP**^Z~Va=cD5uTkzPp$15IRiYs+T?tuz^_d2CO$9Xs7xX$oknu2!0c9Mh5GHtp^Bg8FO7 z+C_k`(_yyT-IJ=vgGRgeVf+p{?L5L|VRxMsR8HGCi}aKu}gQEIQW+Z}|9@oVx z6S+g<|G2|{|H2)VH{F3`fWQNT);G977!?_kfVdX(b)IauUANEUhG#niSI_NHZI0Mh z@m5%2SPB1pheh2Edj?A-Fq`H=?)M=qf5?ssI0zVBBKSYT)&@JIR(Qg;u*1EtJI0*r z{$RbuujN0eA>3;%0#8uT`bLlyU1|ajgogPY83vS!`DFpoIf-8h_rvKgB^}w)3$u(9_o0{oeECWFlhL^6GLY_%rMP4!KQLgmZh@(ni%v-;1;b)0CLfD*u}97$xCQIQ8ujF z2Q&Y3vK(?aIABxUgqp=?DZFHn$^1j4Y^-X^x@wk1wV1CA%6Y{y=u9)Leq!6-xR(E@ zCMybGCZ#_^Bmagck2PP3oBN6-Q^r70cg%JJJ9$s-pFnoGYzYk=Yhzm$N)EH zCY@DFq+>pep{KMi!S|EqwHSP_kM&fHHYUI}5;mo2z^TeRLiVKBeXCoRx3Kj0@iwq_ z%g3I-m8B(t-^uc+|1$qqE$;@zm`5%M|HaZZ?aY|i4jW$StR!?`zB7KCaMYBVuYtIa>v%0Kp|tDHrz zU5Z|m|NSk{WQm?X?y_ppdzU|6bnvpRbob@L)i*Bxb@lMe+QeHf*GJL3`lqYR#pIv= zw*D}m_U7U%g6#!pf!yJJ&a&B7eX0po^mE)?4}bN8fR57vc`l}hzmX3wyqnEs7n6$h zG4F?@>tlL02F1|ub2wk13aJBIEK#SDIu#04AZ&8^$JA`Gn6D(&@V8f5=O^xN+8>hq zVn~}~y{NFVkUIDWIkzCNKsd+ckE;0ta;s|=TKPQlMV0wqBiYzd?k~-s#1tHXo5zdGyV zTf+ZM&&4v#{!Ol(oiQAqqzKQ@$Bos+;KOxQ9f}`pzR2arh7|rfi->38IMNK|kJq8p z&s_yJ4W0uz{pyf*u=OHmjSaEBHw!7J{2UYc<8Q(~;IK=y?e2^f%oi2r?Y@r#I`w{Y za*z7Ptc!{mU5~np>rq`zD(I$`oXK$P4s`>8m1?31CCD`pL$Rm<-=n$`E!RQ}gr~av zb*?(J(bKLy0bZ=IM(Wb-*F@@)&qA?%FUWP_IJ9Z*;^QwAK75MLtFW3cisl_5e)G=G zSZ=4~6Wg1%drr*t-0$8GOPvaw<9gJ=WYi;I9#ep}TE@mk+7<6!(PpMMuZQQbm&{zj zK#T2=~49U7j4o|3N$ z#a`Xe-@522dBcxyunaxL-(F$;G|_gE+46kjNsASjg6Gb|#`%0{;akUBI(cznXG|=Y zx65Y(R;kXm8CC>dpU1Y^$4{%UX8TMwjgR_{1yT&wO2``8W{plWOA0=ZuOh1~)O{$q za;4xiJyx9*T-QS!a#!w$Qd=(RATTpu4r~V555;kD4@N9{0~EV1RQ}QEP&FkA+O(ec%545 z{V6`?J-VI<-`IY;H>PFx8A|=liC7aSmws?HS~VnQOkKI-eaomPjh@%mzi&}`IbBSu zGQ@Jq9iyJizoJlV1(t~A3WsnsLW(DO^5wYLdT;82(a|>R=qTtR-EtiE|4Yl0e%q3n zveuI1GHpYNX3Z}DXYX5iv)p%e52=6tHtU3f3(b+g&E z7quP=)t~<4u`HMqJTM9yJ$N))otT)vk=98h-qw!vXgj>}{ zeVUCeEO^I~*P3b5U<{nYp4r~=AJEI{>7^1C-GfR8mtC8E?DKmv^idbhKe*AGFs z82bX2(hJ-CUSPLKkWJU+a$})4fU(2MSw~p)~%SzbWBRp(!0F0Y{Rx)|5;qm`w~;+R%Zk6ou<;78a6{q^8K4pN%7gLM$j30HhQ z_yyK_6equl0`Q-&Ly}FUK^j;=coUSy_viidk9i^8z_owsk2`_q3#nQPEW+BINA8hQ znCO;*t0XS>nlCPGL|fdtylePwsFhJ{eQYFd{Q!W8rVnRi5X*Q;Gr5*?jED zjy9RQTsqkEglMFYr90^yZr=|KN_y6`$Z90Mjaqn!q{z}h2Zgbi))Zi}G5uWZZbuX- zOGlu^72pl!$+kQp-#fUL+7+^48+swumf_$jXq{XSJ|ANKZ@OVk1*;}leW`DJc^d!9 zlZuji?R=mvy8zxOoka%jp+epkRb1nE$)ae3pTof~S)$t1a$MOTZ^Q~HGQL@>6Kz}z z(j6ECznFs|XG*i;ndV;)4nN4DWn*yvfb7dwX=}Y&_M&>$BJlO&f$*Y+T;O^TI`q@8 zd1+UdcLd1pK6B|T*ldP_N5V>24_}AB3IXT~B=LM5CdBuG)0hVt>=2;`{L64~FLIS5 z*AC>Oy(n~%fR!2y+HT4ROz9aw0Nu`Q8x7HGx(c8la1bey#3 zAPWfScy1ME3a7(UZq8Z@v^i~LD?bR9<|KPYN%pu*@NWtiw9#E346D$>_se=Agc(r> zd>)oo>ZM~_STIbrQ9C>mzUnCJaxRF`pG!2^M)HcTj>>Rw0k|cUPI>Qxho^9`8ah(5 z4+HlEtw-@YVN)5oj$$Qpo;&d$3?A>vJWTf=8y5E~uVD>(C9Dkx$Amq=MpQx<55A)z z4;qR!s=#O_A^Ei+qa)Hk?+{E}Hl8q-{7DUB#CZ_Fc_0}pX@3tx$=$M*9fMxaItTm% zU3uTNcZA}aD}F1E54x@g&w+DL)lS^l*su%FZ1(SU>1?{m&8B+aYqGR-lwicvc z?%Qv**!J0YLk#viz<=&*E6ny#pJ=_h^u>9SZaN`q%#)H33J4PriU@}yj6tYHs6`lq za413%VFE${VUlT}94h(KKJjp+Lj$W0>S;%p-hy2kkG7<=xBIXv&SA+z<=AfMFwi-8 zV!?hl7|ei{^AX5V#ehyEBn?4%nRe1Y=HJ+t?f5lny48~7U5=w99F6xj;V1z|>E0_i z8j7P7Z+7*sQRA(aG2Z1kiosE$w+Tlgj)r-!;7Guc)?4Y&O^(zu%B!37ABBJQ-h98i z`u5AUAa1{)d>8+N*dOV;pjVc9rI;+ft7Abtyj{lJM$g}e`9okm%CzJ#=D!i}n5djZ z&ld#FSsEm;SAm362`wCJ0={|By<|W}*CmV1WTPJn>7X^kWbD~dB|3Ob(l+1a*ltPn zeEIM$JP&6`1I`HelvmdZ@h#I24=eR7*a6J{0!gPG*E3u`CVFG9{NCz^2?gOm=tpwRQ zflX`_nF%xslmxQiiaJmt$Od|eacmQ)0kjbDGK3E!ydU9mgjt~4e)=84rJ#ABsVMty z7eT)VHG;N+UID!ddJVJ#v=j6? zXcuTV=nc@Dpg(|SE?iutyQ^ZwA_m;y{vX-Ab2zpmRNfSt5vMFG`_rH5k1y^I7c5=6 za`DoNg;mQRc%-6w3CnjnEz7HyJao5{RWDyQ0rbG5OR82mt14GkEv#O#98Euc$NEn3kYQ!lN5syX~)t|0GoUV)RkH_?fgZe}C^>QYFL{JP! z3mOVa040HRpcGIVUp`@B)ngM@u6$zdDi+4&KmWkv_;8!S#JeA*S^y4fx2w}%Vx3XA- zOmiEHLnyzeC66v%d{dwOVJ;J|f{;u81^bU%?_uKl`VGjYqWBgcd7 zOeCUgp~J}~avzTx$fBE5^-%SSl~ptvbOqLe3Hb$g=x}*;#bVvU<<*Z>E&nNNe_^(Y z>cv$Hbt{+ZDpBgnD&0y))&F&A)nnC_Ra14T3xB$N?xU5JRV!9Jh~{}hx4i$hRM0P6 z-hb!nB@ePC6-!tewP`x_tWEbv?1m;5MC^!eSQx7x{o#8bBQ$@z-LwfIdwp}_{SNp{M3S_?<`DHeL~$CzZA0^uz8WN?wB0b{`2?w1NKq3EKxQ$A8fE) z>z;8zQI>Z{_9#<#@#Aano!+`)&DpYHkIpX7waj{K;`oV^$D1Bnm^&qJ(!{EYiFxw4 z%8c|#nmJ5A9^wtBE@a`X4H&P_p&vbu`2wMFJrhTQKB{BlKS8HJFF{vpP<^D2-L@$b zKHeWj>iyGy4)Rj$EUvRWx_A*QxI6zIhT7>YvvhQ?7!AyDi48IfNkQapKn?o+qk-#;hP9*t+}eHi5X z#!l7j!vtae&I&#VRVwLMvD6VT3z?^Jj73igFU?7mcRYoRH|vl#3N#ut zhVscj&g@6Iauj)u1E+r}6e4-?ta7=x|5BcTa|w|;m?@5OrwyF{h0v7-Q#lYOGp!lv zPvMw|LDV@N@zppcV!R;aA^s$ei5SQ8xrpC}V0)@zkFNvI^S}IfU0h^+fPDOS!0P#5^8c88@Ljo2|8jmsq`%WQrjV|P9j9iq znK^T#hGm23XOUk#WBL7|e3Jfts?Qwx99|9ew;Me8aUvo@@L1sz+RRP|9|>T z$zfteE^LbsJ_33a^ag0)8UDBQfqefqgqsa5a{y=j!&5}{NT-TzL;t8p4h-IYNjgf=J=2jt@-A7V(IYm zo8!r|nDgd%#$Bqqo8#GcYj@lnpL);mgEz(H^^M4zv16hIQ@QI;OpHN4p>aW`wgc4~ z2~X{4`6CC;U_H}6sOrJ5nSs-@1;$?KKc*x(S;wf){#cHDPEY5w)N}DM HW$ga|&|rCz literal 0 HcmV?d00001 diff --git a/boards/cuav/x25-super/firmware.prototype b/boards/cuav/x25-super/firmware.prototype new file mode 100644 index 0000000000..e48f2ec587 --- /dev/null +++ b/boards/cuav/x25-super/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 7003, + "magic": "PX4FWv1", + "description": "Firmware for the CUAVX25SUPER board", + "image": "", + "build_time": 0, + "summary": "CUAVX25SUPER", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/cuav/x25-super/init/rc.board_defaults b/boards/cuav/x25-super/init/rc.board_defaults new file mode 100644 index 0000000000..b7d9f53450 --- /dev/null +++ b/boards/cuav/x25-super/init/rc.board_defaults @@ -0,0 +1,40 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +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 + +param set-default SENS_EN_INA238 0 +param set-default SENS_EN_INA228 0 +param set-default SENS_EN_INA226 0 + +param set-default USB_MAV_MODE 5 + +param set-default UAVCAN_SUB_GPS 1 +param set-default UAVCAN_SUB_BAT 1 + +# Enable IMU thermal control +param set-default SENS_EN_THERMAL 1 +param set-default SENS_IMU_TEMP 45 +param set-default SENS_TEMP_ID 5963786 + +# CUAV core board IMU thermal control +param set-default CORE_IMU_TEMP 45 +param set-default CORE_TEMP_ID 3014698 +core_heater start + +# CUAV pwm voltage 3.3V/5V switch +pwm_voltage_apply start + +safety_button start + +# Update IP config if needed +netman update -i eth0 diff --git a/boards/cuav/x25-super/init/rc.board_sensors b/boards/cuav/x25-super/init/rc.board_sensors new file mode 100644 index 0000000000..8a748aed52 --- /dev/null +++ b/boards/cuav/x25-super/init/rc.board_sensors @@ -0,0 +1,65 @@ +#!/bin/sh +# +# CUAV X25-SUPER specific board sensors init +#------------------------------------------------------------------------------ +set HAVE_PM2 yes + +if mft query -q -k MFT -s MFT_PM2 -v 0 +then + set HAVE_PM2 no +fi + +board_adc start + +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 +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 +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 +fi + +sch16t -s -R 2 -b 1 start +iim42652 -s -b 2 -C 32768 start +iim42653 -s -b 5 -R 12 start + +rm3100 -s -b 4 start + +bmp581 -s -b 4 start +icp201xx -I -b 4 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 + +unset HAVE_PM2 diff --git a/boards/cuav/x25-super/nuttx-config/Kconfig b/boards/cuav/x25-super/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/cuav/x25-super/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/cuav/x25-super/nuttx-config/bootloader/defconfig b/boards/cuav/x25-super/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..28b9bfad94 --- /dev/null +++ b/boards/cuav/x25-super/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/cuav/x25-super/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743XI=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=0x004c +CONFIG_CDCACM_PRODUCTSTR="PX4 BL CUAV X25-SUPER" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3163 +CONFIG_CDCACM_VENDORSTR="CUAV" +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/cuav/x25-super/nuttx-config/include/board.h b/boards/cuav/x25-super/nuttx-config/include/board.h new file mode 100644 index 0000000000..ce57165a0f --- /dev/null +++ b/boards/cuav/x25-super/nuttx-config/include/board.h @@ -0,0 +1,565 @@ +/************************************************************************************ + * nuttx-configs/cuav_x25-super/include/board.h + * + * Copyright (C) 2016-2026 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_CUAV_X25_SUPER_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_CUAV_X25_SUPER_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 CUAV X25-SUPER 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) + +#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_50MHz)) + +#define GPIO_SPI1_MISO ADJ_SLEW_RATE(GPIO_SPI1_MISO_3) /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */ + +#define GPIO_SPI2_MISO ADJ_SLEW_RATE(GPIO_SPI2_MISO_3) /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_6 /* PI1 */ + +#define GPIO_SPI4_MISO ADJ_SLEW_RATE(GPIO_SPI4_MISO_1) /* PE13 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE14 */ +#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE12 */ + +#define GPIO_SPI5_MISO ADJ_SLEW_RATE(GPIO_SPI5_MISO_2) /* PH7 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */ +#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7 */ + +#define GPIO_SPI6_MISO ADJ_SLEW_RATE(GPIO_SPI6_MISO_2) /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK 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_CUAV_X25_SUPER_INCLUDE_BOARD_H */ diff --git a/boards/cuav/x25-super/nuttx-config/include/board_dma_map.h b/boards/cuav/x25-super/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..04051c4766 --- /dev/null +++ b/boards/cuav/x25-super/nuttx-config/include/board_dma_map.h @@ -0,0 +1,72 @@ +/**************************************************************************** + * + * Copyright (c) 2026 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 SCH16T */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 SCH16T */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 IIM42652 */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 IIM42652 */ + +#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +// 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_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* 1 DMA2:61 RM3100 */ +#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* 2 DMA2:62 RM3100 */ + +#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_1 /* 1 DMA2:61 IIM42653 */ +#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_1 /* 2 DMA2:62 IIM42653 */ + +#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 */ + +// 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/cuav/x25-super/nuttx-config/nsh/defconfig b/boards/cuav/x25-super/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..f08f8a5497 --- /dev/null +++ b/boards/cuav/x25-super/nuttx-config/nsh/defconfig @@ -0,0 +1,333 @@ +# +# 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/cuav/x25-super/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743XI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x004c +CONFIG_CDCACM_PRODUCTSTR="PX4 CUAV X25-SUPER" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3163 +CONFIG_CDCACM_VENDORSTR="CUAV" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0XC0A800FE +CONFIG_NETINIT_DRIPADDR=0XC0A800FE +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=6 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=6 +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=1024 +CONFIG_STM32H7_SPI4=y +CONFIG_STM32H7_SPI4_DMA=y +CONFIG_STM32H7_SPI4_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI5_DMA=y +CONFIG_STM32H7_SPI5_DMA_BUFFER=1024 +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_TIM8=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_RXDMA=y +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART1_TXDMA=y +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_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +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/cuav/x25-super/nuttx-config/scripts/bootloader_script.ld b/boards/cuav/x25-super/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..cbef5dc650 --- /dev/null +++ b/boards/cuav/x25-super/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2026 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The PX4 FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/cuav/x25-super/nuttx-config/scripts/script.ld b/boards/cuav/x25-super/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..50fb8f8553 --- /dev/null +++ b/boards/cuav/x25-super/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2026 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The PX4 FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +EXTERN(board_get_manifest) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/cuav/x25-super/pwm_voltage/CMakeLists.txt b/boards/cuav/x25-super/pwm_voltage/CMakeLists.txt new file mode 100644 index 0000000000..44796cbbe5 --- /dev/null +++ b/boards/cuav/x25-super/pwm_voltage/CMakeLists.txt @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2026 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. +# +############################################################################ + +px4_add_module( + MODULE modules__pwm_voltage_apply + MAIN pwm_voltage_apply + + SRCS + pwm_voltage.cpp + DEPENDS + px4_work_queue + ) diff --git a/boards/cuav/x25-super/pwm_voltage/parameters.c b/boards/cuav/x25-super/pwm_voltage/parameters.c new file mode 100644 index 0000000000..f8ebf15193 --- /dev/null +++ b/boards/cuav/x25-super/pwm_voltage/parameters.c @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * Copyright (c) 2026 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. + * + ****************************************************************************/ + +/** + * Control PWM output voltage + * + * @value 0 3.3V + * @value 1 5.0V + * + * @reboot_required true + * @group PWM Outputs + */ +PARAM_DEFINE_INT32(PWM_VOLT_SEL, 0); diff --git a/boards/cuav/x25-super/pwm_voltage/pwm_voltage.cpp b/boards/cuav/x25-super/pwm_voltage/pwm_voltage.cpp new file mode 100644 index 0000000000..5507de1965 --- /dev/null +++ b/boards/cuav/x25-super/pwm_voltage/pwm_voltage.cpp @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (c) 2026 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 + +#include "board_config.h" + +extern "C" int pwm_voltage_apply_main(int argc, char *argv[]) +{ + int32_t pwm_volt_sel = 0; + + param_get(param_find("PWM_VOLT_SEL"), &pwm_volt_sel); + + if (pwm_volt_sel != 0) { + PWM_5V_VOLT_SEL(true); + + } else { + PWM_5V_VOLT_SEL(false); + } + + return 0; +} diff --git a/boards/cuav/x25-super/src/CMakeLists.txt b/boards/cuav/x25-super/src/CMakeLists.txt new file mode 100644 index 0000000000..90734af2cb --- /dev/null +++ b/boards/cuav/x25-super/src/CMakeLists.txt @@ -0,0 +1,75 @@ +############################################################################ +# +# Copyright (c) 2026 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.c + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) +endif() diff --git a/boards/cuav/x25-super/src/board_config.h b/boards/cuav/x25-super/src/board_config.h new file mode 100644 index 0000000000..32933ef340 --- /dev/null +++ b/boards/cuav/x25-super/src/board_config.h @@ -0,0 +1,509 @@ +/**************************************************************************** + * + * Copyright (c) 2016-2026 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 + * + * CUAV X25-SUPER internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* 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 ***********************************************************************************/ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +# 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 + +/* CAN Silence Silent mode control */ + +#define GPIO_CAN1_SILENT_S0 /* PE2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN2) +#define GPIO_CAN2_SILENT_S1 /* PI8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN8) + +/* SPI */ + +#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define BOARD_MTD_NUM_EEPROM 1 /* MTD: imu_eeprom*/ + +#define GPIO_I2C4_DRDY1_ICP20100 /* 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, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC0 */ GPIO_ADC123_INP10, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +// TODO: PF3 ADC3 6V6 +/* 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_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_RSSI_IN_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13) +#define ADC_SERVO_VDD_SENSORS_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_V5_CHANNEL) | \ + (1 << ADC_RSSI_IN_CHANNEL) | \ + (1 << ADC_ADC3_3V3_CHANNEL) | \ + (1 << ADC_SERVO_VDD_SENSORS_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) + +#define BOARD_ADC_BRICK_VALID 1 + +/* 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 + +/* HEATER + * PWM in future + */ +// IMU BOARD HEATER +#define GPIO_HEATER_OUTPUT /* PB10 */ (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)) + +// CORE BOARD HEATER +#define GPIO_CORE_HEATER_OUTPUT /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#define CORE_HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_CORE_HEATER_OUTPUT, (on_true)) + +/* PE7 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 /* PE7 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN7) +#define GPIO_nARMED /* PE7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN7) +#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 16 + +/* PWM Power */ +#define GPIO_PWM_VOLT_SEL /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8) +#define PWM_5V_VOLT_SEL(on_true) px4_arch_gpiowrite(GPIO_PWM_VOLT_SEL, (on_true)) + +/* Power supply control and monitoring GPIOs */ + +#define GPIO_nPOWER_IN_A /* PJ1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN1) +#define GPIO_nPOWER_IN_B /* PJ2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PJ3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|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_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_5V_PERIPH_EN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_HIPOWER_EN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN10) +#define GPIO_VDD_PWM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_VDD_3V3_SENSORS1_EN /* PI11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN4) +#define GPIO_VDD_3V3_SENSORS3_EN /* PI4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN4) +#define GPIO_VDD_5V_RC_EN /* PJ5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTJ|GPIO_PIN5) + +/* Spare GPIO */ + +#define GPIO_PA10 /* PA10 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) +#define GPIO_PA15 /* PA15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN15) +#define BATT_VOLTAGE_SENS /* PB0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0) +#define SPI3_MOSI /* PB2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN2) +#define BATT_CURRENT_SENS /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0) +#define SPI3_SCK /* PC10 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN10) +#define SPI3_MISO /* PC11 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN11) +#define GPIO_ADC_6V6 /* PF3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTF|GPIO_PIN3) +#define GPIO_PG2 /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_PI9 /* PI9 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTI|GPIO_PIN9) +#define GPIO_PI12 /* PI12 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTI|GPIO_PIN12) +#define GPIO_PI13 /* PI13 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTI|GPIO_PIN13) +#define GPIO_PI14 /* PI14 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTI|GPIO_PIN14) +#define GPIO_PI15 /* PI15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTI|GPIO_PIN15) +#define GPIO_PJ7 /* PJ7 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN7) +#define GPIO_PJ8 /* PJ8 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN8) +#define GPIO_PJ10 /* PJ10 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN10) +#define GPIO_PJ13 /* PJ13 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN13) +#define GPIO_PJ14 /* PJ14 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN14) +#define GPIO_PJ15 /* PJ15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN15) +#define GPIO_PK0 /* PK0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTK|GPIO_PIN0) +#define GPIO_PK1 /* PK1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTK|GPIO_PIN1) +#define GPIO_PK2 /* PK2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTK|GPIO_PIN2) +#define GPIO_PK3 /* PK3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTK|GPIO_PIN3) +#define GPIO_PK4 /* PK4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTK|GPIO_PIN4) +#define GPIO_PK5 /* PK5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTK|GPIO_PIN5) +#define GPIO_PK6 /* PK6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTK|GPIO_PIN6) +#define GPIO_PK7 /* PK7 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTK|GPIO_PIN7) + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15) + +/* Define True logic Power Control in arch agnostic form */ +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_EN, (on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_EN, (on_true)) +#define VDD_PWM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_PWM_POWER_EN, (on_true)) +#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)) +#define VDD_3V3_SENSORS1_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS1_EN, (on_true)) +#define VDD_3V3_SENSORS3_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS3_EN, (on_true)) +#define VDD_5V_RC_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_RC_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 3 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 3 */ + +#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PC6 T8C1 */ GPIO_TIM3_CH1IN_3 + +/* RC Serial port */ + +#define RC_SERIAL_PORT "/dev/ttyS5" +#define RC_SERIAL_SINGLEWIRE + +/* 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_PORTC|GPIO_PIN6) +#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)) + +// /* RSSI_IN */ +#define GPIO_RSSI_IN /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0) + +#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 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_CAN2_SILENT_S1, \ + GPIO_HEATER_OUTPUT, \ + GPIO_CORE_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_nPOWER_IN_C, \ + GPIO_VDD_5V_PERIPH_EN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_EN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_PWM_POWER_EN, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_VDD_3V3_SENSORS3_EN, \ + GPIO_VDD_3V3_SENSORS1_EN, \ + GPIO_VDD_5V_RC_EN, \ + GPIO_ETH_POWER_EN, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_nARMED_INIT, \ + GPIO_PWM_VOLT_SEL, \ + GPIO_PA10, \ + GPIO_PA15, \ + BATT_VOLTAGE_SENS, \ + SPI3_MOSI, \ + BATT_CURRENT_SENS, \ + SPI3_SCK, \ + SPI3_MISO, \ + GPIO_ADC_6V6, \ + GPIO_PG2, \ + GPIO_PI9, \ + GPIO_PI12, \ + GPIO_PI13, \ + GPIO_PI14, \ + GPIO_PI15, \ + GPIO_PJ7, \ + GPIO_PJ8, \ + GPIO_PJ10, \ + GPIO_PJ13, \ + GPIO_PJ14, \ + GPIO_PJ15, \ + GPIO_PK0, \ + GPIO_PK1, \ + GPIO_PK2, \ + GPIO_PK3, \ + GPIO_PK4, \ + GPIO_PK5, \ + GPIO_PK6, \ + GPIO_PK7, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_I2C_BUS_MTD 4 + + +#define BOARD_NUM_IO_TIMERS 5 +#define BOARD_SPI_BUS_MAX_BUS_ITEMS 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/cuav/x25-super/src/bootloader_main.c b/boards/cuav/x25-super/src/bootloader_main.c new file mode 100644 index 0000000000..d61cbe306c --- /dev/null +++ b/boards/cuav/x25-super/src/bootloader_main.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2019-2026 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/cuav/x25-super/src/can.c b/boards/cuav/x25-super/src/can.c new file mode 100644 index 0000000000..40b6c68692 --- /dev/null +++ b/boards/cuav/x25-super/src/can.c @@ -0,0 +1,123 @@ +/**************************************************************************** + * + * Copyright (C) 2026 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 x25-super_can.c + * + * Board-specific CAN functions. + */ + +#ifdef CONFIG_CAN + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * 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/cuav/x25-super/src/hw_config.h b/boards/cuav/x25-super/src/hw_config.h new file mode 100644 index 0000000000..ba1f8684b8 --- /dev/null +++ b/boards/cuav/x25-super/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 7003 +#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/cuav/x25-super/src/i2c.cpp b/boards/cuav/x25-super/src/i2c.cpp new file mode 100644 index 0000000000..1d363cfe27 --- /dev/null +++ b/boards/cuav/x25-super/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * Copyright (C) 2026 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/cuav/x25-super/src/init.c b/boards/cuav/x25-super/src/init.c new file mode 100644 index 0000000000..96a6386fd6 --- /dev/null +++ b/boards/cuav/x25-super/src/init.c @@ -0,0 +1,277 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2026 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * PX4FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + VDD_3V3_SENSORS1_EN(false); + VDD_3V3_SENSORS3_EN(false); + + board_control_spi_sensors_power(false, 0xffff); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + board_control_spi_sensors_power(true, 0xffff); + VDD_5V_PERIPH_EN(true); + VDD_3V3_SENSORS1_EN(true); + VDD_3V3_SENSORS3_EN(true); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + if (status >= 0) { + up_mdelay(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. + * + ************************************************************************************/ + +__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_PWM_POWER_EN(true); + VDD_3V3_SENSORS1_EN(true); + VDD_3V3_SENSORS3_EN(true); + VDD_5V_RC_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(); + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +# if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +# endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +# ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +# endif /* CONFIG_MMCSD */ + +#endif /* !defined(BOOTLOADER) */ + + return OK; +} diff --git a/boards/cuav/x25-super/src/led.c b/boards/cuav/x25-super/src/led.c new file mode 100644 index 0000000000..4e468eeae3 --- /dev/null +++ b/boards/cuav/x25-super/src/led.c @@ -0,0 +1,236 @@ +/**************************************************************************** + * + * Copyright (c) 2026 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 fmu_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 + GPIO_nSAFETY_SWITCH_LED_OUT, // 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/cuav/x25-super/src/mtd.cpp b/boards/cuav/x25-super/src/mtd.cpp new file mode 100644 index 0000000000..cf072058c9 --- /dev/null +++ b/boards/cuav/x25-super/src/mtd.cpp @@ -0,0 +1,102 @@ +/**************************************************************************** + * + * Copyright (C) 2026 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 = { // FM25V05A on FMUM native: 64K X 8, emulated as (1024 Blocks of 64) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +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 = (65536 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) + } + }, +}; + +static const px4_mtd_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 2, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 2, + .entries = { + &fmum_fram, + &imu_eeprom + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mtd_mft, + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/cuav/x25-super/src/sdio.c b/boards/cuav/x25-super/src/sdio.c new file mode 100644 index 0000000000..3c295fdf95 --- /dev/null +++ b/boards/cuav/x25-super/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2026 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/cuav/x25-super/src/spi.cpp b/boards/cuav/x25-super/src/spi.cpp new file mode 100644 index 0000000000..ac6a278f0e --- /dev/null +++ b/boards/cuav/x25-super/src/spi.cpp @@ -0,0 +1,58 @@ +/**************************************************************************** + * + * Copyright (C) 2020, 2026 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_SCH16T, SPI::CS{GPIO::PortJ, GPIO::Pin11}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortG, GPIO::Pin3}), + }, {GPIO::PortI, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI4, { + initSPIDevice(DRV_MAG_DEVTYPE_RM3100, SPI::CS{GPIO::PortH, GPIO::Pin15}, SPI::DRDY{GPIO::PortG, GPIO::Pin1}), + initSPIDevice(DRV_BARO_DEVTYPE_BMP581, SPI::CS{GPIO::PortJ, GPIO::Pin6}, SPI::DRDY{GPIO::PortJ, GPIO::Pin0}), + }, {GPIO::PortJ, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortJ, GPIO::Pin12}, SPI::DRDY{GPIO::PortG, GPIO::Pin6}), + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/cuav/x25-super/src/timer_config.cpp b/boards/cuav/x25-super/src/timer_config.cpp new file mode 100644 index 0000000000..aa9e2c073e --- /dev/null +++ b/boards/cuav/x25-super/src/timer_config.cpp @@ -0,0 +1,90 @@ +/**************************************************************************** + * + * Copyright (C) 2026 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 PI0 + * TIM5_CH3 T FMU_CH2 PH12 + * TIM5_CH2 T FMU_CH3 PH11 + * TIM5_CH1 T FMU_CH4 PH10 + * TIM4_CH2 T FMU_CH5 PD13 + * TIM4_CH3 T FMU_CH6 PD14 + * TIM4_CH1 T FMU_CH7 PD12 + * TIM4_CH4 T FMU_CH8 PD15 + * + * + * TIM1_CH2 T FMU_CAP1 < Capture PE11 + * TIM1_CH1 T FMU_CAP2 < Capture PE9 + * TIM1_CH3 T FMU_CAP3 < Capture PJ9 + * TIM8_CH2 T FMU_CAP4 < Capture PI6 + * TIM8_CH3 T FMU_CAP5 < Capture PI7 + * TIM8_CH1 T FMU_CAP6 < Capture PI5 + * TIM12_CH1 T FMU_CAP7 < Capture PH6 + * TIM12_CH2 T FMU_CAP8 < Capture PH9 + * + * + * 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::Timer1), + initIOTimer(Timer::Timer8), + initIOTimer(Timer::Timer12), +}; + +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::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortJ, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}), + initIOTimerChannelCapture(io_timers, {Timer::Timer8, Timer::Channel3}, {GPIO::PortI, GPIO::Pin7}), + initIOTimerChannelCapture(io_timers, {Timer::Timer8, Timer::Channel1}, {GPIO::PortI, GPIO::Pin5}), + initIOTimerChannelCapture(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannelCapture(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/cuav/x25-super/src/usb.c b/boards/cuav/x25-super/src/usb.c new file mode 100644 index 0000000000..0a6e88c6b9 --- /dev/null +++ b/boards/cuav/x25-super/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2026 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu_usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/docs/assets/flight_controller/cuav_x25-super/x25-super.png b/docs/assets/flight_controller/cuav_x25-super/x25-super.png new file mode 100644 index 0000000000000000000000000000000000000000..70d518cdb1a2ff5d980c628ef5002a80adcef744 GIT binary patch literal 100165 zcmV(?K-a&CP)V;NjymH#tE= zMLIn{G&VRvL`Uf9>ekrVFEKPlNJ`k++b%FNEG{uaMoBq3JL~N2D=jb7*4R8fKD@ue zL`6rlx4N~sywcRxM@dY<#K$TuF1WnEzrw{RDlE3TzPi1^ud}zl!Nh=tim|o1KtMvy z(9+P-)Z5j_!^X)cC@Ot|huhrTB_=4Vue0&;@_T@Vt+BO(hm73U%gfHt+SJC_(!{2z zt=rMQp{1$r?(ZomCZwmU{QUe#OHLvqB-hZv+tb6z%+AHd#mvmila`u>ijTv?!^g+R zm6)8kwzG+ik;%!)mztiatgy$*%%7vCEGsCGl$f@(ue`gtcYA-dv8zf=P@SQqsivZ4 zYHl<$FpiRyO;A&tpQB`FYrwy~u&bkskCVc}!8bKBYj1Pj*v!|@yv4}Nba;FwB_kXh z9C>|$aCCU8t+3S0yQ!s})y}`p&(E){r=_Bu9v>khA|T$^$S*D{t*D?eFfJGw8LX+L zpq!M{)z!ejz`MD%Jv=)O4h~RLRumKzK|eaay}Ds#XtJ-U(bCdsZE(H4y_lS#-`2!m zVrJLOx2B<(xVX4oU}M|Ry7>6`)XB1MadfY)t6E)PvazqCpPE=(UYnhtQ&w43SXc8rLD&d0f^nR-`LPI75i zo{)60q=}M)XseWJXL)aLhI9og1RpjR4NV6fVFEB#9yvuUc|(SH00D#mNkllHx~#0QI^V$Bsnl%NrWzzrB5`UkWR zK7?Nt%}BA!%IYmDbABVaP-922E-S0IC4Z&Tqfnf+KJ&Y*tlo;;%P|#* zi-BothgNSx#g#WbOfry?Oev9mGiuSY`oHp%g^pB8D_{!lN^`}>zD`&_wEABvzNq(0 zCYfReEJRH4-mhkC(6ag;N*-NEW^iKWVAygtaO8AZS^YQppEjN-#W2Al7i7p7!x^ph z?I+d_t^Skzg&W|BGlf|@VTA{dU?4>AxwS*9f3IRVm9Krd8S zb%3tqDtB$*iw>`iSQFv5+j(X`~2Oxur3t^Q2z&anh+&;e=jhfr~Bl~$s&R(}4X7KXCG z90@wX1x^We@ygnv)$f&@?FmDbG+{_$tkT8~r)Flx8y-vxpot&I`9O34!9EB(_Dz#AMNtc>Sx6Y?Kl!;+|MutSNM$| z-T)dZ!JAJUxW<`-(#s~y2r@#LgI4h7H`WiWj6Pf(Bd8S9l7&(v7OoAA^_hScnBnzm zuJQ!;*IE^P-Q=F1?p%;Q+28&sRwOa4R+0htIX`Cgl0HXTLBG>t;rGjz_$I}!-p+D6N$RU?m~{R32$!5m78&6 zeVH&^jh`^?X$nOqM6pmZB`a&2t(%v(Z%Vz$3c~XL24#wU>a|zuqCN0xFG(x z(8nKJJAAY{^5pSa2&r@eGqP<|C|3X&aCj@~}6 zE>@@Nl&uq2$QP~+P03wTl~iaQ&?ZDPH(uw87$XQh^hK|C*H%j(s{9PWLn{ZUL!ML`D-QHr z17RF)rlJ+#BnUYrQu|Z8>uHX2M4eL5P|o%3XExJ%i1LfkWHgLZc=b)Lt>s5vZ_LfD z%+JrQ%+0+X$-bCNx*&K?O{_bXyM6Zlvv&oW9AlcSkhlu}{s+=_GAj`uTI-?SxjkkC zjMm}uPY8{8vGz{65r-~vDEJ+D7j}900Od!Mu{$Z%#${>qa&u; z?qxnZ8g+k>6M1>{{`=27p+F|Nl5q-ECN@cC%2+U@1dF28`cmzvCNK)&nDC+^!+NW- z{Cw*|amw380G6iZBld-A{$PXF15+^>b3+%TOlo6se{rv{R4)}KSLTODR~F9qmM`+Q=nsG5;MWcAdHjd&Lu!tp$S`tKoiyCw1gcs1m0Gggoqqk8_A5el0KVvx3yua`~ zJG1|U7KR*w1G4CjL<)i{-Tz&r%jy9Mva7I8Wfp}`Ypwn5MssN_05NIAe2w6VVOv1cq!DgukP1sV3^2o*iUX|B-v7Ry&mR93fVdlVX=3Nk3gI+HV# z<81}A8jX)DqDcvlb08L4EYG;MDLe_y` zg(oT&bCL@ct_dD4O_VYqnZG8ZfGwoVL^LJ#vxNpb897th?A<`Ckslr3o0vL<2^iz7 zSrYt$PF=+Oee<3S!R$po!MMCo2!TGT7T-JBXIfwEql;b3wWHOd~wLcWtpTbsB z8B4>V%qI>SX;Bx|?B@Q~Y;QY7aY(@|ZR3RHP>rVvRvK_qqW`Phd0XHJXJLvAv46)d z5AVDDOww`hK$U@WWqG+$e;U+GBawyb&f!Slirvelayj9GLa<`7B-r6-^_J|;{CX-h zER+gwTCsz(qekaKDq0C5R3NR0GSj7^1I^=N@OCq|c!0Ku5{5kVL)o(b*y4W6k42*4 z&az7vX<_TAf4WFMm>3;?nk|)RE#N~TH^dt*SLnJ{jNFv7d2 z<8f<;_f)VLj6$&bRo;##dSM?d{|rXaol?D3sWlpn+M;ovM5#K`?Ph*S-tmeh9A|uL zx}Pg9nycB|RBpDHQc`PGx-m=2L~bNQRMQ-Ck2V8#kY2Oc>m-_BTn#*)m^!$?wQMBNU**HvNoHy zotySat>zf_oZgw}GcFip?*J7YbA`jgQe|(y2l3GCWM}c19FQ9HKgl#VPKQwpbu)3< z>S2{qhocGN130j+mZr1${bxiG*``?!rfC8jl6QPKX#MbhDbqLX-2KQ3MnsjNYw&sa zZ*JU~*^{N6{M5J^Zfs4A5>g0PSR#e&-Ejujs?}<#qbOklhStwEYZ$8(92(Ey?~TGu z3z%p(*X8MQefy>}ghmJ_RUC*Q(bH+)B0eEfoIvUv2ScGuG7r0l)(?MT@7h{gxuS5B z%;-!UlZ=_@=tQ)%NA1m8iy{_}Cln+iK9nj1Nh$$}gj_%n8aU}g|3V%DZ3xtd60rIU z3a1qM)L+%L*0*;i>HXe5!FvDVt(T6^+;!u-Oz11f1?24)f0VlVHk9K&Y4 zlv+>BYoFunKiRbrUd?msa8k!kk(A{`PkN2(iwq~EQS+DX_i7dSaD)0Lq@{{xc#nZ<*%LK0o*6yFm!Y&dSOr)i03|+y8+D=uex0}61i@<7^urZJfqP+fk zb8`0ZzsFMwpGb%L8Gv4zS3G$6^6<93U2a_W&T{SQRenLI2&HwTu^B0cnf3BJZ>(({ zw6xg73Idg1wToB8A0?I=aeTJO;}vFz2fAeSZHaQ`e?0`Z}b}Z(%Ngu`OsVe4*gM1hhQ_Y z?1eo#C%D%3*+a=LFMivx%+7Z2vovRUaDaj>7K)U0c_{VNHV4+1jY6qBhm@c^5%x6K z_)~50iKY*FX&33jv<30cKA#w^{}NAAyE_Rc5iZF;V+1Z?fLjUiEGXCx*ap2_*(>c1 zZ9u%?$8Wsz+8eil`X65@pYa#Br|x^XWr@4+!5QfAWV4ukY<;+oA053|Y_v8y6rlUq z8#2h*HQ#>iwYN`wORZqjs1+@bItj~`bCXZg{AU2KRK$La&7h10I;Rt(A>Cr1c*K-%(@|K|@8t-20cX$9=xkz6JzRv>@#^8JFuT0$Ge}t#@uJ}Q1kf<9~+>iAl zOjc;2(8cH>TplWSa7Oy9VA*5(t0hUsyv zCBeK;ogDIVjpxs<+xNYVcERu@BM2ub1_}Nz(7bZZz~}Mm!%3a#@kajg>^^SIp1*Lb17#&BJ!`cfp%-vBsg-mBb!fk#=}HX>4I+J0e7dW|i%mf$KpcC2%X59N}2KYry$Ip7JwSb1JBkwUBIqKYjk}yn~5&N>_X) zESlS&WDoyEK)%|IYNcJVXULz>Y=wvDWBeBPSQ?tEuoF@-yHbQGUC}5Hc)I?q*W0g~ ze&*qha?HN(Z8yoGr9W$I&q(F5-1xSwCxyzsDmzA*pJxrux|L>y7m!Ls4VLe_oqqrF zpc)S#G(gGUSE9yq6rx)~W5;vCgE3SSY)cs$AFuZs7+ zt7QjB5VN@_o10r555bo2sWZ}&3~~d+{ciWei97t4@YLA_ue2hHCJd*r&IFPcL{ssV za1D&2MKH|aPBbh?4a6`-s~CtCv)500z31`3r^x7}e0X_PIy5pwhSt_+QnVnB&^1gB z)TQc=i*1zA3Z5Sgrmo^9Gn4HQ6b44+gem|(iSujtl8Eo~1C{KN6?%E*w3&3`8 zUFDs}#7`N3V4{Ue2Y^-RP=%}$IRMhn+F-#U(k0H2kV-fUTa*fVG=i*gayON`ezZ=@ z{kWBVXzXXiv~X&gduo{+*x_+z(D1tl`4>|gmtRWW5f7n<#=qTK+iDNxQNGdP4UKH` z!wI$iaXejFB3{`-p)gr926-mNDU86vxLq10Wl1kHJLU*%AWAp$Dw?pP5&ohU^?Rj8 zp|xnOE^gnnrZTPiZSR2;sk!Hc>NG-jkAQ@Z$^p@6`ODkEL$BJpnHF>8a|6x(8DZV+XD z)F@&Rqf*SPXe3I@ORrq^&iiiGJ?-}6pXIk7y-YLX$M0{-cgPSjzd$OkJC**l_T>Dw zc$luwNX!+m%Ah3&iP%((&%LY%r{_<;jVt5D5aD#Tx;Zgg{~WL#+)2j5V>loeZkQv? z;0@6!#8%(~A&LU~esV5G=|Ti;Ptwf*qn0-92a&o-e+>y1akUd!BjREzM#mV;Y z9|NixxJ+i~??MALQi_H6TqO!YAT2*=-5uSC(!k`BqpIu+MJK#8WBttu|&yoU%eS9`j|ePVBKU=1xzk##FY7n z)zi7ROLZ09D}mK>RajP;WDox-JdM(Jka%^h!~~&NOhzlxGLD5<^ahzAcs?KoAoya0 z#M0KvMmEQe!dltUC|j)e65P_76Nx(ZYnQ#^t(y(fxlVA^n`@tJJrGM~E=mJb1iGSV zS)y!tocm(}v1=S!tL4kHSwA2yW$7Q%tz&h6_4S#;o970x5ZOhodtpq%S!4dC34p&l zY)2aBIJ8fo6D*bD3uvatVW_nN(_^v6>uO?>?fxkJtg3JKzN{3Qt(5XQTyn>lhy_QEqUU84Y1{sUgASq}N zORMit;3E-UAf9ogwRhAjSLd?9t?|b>pzuoUtHjam%;%Y2XDn>Goac zrqsSKFNV5;jQlngYQ6Ji;3E(-1+IxVXdqnm>xD`75cqq;t0iYeFun7S6BPR$K2td-p@S{9qwzh0 z6LDu4a)bqBt;|v5@V?q=-x*+3i2lKwuYH1~p{|{g;w%(=(E=*A?k3s8zZJ(x3a_F% zVn=#eb13wJJRI2}j`Av0upE`bp^jTkE}<56?C!uT&`C^{6QN;*n8mG~ihOk0E4OE| z+3AhJO(qDe7cGO>ka>Q6>moKH;Osq24!*LMxu3SK_HTPHrqaX|&zFN>d@+pE!C*re zg@{Up?`hMAD`cMWgG_F+J^b77be`PcZffL+L~NK{#@=tl9fl9}i9r>2Ip7&{35>$X z2|Xd~l}&$AHIs;>IBJ)kY!~9JNQB#$pY@8lN;b%L&g!eH%f+rR!szD<%ghPX{0Sj& z@#1Xl-TZYUzj)fEIe}LNet?lmO`9G+#{tCllh2r{`ai_QsBU-iv-p2oa&Vn_r7|}R z?eTQE0uON05Hq%EF^pp{Y1;MiK-{FQNdM8Kt&C(Y$F`R=jp_Pq`YDE9(#Uu_)>jW@-nW!TG6T5OUgM3L5_|CY6JdRlAL9xBB)(I=>0wx{s@B7Eb|m)3&5 z-p_X_Rsyl0U>Qc>6Hq*=fr)$f6_vMgjCAV+S{k6%&7@3znG8vOuyLwcw=<)^F9 zukxkaG)O3h%ICmM|MUfU$>tZ6?cra*N@SOlgY%=+40`_;`-~++n2hIz+B06HB~fBFZ7x-evKoYP{}tDyHQN235mae16#^8bIEJ>>!Sj z*(Am8o@Adl9=fg7yNel3ClHIB;Q1yMYTfJa)u3_ZbEojK9HK3LKiMAsX~=FcimjlQ zJ#`ya@`;JkD_Unze?JmL6&&sUptoxs3%O?{zH_Y36pFIJ0ulrsQ{W60!6li{Uw*nXe|< z!#{!J6q&1JSQVqmd^wxU$U6{{3U4(>;0& ztRSnblGYt~C2Oey310Tt3%U>YQjkNph1)V;OwJzu$&x;pD!DP#{!PbNVH7`vdPVz1 zP%#u50EFxev?%gJFN!p8gsRD42_R}|;?-oy9Oe=mo zT$~N!$Q*k3Hi&NMVg3A|xP8{L;^v4_>V;LxepsfgWQOUhwZ<|&Es3gnzO2gR?BO57 zN_3q{WE_3QIW{7Q0_b%Z4>rjZbaF;))OeLUH1~O-6hSd7*(c~gFu{xR% zu_49mB43D*p8h^6^$J%V@3B@Z4_vkLGyQmzzK-j8idQ3=fe2W4xprla2G}F=?FZ1b z6nvE(!oTY_UO8Mwj3pIcfJG0!p7_H*ki%hf<%Fjt#%vR;)=KCQ!*zlR=6?Y?odb@c zpn)&h4q}uNke|~>z}WB6fX&omU$XFiFwM2?Z=b!ul{LC%H2v#9XcfV;Dhxbxq@L^0WBA_qz=5uiGooI~nK{qx7P#H4ZffXEY)o-3ub| zJfszdj>p@ggp&K8wJ0VJ7l>* zR8eGggiSn5YV(z(M{iyi=xgx4&(;X$CcWKDGkvsyLO2csrHW&GJYBr#&o)cl<;z9* zK$X6x$DOx7{`lh-%kDxeeh7mFU&t-}lm6uF;crD($(`LLd+f9z2ow%@DD!Yd1LHAc z^;22Lr~6AVzEx^?lgCPcXKsEv2;f$zb;<D_Ft@eL;2_Q-UNOBGtYwk0ayYXi#G;vI6?wz=B1=Ro7_CHvjn>O+#k1VKwVDko zwaWojF2Fj4Uq+T0+!-VWdZo2l%$+=`OxHOAlVvSw>BBwXqVUQT+-}uoiDEMKl&G~a z$sYbZjw8Dyi4LRlm9cXWBNJ(HLBj$t7%f89aeV0b@OwEjp$={k^x_sy&=LJgCZsgz z>SQLA7%yxEqujg)T1BWOh!SB(=*u+a+*PZV-=8LPr1WzMv3N#PeXvVuSG;(C(q6us zvoykA9xy>Gm1%_MGd;`S-@B}sh`YoqBHLqBCI_Z}Hsk#MdP>Xd;0(<`6zX_2EJQ}U z4q}04aDzHncg8#*0UbBo&nq_=?h0wdA9&Y)QCW>5DNQy@GKNu`B~l65lS>J1mdI*R zyRei@a74cpA;YzEQY;iN?$QB*C8>N5PY-&&?E18*UK}Hq^KtE%U{CS7G7~$MN(y!HGd2Hf+ZY5rk39wFOfcz8fIIF{5gf8NbXbua>B$=%w!gvn0FrYH6i$UBEa2gf- zzz6@_FvOzXLQ74Mp2lfHGGW5HO6%&upn=W-DQ3xs96o#Jo#&Qi7?y`)*GwzZ-~lo3 z#itXaHTE;%>%14#{tuD@TAlO@xrHlao$5ooCGTkrt<=a2K|4XK4k@1KT#m?C(%DhA zR5E0v72!||`N9;ohQulIhfuSYXt4Aib1S-2DwbOncj(r@A#Zki%4IQvrU2Fj+E@kh zPp03fwo17v4`L|WJ=i?2-fWiNDAawEfc>B+lwuezt7Vn1CfUQVOmty4X@gY&1S~Kt zB-Xf!Fixy-jIZilAX+7jLSN9aJA;{|#Rfp~(NRGnK{o+07LZs%&<=@oAt_i`;s>u> zpPke8kfG8v?&IP4`T2I&P?5MPj}*7YGlX~T%=z|q^Q4chq|O&obNB4ykM~+>W|Aoe z%fK(^yW$U7fFRq||9avNm2|b9bjG}3SZbw-6$%dHCJKP}!!y9aIy83zR=_T`X6w!t zE^(UzWP-3=wV)J@p<=-olCCAnDEmX!;^{)X#Sh;qSxU--I~fBeHjG!P!ZBQ>c_uy zD$xyAyQOYvdnTj4jTGQiG=9%#|LwIGv<@yoXCQDR5j^pVW|Qopob6hVGN-^KUA&-Y zYJ{=o%a4>S>KzO;n?kiTEI~#iu1`XBUFr@CMQa?H({c(7qlP)fYoxg2>mVs7%J%99 z@~*9=(e4U2nItCB9GvLHi6b+?YP4FTk%TnUn1n!xgejy=+7NOe5EO|KQUs;Zi$bpo zEz|+26`@{;;OJ#-VFUwUC&y3XKN4Fotdt@?>@bmkFTBQd)C^|TKf%zEI9{; zo|I7n7~(B-L0=HSqP394pJ;ceZU)Kd@7)&~bA&L|jXKZM1KKg_Ghd>=3#p;mX=ZbK z%^P?90AHA-B@X%NqM7KVU?<#8n}XGJcMiWPOt3=Bzp^s+|NX-jTQ5Qpi(~_}>*LI_ zafin1JuO(!OXg$*HhTgl)9RWA7giWaSaA8VCu7g|Nevf}bur~#VZ z0%ed%;qH8>YG6bWR{>mLD#Y@^P>>?6x8BftqlN-4=S{QAZ!EIk9#Zt~9@NfM?Tj41 zSG8Dnh^6jWy4q{D`5Ans&=m@D7+R9h7VXMSpn~^%$hPV>U<$iJd;mP>^)LT#p|$kng20w2^2>!rrMq-jyq%@;1?O3+RJF}a%}(uAj+dCTX2Dhr zGLa@wmHbdYaRe}N>c;6l%;oAgV|;dBDxDc^ybE+3ua(XLCLoJQi;VH+oUZ(TW)HU~ zEIzM^*`K@@#)RU=47Q#=W9S$K3)s=C=B*6cgvDfmA*IV?=#yv;N_hqpOvUrEAw1MLZejI1E_n7&P{^((P@agtuMHg+=DiygZ64oTqJNmUMYvf79b z$}3LqO*<9LRPgn#{V=(oOSyq6smWqx48I+G)nBeIahPR83sl)Kqb~*a7XJT8i?)J3 z*W-Mk$;8OOm^nOeDxc&%hCrDu!ewl}YuYsCC!XGK@IT zlSUQ9EI}5`i!rDxB&ld>n63aTbR=pKy2^!4rLq5NcJ{oxG<&(1tG>Itn4R_9UG|n3 zS$3u^{?PbQ(an_J4Bpn4QjN2j+Xhh<-UiR20zY&+a`PJp4k0TRAJ9l7k8bI+<^PMc zwqE-}nyf}Bdg|p2m`rIE%zPWqjk{Ef8cmEKj-xPW9YAJ7s@0y}5fbongo5 z9MA0DsZ1ajyQ4svdZ+o}6A>ir)0dh4!$H5y3y}J@^eOLmNfGC?A*g}uY z4>e@&oj?8`3GrL6EkV~vN>^t9xi_)6dWea>=pIpKDZPtmJ{GsTt!7jUO}= zX24{?#Y22Fq+aN<7_B+zx$dE|yYy@OmItX=ECt3&#hO7cJ3(q$Yext#{3UO0V9`ok zAupKXEC4GAU_s6b0#{^M@3 z3m~)a)PD1=M_StyGy^}%2O1>l&I}A`DR#o#m`T%&@b$EoeUu=?NK5RxOonmA7u_3` zSPHlz#>%B5BSax;=S-ni9i-$Pz(N?$GZC`5&_PocP{iRoBZ@f-?$DChY;QXw{aBE}?j z)>$|Z(E+68cJt`!+dg}^jlXBjRmS1{M_m02Giew3uP5VSdTh!UV3J{$nW^MMBT>8l z$+%#tnj%aM0j$Q6g|~w+3DvPFWbGZjqASrJ&|?bYP#!uKg9;5Rq-e!33oh^0ddJgm zNY85De(%jpw?A`t@0@j?H!^`YN)MeytBlV)-&bmP4-Yf^JLG6URiHM+Sn3TlENF=o zPpoyGZKdWwR4_L#Ca>ww->jy!wT-x0OQ7g9t|URI@uJsEMKK1Wl2GpS8D=%p-VdXZ zlqJ;*V&En=UPC(pSYenP!~|EFR4g4*1SLP8qeuy_;>KJbAe2>(>qWrw@=+Z$Z&}GA zqXsoJ1diLn0X(ECOn3T~v z-5OYrNeeg>C<**bNG@N}x~Bmgs`y~q{ehzRa2JNSfGceMvbhv+g#fF*;pIg?I#bs*a1zr-u zGTv~M4#XgxBBCNMNS{s~i5gQ%4DZUvaoad?Hs=MAY6 zhfok7xrDTUtwgcY$-Jbz%^PQ_e$a>&hjzSLYkzm}QUop1Me*`JsbofynHtgGC7>Vc z*Qa0YEo1`fxgBi9@4bDwf4x?2IGCz{Cif(UxG^Sno4Ia%W6+}H4P>jQAVOzMxkod8 z8ff98=Z3J%Q#Q?9%vUa1*P%KFBk2kawZ4ceQmAGSxyJ@+pFT)vp(l%jSPW|EX@bKk z;U#=5@*Xx`^Kz%<2Ha|EDB+bris&lLkvw5ObO!jW1SiBpEP#2p$yVT_qy0Si~F zUs?29lb4xHELJMZON-?6M7&KbCfmf$qK_qaD(4e&BC{y4fv-l$3h{YpaS5w!AC+E(|yFu@Y>)qwFnEven0vUiso(`*f z%cZX4tXg#=Zf8WHMSSIKMiPYE5|#_Ee9{XSdp(ZV3b zph8F=i(Mw*2Z10MNAo}wf76haS4xyaUOp2o#SJQF7=(qD(TJ84`PI#T{H1;Q`Qq-m z`|#v`>0@SW#&J`OjdKk%fMkc+05CNp1UZ~z3$=P>-?3xo1;p*RK~whI=6v%?h3s~> z8&Ma{=#dbYk|W$p-^%uI+h={MOd0gNvR z1hA1k1656^!_F2WrBn>CnQ$fYUcU$n0A08r6I7)%X&uo6Ia81LOC$$wtmZ8aaOg_o^rhM>^on#ZEagD`hYy+;;9bGD8mC`Ey0XI8Lt?LRHjNT z1(XbXx%5Mm)G^?~jg|+h=s3#QiIEX&?S}j=3CIapt2uh0JRw;Icei_);JPbvpvWCE z#Du_Tq+ge1!A=lUz)5z7xNvJ=p-0PIB#|H*$L0Bd7NP{ z$`KQNT5Ujymt&VbAui&qR3^6>wkik6WCbTExk7E?17&9@Dk*L;11rWACiF=FTxdXA z3%#4ESFqz?bSDaXpq8@C00mvGgt$!cEYU1R*z% z{hn6hg{tJD8*4|sGpcr|9NToo)fCedI*N@1HB-2!oHS7tqc4xI&jZfWVeZz(E0TN$ zDFqx$e_cI22ne9?0jg9O58Pe<S6;LZVjyDHiV~xE@=cp z(&;JY8dj_&V93XAFbuBeQi!t{TCv`mYl5&A1E`SR*)5a29@?z3SES|Pa9CgTd5v7k z#@T1UOUMcrHibUk6zT+Y7)_8c6yzPD0E34kqScEB_ zfNanMLT(y6J%_z^*XGPF98XV)%Ajqpbh;UD?067Y!3lEcj&IOd9lMzOI=6?fQO^GK z*G2>_23AJ#)C6X5gaNm5k(oxG>DK7%rdSlGy98nAgs-Rtu8xweqgFXcPrS(ip$N)5 z7%8_qKLF4q!YTy0zRz;hA(X*}1g%_z(5YC9kADfy0532W-=vI+E7ZUONuiZd1Q%e$ zG(~qJo)Gc^((=t?P8aG525=L{=)_Xcv812@Y~^HUI9&M{INL4m>>WU)61>Q^aC(K( z1}h9JtOHys$K#g$qPWVhFnjpS$HZgk$55043Ic8e5guSD;KQxu10A@V0iG$w@?)+b ztt!z}iI z2=bx9qbOOYpcPr6#e^Yc2~x)(3j9?UbE`El1-k zQ%kp9I5Gdk^BL3mWbNII`l)C7x#{Wi^dZ9%W~vy(^_hBP%;Z&SqI=RO*-3$w&=i9B z!hAgjZ>R(L%n*Zi7-1Mr4FZmfL#zW?sR6$yS>*_UF)ts8#uNsUvLIoo>#a+uvGnpi^lmp~LNS1|yr+KkZS z&`K}H3s4paTcxtf)UdA5+NHQ%sqmM}lF#u9qLkK-o(C`@IZ+*uGvrW9>XTtK0!uMb z392-*M07}Cj%&4d@00|zXKb9y+o6`K7s-IYgmLaFr?I`8X-*h|!x&GF&sSXTrw|3~ z=%L$ln2z_}(SjJ(;28r4fBGs&YwMXs!%86lml4KcEScMiH-muK#NDY4vFrRac&B#Kv;vQPb%9PLEaUSvT(;v6RJqY8k+YZ zbXR0$jIxEgyn!0&0Vl4-k}eVv-l75gAYvSPFCDpWEVE`)mng;0Cu0J=D+DkD?b2p)0IN4=?)i(^pXPu;mIF zS~66kCcMf}K&uZ6@(p`o_{)W%n(@cfk{TIQgNVmQT$ff87V!`1qenFkrHrxLi zF3T#{CR0H}J7JYq_Hn7ZB@Mbt4OxKSkP;cPcqdj2BatJx0#{*T#RAS2@*49Mu~t~0 zG8AVBu|Ww}awWnXW5q#PEI%;DqM32~r|fX&`P^Z;GlzsBpPoQugjYiXRwQk?Upnlp zvIAROm347`98WLYvgh+4VJIP1AmEvNS&Hv2vHwFJ5s|z{h4hHm{`{r8!);##;+3gC zz(Cu`F&ccRq2VV%6;BP43}pdHhN|?|Pfp;b!63m>Kh3DOs1-AuQV*RLW)9|}qNA2K^3uV9GQd=TGx zBA}uhQ51x%2qJj2Fp!n@ijW_O&X#Mt>vt@a&h?vTv$~p(fBp~^F>YOlMNku9QKGrJ za5d@JoBS~JAU7yU9PaFnv9oCWuMWYHUS)IvXY>j5Ccg6}+v{+`AO!~PV0(LO`}GU; zS8h~J4COK?RCA+wqJPSIu7CYS3E3kG;?PSGAALz)rcFbCu#m~6atPaVxlUcd3T-A; zi}Mj2zd2!uOihH&4zA?j1G@;ZVp)sJB9c|2o#_s{-EM3x2x1a+`Qi59CUp*)H;BL$ zG1OZXUui*0a?v0tiL_J#5m1wGD~|nPYvEc2T7lSN*F&I^upNz!8bs_)8%@L)(mj2f z$t>o^<_fz@SOJp-+-#IFjD*W4N-EVp(!&EjB1X`&-F(46i@)_ELVPvaui>>mR>l>6 zWP$|Aw{QK5iwq+fc6%(vo3ChTN*b3@A0D6Q5?D!Gr8^~zA}_c$NHI^*-COth(shtk zMuM%jPoxO6%vLmrWOJoel=?w$CpcavEnXGRZ*+#$N@GCK8eT4k7)>B88nEfA84Gt@ zn#`cmCMjo@M^XCx%lt1B!M9#M92*KN8J>*A(!~oKoiT) z4!y;>VL}ua_68HbPxwsbrx`riGaAa%urfH5nSf`MWELO^hiS^9C3Mgk%I%zXf4P2( z7QD-}Jsc9Y=#xwPtuViO?*|Qh^9`IYgcpRR=%k^Xfc9Dwg;-|yC|{2EnY7Xgph~Nw zUJ^=0apx&(Sk$TmhTP)Nj>zsn&itR(l0W%<@GWh2=->2h`1j>s#+kGje!lqn#iYm% zGvkNF>dq8gp$#o?gbQ4w4i7%}I5VxFD<>zfOk(P%6F`^Ybo%L!p1g%KUJ^T3D< z#tWj?$~~KLf*9$UfLWWMN^GMCuF7$f4f^@~P56{>lVV_PjE*>~16`rhD&T|*HmoJ3 zItI?Mml;;#!A8%rI*1LAk29q(*a-&poxPwwRtO~NQD`J&;UgA_e(1M1f4dr8S&1$H zGeFG0Cy(+JTjk5GWGlk1k)gF*yw`8OweJr~=a5N3Pwe>w8W_OqU1Xb`o7GQy{C*Jk zzuD5m-C4jL0Lqx8B=Fj~)y@%f@ZsE-xjnQlM`WK*?PBxKYxB{CQl(e#^m>(EY8V^z zvl~Z0o?pp>d4LPyAmie6Wfd>-*rmJC9@CFClW9XYs^X^r8U-CDDVb~Dnz~7@-wS{7#lf5H_P1YN zr1g4r!=mylu56{SaJpL=o_sFl`ShSQksV$f4|X@BYw5Dq(uJ9{*k!_Y;WHPtim%Me z({z+hkF?+*$mFy$=K8XF30{c-VssI%3LzATdQmFs%0nu}>VUu}qNm@7gI|#t;Kmf0WH7~+W#mEZr!OH-FPjsd`$z^9@IH}JLMb$l`rim{#JZ_S^pONTJOVdzj}C( zYrWVq!s$<|dxzChy4j3R2*;R=56_;+5(+-%#0?f0Zss%>h9D_=h$?oYVPOoP=UU0d zlvP(y|Ln^W;;pB}{Dj2JM}tnIcXFPY{}=GTh<4A1jZ(IWP|RozChuoNEB!M{ zJV%R5SGS89g#oz2RCSo^3SvrW9J_|yr(W5Y+VZe?#Ac6(Q^_63M zqnJFp^+biRG%`DwQLE^(`t)_s`b_R;eB<4f3Ww3vCuVX&?RR5Hn23FG0ICSWFEo zv8W}T_O_1e>&0AmH?Dr20_ZZC9VKH~AiDET5G~B7H-r%=4&l|qn~!^^6I}GUAeedY%teV}lx-?_}As*^LULtT6c`^7jCn+IcRig7;DcXyfIyDDRm}!7sJOUUuVN~)P%;oJ^=@y}=b zclPOSE#tnmd&V8L4&}B)t^pD_#3anSfs*7GYLYAz2 zyO|gVUzwH*uN0N{eZ&VTl=BtwB|r+&E{ztrD)}<#>-U49OA zA^AU*f)-b(&J~L4AZfxv=6GjO=*k)|=j($`t+Hzo%1RIWYip{2Cb&B1UYedIseNZ< z$38WCwdkPO%6`9CT(Ya;D+!-GBY1fNq*pCX&K#e1l0zkt2KbSVzNTyO$mx>ci2ppR zTLJ7X8CvSLdwO4lTKeM9@%@xAhIKwWw4E;^r#7VgN2Sv1bQ+DuhxB}celTZy;r^_! z7F2sT?aida$h_1M9~zjGfr`W)pP)DXkArn-{P9{U3Lhu$KHjV&m9uP}pqbEEq^7E} zsy->LqA!Qm5wMf>B=C!u~m)b1RubTiE$lbn#06^%Zi3f-N(T7y~>eX22f@_0Jy`6xH+4ps;{s@R?LhlZ-C3+m(bOjei! zT(FQ7WJ$horE{P0ZNVl=zx4ax{<&Ap#p)4`-xoW_N+cyIZ28)`BIH@X;K&^Xj4;pP*s@a(4JqFkR(S z&sgsJ^-mM}t%caIoyc!?`t#xC)dWcn&Ak2*d&PAOFf=?0F<Dzh zstFFNto=X#@~z+c^FgNDdCiP<+BuGv!%BW%`2PD}|6o7Y9*#S0bMMBT_VNAOf0*$6`u!Mu1AdSuF?`d{ml#;xz1!=9i;I))%?W_j%@hg;OUogbj*^TcG`T}_ zI6{Wzexx(V7-rsoOf8izaK^bFN5P(?m-zs+poJqZO9^2YEH9F2{*sUCz%rM408sp> zzc?JO`B&G<@p8M6?qoWv1S0)9TUEa-)$v--VuKsByyZ^PIbrkiHId(=jo6WeWA{+8 z`?vNV|ByS}OG}JZtM!r*7_|4=uYULbNA~f9Lh+XClO3H8#nwZu`jYC|uS>-{As9*D z2(A#T(_rav`Vp+aZMo%4zxiPfz|l;Fufu&(j(YKW+*HOZ*U80%&;R=NJO5KlOum2r z!!rFJ3~v}b{o%luk5Szc?V13X{w;$5{yI0W5R6FkLOjCj?2W-H+W=b#Ut9 zX)xA~#_=ve791{q_q*S{nQ~4#sw*FHR&}TO;Ak#4ra$d2O}gJzHd6LUrKEchp$B9D zFgX;|5X{psS9zXVxmiknnpF5%k>sr6_zch>I{rg{( z=&T(G!V-Qs$-l@FU*Uku@d@DzM)U4*u5vJMVSE_Q5xhvRR0cG9l^gZ&(SlAqOOVB9 z=e_xiDiO^z5hVd5N^qAz9{+Owgc2ZPMSw2SXH+3|nCZ2c*?74&2w8&z{4c1kC480R z)H+FAfR83E#P_4~gxW&t2pH!Fc~2;eMW*u45v=5!E6=ocZT_IzLVnV z@~!8(nA~R&nrf}_Sah}Ay76Epki+?W{5f%!s3ZK}>JAex-~aCY34#p9R{lD@`m8^M z;DEi>kPNswK0c}B=r3p#H_0V@B*5{z3~C;$R01tk$|uT#WC(#QKbHAd=5r_#MS*C= z=OUz0z8PEvwR;ZszS}lbkv23Rm?POxB_|u}Y zvj;?MWu+UMsA4TamW5#i6-#!A;t83pWQFNb#W|VqPfC5E%0^=TxgtF-2bfGitJly!Scj5p~ z@plA0lNnTh9ZCrxV5tZTsI)2OdiD8#nmT-O@&0$ebFZ+VgTKO+Ml+j8RsbzBAgfEb zI=LAX(;-2UDF9_ai5V$fzNE2bs0+a2kBreUS;5WGyr0rZ=Y*fl3X|3=81pv)E8Lxx zkiXpL_=@I(O{&!s@Z{IM)`eKZXI;&S2hWxGT{Co{!H2_lV?JdjYKQI)f2b|&Lql-m zvYB9cb0v9Nev&MlNY*dfi3ko@NR9Fh;p+VX5f;BaG_yW9qoDe*cl&vzw={R~`Ii3P zkF%Y74-mis7NEr!up>MMSQ>aJlA0ryr|hPGR|zXKiK=9 z#_zA2zy96t-gkr8cVlPhUEOTfO34z5j$JW=)!}h%eZ!|YNWq3bY6dg%ltGqxZ47@` zKYN@R1csi7f7zo%v7&}}VQ;$u22V5g3go%+Q#FPe!3=rz!QWONG zKq^us(f|)5WmI*fK`J9ffhbZ?l%{3E+xUOwKJ zW2coezkF-$wbwo-F(O*Mwf46p$Vx4-YE;VXIYKT0w|xG{28Tn#;~L)M-L`O};OZ}4 zn{#!|Eb@n&W)fb56+C=)RTv0T!j@*QI6>zG@Fwk`fmSv?zq$D&D`6vF= z!shm_o;K7|V3{$1)pA#Unx0$F$E$-oHB~h))|Yoyh9*X%2UQ5HPNoNMv{p$VE|R61 z)u1ET-QwcYq0{^8%O+;pSkPA( zGGJX>zMxeLd=W7w*@UugvImXQqK8zYFFSez4`9UBprO!Lxx78%Y8>63ce(OBT|e8; zOsED{dSq4PO5vjE0Sfz*g4D|$dqr53@zfXy0Q z2(?_IQZQR>#n>B7L~^49OIDD>{#tK(zCb~eL|1gSt#N$2=y#3xUF-6VPi_z4469AD z^E9hgBJ1|EzErZTC)6w!(c(zSB2fYvdxx+7==`5_0wEWxziuMDc3`v#LE73&yT)m$lO2^Fq%3$M3%T?n;+RmI_m2TYqkLH6Grb z4bAoYnNPC$a;>4l4HH!SFB9#yL@;gKqY1BngkV9Uq@7$kS-dS+MRb^lIXd1Z(@r2@g;}vNRuF zUz~f=fMZ`f-G$Zt(BxV!>oAc(qv0;GJL%fAigU-+XtH#a}L!$z0qvh6xx3337vhY8F3X zi{59$bbH^eK+&*lj-vM6MeujL*77^;oQ(b6k!t$k6~o*%8eeHyvh{;r4ceU@L!(~!o-Fo-n zn+FdczKnYtO_VHFi-9t5J~A?4`uSC$rVs2)#f$T^0TnMX=RhFLXGV!40w@WyCUhZa zU)CUE{iCe^Gf`G?n5Vl8Hh{0tx8Bw0A6m`2+J^eZ4N&+7jV%b`J*}4El!E2ba};>P z&`56*qyz^OnVLYJGDeVap}~v-CKKZax86RaV8x2-(`)dA=J21M&8eTvf4GUkqtTO@ z^v=!W|#(y#=}{_^aFj;WZJ$<_yUZZlG@dh{~o zcUM%egu8nA5=|JZ?g$2hG5)e*u;XLd!HVuKja`pb*B^h+x?KwtdbSL>OJq4baX_lh zN|JGgwloW4Contj43UKbL&epF=_kv>;b_6{L#-9%ieU9c;Ux*URVtSZ^>=vt2RDiv z#bR-!fZO8X*o!`;u8nwo)Gb$Ao1o-V|7UU1iJl}hr*p`YP7PRo7W@G!)h!z1Ds_e8 z|Jqct6f_y~Qn_l2tUdT6ZF7G9$wH_6*t1sP0fQeCuA3jy%WF7`v)uFY(xbs$jlWxW z!t48W1}6tE`a^!q7p~2%_>H=?;_|CbOzAW&QS_4>fw4Ldv4REh(~9lS%39&@SvJuN zvYM}Z8ZIsEFJ>LzqsoGpm7CHUPa9_2&$~J+QWh`A{aGYo;`|aDLt>1=hbCcduG(45 zuL)eEwLS@l#3V0oJtl9{?Z7FKIM#}4s)0$k@r|KwpLb@cVC7D5qhe`8faI;Z46HQy z&K7$)_OaZ8lvn8@KdM^Y=46E=ABs^YDayLX4h%01>Zx zkbAGIxe*S#dM=95*Li%H_d~$y_&w#ui$^gq#HDd=g4e56DgA*?ZQ~F62^oqrr!OeN-<-r z8;DZb*N=AY=)pGv*4^3Jk>!ci8gAItT{LHMB;1m0W^wKv&JosMS{lslh8A~IOYWAs z)`{+Ucbx|9c8TZ~ymUB`8(CS6w62Dh%=V%r+a=@&bzsenVKtcw1_70H)l+2#E0IWq zdZVF(D@*&Z<9WZ7I+z&VIyrF06oTc(iK$AN1eGt9DNQ=qbImGLra}f-jjxI@!HnyJ zjb5nTDqgw&Y`ESC?o92K zlVb3ld0a9vqj9DZMtsnUK+&jN;736tMr6&;mhaM0!tT>gzxf7aeRI8-$q$dNPpr0Z zL#KfOe3hz>UBbOcEU$rsSD{CB+x_cT;KLv}2Z`PzcfBkLb;}S#7+P>yGf{{}qS=)u zH>eT`#GfH``aO3;3*ZdE4R*wm?bNIoz^c1lUa-2O(ca!@Z!|Y?w7>uA4`#&txVDJ@s=5%i{kA%(L5+?e53lC z2jJ@KwRNQ9XXn=^ignd;Wsu(TgJn zS`tiE9nVi39bZ9cr6~y;RCxE{!{yr zw$7#V^D`Soa->1ltcVpF##-{?&@qdp<2V#_o+?pe_L;3ube4=x zZG-bw$LubS9!QlD*2$tv*HBUtfWAyHNwI=2mg6%|$fYF!mFR_Pg%TiZ>+RD=D+dQJ z-hA}(KmR%1ah^kD?~xQvT^gYK>``a?`}3AP?O1pvP#L2S6VxCo{w|j zFfeY?^pit9;G>o>NmZYK1d_aHq{>PwLn&cGp4`a^g(C*t z^mI_2SEt!+iIr}2CpJ&A-ETyz7REog#l?|DVx&$HZc)z}3SXQGUv5V39;DiXcq4TM zs^p3#W3i)h7QGWJa0ReJP^@S)kxR@RtQ@>}@#f9<-I~QBO!gsG=E$=`#1H8ZwbMj` zBUNUi3qgA(huK!`Z0=LuY)v}04GI>So#)f13{8|UEodl4W$Q*aYghpxm&r=iR$5sS zsKn!uJ5%3|kyGMl&!?8WVVgD_J4puV&}&gLdb?DV(2Hbc5ng3qd&Yh@_VvTBFReqZ zQkhJ+2Qk+AbaAno$LNWcrZRc4mnaHk0hY<^ES86@OZ(auL7}M8mK~#!i~Bop3L{W>AbX%D}>%Q!_8^>{CGX_ zVXXlpLC|dw6EYP`{&9`)YwBB?0v#OzM(dIm)eI>NTZM0GE6Qr#Xb4onLLoG{Xf&7p z{@t5@y!-Is?OzLA$|+W*iay6=ZnN_iKu$|Wg3Q2HG^hiGkp*o_;>ELC;dCz^zu3mF z6FRTIe=Zt|^b8N@DxHnPO6yNKg+N*9Q``hR!AW7WMx>l_8H1OA<^zzc@iWCmwPo-7o10-{!mRf}>ZTBFVlh8wN#GRrTk zo^Bq~r{M$nX7f(|^pPe?d6#CeWJl*{;dD0ys8VW%s&)qsWi5xgeh%4%ME7dRmyRXZ0Q9}34{P9i88^5C@3-g4BCqu z8w(5hHrbfA*>eC!FJ{vU7BG{+(!;B&e7pm2q!Ia&fi=!ls#K<|nQCN-tnguU*?55KUSy|IaKs9w*aErwGXltcbL5TzRXWFaz%UT3`rI9 zS;|)Q`wt)9zyJH{zn)cUpk%Y74mCE=vS6Lxn>HB+d6OW7?Upha?`meBDpbOvaiOnI z^YPPozznrUViG-Qma?S}EU82dltAcrr^Rr9|US!JIi?)dQom`f# z1MLw*PBpCJfP4`vY&i#hAN%Fi>-8HwkubPQ!6KQS@ZjhOvJEI0t)u-!9U&W$D>sbL zU{K>m*SbA-`iit*!f;)9T8nNr7}_LdC3k6L4}Y>nFud3vBuX)67l;)Mpz%WZes!U& z#SH{2%Gezir*b6{TpZ4YM&7?K{_9`=`sZt}K8w#Kn&f0eEozF1Qbxee?DX&hspex# zv~<&vZ+_4ydIfB35i*bAn0=nfan&BP?WeLO6nZfefcU8r=98Hg(MV1~qcD9+mN}6s zaJdXh&XbZ2M*^2~ih{im#0i1Ju$uvwfMv_ER)714Km7ieKl@$tNIV@+Wx^?_R!=I@ zlOG(Nf3iCHH0EK5Wn7^qroc{31F&Mcfp`d6?kkz-UC^U@H2Srhxfcy4jv|WUHW`(1 z>?Uet(9_-#XxHc}h*r}L=r&&_fmm{;%wYMVz=^()9W*N)f`UP_PN)C=uYdmY`@j74 zOM%5c=2(%EmSC{4!M(Yy#PK7V07bBf9f{&ZE3kwW)5(d7+MHFaz7X+oDJw9U)av4{ zq+2}6s(cA~@+Ed+;uak+#XzOAsY9^LFX*&c#FR4=u3PikG6yjXbol1i=hvPk&*%8z>3>_ugo6K=6seeJFt?rMVN*8*dh1bGd@rp7eEH${_rjI$W83i|p zs+TB?#xXDqw6{Z;#0v(%7QupI1usta+>Eg{dAZEb1*rvCq$vcn;&IJsMIl>+9Eh144~srI}CkOB(0UjmbZ7Y_}ZM*lYdh1)s(0d<^c@%qXr=ED%lZ(>_5) zQS+H^L-16$&g z!_q=Lg}91x1-Kwt;Y@}_GaG#`lN|wQmIUn9t*Q8cB=SVCC_p6VMJBv?NwEQJ$Md00 zqNoA7I6$SzP0VBhH`q?3B*p?^?ATVn?CD+&1eu5*Ei+gb5M!lbae|djGv|;%5}wP$ z)a$?g>h+)g^ykCJ_6Q++n?PV|P1TBa!3I+*P}6=H_iUsEm3bmqp(*;o zhLcnfpya2$cev2<(DF+V zh;J`V_I{6{hWhvlgLOBt;>@_ls%mf~GQ}4g7zJ!4+CP4fWX*f^$1;QUqo{g7vXzE( zg_zUIA<)7r@dL2>;TO*izjPr_dLASjwCmgq$dHbG0+xC|nxdug7$+)a!j`lGhA%98 z&rG{-i6D^+P0=e*G|?#ad^RI0(G=&rK`%(JCm-9bL2cQTG>b%u$-x{oGNz^xmqAHN z`AkGV;4@FD_}9;VTFj)vDGF6Q6CqPDxcnYs{2ymf3D*@P|A-KdlKm73Q&f#zNZuu`5`;Y7=>G+Yt!YN~Xj&!bX(JZ^C z11|{p?9m*d%ch=y#T>wzlqf4tj0lbTJqwqslwUWMFuDIBmKp zr0Jh+b87q=NfD>)M8qnMTsg}@^iup@SzG$~pvJqykvNqKmZEBfGd(mY7SdQZZjOO0 z{yub-kr_yo00p+>5~w&s&)22CTxewGbZ+>hnKo7NLQ@pPDOd`lU#3zJf$OOh_m@O(gJTo|xvy z7r8Nz$+uLD)F+w>9K}gvE`h~lw&X+J7Bc#atW>6E&Copp3KB?Q=nl0U-%B=h1t|KY z+QmD3(h={IFH$MS9GFJ!x*jy9$# z$TDCv2b5)cGW~L4cggi@8aB~7%L!g&7`@xFV}qAh1dDJ9Wtxo;SEm(!Iy0qMa@z^9$da%ncUlaj_-`m&%7tL%Ia^5IT(2{kbJC&gq1YM9Uh*drk?m-W*Smw7ev|T?oHg@%D%p>Pj z>i|e|O*7!4a4A+0A%dkBtwskxNY$x@UQpwEb)mRgnmh_syO^SduHk+(R~@@KSSSo% z=lS}M6|< zbGJ4d$)a2-SXQ54I%OlB;wR}Y{W6lGfeyM?p-NpLn%I@;x$f0u@a|Tj0Efs7eDc^| zQC|BTU@>$LV?zRx1-(k8F=u8=jQc%_FCKp@E205g0wXmvE(;b1)*;%po=TRIVN_#XTdXEnSFc}?Z=5-iay23a)4#R;MmFNdodz2rlTssrr+%ftKvMjF2}$^P`Tkj=gdw!g)i&;z~V z^|ZWIGX#q;!2`-RYA6M;uqKSlLNUQjo?Hm+?Z=>MfM6&~8eVBio)mFJP;9zNgDWdZ z{WC-B>e&<%s+*Ox%33R8B&7cd0<48CJ#3>eS#;FtaZalwYno!mP_taRP*gYQ;6zU= zqNXtwFA5b}bQUz@1TnM+R%yCb*yxmZnBQ>uDuR%zC(Y$x95BHoyb43GSeU$wGQax) z##ppi&|{vwR|Be=KW(ki5R0gYa@BJzcUlxCI75b2AP_g@+k#(%hddE1T7dabzGKzJ zXkk2?x)`hiUmHm*4wF!yF?)i7KuK?($1V3k z6{m=;1Snii9qkq(bVODxL{2ljLbVLMATkblTu5V$tS?OV?Ig#>1gvBd|DD^Lu-wDj zUDF9yh&T&`L77@5V=AguFUn=psMbqb{NOp80uU*%6$k_a;tY)+Jc(q-=jO)e_G7Wd zY$4(aswa%SC~MUW!PJ2rkV<5;}FFSk|mv6sUj?j z7dv|sW?IEdc+y*b4XAAF&JS!=?3rrWfgJLnpb7HCzbL#SnDsC_n$P0{1?!rCrOq(P z^?$WKgVs&aYHe)=Ul1X%^3hdSW7k2_#V6g6bO?yOJzLoz!kt6cE@5p z*}}VaM(#vwvE09k`Pm$G2};Ejvh2|#1CKtQ24Ykzxrq7i7gchTl=vNRJ=z0M#JQ#MCnLDfzCOAX~B#k$tYkYF6GSm8nNQV7)u5U8ZRd7ogb0o)nzgZ zY&Cj!4%h=F3zx+51K^4;UToCiHzq`{GNcJ%Rs^f*d{`EQuzVf`?}NKMRA|7WUXd&? zfcS`2FuFJdGJvbuD3)FhScHuCXsuAJmZoY?fJmVsQqobam>R8{p(o581+Ok-3!^Pb z9HWqR;oGwAK@+S3H=w~)8hX{k)C}25g#i}BEyP%n^wi$rR4>WeyEX9nXZpt=TE71* zB=wa9h+`f4dW#BHabtK33wO&8N0u!jV#UbBTg-d0L!-{mK}~nA`59lb@gw+X1JjCR zeVaqjUNs1rHT#QSikJF8;-vvRuT_TjZS#y&_d`OGpl6>E8B~_6%a~E9_BRDb4uOfn|G%mSBIf=B6PU7 z*E=;eb<0nQeU2AJOEd0#bIjI+?H3pv$;3MireJ^z?$Y%p_6HKv|PnUJd z6b6+75Vvu(7Ma-s3DqJvu}?>v5dCx_5I3Phb zK(|CSav;ffy`^GRX*%36ryMQ&HZuG+l?P5xrhFs?#2B^X!V94l6I&V5C0m7k_a8kJ ztTe_7O5qfB=VHT8WaAHlg_o)p&CRzPtf3Xk7_&=L*Up%|TDEb}s51muN4ab^)PU{g ztCLt0zDOo#3fbLD5?&>F%zn9|+}4jOES9Uuzr1h{$x?ZbGmHRJ;A#(4vDu^DYW(c^ zbHYW@@>x&lv-^e|NLE4G!ZfgQjA#u_uBZI)gsNHu$T~xnAnDD~2L z)JeAU?bS}t4;mk7RSKU;i~c{-?;3X52uqS0yrgmVmAccJ9)JZkm%pAgbzNBE4JcP0 zGd{uy$8G!WA5pPvx*zXQv{b9mpDjnWRSa#j#i9QIYjt@rp7S$FZ>zF|8MHcg zf-111cYVBcov7ehXK8coq(>twUupNo+1B|V&vkc<-q1Ge2LAh@Bf2IX=P_s9Ak0K0 zu0ls6Rbi2>Jg!+L-ml$1e)v$q60!sle#tW$?9wD6Q9u6koj2E_6;0Iwu*>hS^ZtK!2KmJAKq38L`Y5w$- zh~dsNfR#$2P2B-lclP$+4fjCSR~McegJ{`ecWudusFr}WH6dd&t%P?%)+(iuI(ML>$8a>KfR9wC+BCVqsWvopikrq+X3mLU zgL<^QNS~z|Er~L(wuFQT;e3QEXQunOKL|@HRlp5-cNo%G^V0z9)q^pZ?&**$80qjx zaYD5`#U0B(y2DGIXz2yP65gU!t#phH)qt@Ya3Q?%(2wHHD;Vh5*%Gkk3ULNi$tQKe zrBtDRMCuy!gniYmigH_9FS$ahArB{r@O^jpv&4#5adke@T`B0u2i)fquC!C{ClZE%{%N~g zBdkf|oWlXKjmm}~#xGHX(32@s&F2zrG8~aVwss%KngV8`cZEnj9|tn0`Fkb(8AjwT zRqlBTIwef8!W;MUdAzZugRR2toi!)MN^+5=`^T`LR>HT)!3ikVr=9eDcu~N>l$9}e zlgC)VCfWfdhrn$$n;lPZi?IJCC95fxMD1wzPE2e6g1D-(73DT>Nc5^_@HBHexVxJ< z-8~huegIm}en8E;+MQ<-Wr=d#yLIc<)a@TV|2fD4T9>(%W&(F%0%L`1v-3--D_JIQxFHBnC|KI~@01_~QOLc}QMQ$C=W+QJT zd|%h!3kXc~XCqaRFHZ4F*0oiX+bU(lIfI;W{^M?b_w*E0;f-*VSe>4NEC6;WTF$JdZ7 z=oQEUVjo4c4k1~447T=QSQ|pIZr^%L(V{`LB<(<&lqz!8H8L9?Zxe8chebZ^-VKSsaRnP=YLzo9u%^plEmn-5^Y z6%N7;4)5;19)3+%xVuZ?60k(F@CICWRI~`z)V(Q0T3`4p3|XJa&+@97Q#!TYelJ-f zH8v-8{t2SQN?WZ4H5XCQ{FaTs>?0dgoLm+ndq<}fEk(-UMWF&TPUedGrRNDPWJa(4 zA5`3pjxvIheF?m8NPQiS<1{7xT>z^r+5iiR_1~?=L=ge0cqXG{{D3oBIlTL7;WW~K$_juDey~% z3D(l(igH_RFLw&V__qeI$kprD;0o^W&wm0}fC`d@!-ZTN-nk=+g=XsBJy{&y%3d~P zJ^#d;W^a&VHcFNq zqs7<61Tw(om@Og&LjTKHMe}Wf@j0+cgC%4edRfBFghLoDAK#akdiT6IM9g;iVB5aM zgNBFJ7hhLS&yaL2eVU+l)Gv4J-oG?2&-rs%H z9;+G7V*5GqQgn*C1>=ySmHanz*VC_{^uOADp61(9<~Ioyg6I_0zw5<)$; zNm~#oH=!4((s+LFmmRcD*;q*1A7XLcUvgn4Em-feUKrsMID8sq z$y0jGUP2Rhj)odZ48j!fCD-SiphfHcI1qh*$93a4-Xc>GTJ7VG?F{DBo&5SolVU2wwUS z`@;5`4^uO<5dez#dbtT(TY3pwT6(!8Y=N|- zIa~x|LC(5ER|soqc?W@(48j9UoI`URU<}5wIJ$~*lIdPD{++8C=#KbODVDS-zjVgS z;Rs`%;E8vEjMyPj5ka1E6}|OM!MvG2*iR>!7?NOmTH7;iE{DaU`KKP{nHlq_swHts%&w>cBV)$^!y;BCD}+Zts>D-p}!PUXaM*n=FbT z*FEvB*Ky(3#rQ7MyWPnp`bJoJ&8RXe@BGQnA&xRjGrK)e z$do*CfI?GYE@c^9roJ=#>{2=CDh!7KF9;5rm<-0sd|$|dsR%twx+XqU-$h071Q!*B zq(rt(=m_2z98V5hp%qcp47z~Dbd%h#;%tuGD_NO)%FD|hg0N24w?li+y-In^65W6m zCmZ2&?8UaXZhNU?1;S&sz|{JtY;kdO@#V|KMJ(7Qg0Yt12b-JME;7`TlJ!Wz7E*_e zAg;#qpN+-sD%GVtO8p_0IYQ^AgjgA&80=y zlDWgRN6mzmc|_2b@fOlM*IR%qG~nM>3@_5M$}G{9E3z_4fs4mPLYh!z!j~7^?>0tq z1m`>+Z)+XYZQq2Yt+N<-<0r$6Ef%-yH*`7|TyXvm%RJrP!TiFp8f@Sa?m)%Tb>}N|hvyqxCOkSe2kG zd8D!aF@3K{~Z6bBQ7=9lwJg#aJRMlGc;qj4P~Z7{tkAk+`hq<-wY(nWt;Y z%gQ%;_h%7OTy#jG29okiWyiL+ZikBUnf8j*0#xhk-B{oWWqhoyZHl=T9c#fA4uG~8 zz(dO7&hQ+gc#zg-{TSZONmh1R{NzvH=8GJqpkipUoFP%AZ>~Z{o)B+d^{5xPtI&_; zOQOP<;3B@W-vu4_0TBH*3hM0A861j)Dtqy*9TEZw3FX<~E#xLhUhshGo!~euU`yVR z`Deh3+GufGTWu|Ybpycq{`-Ei(9+PjU<~22;`hgbkYKS%+ysKg2)_NCAVQr1e>Ge& z+D|FYNIL+wD`>)WlI}!2g897#4VW_D8h3=4BAghs8)F?2#wy=_)y%e2C7^eB!tQk% zhWM?ozg+K`hMGleEp7GyR7;y{@Pv%v0WIzhku+rZejQ;}<5#XX(jQJtobue^UN5`j zcktlp74&)T&-?C)5Xwhe46j^{MeFi=Tid*%2^_%41PWD)Mq71k6@=sqZKkbmPi?m* zRUbt@q(oM*3P1+r1Rz1RLZ|?i5=AL^SN0jIXh8l@gvI!ZiHoYXZXS2?%P((p4;WfXMezmtYhoZB(9;d%~Ek-mk@b~EWp@y0wV+DNleD%|&)Vgv$sA(z^c-qiTnRBFCSPI4>cV$_hiD}Z z#FNKkjMQyttyX?2XjPbxAWM;z@Wpqv z5#~#B5QkA9r6U|`t9|eQ&0jobPQW?_BeZN7yP!qD!1&ayIvBCd^LJF||Qo`3uwD=eNCeBV$!zz9E6N zjJs#EXL@~lb9(yb=5)^{R4hbW!WMu<-iqQ%z#8}p>>ML4ilxUr(sBiWLYDE9%xxF- zO{*b=ACZ;sB3%Z@tA>aIOX3wTH;};}-;TwP%;o&-H(hXl(JvW{t^lC_29()EBdADo zKJxQ*D1e&dWU7c%en(1{$Z=uRutm*}+VB@+OA? zT(`HqbpxP{T4 zl9!l?{p46MSpHFRAQ;?;&pe!JFrtYFC1V+7v7KW7XSTg{JC#=o**#KMx4yi*4zikD zo}8BT;D$dmXLxhTY|V&^LMfv7J72ko5}NC{fUG-;;cst?#_+yS%4kYoq9Y^4OMn?4 zaFz~3pHp3f<1>rQ1u+8^VP#H`xY2wEV<+iXzFHbZl*Ll^2bt5gGCUal8&R3Hm3q{Fv>vsxy$xI?Eo*qjipzFYLj$fjml${E12vj{a*o0pJhU0-}+wNT0*%MkT= zrdQc-(jN593)Ky6I=s-sm5(XjwDad1^VKgw6fsWcjFjRkwe#i_nW)8jEIkD(Wpl#V z5Qb@OC`@M6%>1+OFnBj93%HWp;LQ!i2c#utiop_-3c@M?u;>Y6#aLvsxHg{MI+Na; zU0xpGRQHt9V0KAdCyw5{0yIev6=AJuZY_oB6gROB{v9#tBT-4_m0SF46%CzWqzGUNBU>p_ZZ8x zclamAFz%>IRsB)Rg5bVCi?}Mt1fED?3gGu`@O-hlxcw_Z=vDFfw>&QirZw#tOFR2f zfpEl}vr(0f05jskZ|qqu*!lLWX11LORnZf!t^-&-lgqe)s2;4->wGTW1Z8b5-W0GF z2`WH~au(}oW}%icu>%8PVTCV*eby%}MeC+L@J;4=2ZbE-idGitXybNr)V9Pt4oOR6G)q;B1$bfM zK2RIOu;d0X)>s%TRIIv=dZr3z-uD=*QjBFHser}U-2{hNW};EkXPz)?zXC2<{OMXA zjej8-vU_=1S#3P>i-Tp^HK!kk>So-DU*J87R?@CCFwzb!xb+PhQOVO$)e>9TjHb73K#6iqqP58kV%G8nRag!#2t{8QQ-CiVWi2~@Dg zufPr3=_L%Q;Q53yhz;UgYBe+Rg9KJzCxLYZN00v-uwYr1D7OAU zrza3a>Dm**6UHkA9SgwiT*bk_fgv0efDBTFspfpoaitRSklVnGhuUG8}O=oz&I+r5QN^O%75~R5hL}$`_Eh3&a~yMSLlM zXWK-+oS;kVs5@1x1zaJ@3Sj>OtA#79A4IBf&-Vc=SX6x1jBLhOxLGp=Tv1;qJMGT` zUqKvILK+Jw?8EZxVCxmtGXJU!ndaDn-as&IEG9iJ$<(VOdXTcjT{>3hh?XoBH{AOl z1M9^0qF+5bj22r>6i-5^2uJ@IjkFN(JG zqr9eKbz#a77EKZQhd}cNh|X^{ej})`rzJswnewr6KoO~m0;%TiSbr+Vfw+zeQWn%d zVvGU&SQX-{aBY~Qxa+S0SP9>!D-^JfRl?0tBE=2fGQwhgmN0|_4$kf3zR~3lnU{WA zmL06$sSRY-AW9fYhCV6@W)EM&tr(^y&mh%sRZuCz#BW70%GjakP*g1p8`|9z4d! zrzR(F_6S`t#9H7h?GOQ~uEizD@6EGo%@^;Yk_J(h^%~x}Gr)v2KLXbI<55X#@4F^7 z==Rzu_-?yBg2!9m@#J;k$@xKVNG<*y>Pp4OkV5z=yA$oB=Nfg0&N(`-n9)MW%REdq zlC7Ybg1oC*g$xgr+8@@zTSc^-?0##Kk@FQa}#_HfXI-?IO z;R=0V0XdohBTog-m97|`VHOOqV2G88rf13x_y^LNmX`OFy@X2S5Lm!fS+%?%h$`Lb z3|ZhVzHzmb4%IRZ$f~@y?SE#c%3DvT?BJ1i-Z>i_iiyJg_#;hytE;bGE#F$0T)s6q zu0TsRt~g#&sl?LhF0vIPd8!U~fv(w$Yv8Pl1JK|HC}^>Jhjpc30fjPKOG~3Q$uR#Q z0520rBI6>ivR@2fb{p;Z4p6IW7le7LyH1amkm}3s`tSUxY1G0pH zak@VE65#GoK|8EeV>At4r9hRYLyE2#WXTv})q%0DHJlup`OXi>STL8_WW8G?5TgsXIh?gZE4iL~H{oLj^in*yBYMPSwZBE=4T_78!!tTUeOjbVF%wSQHv zZ~GtFiFYIS+zehfnUHfSL|L&heSNF-e|>dp`4$7{1Tji3IAl~3;n zDe`XenxAmaaKM^ldH@DA2~#wH3je)}3IQp4yCO*oc+1gQamHRWbmZVoa=U~qm5@?u z09_fX!s4q)1g#VeHvp{fJ6{;>)Uh-(E>H@+7(*;F7AT0o%f!3(gt3W{V0P%V_=;6n zL*?YFycdZUqMLs2z=d}#aE+EQq$zeka;9|K|He*~{pyMaJ;MkpJL>=eJj)eN_pLVJ z_~%>83kwVG9$#LdU*t#55CN9%n=rsiDtt3wwZ>wH*@26*_n|pJdSDd|8B5$CXx;Wm zOLN+2{-`4_2W?n$VU~d9w06E|f5?ZBgxdltnBy+}$@6wJez&osuxL^8oYjs=6XA_l zfC}3V07}4usab;Bf|#qMkg+=cR;Wf;z(dU(0 zfn}Vf*`QiY)l_{07^}c$NfK6)-TQ~rGU|mZK`UvsJQy0B5tz96YP&rJESH4#($WQI z{zoH0PUSu1EO8Q*Ch>~904$VR16a==taf(3`s=NQTMG-faE~v@4-#3lWw=5R7Q=W5 z@Z>GP%JPQIcb8`GGTdU9g+|eQg>tEM2NlvlFP+#;WciKwTVw~WenX+_ptmF51Iz6M@F7j{=nB83|KM@ag@#kCIT9) zgn=p+D`s#m3gw2F`e1g(Gx$n=Qh}v}-rg_rDNNz%fCbam@Q5Zyx(Ey3C77Kl-}a_W z8bjo?K$UFRf^ijNp%OO!*@N!Zzy9^(p8!*|TL2e)AvTA%7|BzDCuyydvT(8DL8t<0 zvB3h&b@$@kM*{-@7GTxLY6nGGRN)&XJe-IY06Jf&q>Y|j#8G~E3?h1&oFe}K$XPrd zWv>h|5n<%&X7G}sz{{9SZ&4OwUMKDP{ec07f%JXE7*Pc$&JocdrXqfXrhI}afJYGk zl~2WiA-vc8T!@>lP$?Y%3yMRa7EeH`mZtOTkKQ;6U;$b0M}dWlo=|>DvmBX?hNZH^ zkLjGOcxHE~jh@~JW|twb=XIdrfGXqB;Uh$G5lIPSj-~hwm*O`XdGXlsZExOAm5nCq zC=GWsOEO-_So{r&LsI(lrn(3`A%S&kT(|;j0adp^TOuzxL##?mGkU)aXDHpF8Il&F zEL@N9&x#Q|sDPBvqCy&6E&mb2Tb$)pzemC4&A7EQqOD>^IHD=*=hP~%WE~IJOCPP) zGB4;-hFWMsST-n?Mr;kJ%?PN17YCS12q-EGSXdaN%^`xU0DYhe{Rk^<6zTh*J-7sP z*xH}TS7;%RMBoYQYN3xdoE)rPIrf7e{DA2~Q{Hha#BycIBrRy0tUyL#C_4|KZh@^* z=^F112eXR`RNinpw?2X07c@!@q$Z-vT%H$EDZ&Dna0ykantAgF>74jX_e_cxvg;H^ zeDvU9`;@ZMXF5BoHvjrpF&1vFlepjsd5<%MUp8=AtpkAND*w7rn+0S+(E?{Nh{r#- zS%xm=5gT0y4|nJb4>keNcZ3$4M@vJQL-dC#(XgDk~Z-f2xlmeM=Q^C4U(_b{EqJfZsPVK0IR)%mwCjQQ^U>^MjU^^u`a;IaM)o0Aad6ls-8b@5%Onlto}&xz<+|c)5IwwjjPj z9FMP%vnFxDS}Jj+f1`gX=w4#vgmB6XaQJQq(`QSw0s@j1P7@N zdh_IWd%C6xt+)Xv{jxX$k~8!)2i~s5 zFkbm*7^o)Rr3n*$fog{G`IH0mb;0aFuMj0H30>Y%(0Y*wZ%;eu1UD|a!X0n2xIrRA z-SfCa@0d>cKcg#7dggi737o@pV6ZhD$hkj7OaWOk0E_7zqHTG+2gw}~*0@Pp+!;16 zE?r(^{NCmI!XU$o6(~GN9Fp#!0G?{;-0`h*X(W|8ma>O3%w7+wUiE`Scqd6Yu=wp; zFiNAc|H$9Cu-$OQ_9D-kajC6akV1r&Lyt$wQha5~gC>UYmcAwT2tWm_xIvS!xIL7D zh5iYk3Uyd@b&-y`?!E_Y;YjOHuVO5(a>jsV3Ovo~^fWUPAfUR1fC>^8d|_;2J>`YG z+KpjU&9ueBIWbxAI@bGUfpx0p$pHaMLW9Lwis3aqPN!J| zSm|*WI@mmV~_5>3f0%flF-PyT^OF?3l`3>P9%a8kf7aTKjx)}rH< zcY=?IeD|?xvZamOB0H|Q1Sgw?Od2&X1&S<~7tRDL7AfmgacS>(BGRHSWa~4ystv;- z+aef?MZ)TwbNL4{Y*6<4cz7@z973G&jm@P|Fn;aRW@ci07AxP}`NJUrn=CZyTMimOq% zLm1s5YH6Zr=@UA70AL}wSmq~;0UaDoV-dI~xl=&3`eQG$a(loGtfpY;63+a=S6W4H zX^*srb++`9t=(%lEr?!_=jKstAbAxALf|dD=U@Svq`i~8kb>43^%^-t>QYCcZf*;q zV1*T5b#!-hM-cT_MK1KtoN*zRYg#??O_V6R!IAo>&)_H>o{*)Z3bCLzNX3d71h9xK z><#QJR;5mKu0Q}w9Ut8WlkCwABG(@BZ|RmMaH_tC*P3b`N^{4_-O`MQv?){h3hiocSQ1CU0q8Ew4jwT zcqePka&yS34vevw;+0g&6U%q`J+09h$gXveg`*-Vi4GjeV5jAX)d-h&cJJB_+l5~V zBbVI4!@=ksWe#m>5k52~qmMtre@(!N3qBf1k(&=Z73Sy=S$hGRv zfM!L1gce3gOUo)|y!X;FVL)RLopfwHFQf}vm zH-W61@P=KKw7M>0YlvI%I~WW5dhpeq>r9|vX~FJL?lA4pkGA%-M!R<`Xy@Yh=jfX_ z321wF@2L~s{BL+tlc;vMHl?~5Xn61zjTPYiDx;x)wD(P}H^cG+dQZ#Z_<(oR8Y46y* zIF}jZBGZ{a7GmL*e*j}4#)@yq8yPuyw4oTl0t-(JEC^6C3%Hn_Mw!+)i(9^xv1iG~$;0+9HX)J1X+X9H9XVbQOto6jltkw^xLU>V}@JJe_%(X;m{GqTGXyPkBSK z4MlgwT}bD^z*yFyld|vd&UlT9#G>F`CP!$zCF&A)0Z{fK$OtXD+RF7e1FUyDPw%t? z(Vg+Y11j%&HM}vXm*9|6J3R8@BOI<IBnM1fkqz)%;Z)xH&sv=prNy);J zUm*&pWu##^_U-mO`mfO0#+>%{iQ~Ht9m4s+TX1D`Ww$T7XN1sut8CP!8gVy@N^n3w zJ~=rE+l%<16D)z}Ba(Qyo}%`A{YAA50j>ZR>imkJTwzozfdypQWJr|ug_U})%>k_1 zhbux=L(d=gKb^UE*kdeWN4Pqp7gI_#kUf6?5&jj5W_+q5EbFcpqIB^ah{<$!QkQ^* zkBYh^G$>?uSApfYfz&fE-vqEud~RgRA+W>~7nuvPa0^%Rg)_M|BQJjcVMD`U4uZxx zIQY4xk3S}`6vR&gT?^w(^(;&+PfbmY!x>KDCaO^FaM^gPxeL6760Ju|(n?uJGeC!k zykQIVEEBYF(;ZH1nM=d@4%PuCk7#2_H7L?>r4b7gdAVbOv!D4)u&gY5_pXe>;)>h5 z4(;8(+s#9^0i(Xq&JCm9&aQ8<$<3m?P^d)vK)OG8KEoB5_%tWR02n*pj+Ide6?=E;-afBKJW7rILTthr!$`R%XV`U$Wl(y|QVB(jGv za@P3xO(3gh{D+9Orl2_hVU*w(yW|QrI^-hl{_Ma2yQEo8uEsD#S^$=Ehjad1nq6$V z7nY)DnV7Hz7J_BBOx(^1_qEm3bU~P!WNZk2|FB9X=5F64HuLDoT-^Ulqu+|E}T6GSDO|4fu;93kV_J5YBUc1Lm%guu^SQ z2vvD`Kktk}oiXkejJonsuKdwtQPLoHg>tpmUpuf44Sy7uqK%+rQNxm@a=3C!sPFD1 z{*;uMqj`~`Cog{g>BpV*t3`B%<&bg(`^Q_$amEanaM zVW8E80a`T4+XIgn#6u<3WHw$l`j5C`JD=|kw_Aos=4wX;EcK+O;ZWC&?%IlqNK;e2 zv(EaqnzGv3b`4~s7xc->rrNrn(l%G2>8?WKU0siCx!gaM(c^C!CgKa7T)mN{Mj?O<^*|Rbq=Q%A_SYay^+ zYYL}h1!KbrE1}3-9|A1@1T!rbWziCo2HP)<5?KHE?O&VvHX0FS1%vQDcb7p~H05^| zVB?6dXyad>;tug9y&;?-o@6Z8n%eKFJ81GB(uR;7$W~-6Yq3zA#onubi{bqfbsTeX z74a0_zth$f7_MrnZ!$AzwQi*4L>fPPoEtx17j^h@zO>UN!08x1* zp^6YAtPpNm5lzmpgbtC#GSQzIX@SoqHLz9&Ngb?3xt7l%tjypH^M?&r?V;|YBO^C1 zjm|%w`QqXEE5=xcBQKdFoJG6A@C|!HsG~`!U!vLoGhp%3lt?qul|vL4*p~VRop3@c zhyp9K>@|xF)RjS7<%&izyAZs>g$NyFDsub z2eRfGr=2S#vSj0CKo~LhLkL>dbx6j#xyS?@c+2W&C_CT+wxE@2(vj;rY~jZ;Jlp-W zw13>Cr3k$f2+LoVzPy$@++nbK&{x-1)o0ME`%G@%*|eZdZkOltM~h0D-+t)O`BySH z!IC_{ir`Y@o|l8yA_Z4)i>8W#t&qWy0uSzz0aVQB@K_3JSmZ1lh^4?C*iut{I0RVL z@QAm-;K+;js&9-8^*?_0#hp)jjj?D-J-Y}UmbHa3#xlyHJCr}n@aNKam8I{v;!!uLX!vE-h0gX!eN$^wYos^;3dt*pGznSZ z&$WhcXQxHS$(S$Xq6VKsr%s*P+x*v8uOfk>JQ$z^t0)1o;OvU1WT6mCQ9K|P%7^6u zQpR9F6?ckO^UhtMly^EoRF3NOXAJ^jVRGScjl)&AdgM~|g@#K{u0CFQb|41xW=L2C z$`G{I6u5f@rP?WiULZCcWc4VKC6myA#g)BNT9DrEv{4~kiRimeuG{rcC(=@jwdVw#q15xc-vvPBhWS>}+kgVp{qCC#!@hbyV2 zThh`5l~?X=3(*y78+#HC6IQK##cCi8<%PmRR%=;F{n=oebAP&RA<%XMR!}64cdzFY zPrwx@3p+xP6~Bc-3atP#_&(q(pIRx4+_gh2EL4vnTp%*i%HwF3A3hp6s%|eOpkXL410i*p$TgitEKauV^gp`mM|^F-F)|NiN3KmF}$U-zT44p|dj(66E)mclIF z2;nEc-ZMqMQt6)}c&{@Iz-mTE>s@4|?=pa&MY#j)98)~5m$d~ZXwALj*TZ|0|Gar1 z_*Rj7sVTp&iO8z!={Z z6@U_xIg&neXiDr90%@SGJPM@LM`6nBsDlvLD$dvWCb3^CO(`$IMZ=*h@2&8LDA~#-l#yFg@Gs8x6h$U>yuA_DcO{; z#bt7O3Nh9+ZkQ`86|iu1tu>=c%X!0D6g!|gOFb4=odsYKT8#>{(ze9#f|eCz*)*E6 z{Es5#bp+Nb+Fx2%fh~^Ru-##8TSs}C*ve~r&fsB8+Z|oKTV9a|w^vb;R}mtrKv*yd z4WKLW6~FL>4`m4h%0pxE&QL9-Gz#^Kl`;Xizg#<$kZT}x*5N9@33N3GzPf;uRfqZ? zuB`OOpPny}yJPB3;gI^Y2oHl7{h)Hx$1-CRaWF+{x;se@u<}Gwngf>Kn(9?C7+|Hg zTg9`SE5o*DYlmJJuF|S|6Jqu?t)5O;8SL)AbRq7rHhn1vzxDxOMf>JgKR|qV5Mewp zrE_BSuVBY&YDejw+6$MS%nMqdGSvFGJ2G|$ssl(XJ8f=u;S&)SDNBZjQiq7)$2Hzz z5~$*(agwaiVpZwIyLV>|Tz7~nXj&-Hf>|ZJ%tpTWJ*|6fz=Jnc4PeRZuKnyree3G# z1I#mPY6ZZ$I|og6=tMO^ws&Ya7d_rZ)J|aSJ>DLoa#c}5vLZjx`!SItk5~e5aZ^Yu zL5M{>A-3Yms!~%$5xR3fScs3@AkX>IevnOHg`_Lts<`33lh+J#V(s~Q) z$E^`?J?)F;S8O+R$c!_8q}Wx7!}3{l{DyH{O9z zDKF{XJ={vh>TB&p#NOJ`SKVNO*0r(RvJ7I$n>32b(a-K8s^|u@fvCLUVTxCj8sz#A zX$e(?RSDk_s23>(iQgDkaa9G4mC6uRK$9IS4&qXxuu4{30=gq1kIMbjvYJv{J<>J^l@w;~@E@Okyj&Z3c|J&JrDdm0eBCE4 zCpw@)YurX2u}tfxCul)|pH`OzlhMsaSp#G(W)0oxnXFV+Ul=?hSJUCmw!s~`LM%HI zpe#3dsJ5Qb`-9b{)(5NI59k=1>hUS9$bQF*+1-#^FKXXgo)-dD!4HC>Dnb&l6k*Zv zVJj#rQYIRL7O09MyGk1HN_0WOVz*ZjI11>37lg8)^8&&O+QWIArvO;hYU*bh+2bh1t? z4kP!DJaLM<;mQ*mROSv`DYP<8)ZyxR%WI>njKP$cgx)~zwT?Y0`!3Z~$59wf{QS;? z-}nRU&wu&$k7@t>&CkB~!3ST9Ie0K7Ir#w2Af{4^_&zZa0?O68hjks*BTwe%=Y=d# z)^C6N3Z)=-s5%f?x4S<1=$Vq^0BL)ZE3)VNFTe?rtD!b#)ckS_Q;_D_CboUeGIU zaO-Z*4eqW9RSd&GRw0Y4a06C(+!d0cNMMDy5!TBYf~D9ACUB`O$Bul)g}|!N4q`$V zG#-I5sG_;;Wi>G9?Hlinytsf#=1ug3h~P(otNtf1;(B+e$1Br{Urh4M#G5|&)yvKt z`2leCK069=^a;_0ypH@I0H*#Nd|Z(X!K5sZ4UMPTPFKt5iq4Sn)sgwM6R#<{dMEre zCgJeRy_2aY>yl?`uFlLbQv)wZT>bQKpM2|EKmIxG$KU$(AOG;d2Op#!Joxz??ojJw z3h#-D$WmPxI$G6tbad#+&|4KY0N^vNx%532lAB|MmG z(kokLxW!28GP}ZHkl^p$#SLT);No~Tj&`uQ3Dn@v$rT!Bam0h4;ZgsyrFcG97AVUI zb6*Hx;cBJ96Sn3sz;ek#TGS2h%4T#0Oo6H(GiWFC^n$c5 zUO2I3%hokE8zj8c4VevrESsBC?u??8=*C&)6_N}USnr;Bbw92hUlK{qLTp<8qK1y| z09n$s{IujlUD3t?9!hu)hEc!+Tb!}jDU7uP)g71)Yh~Mu-eW=9GT9K&`o@TcH>QJ` zP>sYQv?Q4CWGzJ%?1s!RzmZWwF&UT!)no`|MBxQck&_ri7>YUSUok<7>~eHru>?)3 z3Zi?(54vFu-wYX?kQ*ql11oxB6tf_4H5KMnRyyW$^761BGG^As^0t!I4HX;PY#wg( zoFuL3+CI_dfQ_a%20W@M+elaA+^Mf*TvhA_MVCr;l~?9G2)n9fMry+DZ9kgBY^Z6F zp}iB|Dtc+O(%{2~TF|s!5meIIb;^FK;y_9REcHNy?ckLwTW=110$gc)!bjDm54Nm) ze2bUO0>V;To`X7pZZ>N}No{;|S`7Y+I|9x^d56F{^XgAti+^WY{dR#?!1lGz4h=bm zrS}tCGQ>kzL1r<;b9kN-J_n;=%OSKhps`*6tZ2aR1GpR)q^!`pEbd!c|DxeZTITX5 zgkMx#YHReRQfX_M4$7bQk?J@l|64cY-J@>Nt+Xa=Dru)^#N-lZQajH*3UcqFX5`G0xX&gQ<41OwzEDcw-HVUT`8`@lja^tt_0km>thS^l2T(fR#cQ!WX~7~ z8Rrj3$fjB>kRcVZ)k@PH1L}#1?g`*(_oL44gq5~75L`yHGhqs}biJs!?p=+Q9Ok#~ zc}9T6FNT%}L*99K)Na6O_jL2$SmSl16D=3*0m-~r80u=5Z3BSy`cPGMRVgurcL_mQ z?*~74?guM(MFe~M2Yb*irOvWK{d;HUR?M89nLl@+g2;k;KLf@ZIy3acLvK!BBFI8) z-}$1=QlC$FKfwCxKDhz zvw$le4F3em0Og+uXh*;yp*Eq;rgZ&v^lyg~|?M zJ+UR59U!(ySWAE_$%PDUEX7Rgh=wPk@G>hQRdwmD0y<5|ACR~H)w~J^gvvsrh_6s1 z;YDo)g_UU%q_E;Qk{V`I$K)q>c=>x#R1sHh_yT7EHctF8-ia%wx^Hd+UCr^*U-UAG z(yaL7R5YIy|JpFhB9Ld=y!gsW^nbbR`Oy=Op$TA0#S6DD5pBxjGzy!ypF3h%44` z$W90%ifND$u3`&JrQ#hgWJPh^sjd*T8RWBBVI&udBg7>I(&WM%M%aAAS3zmnv-0CO zpA!xEA+JuI7u%Q|6H}bk*X8Eo=H&%UAz0V2y4h^_DC{M3I9`Mn)8L**-EF`csf@tV z5NE=)H+)l%gIddRN{!C+&#O#{jT^TOjD?UyNS9$sNZ$C-Qdemmo@N-rvoP@}6AQ>J5*^1XaBPN&G6<1~Hso5KoFrOM18xLen#z1C9 zXi#)sQhxD3r^Ura47quFQu*>A1$Yrz_#!(ozO@bidH?7Up)*P>cQPCiM^y2pBFuPL zdNJ#)=;-`$DXUvzW1gdUH$lD{)Ar;jrNM_Mul5J7T+RGeNO`ue3)7$zv*48zXL=LC zR>ajWUq&=nDY9A#t?vGzyI+3kjDjHvE0`UC+QLkwvfhP&n(= z7oR>fGiZ}ZhXEulKuaGAEYKA!hdOR%tE;PnQJPbSREQw55UB4cwvY{x3I$mRT{SDn z8nNNg@!*(g1+;MGfSHQsw-OkWpajNPzk(pJzHX;=2TwXGsBc$b^E7o{S=O`Lw#9=^vkV$Z+ta1meCTAGBvIiy4 zotu>z3tZuq2W(YN47KB5i#;f<$)m>KqJK6tp*0)mN=}lNyH3$F4L(D<@?sh!u)HX{ z%=nkU%9Is}EGb|=>X`{(l{}FhUzs!p+Fk271lAMQUpzcoX>hKqr|yrj$ov)xGnxk1 zT)DDk%e`I$tDpYzjibZE*YDivSpZx$4<9|+)6?JI(|_^wZSa-9zlR6mMaI(I+`tu^ z<=Z>j8)sHFruJn!+^lzrD_C0Zyfh(7ki~ckWQ72*ek(5geoVAtpp{+&mOB7mb*qpG z5q$dv@I?b&u?2A9V93g$y6`CSa9Jr_crzMihIj;72+q@gjTJ=hnB<$@Zz!lj2(ZTc zP_09=L$~7rIElg{tXPN!UlC{EDz-KQNK{)e9Y|PaEP5I{-h(C*S%8%>u<(+poapFj zT+;zu*?AhA+lYNdV63#lyu!@9xHxbY*lb!#Q%!k-tB1cYA_S2T!cYFeKp5LdnD>CJ zG0z|kKH==-zzWSOL4N;R*M+==2g2miq1FtB&oXL|5a> znjq74u!}?^eWKP~yKFY9tHWogt`<_ZzkGBMsJe5#`7z?E_4@E2`Rmy63zuDy1B3l> zC}cLInWfA}TtR6SwAZB0jLt+l92hty4*UgXL_q7!2@}@WQ^GTrKxp9$*fPLEbs9}H z+($!P@sWdo!V=EHbOpRD0t-Go}_Wy+}ira zo#ElZ!NIpbdq0@C0%7@^Za)zM9;yf|JX!{Kc4o)TOD`-2vf6$}Wbqr%clRH9>8YiY z6j^@tIfk+XSy=xEp+#h^`!PLI4ut_%kXQ&fq^w9YACj*$NLV@;CQ3`!{?RQ(2y4|p z^nC>n;%6%7M`8q7NR>XEKt=}40JbtjwlnY{G+eMHein=fYAf9cB03&;l8)qX+U=7$ zohnB{>F?8vRJosl{IxjJE~|wWPtD5iD~{t<$jm})nl4OBOG?RtyOxzYqr9o0Z}GgE z+?uYA_Vx}$S4US@S7&EuO+hX%#c~rjYtA;Tyd7r)$Ut5Y?m(8B4a!)Q?Qq@Ich|k{ z(gjh3IsTUTBTez?9VqCCy5cMM&GDn;UB%YwVj{EfLswq0g0lv=x_jo6>QV&Gf-k>8 zy1ELwdTi0c*8b|Aqj#FIe{F@0@qNQa!U(D=j8pW3m^F6j`r9IpQ%k%b_t^rjRd>&H}AY;-W8(2}zuNefNz zFii=p9jdelEZv|539qwZM#FEP{V+EdDX{)0vd}a1pbxrNfGg%ed^00z@TZUxjqRXC z!ceiYq`0F^qd^j)t>k_}jMK}o7iOLr)9Je-&jD75viRhIn3QZz7^hZ(H5Z>&o{(tSVJp8M?Z9 zY~i;TEh;VTIkxodAd=$sbN5bIi;_buZ1dx}(8VfiF9|JMU?71-cp)K%bkwxP&5O@U zZaXqCz%H8K3%WScx^KedrP~ErK7N~iE~${A^A&htnze4-<~mFru7XLLlcQRT%q677 z$_{9YGJZWf9(X#W)S_F;d`Mu?d7u$*$5r5d-=LNvuKpLYzW=oc0wV1kkpWqOqnHfC zOht#Eq+%FGa0Lmv*xV<@LtTx<7x+q6_{km6K@%vkXt&d87gS-q%WiNLS~zQCeqJp0 z%0O8GS4re5H1{FUklfUj+fx6PpFK1iyCx<{L`u}-uidmF{7}l=q8bmcZ$3H(kOFs! z#)87~LX6QwC~xEN?I;oATQ!zbi~uV-w*46-LZhy1AC1y!aC~SjH>b%~2AOjf{cg1d zI;{b&4xi~YuxbWf4TG-kG(Yz3MGH%tn|qFb_}a;uGlR+3$4mQ__0iY5og@8rZ?2naWLI7 zX5M-FG_H0Md36YVF-h?#ICCc?o5J$5va(W%D^#CLR=2koSlYh&v#$X0{}tG(6B(Vn zy1)e}g0!OR;0#pJFEu;3)nkzQw3&p~1%4*7qZye6+thR?t~z&&QW|`)(H~UB7h8(e z*2MfN^5B{^S61Hs5bh_`73hkpopiO}+r$<0)!@nVpT2kX+^tvK8eFsHw?t1$mTlY- zHk;Q$_L!o5dF9q!u=3P$4Fm^z1}1cMR%p>7qd&&06tEmo3G~ zP&fZ6Wz{nqauuha-|Vk`4N37ns<6`Ufw3^ugcTrtGSC@CM1i-2u+(+{N#Vz$+CwD) z8YoHgA1lx7?~^`c+2_uSdMUH;;H>k+d0hAr7HM#mkr|UbD-V|hy)-p>gdBwgAUJ)bY=0DjOd1@NG}!alw;x;B z+ymL(bL`~#kKg8B+zK#KfZIUKRwLaTYp^&?1_6?!GI%rf2}*-pZJYiNqO#%ps$`Iu6P>!`Y5UP_)h#`8+oO9 zP;Qv;^;olI%axmFKv&JB%|C4hT@hADgWrZ~FYWLBUeD2^Z=XN+#pjnpvNzVaHKkP4 z=Jk2!dIMJ|S0CK4;q}WmZ{9p{5ZUk`pat3js^E$Nbsn7wElKH_DRVa-X*+`UKZb(q zqhCx8U+N&O+3SHTV9Trxk=VQrkptqQ&~gO39B7q-wOBWlV2y{i1CNKYoQSR z+ac(-`^?7QXEql4;Y$|E_+f1=2+LIgYP>FCp*wH{93uhHa>pIl! z+S;cx_4qiAQ>wCL4KH}4)K}p^m8QXo#iwFYKv%LExiO9MDg~-NW(H_%?%eE(l7^=C zt^%u@i$}0;0vrbULL?;6Z9uV~b9Tg)I1IE(wfHPYLVyd%lEG((iKU0a``3v}d%!-qo2`IPuUC*M^C)1#KZN>@huj_~602e;oR-xA)?uGanqjvf&`0MPPX{83sbU zrbz}v}4Jp`{}UmMTU^pI_fI~z*UC;o+z|PTRBF; zgR*wg)M6@R^-!;L;_~$Ob zVj9GQ@;$7KB^@c_sCEZC@yXBHpKO}oCxfrJXbr$3SIKH*HqEd@247P{9k>dOi|I>k zj0LRX*elAu=&bzW;^gF1bR*B*SYBSy&`{LgQDAkqVY>mFk#u-7*gqH)CjO|W_*nGX z5mF*l%Uv7%_#(6@vqtiuX=~sz$Y*x%fx4Qbbmcy<;=7~M*523w8qrGt6jx$u@}J&! z!{c{{deOw!+SBvK8%H$@zD<*XxO(H*$q!E-A3lHUvenvw(R-iyX*FHAQGho6F5v3* z8y}*nMq0McUO2Jg;07W~40s@m*a|M_DruY-Uz|N~1RJz83~9ZzY)Qs;M>9p+9ZbbJN>C+P5p+enot}frHEbmay)AyQbs zO<1u`UyOHVL3DyMDBJ~C6ju!P#7i-UFEc{nxJ7k}%;Ia=IXC{n?~abTYVh`yRcZ*u zmbb3crT|}a?NW2MG>7&K4ii>TR|`N_(Cn=}k_1nl{~)ll4J2JYwWK97t^kKY#noZ7 zE-S2vtnN#9uWSIaz-1O_cXT+jbZRN+>d2oSotHoB$N&-|UfQjN)8Qe&z=14|hXGW2 zDqN>aj&cAmn56I?NLu1$If~NEg-D4zfGeg#lz5hylC-2npo&RRyevD=gQk1pioFaz zej0cuvUn(zR7itV&V^BYW+=WW-$7NhAi|Zt)F0)(84wlML;_q4zzfb5zt}RvdFP2? zcB9%C$DQhnX^g{_CJ^p$8PLLt!3pHSRE1SG`rJ!a7d16?CAh;%K%Vm?>GSehoUic~ zXvL~18-78A6{8-l&u=!@dpm{_DLJ~;QqtLw4uk2=fbLf#s!S@1g@%SI^;&g`-{ zY<7JY%`QF`6!^`d)^606fsE>&JAl=>tF5G~=C^x+tHI;v-uvRyn^tRbK)kor)!#QS zvckh+bCNW8`0j^^#8ovyd$n%CWL@JF2v5sG!xWQ=Ootr><+zcrcq2%Qtfk1JtMz6E z%u-2*$WT7ZWd)7KI=p}?Xe>MtU@gE((1nMLg=w>cwmZ<$dV#hB>pMIjG9!xpZijgH z*v#1*E!vZ1dq zm$SMEWA!y5fCs%PAjr)P-~pa+5X3v4Rw>~~zp|GjD-vbK9Hq8$#@HcPiw}lez$&1E z#xmDUOc`_P;n7+3F}Z?kYUwYTy^s2m6@6-D-5%;!Tmf0F*ZbMY0Cm-K{Nl2=hlkI9 ze%Iz!6x5gCRuCT^Ke5HdYO>(#w};S6qma_KD#p-FOisgipideIXdwWzu9~L&=;`TM zb7u^+RkRUU>X`oN)nDvewlva*${Mc~Il@)QfW#G_z?EQXGl+@`UPTr%qE>fa0KAOM zVgn#W7CTD$y+SQ`f!1~m%}z4%ou@(GPe`ams<|x#$r<$AVUmKbBqNHbV)hfYr2;-2 zFSfx;AqVk#E72*EJuF;wA z`u_anTq{q5d?}tx=n6H3*3Ca&>=u<&n#fq#%#!obljlEs@A~;$Cu%yamRa*-Yu#2y z<+WRgtHX%Pzdy_0npmC47(rI|jUQl$XN^sKQcpTs0xjRp_U!nXmHEki7_=xqb?SGL z3^~*K^uA>{9s0?i`t16(>!hfoz%oIis@n|q;s<<*0ncP;fc2F6S$NPc-Lb^rN^;>+ z+70yq_28`SK-L33nh9w&jKz4i0?RJILg=Yb9>!;g;)CCW6jVGz&xB+ua+h9PPpSg4 zFp+~MnVI2b23GdTX~}&ladIaw-K$2StCZqmlyP7(Y@7?(jx>loSVXg`)0IPn01IB! z<%%!{5+r^_5QK-jn*p7G%>WBetq{r=(WQ$+%nnFV?SXxxlLp66uZ8_#1eOvOgHQHS zAtP$XOT@L)1V!`9&83O77;r!wJa+Qjdmn##&BHZm+Qx#o=;@)wtFvYFmZU^t3akZ_lx735#Z;IBU{PmD*^oJLt=RD7D;iqT zsl}y|1QxTQ9l+W?sh(DrNx2V*#0v0(jYg3rZi6tED0V!hUT6@Np$HSYLhzj{*C?^r z;h@(*PZVfL2NsvON6C4CRCp*UwKy$aZcc@2&!c^nf}bjm0j@AOu@QN&0rCpwXl+wd zdxy94I6(^NN^3OcN7`^DR)XGr>CQnyH@H{$Sz-}^hu#^WzeVqmLkP0W<}24XaT*+r z5>8rzz{;Z6;pn{*M3ce`z|zkYT4%beTHko%4VYOkAMKyrJa}yQD%90w{KdH`0Z|8P zeEXskT;(uG)&BlP($u1bh|)v=tGXFc#pu7q9{2jhk1yg3tRLtaFO z2hWFMWv%DpZc-P$EKbWJ=^3LR)g89F^Am9eB}BdgVS%MWi7o;wOq@~#QzAj8FLALZ zGZoUoQjARt)BAFCd;;2iS_U($;3_^fH7gSrFrk+LbVa^uOv1P`<<+c>ctKuORDi9p zU8bn1y})%0zyPK6h{8l5Lkc3c1U7;b+6Z3KQsOL=6(A}_pkuTi9a!2qN^OOQY}sZn zL+6t5qqF|F#L5;HMV7_nKZ+}PF%@#rmAND!_(E@0E1HiHgD0z392*|K`swWmPbmPE z1VqV`rArDes4OK4ytQHYiC;~xhEvRaJ8J-1G;l+DwoAnZkjDY39;L{rDT3d4j z>9DXkIR%a0HGk%f18C7gd&A~sD>CZEgGczhK#Noi2aP)ZnDrf650VZ!y~CE$r!Z#@(6TfU~Za0rSX)PM}SslWz536V;>CVPZBI)kOe0)?%57FT6Qc z0GeT(M+Y7n9lDCmb@Eh9X)Yvw2r08O&DDQoTRV{zcmYhWj}D(ZpL6{B^}pPd zVm1EIw^JzN}V@Y;vqDDstzT9B%!;xTH0BLEjY{N=gdthBj!0#_~(77Jdy=^o)^ zZSSfroIX7+B{MoU^RG3XwaA9=zRR|mXZN87BgkSr2_%uTUZl`sN>mNM8IGx-YLztn zVE`Zg`zmg~-AUJhI*X5GR9Z{8zFS0=eG@B&s1`;BfUE#64o1^#Kt`N|z=;qRDQnQi zWFSG2yR=U^gU7%q;EA}BHsmPB`aWrw;k4>ZohOvx)Nr6mPXsfwlJgr;8sxx4VPSk4 zGGPje&gwF#+ujCbQC`)qZt4o5XW%XcKJpfTBx`8#QF~v23}iI!vYjH$GR|T>@Grt= z(?4oDl6Bt^HysJKbWxG#YokL~8FLA!5&KpPI0_`k*cK}Vd}zO4;Gc)iwsLghI>go0 z^EX}*S*DNN0yM}V3nEVZz8AP!u!y+As0FP0W34<$%A`dPMlHJgKfS^XNR5RTNQ?c- zvSuW(ptHTNa=Kh4n%2}()858h$bPK-%SCAUInrSr<-0i^;wiPA&El3iuw`N=^t;xi zso>Z11N$9t!=W4wb+Q7bXuyg-)@)XzjZ2D8pe$;vNan&a*bEso-_3Lmv86BzW7%0( zCQGG|^Yk42;!;Rp3RERy^)yE_1gkJGqT-5E^W)^MIJ)gR(A$ z^qVa^zCSv2)y^#FG7`iP??mN2yRbooyX0G^PG!~AE4NPf_rrXD@4YW>T(da(O9?=h zaMTmMHY92txMFwBFn;%7)ySv?rPxb3WtOh;pG4pLUDzc8L*)5uwHp>%+!!2SD%w^9S8QI8QjSao(!v7o$YBlyb^lg* zozt4b*EnakBQq$x1W=AuAPiS4U?ffgstb21j#ugLqzVBbja4+ z+78wtsMIG_2K)1^GoO9--sku32CL3@Tq_=^S@7VA3ulQcp(||$9By48qZZ8=wHWNd z2+wC9yrQDr%o@^ekf)p|ozPm^eu@LY2l7)-W!Dz8z4b0`&E$%ZXIH@~-|j%xrk(4w z+fUpqLJQzh%K>jAz3_@JPFT=&V64X*B-Rf24&pelVhFo|%TVEJAQ_Hju@E7!V%{>q zLMX0G6RE?#!qbfFL}7q}f}JjdOh1Q9TihTv`M8T zF~-)_(Ux~0FNH%qB`rm#e*4k>KVXysUGF())C02Acko$@dj{4iZ{+}FkXZy5(IpC= z!P+5pyt-MYD!q)`j$oLoQOX8oyrACcH;}V{EVecTK)W*nU}Z`RDbIj3NcqCMC@!fy zvxtLF>>K4%mbuF~;Z*L2#3vL9>ABB$oCc?*y@jbk&{ZaHr7uKRUs@qx1)Bk0J7l|< z?QKF=EpQofJ)Ox^YD}r?DGrs9Omxt(fDIh>t#MAW%)#B^p_)43NTa)cDTk0cb-Cgr6R zr=B{6t33vO`&(QpLSQ}n;`2|g$S~;;M*Jpf_&U*AKh9z4P+U>~Ob>>piH6Ue5Lsj_ zw3Y%^OCa9KT4;EH#*zWn`bqWnNfcFD%NZLWnJ|EKh3*D0mikzs(wj_rLX?@6ew0|q zh6I?5=FoI!V*^*N1OG|r42#H64BCS#`zFs#V6Mu1F(iq-a~7H=3ufGupALcgp0r;u;AzM|8#Ij zXL5dOOw6h5wx;a-KOnf;kL$VDF3ngP;7Er)tHdh>qL>Xg^K6Lz8Tt-7xuZtua^Q;H ze?XOZ4ojrIBl9~uOqa49URJ;)uB+7PAZ;FH5LxU$&?z0UNU5&ygEH!O!bz4EvBw?9 zK@JlNU74G6be<6Cnp`%?Q6GxVPtA;v2BKgz$izfrA(ucxUIAAd(bHGH5x81San;h^ z)a5NT949<%ZbTMY9X|kc1Z~=MEX5gTHZ*X4LONyyd|Vsp#Z)NT>VCV7x$T)N+`nVZ z8>PnffVq_I2>t;hyiHpJ%H&>K<`7r-Mm)Y1P`9{_+`#0h^AKtr@X|L|OdO*B_~7f; zF41HVTs3oq2l6TrJ*KQH_Pl-k>66#*oczmWs~}qc{`}i3u7T-58$%}GI6r9%4sJ`1 zIWEI0! zCL547*EzEb%S|hUW^0kL+=Zv)w{YvWRG$&5+sAe88>Jn652gDGuyotU$RH{HdAF|o z!4IB$X4{Edx8A>d1qHn=xRcW=*^dxn7^&rw_~6|Op8!^x1z(nK!0WAO ziKl8uz54BwpPjq&@x8rrX_!hZwcMEnJ&7@^L6#RiWc;@@F3`7SAbHk6`RekwQnUWR zWTSw{&uQm9?Ylv&*V5oI^HT09+_;9NXN2~h z-Sw{vfu-<|!d?5(0gy3BV0jv)$RkP%bfVw&=>Z%kIJc-@C)iAI6kDq++ zz0Yq38lyi@5zTk3Q^uD~8kO%;mY0-Ay?i^{lKYM{WcQ`!7k~7JkH}cqID?Im%b(m- z&vdAk)>?`zxjz%Y0>G%`r54SFAwU%~qSDrK5*C4_wL{qn4|mLQFhpgCG-aCn2rD0B zWh!N95!%e>$hmN&09_Uy&cQ+j7WWrPPXqTNPo6n_G8#n{S7Dj?C@K(DY`!YYY%DBH zO2J_;s~8Q)GBQz))~ga2S4~ZrLB%YWx>4?|{oz}}T|fod#gmQ^=j`rtG$a#zq^pth zpr*n9m{H}r?Ut8D?c$Pvss2{r3BV#{p<%}0%H3-VaP`b@_Wb@VJk9WDhS?pmecFMn;#iah5pi+If~*b-uu#OA zi`FZa2HAU6)B>9UX^;pKqe1Y5FRST2)-eexFA?X&mEkL!wz-?(953}Hz-lz>nFQ&9 zNg||nKe8RC!O>bOn&d`fl&kvWFv#F4i47}pZ^^dbtUTR~XqHCgOD7&*xpFH=%O=M^ z!%;X71`}G^!ta~AYwML0L)D2o$=Yn_>N@C(xGL>=d)W(vM~^{W1-g-}gs*rMB*Hkb z=w;jBg}(zrJF{$Pk0fi!l1z_~T+EwirX>{%vY@kGdwT!#pr_4i0R>nC8rzo>RN4m5 zU@JVkw8YA)Be0~UltJ;XTO~nS*!+i<9Iniw#;OmPgfE@#mkxM52nc(m9186e@0^4t zWl?LufS|1g**UHSN)-5<#2W6XFFS=ASB<0rQ;!Mpma zp@rZle3XqJq^%7ruc7e@D{f&`z06q)H5pX3w;nrw{Pf#{$8Wr1wel1g=%SsYE)nF* zT_C76Tk*AJ>jtM?nhud05jOrif#?jZ3CWJ1o(^bb@zw}zZg~EO&$B&w-Oiq7!#VM+Qk~*T=!zc!F3PHjy4fAxC|Vg7(+VT97N_TDH40x*UBzJ{mHU|i zEXXU!_T=(xsSP&NGSG$W3f&}W5Ma{K4UJ^Y<&Amq@cX@s04p?!w)Oy3q${?>CsuW%8&Hzq$}N&uAl+71XrlO_*Gnhm`TrfdjAM?vtk(JRQQ-1h6z#tTL5D zb38Pe5U*8&tmT>xcap5M^^d+5CZxHwd+DYXOY0e^42paoOK2%$ImT!x-mzHC>;u6Y z(jWLsb0NNE&HFUHvv;yt(=dT)aFT|7a!PR)RJ*$Ene6E+1getgiY7x`!D{EoL`4aw zP+MBMLafe0NmNo22#C;e2PL+kH?hKJH zX?EcGP*m1>E+>`!AYd#6PlRk!Cbm=?ah!tHXNC-ViPZqLE_z*7kMc|JCFI2u47SJw zEfy;bQC69hQizpiu-m~`$b+2lVr?)v87>2Hg|SL;8H$hwn>tG(5TWiG6j2i;NWmeC4f$VV_mM>9fw9}!oS{Vw7lp&}TFiv~Y9 z-7RDVp@gB-pZ>DBnOnAjmk)11!*AVy|1Mm3CZs#6v?VWm`~JSaS%I}+LFuupcUlug zTs0s2WK%zuWu5%XT}^|5lb-U4GkbRLxjl5|8cvqGcJb%gM^paRn@8*q zL^V-)S$sR%SH}lUtUQ33C~(#RV2d|4;Ue;!6_ND;imV5|F?(swIu%;xxtUX8+6=Eo zsi=6K4)Ksy8o2Q&>R`G8&_Y0C69oYx+)WKyT3qHM*yl$hi*!XuX>$YW&_onlWwZf{ zV}!C3aw4D=W_RE!G&3oSQ-c5&`Zf@ajgak0sdTTXugF(4+lv}l#p$Z?1Uyuqv!R`+ zvH?;CUU*klB3p5WP#DYIku43TMl37^mbo}i(%_WNeHfS+)hKg%!rd}5=Oyrks%FH?zvRB!*4F04(rQHa&|#hq@qg6QTSBF~QWo|5gwL1n}_%A-9^g6ueYR>M;w|xU~w&| z@wWwfbhdP)VP#qRfdhr8As%?`X{1B&*7MJ9UXM;HKLHl|;g{ac6W*1vuEnO4WS^yPQmYxua zspZmHx^Lf-eJJa2SZ65`UI34UV}+@x;TaI`K8xq;z^c%dV@fqcdmH3_LX}pi<^)Y- zQ-iK^&v4My{J5m7!bMI^}#T89Xh1s5s-gXQ+*Fs!j*ck&8>L1RbQWAj-|%rk=a3X}}lWwI5!pIY5`R2AU3c$g2YnBMpvnjP=~M&7E1$ z;EF4@SAGsL)QdwM>U-CZp}9qlb~l#ynwtR`2< z%LeAxa# z$;=lxi)I6QWTu7FzY2?Vlo~_hpbcXoudvk2G`HtvVLuUTp(r`elA3dyRtI5<)&$Cx zIOHi^!XQtp+M;^Hi5dO^u25nn=7>CmNPOWcRauT}0`!7I160i1_AD1>-VeXg!K7OZ=KM!NE+lUS-uRq0)$T7y?67=zn@8zCT1bK>I-*Y z-@A7&H9T4XT|Ba0%56*SOnNgnA;RX-)m4;&E`fO7_;%p6{U9wp9sYRLG8T9o$lAW# zbSs0l0?TGoGZaq^FB`R%Ge0`=AW=nc-kcIm*QkUJTQJNncjvZx(ADV2*J>Wwz559( zyW0(6p#psEGXSd_>b;d2t!J3d`RBJjJKnsIoF(8o{Q*{7(JZxESm0rZ-ZB+K*WmY0 zSCt}%zKlZQ$+OFj4Gx~f`WZ6;q;{E!2&i_z=i1Q4TYvjNn&a8PwLs#-8z=T606qT3 zQ{hJ%4(%&Ga-=e;#u8D`)skHqG&MHwKuQucJVI{8{IQajk01--w@fv>!4;Qw^JIvq zqvxRQer8rndpwT^LIeAs%{v4nLS%3B#oDtgSMf z$DwN1JQ!7ZAT2XKofm4+ZI8_?WO)!SL$S(s4m!hZm!dNVQeD*pb)bl@r=&jh-sRVr z2>Ahuonh)YOpemKjP$2QgJXEY*;I0*AJ8M|t6%xQ#P}|kDY!n<$K9+UcfP;5wZFGYS?lbLD;)1h7y@VBTg?LPm^~t+8_lk%IX}J{S?|UgKGBs;O-aEhQ zfY9n}YB&%yd3xM|6y%mXLTf)3b3gs;x>ZY1<};*))>4v|o(_R3ZgwD1N$a2P4dFLU z2RQH?4U=slE9f{Fzd`&fz)F`Gaho68W@tAksK{K*hnfWeC<2SZileFAe-#yJU}c|} zN4kooyoyhclM(uq!Zh?U#OTPx3`|V4Val0BXP8$B7RhEZKW|`#501HJm|6sxg!xt3 zTO_#Ri@+L@?%MRgp|FvDhSmGDHaPn6eT=|Av3vKPM?93UbRUl8@`ba#>NfoHm!%6H zOZ?*FFTVKr-0`0N(@UxsDrt3}IZR87G;NB7d<7F=rt|NEi&d?_73U4Fp1f!JkIjBS zzU0l-ch`n1hcA4RsFEE4ToG803ACzD-vzLs;CBT^MEG{1A8En^>pMdNQX$q{b6Z;S zgF+|99zZ($h#H=(g|B}yckN+S*Jr$pTjz9|a4^Lt6*qM<#W;#hEmH)O#{r6Eil7^V z5X6~=s6k%RGIdijiW(&DAju_Qvs@~A6vTr@sR)B<(-f4PHqFbnXV=f?eSe2~_Uw7~ zSLu6xzu!5awuYZR@B96{w^x6@Kw@|$EwqO*DQyT^d}FY+it#%j2AT9tA+0xlBHN_7 zBMc3(ocxYsAp{2?g8I8=38fZmpl+p1k}lPrEVKxucrrT(bV-RjnkUfbHG$A1DC2XJ zD<*M?Wv=<-(^5o@P zr@k@6O}WYkH>3mrYh7oDwA%}?Ge1;>GC7!1x;P84VpU(22dYEG$}KZ8HQSXUht3`AXlnXPS7(6HqJgKB=Fk<| z@Ew4~w&-jNXV3_+vSt1xlzuk0PK+S3A}6-(B4_yrY@&*LAm7tx@sYx5Z#^Z+ZhyR((&!RJYmA()`{3>0%^Cr0KmkhOxg<sp@K1Xyqe~ zIJ}j%KtT9p>+FcmR$L)*4FQc!`^CSpw_mISvcOuA5gliDNu))0XoF6cSy(phKtcZ* zB)oFC!;s-aXID^$ub>DIU&tW-)i;#1G=}fHfSGDBDqG+yzVUeI>fd<}{j49n@$3Q_ z^~W+&ln&4A0w6WLyMsUl%+gTkXlmR)%1z<(1Wz1 zBO@k8oM~kUUter*zq$gfMQAmj<@Do4$Q?qm7kN}+!#BJHredBhGl)xWnFE3;5C*Vn z91eRP2T($ktv`Rf4kcWKR%Ar``NMk!Sy)*PU^VnApBY-vPyn6OW}8x0loK^PFdXX8 z3~`6+1zD?Jef1}^HV!nPg$&QEXXy;JP7AP-#xNs)DDIGt4?tR|C584rZC27ONTe%S zia=bbND4!crMOx`OhIjzWFa92zS2fQnO!@SsprA6Q3Lmgz)6W|li&u&0ab)m^87T6 z71bfgAS}`qyx`&&G4X?KgQ*@=t^_ee5^oDX`NK580(#{31=#ov8b8roSsnqHD{|+p ziD#yrt3JHvu5Z`oBchV^W7y=gd6_%^)~$o)&#qd$u+r0~``Rb$p$D=MXssRJct%5b z=h+Q4(Q!!Cz}kCGhXKTrOUc5Mz=C5mj)A}(@{nv31G6bvaZ&^QVP{(n(~vNG4Z^pY zgP*{f&fTnyTN?o*x~?A67#?G^z={PUckkX+b1dOoCSqcr7swV!~qe)&@rDRWX5YG+2Q)T|D!{>0Zn?I~1X zX&(jLo~Wd3Asi*b=rE3Qm(jJuCb;za3FB}Y%*EpHT&WZ#Ut#POYh*aHok^S@QM)Qk zXKIi+9HA?V;sx#x7vA*Xr?_DODL+XKgW$>J+k+}@#neNg6n2X=ic8o^COWw9n*}%c z?OGHW%Z*a)gRk*)h`;m7`K3AUq*SKOo#M8u>jahekB~3i2L7nMj1a!H{@UJaj_6;- zDQVR-BZddEKw6U78K5nz47d2f2;9W+=_envoE&L}P8xKf#Wj#^BCHqz|B283(&)%$ zkVR<0A-11WWWgPJ+R7JJWNckI;d>b$?Dhj>Qwyq~!w(xfDKQbLLj@LhWP-F-KBAn( zJ-kdy16BkUr%6h2sRmjim(t)2vG*Qo!&DUE%vw1C+WSaGSw_)}lw)D?o>nF!wqo>d zv_6x#SkoZmiqJkNTD#&Z34=ssMR-p~D#a^gaX1B;wO5SVL05|lBso~sN8n_UBOcq8 zR7m$X63ecIyaFu~O*qY^Ku8I^F(O&3-0>1@X-^m~_nG&@4SvfO0*12a!Nd1uAnQT1 zM@ec<;G^azhaEA$*k|6^KYb26h{GWQtq3CPr1QqDR%h|rINC%g9+(IF(pwJ{NQ>6 zR&j&eaR;v6|IN1Oi1FF&Ev=20FQ06xjn1~$Wk<%b6{n^P+b|(%xw$dAf(0>* z=fESp6h1zpSt;a#h%MzTiRFFFm@k4sZZ2ejpPEj7cDc2&wz#-?L*2yj2C{y8iqK*R zkAKAefel%sD++=+4*cL$21ZU2vYYT^uMM7< zgO4{2;hAPOiBKg(Rh~QD-DDCPW2LQb=9MfDpw&;JD?mzC=18qfJ|?z*2Q~tw4a%`h zVZt3E&@x*p7go7hteFdkhb*)lzIBE{7Lm0rZtV-BkxWJi@3hz6d?PPf+~LHUw!?FP zEXwenE>j#4Px_HB2J2iZYq9c^54p<4YNy)Tdz@ipM1=iM0B^nB(RHgX?uGF%I>e3( zyWkI*l}3Y5$_G>LeYzqu;ohxJH~87iQ_4yjf+7>mh1w-~N;LwqxcWhu_L3lo2e+5{;CZXW~oBW;A-2#;;MLk4n)f zBX`-E%657biV{|g`bX_at4PenHWN7wa!?-|ojG7T1G`Ij7-VixI=p1|;{abJAdA$2 z@;r!#%tFQ|jkGj!XN?R%=6NKre~6d2zorMZfCh#-cbFatVTR5C^E`qa&Uaz`xxqkX z5Waa)h96@>+o{#FbnN^RzbBTLY`NabAd5!QvNxUi3n{DV)Nv!ylHB2GNLpS9w9Lk6 z5Z*RH7RgC92q+F#H|i_=k1>GJyTo2n@ou|tOgRg{05j0af>eiGSSbA1pJH=9#=;jOguel?l#!OW!`K#PcwCYeO?1+pG2XaoXw-1; zM=6-B9bk5?vsdw~^UFFHXVLT3wb$1-UT)NW#8^ev#Ex^j#2*Hj;Zh6I-`<}&cxy?a zABTAbWfm12fDS)4CJk{GlZR;Gd2Tgq)w3&Ix&!vnkACJ&D5!EieD3Ga>3Kbe8@Ss3 z9`ZWaF!1*C9F#Q`HCaFr6$fks!;?W4fi;2ooOoSE;hHX^D|2L+Ob=c4oiG-~p`a_k z3IP^y1wRPBf_w!(DB~Yb~sIDo)ZYx9CTe9g<#qqNBEwm3AtsBCtD z+m>6Oysz%C7|4pNzu8K$^kk#`S7>#PC9;s!JEir1{sJbNj}n$10(Dvl_=?NFCZny| z*AifZcNFD8^OV)++BMDsXAwnB2GfIA9zp7S5qOS-WyZ@<>SQD{atRDwhP(;*oH;GCLhjY*p{ z4pWhpu97)O21(}`8Q`m#+_r=Y83Kz_kPFhYFjCZz+JPcoz?4Pxbi*U^rocei6bNFR zRgg1x#NA>2`1j{4z%p9x@x&lWS2l-XJKD*;7xqGU^&Qzm`DQSd=nY!PgI-m-!ymwH z^+_C=F*Y~TR4}A`XP1-6f-%sF7~i|G>GEH0HaWHx*Iv!bmOv}EOP8X9hq1a& zZNo#eJ4#I~CR((P9o8Jd?Q8b2DX2hKDwm#>)8Ry^aEKTm>1aX-?Fc|quy}Rj~fmTH884ckbZ82AiVk(k>th6r}!mr-( z5}@@{cHs-MXwSS#15GipxC#J+(Hjb3JMkcmKy4)Z|(fMPcwT}Z|0aQ^qRwT15k?|GB^evYe$Sh@$0DwS$zm&5dM-FLX z&|=Z(oqrbrcv#H--riaqs%Jm`y6=Fr{=F)|Nv08{nm2UQ2UCTtQ`V@RgNW?>28+HEWceh>eU@8X*o_(b#S!qy5%g6 z0}R-tTGzIB&6-6*QbJLrmj{79A(?}TLMA=>4 zA{`+Ki_7GU9Vc2g3R?oUqTw_+DJ^C;*6<>1&jndU%}&;3OBsl-WJ4;%D>%Xzr4gs3 ztjY&?;fn$Tq2;fi&{%20XN}d3xJt#L{Ftcy%e_4-^C!i?0e*j-bQXHcL-z=1bj6zk z3e5ZOzw0}-#}|8;$yctDR^G1D;Sa5zMd^VFscxpy+;Pe2J9#=3)+z>Rt+lsa24!7C zWhpc*vAmkPo84<(3D8nMUL-Dw+;t`?3fm8#f445S`N}{3@y~z#9TJ6G0HB4#q54Fb zn%wp>L+C2Tr zOA3*e9+o?)Vm^RXp)=Zezx!-Y(K6lPg6Cd>A-V^mm;*vB7Ze8>n}zsYPlXa?5lk}n zUA0kC7Nd7j8n`wGswfzXSwif9Rf``siIrF3W5+RUpA;pcsBT-Di?Qt}>ElWqHsWMa zysGr`AYK$$G8#-(D+6YNCPrEsajDFZxF2OTmYk$v4W8a!uS{Mi8EMK4gcVJJMFV41 zqD1DqwZ~JSD+!?FC8rM|VJUd<_Q+3;$;_M)pIfzWzSVZ++Ck%VSezXfk=?SQv5}Eh z{kCFzT^%Mo)H&LlyVr3qqryqDJ2ctT#IBp}ck>wOxBLyr`X`VzZxP!o2r0wRYjNsJ z2O7>mjM+ri_`JqO0N4?o-G00U(gUCca9zadP}{>GJme?uo164@=z-K1Gcpjvr{h_47Msbm0O<@-=f z=fW-nOt^qAiP;rKqG8b__@X4SFD=N|wn*aU3Ht+@&jVTi07lwT!fi?QQ2UBYllY`%v(eD3MK6ibz~?(X}`4eX-Eu@UHk(HC+6&GVQK z!kVmU2(mcCfew%j(7fmz<6#Wl*`gB&zQP5*n&6_VkwY+xVO&_)SolFUrApE{`5h6j z=mwD+TrRa&6x$1nO0W@JrB7nZKfppyXbNzn6C_RPOM@$XjkL{_>1FOiO1<5xlB!G| z-rnnY8h=nTJBBZGhXH0r*dD~iCEvNtHA4vpu+(`gZD|dx`^(JmV4LNL`PR%qC4qMj z^>EvH-Km@hDWTgcV28h8$jiNvM7^=vf%3$;yB6tF~vLAMQZYK2G+pebU8PmNZ}0`HHhnlQ!N zEjY~`?hi+yIj=m-gCUQGFx?O!^B`p=az6UIZiA(VLS^5KD_mTCq(cmfk#d>rB%p&c?>p3;tBoRXtE|NbySO>dM6knfM<0 ztGJ1j*PH+KkAHMsIX!RQq5vDq;i)%B{W1Rhmh(c5+1b(19bS0B-tKhNpJ{T~*RDmW z1HeVgyRZueWSQB=5tK48sbXV_Pua?}Ae$|9asGj@(2)6wP$V1nH#B?-SYh!1cUr7; z)hsiHpSFI-1|W;5dX6foFxDHaodK>GX2q{0s-z;hFQ2YSGtx)_ABck>Q#nix>Nv>> zyOXh@3Ug(^SK+f+BvUan0}JR;(+6B-EF`W}yy9qvqI^I0c8T}X4VL67F30AVYW^-{ zS!76GpYRz;71QJUSY`|{`C8^pUJ6_>pQiGt$f95@72G+&wrT|E>NePH3v)WkS9k}c zyp1wfydIX^q1C5yVaO9hqdY6qr$1@gb*ug(^2tYbIIGBs2!L9hXKwxF@@FTUtv9Y% zCGm_0Oez`}hO%$))R$KyNmo$n2`t*hu8xSSU3=H9n};}ydV?0$XcT|F6&*ewZHp$d zKvH#1CnK%6IHbW>yZ{5TV%s_;h8NPBk}z`rl=O64P{w^*3jnQxvVF-RF)3OzX=z0k?5+36SQtA=cgT&uL>9t#cIv>A;@?^sPs+l}h}>nps>)b0yp~HY zmvA(j(ADr5>^c~SO>sC7BD_MMGn#M`FrWxtkZw?BYnO7PGm5VYIHQk&Q~&@Kpzr?T z00n1KG$T@|z={yVKHh|xg95YW_D{}@@pBKla2mK0VCk?Bts3R+t7Er=j@*0K?XeK7 z5Z3-$gRP8r{VbKGV=O*}e2JvRARg||FJ~*JJCs#SNL%<}&XjJfi+e8R)Hm8inrkvfh(R0N3q0R>lsFkbkS8(Fa#^a z?75;d$o7(q>51@#5E&4*!x5&adIiG5fTAitl^6gk(b>5YTh34TmNJ$k4YjjNj#ZgO zeuJxWqRdqxyN~$zo;}7v8f=z&#a*X^xW*R2=n8$)vBvT?S!fSoQOxQ&94cqQT$QB> z^IzP*B&x`q@kq`loDM$%uu$k(UyEH{jVGmv=f)N39fS2$A(O*NSG&G!CywC%04xCu z`@FPaKd<@1hTd{EF{v-PvfUVyPY2jMEfc1YgA+2Y3z!1i- z=Lju!7ea3k#(GAk8EKp~0#X(+=8_vkypk+Ve2*I(JT_($&w>ONQqByoGEx@KhgP$2 zA&VJ$7KLLQKp{j?Pm+<8El6ag%Q!e9(**9)rW^Gh;s#;nn1m@=nK4Cu+%i*5wm-LL zA6w)C7XC>+wGHmZ_Ee7stg*aZ7SFBcO1H{a#1l=wX6{f=hXWoRJa0x!WXTFJnTnJxdseB2ws+0h zX{L}xWYHnYZ9|pTO^z{@b}%BVzNx9U_9psffvUCRHPVXx`4x~>HIW5LD>eMXa^#6J zwx*i%QE4%#tSF;m#!M(jGaG2+E5X)pSH0E$8>ID%)jOchzw{g{|G3o<B(~@ z!x66YHR|A%vs7mAjJXH6x?MJqj3vRlxIa2-#TKcTx5=B8r4M^}6fO5yJZea#8H{c9 z?`}GQ#(QTC*TOlRpPl(jCmQIj+ysD24|x1(Jc)W0Gsh{&~U*MaU3E zO9uJ60Xs@ncv*2{_8fyLIXTfWvRp>KW1)NW&GPpfJk!@_T;Sj$Z@04-^Rfx7rE?_4 zayQWxy5l98Ldpz5*xz*IU-|wIjNU$g8`5EnvlNiCVh@tzLqw8b^D#nN@$v zb~Y6$l=iA`*`v1+Tyi=*8r#%(vej819hcpFF^}$0GdzcPRjWIs-fs)4=(TdsfhtcK z6Q5t2kvM;BR0S4x^K_{GkofvyD&XJ}9(rxu4rhp60~AQ5;hv*zpGFfH;wiisyGv(1 zK22bMy^Qh$u$GXn)D7bNHx_%tfhzD7dvQ2OCL!mqPt44q%s{by`4ij{E}M5N`*;g8 znE)%8)lIm{LJ>;|icfqKA2>r=8l8uy`VD^4>%iUPQoVdHv}DtMyADZL`a&k5UAyD@ zNuF@==(}#K-Pgw|t=ZmwR$@yvh+CCL+T zy`wm~2U!pvP_W}H&c1lPIr{~QS`^}Af8VXb!xkGgt=y^mY~049^Gh?!3m5JV#l$1B z)_x+Z;m-}90$!K4zBRh<*OJzPRjXfG#m)+?oOvG0eW%II}0+2_y2#$7mK7PfQV2VuotoRZ7{N(@Amm2~BAB|qUK zYh)}M%;Ppvh5;n3Ld%PT(^E(NC^derk9%hu=nB?;VU48o!C2x2Wrctwb5bji!?~^Y zfS=SRo7{6UE$Rm~b?7otRxIv625F5k>Ff|ikJWbekH?yun~$}fI|bfWSmD8^g#!kd z8pQ5;16H)+dVBE+*eAs@mqGpD#kQ}Ms&pwZKf;82Jf)%aj}GEW11%tnX=(e-8;;_& z8p5;U0b^;TN{bs0Jxj`*ZYtH+Y-vp-i(?xM_N2Sw3PdSKQ8v4@H+zS?Y_rP(co8 zi_l8_s{5so4SCDK~E7JbsfS>so1xU#Fd8jNL@UTN*=;3u^7 z45}(DObi?~Y<3!;wf~5S4=@ndr4Ke@ONt9x8=rpj=RcwSY&%xn<76lUjgn@KN{T0( zgtPE5p5S7K4%d!p)IMbQq?mDGL&L(@=^O=IC8I`0cj92=2cvd2q{<2}$vJy4b|Rb@ zqw9NsR$viPz#CyFfjc;izrkmpdAGSF*S&H{q1E@)@w#XdR$bTRL%`L`AT0t*LbA?)P9@osVeLpVe3%FlUaqPK8&(@iX1e^0viEZ$Q{xhx|C0n6PO7%QN>H?3W&3i zl>HgDpLa#=arTz+n8D^i71zm=c@da)i-RHEVBN89n}?u>Zcs|H{Bi3pF%Q@OSog7Q z-z2TrCTHtOrz1NquC667Lfv5``tV`s1|zcgr?J<7cMvSIu%KbssNuoM2?(?REP|_n z%=PJ>X?;ic)Y6RJ_=apoS;f9pP!?U`)M-fGpk8zd$x4^kCyDSrp|1;9@xkMAqry-s z%A7NkIGnG|VYRHi;^tipLH<#Sl(v(vuxAN~!KGZJW}>^Z(si>2%ioCLEgobpU@K^$ z$5_jh+3uMyn%z$|Z~Gm~NiKG7-V98wdHLmK5J`Pqu!4H!_whY<-F|yK%Pb=;-P04x zQnGT~)f*bomY7u-nHe6I(r7fK9nJzKJqHS3$(x1c8#{R#Yy({(Xh$n^oIT?4xY}AL zfYrDnG7`ArxLgGOZJcgIR0R-}_=)OL3Rx+jnQZ2zZKvAs!!*RwwMUP}IzKzvSZ~kH zK7YIh4pHm>TF!y9stGKc;HeKG8aB598ZaXgoVva_%dliU){M18?`$(YIiWAt6;=e7$uVn zSYa9*#;Hl8GYUoVqAIElUMy^o_S0oT-3?=X#18e~j-;%!YZK+T8N$3++kQw8P zdZup2w%-w0&8H8&zLXV{KVAyX`k}8T2=RKbV8m^AgIbVfwwhSiT2`6xZYeGp)$O*v>rap z)8Qrp3&bHn4FX}WOhZu^al9C19%-FXI;9q0L;@9Y4z?k>sgT2d%s+O zbm4-xInpR}7DIIa3sgnM!iNcu-2FY*lIXyws9ca$IQfb-$jLYkrp-47Gq6Tx`f}7D zqW~H56{e}>+azkI7HTH2Bv=Q$)J%dc{0sml4lTz`t;<$PbaP3Pa|ES~JV zV`~mAn+yYGaqHh>GOmHEE=>n|-F`PHz*^3RRWEP1%*vU;0}`!i1ukG|?ocz*Rwe9* zrLvUsKWNG*U!x1(u$pk(#f)~Q1|#SOG4lwxigq}iO^r@xYaPGf{z91ZMyCwh)_@<7 zgrRa-4$mwtwdv|<4=ETlcOEMiV5#m9;b?4h*jukT?Qtq+Nde%+vp`lgga?q;fFK&M zg$EH%40Dzy?k%w#OZmPS_k0r9uh zO>uR$Iab|ZtfLNMdvSf!8I1Ld!08Zlg@klT{#PC~yEHIWJYLFj|fmTsgO3bKH!=e%q z_%tBNqk$Gwt<`UARCg%I>ec(+(QiHT^n&NHQs5WQza2W2Gm&)y$ddSxeZPm_aW{;( z8X1a1U|0zFDj2{Ti!2UHuegC8YoszTorp7#nRMooi7Z6zHqtS51waOz1z_pZY*N)h zf_90jtTx~brtTu8p)$klwyCQFxGK&@1vuOwU_}#Tjd|GDTbjKJ-@YTNhsKB5KFzD~@_Uz3ck<>({UBWuwKS03VwSbHjzyA>M7BH=+^4;|6K*bjY-{ zBinwyttRfM0xJSzX|&*hkrwep%5ue8ndt=wb|;MriNc;hxHi96)S0_Z7)nMCcXZga5ut){MR^Py!1tPnKdnv8-O z(MC&q-*snMAX}k-FnJ6(6{O|vo*7k|oAv#i#fuwaRjS86BJZSb& zL2J$*YhtrydA*}O68YoWrjuwt%zFXhRrEH2)xpMF)fUYxihhr!_oS;Wr_S>nNe^1r zdhOb^b9?8VUL>=UZKN!jsKpo_)gs~z4R^S)uD+3x7ET2%b+G^z?c#;Q+AQrOuyVOX zQ65qY3-$*mJrfv(J*`l*s5rnC0$A_U8bGf~p|SxdM)u8-!VSSwy_@Cn-T@04Wh#6d7cTG0>() zF8k^@ab>S-zH(@@xIx_N3sH#W#%1D}U))h{khX;74G%shw7TZCc{VSr4XF-;w}`GWtSq(q7|A`FndW~5OXae~TOF)>XzlyaU&k zCtJ~s)8Hl$%;9s*kr9NIC|`9quidzHW#{RgJK@pH4BcG@vGn{!{L^7^B0Nk4u$tH% z*70RaHi1Q}YwLtUi#RJt=}N(+$HPHo1*H|k;{!D<-7pj3`=#FkSLnHa{w*8{5uK~4 zQ~V~VV2s@RKavz02#sMVv@4w?gYb$CsoLhuDaa`4BdX{Jp|$7t(L|sISJH;vp~ z+B*r0DubE(*MUB~(-8`=s?W7Lu-?dywcMNO261p!T%qgBS5kx?f0%X$MeT;I>_cG9 zQDAM}+xFFi)>Ko*K+oJkQ;H;nXEBXN?gW*^Okf%1@V<=RjRry?EX%28YzYIQ09YqR zAFVy;JbA{MEp(-ISgq%5?VA17nM9cnqey|onu54GoS)fK}Z(x7s5T;IDB70UvwL4qxQ(jY!ReKBJA!NG{( zr2vqWwd38F-bFpu^BeEIhY=NNN!_9gX0Gqx^~i|$P>h2N9wN02<0y-Y$}ks}FqfMw zrSb}6MN4IhOe$h@lVqBeudISB)-#x`)U~LPYRMmqL}=tIo*Q9S(^oed>j|tDoCenr zQikD#W3=U@ruDw_aCO&6KLE>X&Kyy3U*FkrvCG}pI(B$WT4`p;Ty|Dyu>)@vvq<51 zYTqF@XOgZ|Za_%d-CT$M9oUJcrl!wN)VJ0$YL8aBI(V~NJOF;6{Ox3`O}k*7lB@=z z)~@{(o5#4|TbzZ}RV&C+9Ud*Ms9CPR)>>b~5& zXcOZ19vegx<{FfmUYZ`2v}9P+{28ct$hh<=+F9RyNqX+ze17zO55XR|@7`X7k#dxv zitbT_2oM$*Jcl84M-}o|;)*MA=m!^~09l5LLT2D;kSXT@@Nxnq29^YkKipl9ILe4! z=d1x=j0~(E{53s45`En_olb7eYTmo~^)(O5x8E=I4# z=bxRq+*Cgr!L&hFklU|SGg3nm2e)dXn%bZ>KxlmYpq~7LhAzYNZc94n8+8HbTfRuWjefO+haI2RIEPxQr8GWlmv5X#DW- z>H1nGVp`J z%;AisESiQ!=d^dQBT2yp^OVrijroC--c}UtoYsVm5(ADpv+29IX zIlFf9Tx}t!ti%<>E6~;9Hb6mfwHCPIfsdaBYgaMtd#BB;h{BUQ>sStB?(X>A@7UW| zY%ga0Urkfv8Ae)h*%w>tbi-3@-j`c88BS0_cOfm~Bbuj+W`@S2tEOV%LgaODGTZ@V z{T#2CR_}Ok*8NXC{_Fp;yB>e)fd}p#85$fM!i`?T!gC>sj-?kQtk^%FA@LQWtK}do z)F7jOzC4q#Qb|Fx&cKxi35f?pV#nk{SAeYaXVea6(`sd5GytpKaq;?Q<^}~+yyymX zHl+W|2kyEvt$!ve{d@_m9|Ks++8kI8(cJCtYk4$lSWM>7#pRyf>IMys)B>YYO7msz z(AOAm#ivlc?}d)M;)5pvED^83R@?%1;@TBAmHn*rf@Xh;4Aonz&vpPrqNYatik)FJ zV@VSimbdLay@{s-l^j%j7{D0*xI;48#Sj^AI?Q&SWTchdakjZOTK6hucXS%3LWPz* zKw*OfS*ckCDN&=6hUHc;TikF-0{E9`JHDv+aQz3*jK1%IryjrS*LU5epn`L}d*rC# zFsh*;LxO`jtu_~ir8wL;$n2o1q8xigU@e9lEc2tFF8DBxgLv{}DB+fwwACYuBEI5b z*@A~4PzoDhU0|$Zrw(mqLEqQ5PWJM;yH#zyv&5@!*xi*J-tgGuF~HTb*AFc_+W}-< z{Ic3NGczP5bV*K5My2~Vk~<_UL6w%Sb zrW>U7D#L#p-j9u0ii)viuWdfGc~KkIGdYf(_43NepB`m4y)*QHOU>ewfxA`;@rR+g zL+_r1w0UvZaxh@^`S!f}lV?6h+hKNIEgHqHA!;|nB)XDW7ov%Fzq^8TMbBryIyxKV zMl0qC+I=eSkP?~yX}t@~)TNfLS@zm%%U)gvWGy>Sci7(LYc+X> zc=mfTY;L;mH)cA}4@yQ_s2ilky#ubwnJ1GHQo-q_fU_MnwN2U{R_AEyLTZp+kZ5GT zp__=JyUw>n(j-QKBFhw6;007k0dh~R9zdgY?UEd% z;a7AZvKt>#Jj632K}K{5X&Du!rJ(B{{#x7+Q%sXg!J?e%DBzmza9v$u&sJO>>qU*Vxz9%cK-IF-gKndm;jBNjuO zXX>l^c%4{_qy5;GO(qLdl7d7Q81Xc?rSll~dm%N$usyD}enrg*I?Y(dT$~q)bzpVJ zJ3V~ZaF2&5Sq8KW>av~XvR`E_Ld$W2!1`$0#JoSAQe0^{mOzQ7?|v)-6auR%EyxHR zm^5@x;tX;YW*+fQTm9koJ$o=jId}KRyTMLjIQ~V=X4)nOmd0tK9Q-(mi%Ym;LL^Z{ zSBA!rg;}*lneg_6iJWr4Pz=WzJW!z$M@SzjyGktV#w3ZE@XL~ukTA>4gA$%=4!yn% z6<3NZ$_-u^;J}XOBlq9IbOpO7hXq-Wz5E(*MPMz3K6U8I#X9?M-oLTQ*KLYd=@6tj z-92=bwNe)OO42(jJh1O@nVSr$^@$mogWt;F!1qFPJM3cfxlL|XO;zB@I%p2ds@~Pz zF<#stm#09IVBzxTCu%8s#YubxT($hMIzUsAkQ``$7j-j|mh?>64j&@~UC4?k{?liF z`cv`5_6t}s0AMMs6j@rFrKa-3Af66Wic*G7fICc^0nYmLQ_vL*;XCZ(kN12GZps}; zmLjBdU&$l@>YcPS90NJ99dgBV7^bPoVXzb$1J*g0rIL{(0Jq8;5JD&DA#psQrZIZ} zDa$I6r)N%JI=?Rwy(D!s2D7eteHnm7RN;o+z@BI544${Wzw7_mL(}zps1N;O~3)`O&DEQsJP;QZY-VPRdgKq|ripDF)1pPiD6?A++hM z3+FC$1_)bOHFResAj7LIaAW^r@7jZ^%*$|>a}K9-`r0_>&>n+TB9Fr}I*6(!^< zT%u~B^kDPcwa?94x*6_p^`_s_xZL8*>#rX>12l06!%}l=*HS$KqJn|y0=gxrFQDv- zh3&F@9#+8|j*I6!b$(}K@!bfv-rcE4AxcZB4NS!>F4ni z4_6pG4MI@m9;U`)kL+nMXrJ3?16I;YOkfG?mcY5;+>W(@H+!vdo9xcbPiL)gYD!w; zcie^(x4J`TD07F24iQN!KlO5_k7Q=R%*s=nn-7VuEKdnLI*-lV1}P2cI^Z-mM9n`jP()#ZELU^zTx;ggucusegD!Q3 zc=B>#n-exm)BLfjXqkmtjd_(P<{^g1GR@zv-?9m|>Nm1QY&paPfQnr8*>&)K^nX9x zxNg;YPSoC%wQAk+jjI_};o2?|gKnSSUmxez-GYYZZ{YqkDaeOgvx0oj?q)*I?R3(WD{Q}RALN=nFBFq{VMQf^`m>3jrpgKx7hGyyB#q=$i3%ozUg01{Lk zgLka9P}G_iHYiA5KXrGs9CBu!;bmdwT7vY{MzP1D7Ju?6mM$NLRfO z89-Nr6@XP+G^3@pvFMw{7cI3ts&GpiATxn^s*}w{Go<=Z-CdriD47 zxDU{Nj`$qaFyt&OhGW(7D(Ij;1g@AA+`Rl#pWT$RKL=eBQp}fMhoBv9u)5J@5mcF_ z$EqIiNnUKC|h4_#ML?Kvw^RJv7wy{AXusQ<&=S;tp{Ms`Oz=FDomF*Q$lQ zxz9Gq!G;fYn0Oe>neIh}%pHmhDQpoWuxeWSdQNqBUpTdU;e+Cu*1Rg0+#!G&wi&3In_d9iO~m*hK;7HvSjb!fz24r4x)mnKzwap25fCaz10sl0asZ+T(;}kUB9fy zRwb7&t#W52Ew2LBP-^2mQQ(K+m1qnOzBSvO#SBA-6G3b@AnC>0LO=H0u0>C*#_!;V z3Rv`;3apZVhVBs-T_RWa#Yf%^ihX)kwj&f4Sq#z=!b<1=k;0Sv_FV?Dkcsgi+qrXQ zo|T^Hz6vjN6s&e2Z%HXlz#+nV^)rj}#7jB|I)Rtd$$rDVGBYwo>8hxf#eh|43p?L; zYl&nPiK{Ny?=hK(8A#qt{(x*Q?h#<^kwy!@xuHkpcz^Sit3_D5GBkLHG)BnL@T&gM z?_wc*TN{8yWW_M8?PKHxbP2y@AKza$dok3~&vHQg8ieSisHO7qB94EUdW@=Lh*k)% zHm+a4X8EqCX7B3E-Ji`32rY$54BEv5*#V z1$6Or_={1D{ph~EH#F3@c!gUwqL8zKRSt5?0ohH9FDWyTWn_QqiS-hHirS^TYt75Ae0{}&6^ovk zjp=D3C-8~5iiEWh0Twum745*<=H)LQd*q;AZ#1%rJ#!uu_@2_rXYRnC>>l#bA zJadei!>rlEi$e>qbjJh>kcqXXXogv$6VMy?tEFK;KvXDEpZqH^3Ja1JT3_irqDYl3#YXHcy zJEhEF^{fh_O8z^2CL(ushTRyT8p;BhZLe0fd^e-2svF0_o+ZiR25SyNA?>+4CNUX} z0e3m<@U`JvOL}hKzWY}1MIZ~6r6esiQdcnIg5f|ILR7h+Ob}NDRxe5kuigCVL}6J; zF>9V>e24~F1Qy{{nwPg}Hpa@l{M<9od}`Nc5w|0>LMi+57ZG9cRQN*#>&p<(&zm<3 z+gvy0m6p2vrn7c6RyQ=%H=tia*2g;>S`DfKxv zZviWzD?Gy#Svy@m1N!xv8?ol9huleCnq6k6fg_51U;%$AYvn0>`OGtxLP z^b8_S#|Qc*WNoSYnR{3>q zk(6!ztzSJn*aG!41wE$3Rc0$XE#B;I?F8%NtB z0j$!}Tu+1-Kc2EF$&AsZ=!%A?uoyxlzOau3*hxFE^Y{nWuAMPEZT^YvFKqXoOpK3= zjE<1h7mYRXmh{3M5f<4@;b}Pb$h0~CknTJ;8K`g05mAt;vzTzMgv%aD!^< z4Ie)C84|vWSQ;v)Lo?&-Ir`wMp|bD7{y4mZV*=b!^zE53_zQ{)R{MDP5qe@w*5O- zuHKoxFAcP1d`T@$K*8l7iYr{ZLnjx9Re*oV5O`TMApe0JzNfO z*<4`3r`r&Jh}$rQc<_^YJ|hvxN1xi}uoJ68e3Y`H_6!!KqJan1d^H_kS%Pxq zJ`@A?6eSZ^HB~jl)rA{T4q_5(QV?A2-7C22Pa&@0J|%6FF^V3Z$=){9w9^|haA!xW z=>vl()A!AAgYbhluA)f;rd>eoD4IK2SgzBS;SOP>EiqqQTxmsK-igny{n#gGy!U+{ zdIB9`Gv14iL(FPGOa1&~zpUJkol26e1fG}?fRv9+Q>-O{0a66l19}ueL2W?}a~x6Y z5oy%I3DIszA2!U{fUO{v^K!E{Jiqc2d61YB6XGMI9XuBjTQWW>foEi=#j5M($u+p<035Es7{4fMscDTcIMD`)aH&^7W zI-S4qSr>lUvbDdqC?oSnu$r!0-^ck6V*7>6Z6dbA4?<_SI~HXoB3Vbdm*G|Obo(|* z{V1@Q5bV3%liYs;hddna!X!71M72;?u*OsadeBfa++gpOBAt7a@@fillYrN7VaXu2 z9s*froMrY|@J6C1x4ybMr*qY@AFN$4W5!I3IeK!&%oTHHJ$qnfPD4XOsqh<)p}Ni5 zT*mKBN{UYeV|gR!3%Q;IiUW*l6+hM8C8RP#yr(-h%N0}qh3)=T>*nsP|IG6*ys#ne zWFRRC@C4g4=M$_Tm3YnK34i@@q$`uOzF2Rui|&xPL(YcgjGRIs>*Da}sbPR{NHJJS+Ra>^z&%8p=%`9P0y}iJXQ-#E>(qtrr-)2Lol_xzKKUdj2) zCoru$KYd?%x&Vuzg_^J(8OxdTmB*B>)INCvIt(WPL?`VCitsS%4kg#_4L>~fRz(Mu z;2)HfirMsZSe9gQXK&bf`h|+zo$EKQdL_=V^bU^{6@ZmZ52w!+Lr44PpyXkQ|4gRHl;OE(1FGo7t6GbUiD+IDYTGJ0TMiWVVs0PosG>zEh>7}G)b-No+ z=Z0mi&C1{K>^e*@@L#@KPykI~{5+P1wScY=!Yi&=3rK+SD8%MyGinFfD6a53k7zYK zu_5zvuTE?&cS)e`CttY`PbRsLOUl_77HrhupQqu72&q)4jYNdYC21Z7 zmiR}i^J3vN5S1pj)!QIa#*AX>4B}XKVc9 zpZ@eGw2V~*%F+R>q@+ZTFcxpp6>-)07@h{-7HECBK9cdL#~RJ}JsqOfePopoRa!x+ z*+RKZ0sg)cY6=gS@BrN*(r|?td5gEZ4CDCXdi>tKclwJ84xK}%#rXpKa|2d~#0}oQ z5v4G7N)g;%^3}C(WGG!_v=n3>5d;>n;Y&b~!S&|X_6C6@ulLi^E^6&K4NhNOqRta5 zG4AhLkwy&_AKEXM`$<3wD;QIUWGmijLC>fNV+~FiE~PeVW?>ZmWq_{Voe&6+Z-SH+ zs-#8V$51|0yr99#eIkqbujLCoxwG@btN%z~{pm!Vv9B;)kd@#T+Kv&0LRQXoE_i&y ztA_%u51;0@26Ja3)72Z&3QJfGZ|()dt*2qe?;tU^1n+#BHKpb^FPiQUNU5CP02#XR zsYVMUj`HD_0xpyuPhE&EK(>Y9y4wqJ$Bb5^6j#kxlx#S!Xy|HHjmi<+Xpx#Bb$}TK zEmz8IGVxEZF!fJ1qz+?a$KVHVg7CyrT82;v538bOK=a^2PGGG6j?3p$7UFAAiGR>0 zX2L5DxC**Vm0!as?c){nh5A+_p%BPQ0dSoi9Xb- zBb?>7IUI2Q-^*tBAtm{SUgbM)mi|$VFS;=l+5s!VY@ItvBd*o zP`onZGcZ>Bulf%PE|1nOK`UZaa6{C0t=VA z+z@`m09eJ0y#Xv3r-5=wr7~8im7VYquV}tyE8@~-p2ek$U4?&C$K`jiSUK60FVWYlxbZu!DTu{XVw#&oOrz-#?v^N z+w66=<8)XU;fUMv)H5f-bMv-5{lp0yzS$G~Ew$t4yQ)~%UVHBP?Q4?O<{br-@akH> z(v>s~rndGENS{UR5`^8gy9E_R?E`moN+mG`&!lfS_(-Dm>2K&6QtsM;;cltMsY+Q0 zWGSvPia=P37R8N8SPC;ZKLu8-ywZF+-J6b=PczQq=kCP9Lem#U2xT!trUU(HP#GxD zbL#l%1*=N4K9*xi+g_bry+5y#gjJbawl9#bp3rKx-s{5psERMYL+HxX9X7Zrm0CT~ zrYD2}Smx^J2Wxh67acg}bEE|;v{cM;YYnpdq1>V2jN86u(VW$vom+1)!YrPt;h~o9 z7F3D0v=8-PDYxiY<|r|+Rr%CSty{)}GDB52Qa@O~Q((s3(!Vo0*~^j?3OZN+zRB<&jJf(@BV2tG>iikA*47Y~$K?}owGG|vR zs`MEIRxyEP%I}O)b@n=+9)p}p`Kl6oIoECJL@XNKRK0(HUS9qm|5$C=R|ZT;=pJcE z539LvCU^CR-t&&KPk;FJGzcMe_ZVF~{kU8he-w;QNKGve$sQ)YI=(%+L zTz7^lT7s*L-6%B;BT7g<;3AdZ@!*Sal)e|Z1%ahtVs(z_{P$0wmLOxr$5VYLUva68 zn#bal;|23LyYjL&oo=wjgq7CU@2|+ip4I%u^nHa%rX_?r4Lxd8XQ+I%W~(a_|W zZ2M(pfnNxVZ(`Xh(aV%Gzk()!h5(yDWWT=ME}a^e#ub^sscv>1M)elyN4%QWFw^s9o|&G zzZ!g%lb@f9EJb2Mq5{h*v)y&RKGs;ilic8g+~Ib7SGdADUXcZ0dCjUB{m|;Qm5U=V zxS&%vfNEA+B?rw(b2eQW z#Vd?txcZ$APH($(z93mrKiYslGL1?oU5luu3oKy046g=F!sGVLk(;B^sqwq(8B$6} zD*&!0P4>Z4qjHy|U}D5C()3AK@uJ!eu^<*WOYL8GTbM_k>81zDvFUdevy zxkih*nwGbl*;eM$m=_-FS7Dt&JEE(O{tI1Q7zVins35MS(PH!tT3Gy24Nua70|csE zf-Bfmf3ltig|TV}@3z*qVsLlLwq&i%sVS&Q9h!!qimW2JN?6OUVx|Sq3VArB3KMOC z1g61Q2(g8~)2AiTdKUEu(gP*;qxVQM7B`$SsqYQ7QAQO3t90Yi6&vP1IrB5w_4U>8 zgTPgF(#f(U;)+f*A%caGj8y?F*O_kq{;Bw>qLtLTT@K&-mM`vVe z#TI(Py4zbA#;59-t%H52hZoS|RwY}8hES(Od^L5Yov;d)sTQF7r@OVIuQgeaSpYHY zP)+;5m{i;-XN5teKo1Wlf=6xj5Lr&4Fui@Ia23YvHc{nwiD3eYltv4_EG5MNRv@4X zX{4m0?YOO8tAjGCM1i)_*&lq}=gisJP>LkC@KsKB$-V$23OK^V==f->)|;}y%ay<2 z9ZFZ~4!_ljf(OYRrjxSb9S?k=Tz1xUWLGW=_dd0~enX>%oo26>-1j#aMi%09Xf+Jm zvmct%=>jBoK3lD8)EHqg_0Mj@iGd}Gt7K@RMOYw>pc@0#BsNl9NlHr=II|(Yo`_6lDHo`G5UI1w$YKw*k%|u*|8WxgK#AxR6w)SV$Vx2wQ)e&ebNdS z7f4(wU8xf5SJ@1IsW#IFN|Mq6EY-0h0W2UZf*#Rou!wG#6>-b_yEks_EyCMSs`7Veem#)1jR$Jn5jU1iC_nmY#>b3DF4X!#=Yr z@40337QI*}VHPb2ECyN1D|V7rgkjsXrh)LRp0zm7pwWM_ue=TCL8)8TF4oMU??7#@ z>O*wZnqlIKu!IU-a=u4?(_PqB@gjr)BaOXvnoPkMCl zn%^89uZ3LH5ZJ-fwpF^rqO{Y(G?$nXR+yO=q`-k!a-M)X5hb$#R=S)DMQ(^By1e!% z8>glUW8r^i<$?W9w=1`yT5wgF-^9~k0)fSoq(`DF)!Xa7^v*jCzAbn7wI&I)Joco* zl0;p>`e4(&=e4gUdJTuI^4TX=e!R1BX-=r2Q!umyln+8cMrRpG5KH3?Uzh`oc4EcH z8*Ea_#@pd?;@|b~aM41khX<}i6Ky?;*yvP|MD0w-KzZ+Zt64znS8OS5;T^me0<`Ag zB6Wj=W>x>>Rq50?m7$D>%EF_-)#Ma6x6%))T2Jh-g@?e}vj@##NK6x2qK5iZQjo&u z;G9Zk{3!2pw;ta`2TBs6(DD#aV8ureSun3bcp?|TsEoCMaWg*7@>cZQbE$>xY7 zCn!kz4TIy6b-REw9;ZX*4vn~VGgrIZGJHnmFWcU&d&WkEu8_f@)pYdyt{Z(|-AlxY z71V%kj-I_eCDVk#Sp=509cr6QxWDZeQ==)#f-0%q(s8$a_zFr_0<5E_CWsFcQ{W&9 z6u=dLH9c^p1mj~_PG7Dg9z^64Mgx9S@6rMtC!pz+pl`?*{AgqBUwyh)B9_kKRy*9_KnkWrVo8`5McG4BY z?G_d655fnEw%woTm>Qr3(>>#`K{7v;f%qlQ57trki4d`obDFZ zH~0_s^gzG?85pi`hv=gKN@PT2wAH48KM60`b&=cDpvS@d`t*~9gcT%F24gW4Tx7DJ z(e!v%^!<~$!(6MlLws0t%Z?c0f%vb=8aOXLv#rcGtkr3A*W{Y@q=XgfaEU5I`|m=G zbWFJL;-my$Dum@Qk+pSV2*M@%cYf45I)bR3%G0R}2)Y?_*GOr@g}3&iF^VjwVVjVl zO$^LYe)$$Ej|r@TcFOha)EMvSNq%D+zXA;VBRiM{qTVGTIAdy{iXs0EWV~5cKQhMN zkv%M~0P^_TR5It26sL403#0Ht!NZzVoMiaj9-az$CPc})gjpUJn_+$GL3JxkSSfG? zxgBmW7pK8Q8r`7R!hU+Gzp})>JKSK!ev^GEAsouZw^RL@ASO^2IyHXPUrz@Y85Kn>; zX0Dr=0P1C(>cSKq-!^!o3_~m0WD77%b{41ypZN zfn_(~1cMnM#`rKFa78}|@yfc7ZZH8Cg$W0z`Dqz)={x>3_?O7~ z4&NcF=)=H9RL=n{;;Q%8x1?5C^GNNJ#UL#Ji^x(HRDnh2@|zliuG@DzkW>ba1ptQof^xq1%AjI9gE0%F7Ks}i zmXKACdtv*(7HG}PleE1x=now z@b;22IUTa0b?JgvbRJDq+aw129m1-V@k{659N*1uLlakr(8bC@v9fiP$YP(gPTP;c z*XKI|%zvdlg~&R1?)v%euA)zFBd#(`H;CFTC*^Wok}g?4!PVi*w~|d<(WL%sXdwBG z-IKDYH5SDaVH)d89fgpjc0XI<6O$rcXz2m4jOY^669QKu$Yi4~Ra7syQk#_YEn8*WV*@yP{%QzI#vH8ovtUO#_syhWq-0{tSxy-q(BRU(7%V5K{|fO>~_ zC#ygK+lEV!CHFw@VK_vQ7#O~*2Ne2|k_tQApa(_FKI*2Hgpy($@FW-~uEKrfD$V7{ zQ8KQv5$D02ofUzT0cfHy(3RJ!tpWyxhU$0GY4B~x+L$fE15!LfS%$&j{WVNoEi5Y@ zDkxylfx~^`sV5ydS&oKEn@o$8(m(PFjX(6{3`;s>_(+EgbM0I^yV@p-v*lWUQO3dR zmoANGCIc0~1Fh@c4gOUz{93$W2Dy)>tNmax0yhIogBPZDT^~PxHU;4oAXRm!2FMz@ zQm(tF&A*gx-fgXc~_d;PHuIaO4#pOeBGtfp8P}-O~5=WSmS@xit)9BCquWSuKNi9PWxvN80Axy#;_xN}h z5t7M;u7{3rIH1i&d@wp9ykqq+ICkYKF@#&rqc}R?RiGtt{I;UW=5o=z@JIZ5Ak?ru z#)`$Epe8n5keqBd6pGqux3QfEu#yh3Fs%i|A4+Q^u9^~X8cZOt#0|P_L6yO%|M_Dy z^y~;ziqSK;nun5o^okl5GoTtX(Z9R))cDaVw8Cc;)Sf$c_XfxQm<_SA9nxZvdS8H2 zlR6448jn^Ob(@lTcKqy-O!fd(b#)yaz1-|Xbq#?=fnF-c}#9`51ekIEg1jKdMa`w)?a+RV!>7f>0*Qhv(b_eWZcuAK{a8->_|Mu$eo!jSVKmAO46tPFz`lJuZX(Vq8kvj%4z@2? z6mI0NUhl&^JD5<4jhYi4rnwVwI!sW7zW(Ej7pzZXCpz{H6t#5MX6QWbzAMc-DOsBr zIrWvDRMMot=^Bby%}5&l6T5s6BF1hOWwv&u5*lm*x_yUvMVenw%`P4h87_|?w9;;k z-Gjfch0~?$MYSoh#UT%wDJ|0!DC8ox6jn}4bW&1;?ZM1=^yowcc+iUq<49fUl_s$0 z3RQ;-PDGjJMAh-VlUDdH7PA`*5KQ^EmlVe!dy zyST%0BqpAI9??%&R-Fdhvi%wXh zENQmrW&LxJxItYV)<1FTpjc*da>2n=PPf6A$QW)WCM5+#fM{;Y3ZcLX_?XSn@OyqE zF@QD*8>1`o6rURMOP@3=W%7{2VTlYGi@nmiG?c)y_U(R z=nmrwp<=kh!)TyCa%6PM5*lYS!s~zd+>0*N$YFR9QPU&<#vXQxrKSw8)uep2TpJic zpT!6^T96f^D9p?FE!j$H*}CU701GCSQ&Oo)@geuv2VSu7pa^eyXP`(o@$_^5v{VHG zQp54+Gq;M>H~E#dTr z4qz*~xX>J>g&3a83y0g0Fs{AqH;}P;D(9J1Hgm~LLROaQpaQd? zlm(P~r>@;;<^WiZmC^`{fQiCThqgUL)y0?g=v-~^5fDpF>-e0-`97+R)aCEo931%R z2z-A*^)ZiiQ}zY+@9%8Cr*@K=RvHq8grh1APcx;luyRCTm3ma5}UTI%*&& z9ls@xk>=LTJm4$9N~XQH^-fRUIeZb5a)~TXQkNw)O{+e(u7R|uXDtoMY-)bL91AtP zy7sHxzz=O<(baaTQ^hvAzLYn%iRwVc${ZS=f>>or6#Qx6*Kk{*C@{TDvhpdiKv)(G zh~YVqmuRB06kP{aLUXq{kbVrXYmniUHPp}{n#?@py=z6$zuCf*QEz(0X9<8E$i?LlpRG>z>}X zhOgebHS&$&8(V)-z8BDP>b4qqs=8TESNaX7AWM&;{178UvU(XdJ&L{xjjmoTx;a=? z!)n0uT^Vm+_6pf{LlT@x`1-6I@r!)nUbxE!bq)HyLHP z@=t4pgN>IS4%Hiy1upTqi}O!YglD}D;H6m~9a17uJM8e4TPm%?-gvcY;7a#F|L>n)xHZcfc9x%IgQF1W#gowOO1Y@PVc#s^x&>Ev<*3dG-mg5+e~^85$6X zbiC$qo&EST(^>}VZqb~r--3zY+uKE(9EM3bNI5Ie)=k2IDKytMW5?RFiTmV$Kg@L@Dy>;JR9s;SiD1g7Zje{7irLIr!xf^w5&ec zP(Iw&`}=#SYKL~Y4G&~v2FJizdtss}NI~>3XDnziC}}(8c9N`6VJh?D%MahUD&aYz z_9FI|rJ}v;&9169V4Up6Mj+JJu%OUrSTWBO>ofzYILRI zl|oA4#c>USGB><^QY3(7u}Ml^EdO0q(f3cf!!_X^BFht>BpZuO+X3C-H7vt#ZS9{H zkwJZ-JcufIL7HZ0b?7nOVIUGIY?ulUFv3fsdU`=waro9o`(HzHL(y`VFetChtS;uRNE(U@{9r?_(K4WTQJ+!}2`DLvNsym_kQ4GFKzA#nF@ zNHO8DkNKKboDK=onjZ*u@phLvhfTo+V`F|es~dnTdO_xIh%K5Dvb;DWqS?Y~b*o>c z)6UL%msRxrlce>%Jcq|aofOCl0!wnz`wFK=TRS>>E<4R2ON-w%iVhOiePo%Z!z7Pk znz%uI2eZYHl*%uUj`oP2apW$nd$Jdx49Ty1VX4ctd`-osYOFCZJkbeEISZ~pRPcqW zERdS;;5+53Fmr2^DXI`(c<)A0w+=G0soq{O`~Pn6?<4E`olXyT$y(zTSh~Pp#L~85 ztV$X78)h3AO`)ai1yf*|GaemDXh)!=^#E9WfjM31I{d}qUlUc@EukjLIY|qR`Flmu z(!*zrzi!s7<9ZTBoW=83cr4n>a2iy)BCrZt@7}IGgy^dERl*9BD1UV1;L(E@Cd$EA zZvST%Eo*SQmd*Lnu11^F;zjqn6D$=c@j7=ui8LziPulbWFF~1_48JjdXl$5_s+v7b zD>3{h=KtRf{+YdN4~pu(!VNC>lHG0^?(U7OxGM_kijrs)l@w_$1{Ax9Ew&D|Jf_S# z=!U6iA#n^r7_BGV0`g(djO8Hm5)TExA zG!R5@QEXhI8)ncT7W-K`o_ujbs)!Xns(cyrl1t@uBj-u+qE?Xby|KpfX+5FPJ6PM1uapId26onZCZj4UzaRRS= z>ZG-~(`P=K+=c00v5ASX3QbdnK6xl`WlquJ(ijegCg?0vBD~}4IdK$K08WZ33|@lv zU|010XPA)ZrG&K84M$73Mc7G;G1i=5RaYgACK*M;mEO9mLYi6 zoCCQcULCu-pJV*RkFK7dd${Z9yuk(Nafm|isgs3@6U=z%tWxw$pj(FgjX%&tA5N@H zvf;1AY%(qakzFnSv1JDTBdqx15O275M#kMC7BLINl2*co=Mv#!tednZzSCY*r3$ge zhaQU^A!yDNbW+8FQ${cgu3U0peDhAb_{o{%D9Aecs`SJAEN7)?G z@sNxm5$moz9W@qm<&cy!m&6c}KqXlT?4>}v5Q_~UJ~)C)GiDSyak!;Q2+hc~OC$_tFpz5n zMgLQzeX`mMW|3%tRirYTAzFGDqQ&IiC8?6gajy% zJFz=DjM){&8@-8!)H@wxqil-}32n#8hH_ra{m&e+7?>=+9zXrrY zEfpT;-=UBerKKGd)1t^i>0K}{l?=TOW7Ix5D zlAiK~L-lt^V+o=*HH!1OA{f6neuFVZt*_ktV=K|bz{uEf4D_BRpg04v$p6d|7Z!}YIbr}sb#Yl(ep^LPRD?@{uwPr@BQFA!m=ze$W82Kz zEiA zOu@#GYis^c$kR4sz1OAKBQdPQ#gr0&SK?bSv4~Z&*Bmbf)V6qW@|?jL>C3mI52VIL zQ8$or8Uzxye%UgE|6>c!kb{fVBa^@^HiZtCKCpJ{@}+i8uh`H@=n8Hu>Y7uXk-nr! zBJg+!q^?)Yp*^LNDoe%3@_(lLGr^Y7^J6FAePh8Km<7YPX#0^P$NqHeNNY{=vTX>K zGCp@>j3Zh;;TBi}(ONn28&lWtE&02VV&^`P(>^|2JiJzu zLETB&6*Os?ngabz2dCzRJhZ987847L=ox$>V*R{LjR%`tGI)VmMUIvkCZdT5bUIA( z(eD*qyybEGQ%^brwrlUdup2Nm>-F|ySAP52iT0N=H;;WACF|tGlV}|`3LYR=GRno% z7Qh>&qg{6N#A0P3Z>YF&{ijYq9T+SxSlpt7+uC|PWCr6VyL71%rR85lD_T^@&Xp7| zuwoI}%tTIab#i+0ba%qDGty@`u?Il%I1&~O{MZVLeh8TIvfs_lQ4A9+k~E|7vky<5 zGo->2+BVeHxxuDzhn_oN?^+xtTA4!?B(o--F=E`Bo0vt7gq<6<3h3?zPQc!EG4QYb2E_YW16)3QR*SFe$I9!yV8 zUs#}8o3cE<+m^eq)ZG#6yZtKVbTXTTS>HT% z_O&B>T5sQO2eC|Mee(i}v?N%{t7({84uu0+yc`~ea=|noZ;QuI3W~x{rO)xN>rg-iP~mOn9!{<_st*{sOPW7fv`HtKO;Ro-<3MqZcOtfHO{k2 z89p>b3?|4dnxvgjEZ8E=*_2<<;U~!evA`@Jh=n$3#rdqicpxlo3k1V|mpCMBkeUc) zO^&v8<$b1YW3dt$U6fqj_XjLNIl#mJ#2lW$l(pZ!wy%|3_(ft4U+*6~&cRX#mpeUL)$7|_Qsh7&6Qi4eQbaKDYP8k>9>{ zq`kQ&r~mvaIUK?qj&hZjk49X}EF~coaSC6tX>=Iq8r)dEpar${kukB+2#VgRWRQ)% z#437IyXFoB4}T#&!1U)A|8bR!AlSiLkAf+gWAJUYH$nZXa2SzqpOBHHM( z$GGj>J?d>L9}3ZqZ8vRysI9H9cRQ4>b@L8}=dOSDpsEODVT8_(jp@caQO%VaYx8?C zvAJqSd}+A+sm8L=V;pn<*wK3B$Zvj${7z=()pM)FAi^A;e~YrxbTlMN$*?v&h*i^= zXwrMg%{|U=BM9imPzAf;wL>p?Z7-z-+0~+myRvd!TfvM+s#U3I;28}>tkCN8^u?=_ z7iZ*ejLA-nG}F$3ZYwwVVIytQQHO1OoiDnX6+NVoP`JS>7{mHs?7xiDVPlp5tMlh( zv~_qDf~XcJcKG(vO_S8KyaZ3Hb@z#PhBIF$ zu&4Fjx#RG(Xy5~LN4B7oJ#^7DKs@m+z*IBja1ej;j<2i-5=?hb!xhZ!YFpU2c3tr! zjr1iK%t#@Y9!gJ7PKNuwI@gw+6l+!?m(H`y;Qs+rPU`Gv*~xXmn>3Z$Az0*PRX%rU z+pjb_mFIOd#VdJhTvAcWbINqKG6L#>v1dcHY_{O~a;IDU>dca!Enkh=|9fGUVGe7K zT{>}~^_PF#w;Nx)&Iukm9bRNdi+k-Ubx4D+*#^R=7qOBqY98_&6+79@MGOEJALC7A zliWQV{HAth}EoW2T>~vOo@66@4E*q|u_wCff)B zaEpXN5yh${V&$xQ(T}7~Q?B~iXIoZ!IRHN%bs$Y(<>G&1XDWR77^HRFp;-$TuEX@d z(oo-9?WQ&4)8XF!_5;5>d!(HbhnU94n)Uj~%|nL{?eZ<4pufWIx-d-Al=Oygvo(yy z;z~P6g$vLzY^82Rofl&HD^c@4~K>o(q?4-D8j$k>o zJZsv={|%39RcuC)v24f`V$nd{oeg~mQQm0N9O{~)`Hy=uIvsv5^GY&1qE-wFBsr2G zT9c!rJ+l^e^{#C5cW-Hmtb1p8T(n50wjDe5+F9gxYMQs*cyAd8;X$#h$H6QLE)cbe zQg-&NoYE@9Oatreku+N@VrE{mYu$NsLba8vA`edw7{kCOJ=^Xl-i<@5K#T1SKNmqP4wUlU!H;)M69lj z>G63%Wr42`qq!ufqw?`^@^kg67?G72>vrO=K$(RvT4wP7iYeb~l97_Mxryb$4Z-4p zM-A9ff}wfezK$AV-Enwn`K0Aamq$?r)td_@?Vv<(hi>r{YJ3mIdEZYj^Obqp`UJ_OrhE$9n4io4-W(P#eZR?tqAB+kt zpE=kvXQ=Pm`}i3N=U(3&8%CLLY2Vaj|Z5 z0y6Fd4!Gl$pv!%@B(!k0s;-^wfu8zz_4W0k(`kgC7B= z9P~t+#p@U|T2@zBk(!MWfY7X+=e9$%-n)!{41dPMo19IbUAn|?&OFcs2D3a~GKYve zq(s_6)8~YqnE9!V(VnhG<Mt(;b zciz3m=}==QizDJ%92PIfx}%%s9d$UuGa}N%kx@}MFYFd(i8*Y2_3W_|2t{1D`Th&E z5+G;u$W=F`a13HO*?;F;q0{HaDs_eWn~7U8nFwOVE0$EU#(5KSgG&a33nTKYd)3gH zWi{i(Vi!;okj4@et@8=%H24wX;dMPcNEEU$8O)Hb*1|$^;VZ6=pxk)x=EyOsr1|~rH;}5% z%-lRY=9ZZ^a&bp8$OYIiTWDH>pJ0qY=E)31EY_>ep7<@{^%2v1a+l4YduD;O=!YuQ2_zLy`{O0T%ucFwr{md;N ziKR;#S!FYdldEYWV`AX72Rywg#q;Ex32p3Q$$`tO z3&1Q2hKm!g#$@kEO>{f_j>Qkn%E(vmjr;#7<`54qcsO$9z}ZVzPGP{q)t_<} z8eAHm0q0_KXvaEYx9%re1wbr=To6cHbk+-I2x-x@M{LnS!Nc3HUb^)58$9+=R=vt`P(Bc? zqTNxkP7iS^K-2=Uq!5{lb;t~ES=^=SPb_w>nck}@*ZUXM@NBNr`!}#HT)?D~y}q&` zbHG|$^6_BBNiXN=6nAPxY8EYK6=u;Wt#|rqt>ExQb2KS&N;N!pj8&(XpY%!`Y`>a< zb*47EJ2ZV}DOPjFrp%ri)Atq}t=%*%WcN3Lngc|v;p1*Q(i_yf40 zRYF>x`lv}4jxzLUX-{78iPcNeTO13{JzXQ4%!m65X>)-OrchigMP@0t7~av;HIO$nxO7SS znn+vO=aH25*%vF@nIr zDny%f-Mb^3TU&2j^(%@PL5(i+Xejnjs3qq&TM~AUL`4VIPF&c%X{d`gDE{>JYp))_ z+ArF5xck7B-;eI1B&FS$2Cm{kMiCE~K@9r+FP<_F|Fh)Zmt)VHglwTq{Ia^up7s+RR_A?4!f%@`ko*8c5R%NlkR z))nIa6SZYFJ{6Lxg0G#`R&Ma)#){-Bu}1dE&@6CD?n0U@S$Ga>2lm}G8+KT<0F|r$ zBn)7zu+cf}WWy4XSeq?euGyqx+KyfLm(TCr2K1jE)trEfVN4&9MhZKEqAqytK|da5 zBFB&0D`lZA)8otA^1JgQ)-TTUE7#8>IM&?!^rDf`o%LCDNTDaekk^$hAXdrPxZ-bF zX7J-j+9z{eb}n5(a%Y@dkS|&tcD28~eH4T;dspctvLyhwm|1)UJT5YaR5>A2a2bw- z(Ra_C8@r})RlB(BvK@*G8PNTT^{^UjAp2HaDZ|Po{m!^Me}KXq|KoWB5ud8k7M$D0 z`*m_^`Y+a3*4CAAFKq#F!E4wgM4lXc-O*2T7Yi;f*8+a7}{N4cZ ziiu^Es%r4B@&~+HaL(bU;(Hwa7juYL@Y*ia)$iP}0d>{FtdzKEnn;%C=hkWPuED}m zg{_l25t=nlE*{~1aripdHZXMY;!UwK(mUV)TSPygM`ud8pGVqFs6<3&8nCRdF z(uA%bSaNmuAZ=1!fX$RWhSW;#EZ(H~iweIg&`b|Y`^&07T}&asJ`y&bCSl$Yd*x;u zs$%R0W;1By@wi0BhsCf9Jbn%_7=F9JI1s9v4u)Ft2lTethczwm?uaCbp8n3ohRUq6 z4JNTrvLEB*z-Uj=r$1rgZo-6vof5OO)k)L=PY`P-m=&dREx9~#8iC{-3AYlj07Oa=WRQ?3E0z$8gbO$ zn*p2#->t2$s4D{uTUb|Tlf4H`)*8#Z4lBMpNSR?pb%I$;D-erEc*ja7wA2pp4S*!x z@w6fNL!vcOm*B*rn<#VX1#6W2GS)d3Kane#LDe4&1_LB@eBnixq@MNiHKjAVl}5C3 z73he>M1B>oj=xA?>klmFuHSX0a{AJlq(GT}g0M z;MKVbUO<&u;$|_k$gnx$k`iN_Fnua>OY^cKfk1vQpDVdj)`sMw237@#PIwSFNtD2c zL9L^wV^d(=fZCEjt4-4`Z!>BoF7#FIfL!(Ul`*kk2{*VnL+Hq}N*V4>tXS!XXAMM= zUIDCFl~L@lOP!O-9`+W#*m_&F=}v@ox^-yRw}WCG=xbyAN?mS zxw>1i;>RrtM+R(kCKO`rtd9}v#gTVrmqD!gif%;U#UM&Ni-{Esc-)gG$JiAxF~JiE zhI+c%T3Q-g+PZo|L9eEuBH9+|b_58L9VDeQ-F8_(=!!2d?+$@jnwl_rqek4Tk?WOo z8Wez5fRFq)#nbV9ORnx-q)j~B)J8MCyK0~j{>dG8U^4@N%&H3)eW5^wHv%9+%-aD2&?Wj*wS*qlcxf{f; z(uGaMT|pUy%@3j#J@{-0=r)X_4fg~Cp`MnG;-{7_UHas+RgJx&p2o&rWVT^8?kzPKzV zR%Mcr+clgk6*qfZb8@$qt`F!8mGg#p7!gjXeNojw+txLkKGRWNRs3XL-kK*r^W?^Y zlNq_sHipRh!M!44nc$ea7*wKZX>$42jX_-*8+pm_+Amhti(Cn-pjZlK8Cj>ndjx5Z z3@IX7v2rX-F;dVx`I_FnEMTtb{-tZ?l#l}^qD3+z%7Yg`LKG@}svv&q!&4rc@KEx^ zM<=X+9~ZHB`I9Z7@mRY&JqEmVCvZKEYj$ZMq$ix)EM{=gnYue(yTnG_Do-v7tejxE zSN8-S%hfpxqeOyPOe|f_g?NY=bkqLZlf83F=4U9IdJJO8GI`p1>SxVjgsN6h4p%xRE9LdT3oO}#e!lHp!muBfjNu`+`z#rlUP13aQ7Ux zPJ{Ol(jxK#oYuoeiyf(C{$%N@xmDTLR|dD)+Y(;c<5;q`xVu~zNH&I8LY7eY6%6(? z4y>!5J0F7r*X5OT^@c+PA(q&|JAf_a>9x$PTW9u)Tx~zIzhNgTWcmzJk)x$@C31M} zqo1&FFX6G5dtH<}c0{IDr~+0jA(qcqR_2?g>dM+)C1c%F%d6KY{mNl9sGV_O$RNg3c3E*32#Vo$8RGaXsGj%iygSLd%+eDE~50VVGE?*_5d!#}Wc zgZCPy%xZM;cr1IO%20UCoRs?c`h0zGa#TI!Q3|>dsG3zytkUj;Ndp`~V8IF_>fY6f z0BK8GCuqfD#l*rT){t4{VSb6=(J|oih%6<*YPw3~2Jb|#kk5f3hJgC5#U=M5(mq{m zA75XH7cd^m^7)8ZWpyq%&p+%|Rr@nbRPo=z2xbVAh4csm7ApuKWHGky1u!dT)eThi z72b)7lH-o)$aETPn)(R~_bk%BHR$DTJKTE1+@ctSG|&sTB$g#!7QF!J+#lOVyy}0qwqZxD>9Z5cY-$4Ws^#a_ z{;qo(X^*TAv7@E(OW{D424aC%Oe}QET=uIi&-^eiPYV?kNsBZqmY71RUGRz@FSS>U z0KMpvFL)&6or)|S#LCP$Fa2G2h=tQ2TVn6vS1dDluVc!W8=d07k8j3gV&NZ}h_!54 z&Gr|AYOuV#AgqSxw5Tfc3Jft+iK#ehXg)EuY=S zu99>KO7NYHn_q}!)W!#yTS7B{>4eX^M6#e*{d=!gA}DI|N-D1sxF*`W+zMXZA9!pd z+G|YLoo>z7=LWB8F|@Syd=0Q|Owq%$t6WN8B^K#L<$$en{z1n127O2J&#zs+kTM0rnv4i*tUU+hR_12ruHSEOb8|m<( zrCQ>>Z60=g1 z@GoCih{=-AzqkxDY)399sNUe3>bVbhdxbi}6^?td^F++TI}>Squ*{v}QDdGh%a*GG zyuxo!i9rCtD;_(uHQzc7-fvj(rACLj{zP}zrKF~$B$BPFtH7Y;w^l*3HlMzxdNw^2 zzqE%r0>Pq!Qr03G-7U;wBPh%=@;DrfkhnYXPM{Q4WYvmd;nAn^7zfW<>oj;D0^|P_ zgIZc-66|1M93%x-7R=!xIvqCmkLsS!ByUwcMp7BKm^LDofIpa0MaM=_Dble7o&=(E zla3=R%ODnc?Fpn;YVY@~)8PGyh(QjM;)+d4NhyqDV+BPitjFo_LJhEYOjFzP$;XoA zN_^pi^jhd7R$RU;UcF?ip<%`^g}vlLL3}w4vq?^i|_S%C-t<&IrjI`uI52tlh%no6}0<{QP*gJ6j2AGxkqw7ZXI{;!4qqvMq63k2+ zfCNk84CCPM8@*pdtin0~a>Zt_?PcpUcz@&JwIL2?Y0lWVI+iQ|We2r88X69rTZV?^ z^S@)k5}MFQ;tEL?d*<}cFPXV*Hb9d-l(7xMJXcm0IdG8kH)Hr6yk;=^COH_*(#g{y!=XDwptJW=p<$GSX zWaEm*|esCdiT{bN}dr^b)dR1Uv%a9mVK5 z^q|n8(55jH+pPYs2LovnhIqSLI2~R*zXkv zt+9OIFkyO+!mSmWO*9LQj@AmJ!xI7XqMQ+tcK?rM*BBoby$y)sPTYU9+51LXaT}0ukpzgHu^P@^`PRD8$&7^In~X~5}-({9?MeB^JYeNu_c~G%B-U@`C}W{$;5>SaW)M6pQGbU+QCwANT!_{54i zZNemB5*lMKn)dt;GF0{iSn$X!gMaT-iO)x4&Zf8R2L7Pw})M3so9 zB6d(#2xe8JD&Bx`%;QTMBK}IT{N#2C=Oo-UU=_AoFfie0P!|u$%{~^dJ4C6TZdN7h z8a<@;81M?UWT7-W>+(*)cIz}~;SN^(phFk<>X=xpSXru(sv%-A@R1&OVx(SUH6ihh zepUJ7mKn70K}=j4kg41*k*p6Ai~KL~-o@G(F;V6e^GdeWdoikZl4S-h`~}h;ULRC> zT%_t|W{Hmlg)+<>ds@OUeEos`i3EO9{HoDfTw>vGF=cj-sxfPPYz#@UVDrSqQZ-K5 zNW6g~>|zJ$XM9k^H#@A;poPDOw1-Mm@uQs3EK)30mXR}?G;oZ-lBIL15c@G%(%6|- zs~)w?poM=RT1Cd`P>D<=Crcp3KXxlqdZnlj`+u{P@wz=t<)UQKF2ok3F(*N` zI%z%YBP?E7_!nDv*84R%|3#)a=!58#%6cUVWi(6}74N#%HQPE3TKLzZwYpaobLe)c z5>FRDO4B4~C~V_sg9cuyrBkibpoM<}X%kC~9F3-E>{1~r%D03;C6H=Pm{B)b6WcBP zo0v2xZ4|i32Fl|5@x{LyJ)~4r^>$6SOY$HG59UZ zYq#(pV8vGkbQ8iXo_>UPdPt>=u7#elN@V`LQ9v57r?Y)_&kh5QK$56(Zy=O^t=4r+th9@_}dH{SQ= z^Juaf1yo5}p7J~bQtIlx;!HeZo};O16pVsl0swtZW_GuDjA{S?002ovPDHLkV1m1a BQ1t)+ literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/cuav_x25-super/x25-super_pinouts_01.png b/docs/assets/flight_controller/cuav_x25-super/x25-super_pinouts_01.png new file mode 100644 index 0000000000000000000000000000000000000000..8f2df218bb1e656177eff3eef665c55e80b55da1 GIT binary patch literal 26772 zcmc$Fbx<6^($kCs+sx+@T2?f-Mfo0m%{I z@%!p~e|)d%RlWb-)b4Cg_jFIs?Ce(0bWe)Dt{M>mJpmdT8j*%N$Pf(;6Zp@Khxv$s zMzAeEK63T7jlmBO509XtqGEJ(^ziVoj<(L++?=1EA1NtmWo700`MHpgke!`fMMcHd z))q4}b7p2HG!)v_)~2to|LfPUgM)*YW-k}!7n~fO*4EZ~dV1>W>Reo0^78VMlarg8 zn!bGb5*{8tHa1pNRD?t#+uPfZj*bQf2EKp)?&ITAQe2V{pD;Bwm7bn%Zf^dZmTGx< z*?LR+4h_w9Km(*?9I|>c8uO?iT6E=I15E?Qf5881av>qc`VTSspY2m6lmC$tHe^-} zs1jj91Ey;yXRH>nZcgOHh?}TS6lG2BKe@)FusVh}m7wo6?hPH&g(qqMlNFk;0&dGH zHyDm}4FfqPz{Bjpd&AqSX|~_@v&J>~qTEFcWe?8c9}l-`egUOI2OyZ58ZFiQo!yaSrq5jwt<6tf+oary`@de*GV>*^UZ;Y+TiJ$RLb`7r? zz2at>_R|n~&(I9&+NQo)BIN2s!ulrC0LDq#+Rr?N6sT{Q52{E5zbALJx!V0iZM8_; zGP7ob)#KCKq0~U3eeP_2mxM_6_b;yh5XwzorfZlQqT*%|`uYwV)Fph7j`$I|{R9Dq ztVI72exwwebY{rdJW~*{ULFtXS3`nN{*TULI;f2G{QIZ44@%_Nk_zOa&~Sx~@x&pHjvn-8I#F9=A*vTuvO_ehZd!zOb!Ao`%94 z!_LE&14)Fh_M2qwDGDs&k0GH9bv@-b7x_)E zgrJ_{L$(vGBiE42ze@l~4njxAv}umS(`62#AY&a^rbtzJ$NS zYJ@=wYA#K{W$vt~d<8`Fl7&FG^(pw{pI*H)vM8py9^&WR^Ef)ieZVhKP=!g~&XvC< z^5DhkpFw~K?JGmokKH~4HbQ#8j91lJQMM-x%YLtJ*@>r$fA*b`p(sEVa_fV}{5L<{ zEs?_v58;A+-dK87HUs}*L0e!HgD<3EVR^yt@}m0&fVSYwruq(kgvOjDqJ9Pa zQ8sRhz_>41GCC~}eM_D`tPyxmy*Kf5H35@PkRN3sD&K$G{eAs`74}yUB|e-ISxt#x zkA5q12olf5J=y`8DLsjE|3ROBO%78a06*_T#r_5YSSi~Nn$Qq*q>G9gVnX9+Oe}r# z_|X^to-+SwFTHnQMR$vpvxHo|0h@)2h~Hv7|3e_~xi=5MFvR$jmq8}SHsT!gAwsfZ zxMWV#8;!{qR-wL#uTHcQpg?baFa2XL(&HLm2zu0NYYNe0OiE*%EFnD+QM%cFr~#JQ zH`VeDTh7XoB@udx1S5OjTtfFF@ct>av5ud&%aTtpqZw@Gd{y9sqLGJ=)0c}-@5X`5 zh`ITe2sXE$V`-rv4i|?b!Q^ryl88)p0!6jd55j-Y7Iqbw`#&c+g_=@+SJeJsG8_$% zMR%rxSaU=$FG&%iS+|p9v7X!tl<>pVdDp6dT=_G_8%|?%sSfBn;A4Q+; z$h++MZjZK*D6jD3`>?9%@YjHAeDzTa3HGyI8D(Us$;Pm$f-ZHLtew~sHk%(TfFq*C zS3H||as`6cy-d9EO<>+RTPdv-KO2H3@j}rO=B3@65-HW)Lf@g}5Cqyd4$p_!J6)e8 z+r)jwPxPkr%Y8j6>Q=XS<9l=oK~#^*Fm(m)?D1(fON=sdypU{o5{Cn(8PPmTB>Kp- zq-RV-*b|rOM{%cbjFGFY9z)Ez%%?5cV$R!#*0^6c^J~W<-GX^3&%SOo!WI5+Z>VwB z9l>q)T9GN$$5JI0eQjY+>|-GRAsdWv9k0~JT^-$iS_YV-iqPfF>!hHzrZdW&{Dv_(86(d$XBy{yA$lZobq!h$qz zKGQ0RJ#OzuD%Bv?F@g9(9*uRuj*zQgzgod&1Bzz?I^3s3`jchKUM_7o!!H;FTsHR2 zk|8{rpXGfSBxq+;#-0g$sC=Kh&QUF|ggod^IG6+d`=<-xltGSzdWb)_P6&AVjK>Dn z8PpI)5M`8wYv%KIh{@>)v-WsGTXfwtLe1O>K27btf4>$y*djaEI`?MJ_G)6qK&_9G z=eGM~@p!^4N94>Hao{l>UJpd|A5_eZKg=%2nL`^LA(?Ov(==zynjypM90AZXk$(Z| zXN^y~eEM31Q^dBO_cf{_k~L^2qPWmi)sEiP z-SLIPfF;i^#Z$^Mx%o0x{m+Z6@wcgC*?w9OptsY*q&Hm6)PH1}tqxacU68 zr5Iu<{G{)EvrZ-|EUZMw7E+SK(5S-8%$EK6?gt#D?AqKOgBK+EXU>PpY1S^F4*vO& z7Qw!m9h}F}6vIZ0t}Z_K9LAzqXH>1^$c={#(fC}YxPVERBwSeUiEE#<>zH~`pQ3xT z_Veayu3Gd6Pg0CrJAbMZnO(zu@x%6)y7*HF8*!6=Zgd`dd9k0@iZvR?Cmh9}d%w$S zxn2B8hc2x`2_-;Fdv#z8T_R`riLvnzQTeV`jx1KZ` z^hy~1&pvgzHzac<;&2$H_@Cg&( zu^OhnWra32lCNu2fTcbx!i6b8oK!u~>jFJ!|MUBT&>L$T*_^ z6(aXJg2=-YkVuo9&pG-y(6B9;ANn$enRyC--zA_Lg42)+Sqa*b0>h{VrInG_8nwuo z8{f{S1<5&2UtCVVJr&&zG%pLzT$Sqo+jWx8P=LRPSD&oAWovRJ)E|KGjK|w}>af(> z$=AZ`Wf;9xEZ6w@sby1Nvj`L)ahC+!a*xh_d^@4jheJ*pAB(X5?N#&CN%rBi7aeSqmaSfeddS&clUHOUOdHMK_6nIvJk7( zA&vNH-*UXE_!{>6JwIyWruL{aci`y2McosN-(aIyP&{6S7W?(Q_>s*a{A_wG1Dhy{-!I<9?pLVuz1FerM7aU9{d+dTb&SI=#R{ zOJl;JkZi-m(bov7E$6XD%w*odB;94%Y}g3i-tv^0CvQSuztyzJ%8FM#nL27t7`eE{ zG~U`3UCNR~1XpJz{SzyfJ+ZL3UVfrdRmt6r_sabx$EZ#3CUk-D74E0Lky~8(lfL0b z?B7es;wE;-7^EWVo!D2#l>Og-f2qj|+{44W|8-3jC;luvRuP~5v|-yWNSpVWdyq`} z!(dT||V>_*?l*SSAy= z_wkc3Y1>--C%I-^!JrqR&_{};Kq-#@{bpnG&#M%es28t{QBq>KpiCS@+8G&t*hS0@ z&pFzt)nJBiV~O#4E?#u7DR03t8&(uwschzW%*Y2%-A{hQM6Y)ltOytY94R3W5+=pc z^l$4!KN5d1e2E#8Sn>J+IsNXKtLG5iA>~7Vmmz zA`R?`Zd&n=->_PglhTEJx)RDNfu>MooN|9y!Gp$!htI#g5oOG(3Ym@0Y-?=>cvgZY9pqKSjnr`1T+E; zJiXEc$P#tK@D;Y4+zb9WV6Ym%2``s=Df`?avQQODKtz=UZS?BX2`aGOG zD!XJq%%*TU=#|ysxzuHO%c+1qf_?XuyG^ycHbgUpZQN9HxHDlck33FNJi+c$Ah@D| z{kPzAXgsItrmhwN_SJd{Wq8LPkUI>GRd&CKc`0C;%m>X zgMG0$%{qzLSzm;0q}3hyHyfn?RF29w`HR7~-r69dqpxE^Y*si6HQ;*lEB&vtq#Ky( z7-Q86+7NP8@6xl@XBd0281MKox-b_A+_lwJ%lKu!R@g8N+5W{BJ%(B4Hg9NZY3OJu z6}8&Zr8l^P6B}N4EKo;;x~$)AEKI}JbbXvj`C6a+2`#Enqkp*m+`B$IsQw znU|W_6;)*xA>BaPp`NW8gn)FJpci^d{sK&2{8^cfhMfL`#mk?oGlg}6P?LsSFiG_L zAQfqImgE?}LZBv#avDo)U<94jkn7^3=HAHYNQlca{zaEkr&M0R_$A&Yl=Ta<=he7hPT-()fBhP0jZmvpd+729VCC zQkNFPd1BT2w6Iu!8TD`P{aMU7y z0cja`@pBO89?BB3}3GQ+ompP0fS2%TdGCB56GMX1G5zeBS!S1Jlpjw3F3jsSxy?n0~~o54OF{!#or z4fEQcy3U1+26EhuAnlCmGKA&=1Ts2qVPr3pp5*($jEHC*9943rLHLVm$-1w^xc&y{ z(tVHWr+Hnfpc)lXeA=&bl@Y=sqp+ZkITEN=_znR1J7)=aa0EU5pooYq0XCqM+GB$- zBD+ko2(h;pd|N+6tZ#g`n!f8I9;g&He*Z4{^Y>=4r{NXMw`w<5B+1=!9dvGwrb~;a z%%->yiQv>1d8h=oY@-Hbzq~rLx&5$ShdL<@v($1Ho$zk7nxE|~0S=OV7?#zqIZ)Fy zQt7a{afgzlHpzWDqPKQ!_UVyC;rNKt>jxv8=c))A3OQDaopIixSLZe*4}+Z%mlxNs zybW%en8UFV_>n81z|7=Muw$zQGMA*haAVHBZWvDft;xQa^9!;x_#z%j?Dt}4pZdNL zJg5I3n@o4h#MX24OAx&9m~unxe5O@iz=XNY0#X2g5Uxj4C!YKF-srCGPb1Kl-*3X}K>htazcB!M~4{?Iw>SYtC8CEC!8Nmi)^ z%%nxC)Rb097TP?CxObFq6kf6-FU+fYLRiKJlZpI%|Dn%rLv)WYqT~4ND9K-;oDv#f zE>ue>_h$i<{cfQt4wE4NW(UJBPaL`Olw!0iY(uTno+DTJw5g_wBt2PT^CrqdTHqoQ zTMKNi5>-|^AzJ1tTjjbe@C9Qv3^`@4Ai#-s(26-h zejtU73u&MvNX8ujfR>DjJutGBnHn$h?{SePu5QaMX4XA*-Yfyt@bj`O@FxtYLV|pu zou;HR6Qhwe&BjmX_cF9b{9ipytG2kW^C?l^D#Pj?u3fqTOXJ5Tt!o6>9`MkDu*PKBx$Exr6eTF%wu<+1|L68Ucqj@CPT> zu#;cUUMsKAxKN^07H`8|Ur0yDZ~E8>j~KiH<9y?RB(%brm`5*#9l8FbdoU-Cb@`J6 z@0d3&AMsSEI|}%=aT=Bk?^6S_+v>1W!&d zFwY~nOBG(i?%F8U=H&P0o!~*v7y%_%zP4h-YvG~;jHZezN|Y!n$3_PJG@psN7Xa~v z%whnT;EoU=3%jaSp+p72U2owBazO6KiyF&-0}BSDh{}Kj8wUkjZe(Vxu5IMC!bULs z#rAZ&r7pGL)-{b@FW;=1UawVE*vN|m^pI;sV}J?gj^@G5ePJb~nh|M!IdDSl^$M=C zYj}8R11{Mh{(meL#JmH)s-X0YY_Vd|LE2m>RUJUNDo3f){tu zM!1k9ak?!L-l`zfl?8n*@!j-lJp~OBrZO7-=TvOP2DoqHrd}1N(Gh%OJtFD}RL1~s z#Q1T<63T@jVZUH0mH>NEYWn^0eaT?Iy)Fd~rqn%_c8GW!H7jL{i9uaxBe)sxo| zv8o#bjepO(`-808y#Hz7jne}-C^_X!Jp7UFQ3CHUGzpe}vcTG^Vu2{!x9dg1EIy0D zPDHR<&ksHTY^~^C8Rb&BG0Iuyi(-LUF1soV)|>l0g4jvxM$fe*b|>7fXyZMjJU!i@EPA6=z3#GpDmo@^l4sRwKR#JwxJ~8UrGF=HZ|eh{E*jfE7UKh z=82G=N_w<2-xkNJao*mCH(Fy>&}(ZaE&uzw~zPSL=tQmf)z?4ivl z_)}ifS%KbWL1)?)BQjoi-vD!P*n;tcbvBYq2(HIk{DPQj78#`+6+tB(8#yigw0Mnw z`??a7E!W(k?(FW(FSH$TI?OvU*tD2lTNdVw{EU-T9k)&PqSC zFIy`Mrg>p<$%ceS=}amrxYF_KZ2Kx$G3mOgdochhxjNDNczw_>PsawmU#$Kb9~^iA zm}VI^#oYg%4Q^|J?e8U_);c?HR-6ctxmCfp6BVCGDK9zK82?m$3b-^oCGomVIgjup z$H_uV%$R!i9=vq=<_!W-`^%SP@QDgjX2X@I>^m>d(3M++nz+N-qo#;r!dXQHyumd= zMsn-}CBgj@DX24 zLztgyn~;%nXM@bWEWaj1YrTpUlR?GzCXJU#jKw|ha=Sd&?V*XW52$5J`RXD>vHXu2 z+5Q>Mlh$`S>z0020(h$o^CO?lgNPVXorHBKN2L-ZDmIoJ)*DG71#l_Z%-#BHdSbKX zMa3z25ib0ny*a^w;h3Y~jVzm?J#Ivfli;6ODcOCU;~l+af6?n=J;HFEC3rQW;LlRk zTwPY$E{kB>W%7~U^z!*Rd9`@aP&Ik4%m=KtO@8tRE!cL9+w8 z#?XBri=eDxa7p4>;SHrWbF+f_&Zv?@tb&|@51441Nc1W*;Wsj$U$>zXY={?$zzmPy zU@@@&d9H*zhq=$iBqqSpy3^agXHyV=2VWbDa(iGtJIkQ&NhrrBsip3%APUertT4G$^{QYl4e$K}Z{0NtUPM-e&#sX#VE@VK_{gY66sg8ezh`CEazE zUmmu4kuWVnhf@la9^R2f=-z*skR$>>qk520hQGIiv!T%ZG5XwJzyIS9uYOZNE6+#6 ziWvJ5X3oyr@Ja4_7R5T@5S}{baR15%a~|Jq*NPnbGs!yXtd`w)LUT^5SW!JV6Jqp< zO`NN(--25b3c!mSB_x~DfxSqkcax%JhB-2rh8f(X42MTpCszQY!Q}v-8$dTcsLq4h z?ssjA*}md$U=JLkQuR(5x3bdg#cO5bq#B&H!6bMh;zhpEJ-P6+Y=NyWl5(T7v>KQs zWqtVB95&SVK2B%3%Ox}CiCH#QElI?OO}Tz~<0okassD~(7Fo(fYAG3Z0|K&_Iy=m(mB*Dj-_og9Ep=d`pw2o` zIN58ZuCol8FG-BF@Xm}gtogez^-tyCp)8VwjrfVx633i%3b>1R{Ei|* zH`wiCnLni`VKJD=jtKfvEo#|@W+m4mz^pE6%Wti$SJ=`bZ95=ZjcV}7Ua+>IZnge2 zxQETi@HD7E-NSt4XJ@CqGKWJYXgI4*CNuG4$z*$I-~{aVU97iB0sOCMw$xdX^_@C+6MvJMJ@&FnTlWO2u z-L?+X<(3=;gKFu)UImARYW8SKBsYSkz+86&qdDHO`ww5DXFXu+-pEwkGEt^$v~hD* zG~Q>CrNpsGc395e$c>nQ-ICpG~Q()Q4^aoOC1V9975kC z?@#xBtx7)O=Rj!K&ZRN(BAh|ExN6Lq&LtCF;m^ImZZA=q{uAh8oiD z>9ET}b7|7qRSINg;;I%!_)qzeTbU+EAnz zN#1RMoKQ{?F!#(9DI$ipgsK}GG@pr&3dkQ>b4`aL zc;`xVwvfP=-Umwv*F}_sYNlSk)~xz^Dy8PP?a%9S>`9oOW?!yvK)3;UYYWtxkc_XP z9gO%NIA%z62B^(ObtPI0n|olQY6T7+8>}c6i0^3GUoDtI?%&bhWTfGKnS#GLl=1CcPDo)zgMv@*qlnEEr$iC_}7q zQK3>xW2MAHLV3VE7eX5G+S1a=K{NH9`rqX_2b6jWZA}VSeTOusH|4|tgu5XKet;+M ztE5yv^+*>`dnp!rzqCsCt~Z4-RTqJQj%mHZfQglk$SO@2MLXl@)3Q>>AXiaW$Gdd& zig|NTTR-EuRlmHdgweW+VM$}%5i?a}mm+~ij5!schn!%j04$Yhn>DcBu@XDgc*Aaj z818V#*?5qfiqu)pxoLN^F8m!OaI>=m4DK=OP_@P^5H5vgSFw7c%^2CH6<~5+L1s}xopNp^? zhNfr4dXQ+=^d}3-7y1cjw&`R#X~LedQqH|&9wk6});sFK^OybTy&BpdTb`VG9E7oi zl)J=`N9Z+y^)#|dRnMJQ7`^PUeX^Pz_f=nPJsDlu?v8>9zW&f#%#$#U#Wkxq#t_$? zGPKg4y7|N~nvEyy70tCY;6v6|uZfiNroO8TrW&LXLR0JufY|(Q>PK;!+;0B%fF*}6-T+bA;weXnu$1F`LG%>U z+XcJnv#%aYl87h8Af_1Im~LGp8>|205L^l!1HPcO-&1jE?u~+i<>c1o9xPp{o562` zAi59(z^Ayfpij?|rjOIUP?0(jjn4^fJ1EDN;!fvwM`b#8;Fo)2#jV(qh=z%G%$wTf zRXVn96I4iEo|}jd#sastSfPxN$F|ct_^f=9d?5Acoe9iy)2x`s7-j@A*5Kb#Vej&T z1}4I~1@^gXo=hEDnpEZD-7{Oo<|kf7GEr-z9EVOI%p`MWPiC^`|+QEj3; zKoi*tCql%)FeUAn#sVC{v+`XaHFQyDiHTCjuN#6f}%z#n+gcJj7SdDG5LNBr?v-6#kCQOOvpocqu5fCeYzt%^c<8# zN3ZZ`$D-Ty4rJA#j9uD79{^7G#_nru6WCVD^td7HMi=6;szA08f)m|Sr4L~itOYtl z-WAYxYb?>;ZEE{3;vz$8=_QecKWL>0tqGEXtRV0FFLL?c zCDvc}^$@xgH}AnR;bg(~MmCY=V$0qL{skwVhFU#XT+FL}Fw+k_(97KE&;c1b(X3J0 zD(TZsz^<|mbp8f-cpqHX@4xmK8n(r*6VMyiPBi6T+L;*hPh<1plAgc%`)-Ph2G4gH zt~#*(6un{6?O+X|oF`)Ny_mY<_p9}aA4;*0Kb~Agsj!S8L&(iJD{B2M=>cC~gBxwX zkrDZQC$|oC3zoYbXtu$`cy1=?K^EZy0;JQ3{ZHb3Nl1eKncjaSX5x6P<2n8tWX5YD zwm-?Oz!^!H;~QCHD&@uq&Dk+lW}jK(f3c()Frxs5NoS*tSo|WU6g( zL<_mU1K1gN3SzrWEi7A_QmklfZC|!A&OLhUQ{vxO z!3Z=l{)!>eT+k8|VEB%4!Dxo;KbQ7_%pT)FG3~3vx{f~Dix)-JYx?5O)6(c90M%Pwg=l07pm8MTbpZw#Kd}%kLTF(uJh(NA6cbR)F^gm#biOt=)bG2o6}>56 zqruyM(A!zljp`{~b6rYv^pphBQZ%Nm7$EpzUAE0MvmlKa47z7SXkjEV7k(gT=e!Ur z`QxRZP+9c-07f)0mJ~tx}y;@3fL$i*QO4_?yej+79HezuW{D% zoiF_;yw+P(sAz@05LV_8x*iBXBYbx5?=Np)$J>n781HIX(T#V}^4`Oq^ww#eyMXYm z(z(UNWy2-j5-fr2e~4-iSV1O8D&#GY7T6W&f(;x;-F%#`eL;Bis=SQ`^rUpNvsOs@ zTEGjzjlP*9CM1C=BxZ=jm<_XU<|v#t>5sng^XNAUAfL72gKpF+$VQ>mVaIiRJG$o7 zQpL3CC;H|V6m;?$7kK<}1?Y;7pE$K~d(<|6#}S{4*$cB7)q5Eo|)k{meNdbXzTxc|i;^Yx)i5oTScBO+7QvZpU?hhE>;fJ*&zXUXNzYVl$9= z@At5`MIsK-tE-gZ)0(VN^ zgtL6C9L1x5I+!13_86eN#KtL9`zAPZ-WA&7UYmKrSdglFv>&5jNd2ub7<``Z?Chq@ z#@WZ1+=FV3&RTB<`~DGowN&#XG~n$OU3*~hM<$d+wMQmYqme&gVInBvP0jZ zMaMCaZ#*ym^K`coxG1%7W$qC{fRe?k3VK?vQawsjENzD?6_J;Z`*;m|x4AX_^-K!o zHiv5q{nB)tWa;OLqpzCyFhAzy?_gm3x(3T`EO;Qj!=j6;0L`{Dv$>M0{s2JTLlKGR z>Mn~ta5Zz150t^Ni|P9W7@(ShZSnB{HOaEp6KhPn@P}b5znj&S(f*ZnBK#ZV-NBPP zR6Use%RkM!A%9A|wH{-hU2dIu?7kqb#G_8?yPY}dG3}?+8)>bC67ebs?$UsK?&qha zqRg)%6z~wXmOV?gqR04e?4#X^{nvWTHV9a;e(zg`1}=Ly&UuK3mmKNcuO~J{4v}rS zG7Rn)GQT29wREOiYcHK&Atn9l7{njGRjc(WH0}N{n^7_lQt~b#B?)GP*2p}?Om0=f zfDpe1xl%N+z=~mj^=+=<183;X9-;ntcm{wpiTc2hVH0-v(fDs-)GTV%$t7T5#iY2U zy%Yw}`5%~i5q;q8lQh=x@OAsw*l)p9NQOr4csGp+GeY9*sN4H~)S~k*Q=uQyV;U4U z6p7UA+FbEDcwwIFb^E7owdS*CxQ|URJ@sAwn$VK(R%GN^iJ9map=cLH-AW&o8O?6!#>;*;9Qs13*b>F?Q873RtG)T*Nl^6&?=e4_4 zDm};AvPtCUGO|dYIgY5n8y+O&)z^QE4t@1qtXLXl%EOIMYsvGu(yJNmS2s}bv6Z_9 zM;9h;6&sgVYx$FKq4DZ#zJ9czVd7OjT(?Cl?{~mtgu(gUNIEF{nD|-0b5Yf8d#OHG z?$O#S5|-M)UJ_?cDshk-$?^^3!k4i@#V z^tRNtk{MU4Tf%h^Pn4glM)fuuS!i%mEjh)DH8^KP!_S|1xjd&wU+QCL*38HsIP)Dz z;py<9_^oITjpsgXC39Cd#=RktUZ~jB%vc{+ZqwaVI|m2vRuM3_a?2E@^8Mp@J8_EJ zMO(lr!KK*{+*e=uE9=hYopRlt#F8Xl7Ph^0{@;;9v~y1J#A>|dPq^2vD?MgPIv&u_ zS@}LJ?cBrcTkXshO6#%fw4(R<#lhNU(^#VKyW2<3lT0-`vTYT!Rjoi#Po8X@>rlIq z44UQpI55a$E55=D`)a_x{HudSt|$9;TfWbIz1zJEO~A$kf~`a_rfa7QYC_(H zY2!WmNGY0L988T{HH-apY|>D{@b`s%ps=Go?IDMRUz~n?*3tkv%M_j_Z9Tk|t)4*M733*_~N@f<2UaklR%7!&46%YRzMer9w;J0^uEuf^-WfqdAl580rzEMbE& z8=P4b&_>6mVGJn;zWf{cqQbdjGqi9zb9_A0vrLOIV72*8|8)YT}%xX(!NTuSzkE*Ib9$wTh8`I^)F= z>Hv~2H?n-F*SC|BLHaWbukUqorCf7J^dpU#QP zmhqxmJZRHxD8d(1+cYl4j)j);SARuAs8pQD9O_Mpn6j=L2h_uA!x%p4`45KV0Sq+k zNngs`IY{o1inqEvO13XIpw<;%?t4yqazuOwnKQscpMv*1CNOzqERh*Xi1T&N=ct)u z3kXpmtL5T4$X8o%(rP!EFgA2%lW)%;YR~75Xj*vo`NU$m-YH}bf6en@o&4_iVGd-D z3i@rHk-k$+$?%FqTEmqz?Jc=SFZp(Qqfxu>^KY)9E+2~YqhxM5K@azFLkq_ws7ut} z!^7KEDzXC^wR3GVViQ@jODwdMpp6$5EBs=QJH-bkAC}bTO+~K;==v07SEy~7`=+Ru zM%upB(^jtzc7+tfl-{9d;Seg!1y_FOle-jr;=TWD*k?IE0x4Yg)cI=q1usv?iix2C zgrzaL@$NBN=|_T+^P7^L*f2qq$JN~F>DW@M6TvXmpq|%uOe0*%>A3fI*P9iUH?5}^ zEc09ry6RPfS!r%$5q$HCSx$xTTl)FERldk@^##0<>^?@Av=WupczxkJI2Z(wSNr>y zFfHnB>}X9K%o;M-O1{(*N3DoFuT1Kj*rzldH44fnk)xkD{XbaelXfOYVq|+-I$^U} zvof&boI|G`uz1`Umxk0D7)D~)#=iOwMs#FGN(Km@DK+$?BdD_2$VO_KF__hoH&Y!_ zyxtO`U93r=wYFv{qsp@YAVN!XWx+}Z&* zGzO^Q2tnd$uh86GZ|~1ED*b*wNLPpY^?QoM<6Zd-E9xT{#+0c*#H9x2j3G*bLBE9Y z@fh4k1CV~`kK)@XN`zwJk9_Hib70o?v9L+#N4>gK?eJS+fZs%wl24~!_} z*?(Hs=O?j3vmt}06$a|z^l<+9bhH`~)B>zndK&=0kC4U)}26YxA3bk|vC% z=13XwInvshAb!DVG547cx9$>4`(nbx@0uiS$g7S2pE(wvHw$kZLrzAL!pHnc!}OH; zkh8iFnX1TUFfu{fhsDBIR%}oLQ7JLGP|dV5<%|Fb%Y{yU#xt z6(Ec!hKgx8Y6sHM4f+s&|JxQP6532P+j>3yC<(XZg(D-b%SG+E-ZP7RPhUc*?d^~M z^bh6pXA6ubdgq*_O=Xw3%lOM{vfvYmGdJiP7X8?6uAx@P~0nOnG4ochj7Hid| z;v1xF?$kE_RqJ!-1OvPDRYZSfl1W}o)a*pxn$byJ0LZm%ad@dUpGw`Fe&O`r%qG4y zZ}(T+k}TI`+`6jk0qW|Ia%`hhvI*o z#r*WpMP~dzj$4|1i^D|!4~_X@MOFWQlKzj<|9j2aa?DZ&_5-%7Z?d7ukXtayb8`?qjyZZBen8cTtHT5XaZ!6*)4MK0b!bADYe^ zpyD`OTXbjh?mOG-Q%vWNd;eTpKO*Zsa~!QN3FCZM`)X@AFVs_Z($3c0Zp_0eJ5k%i zfHDB}4T&8peueyf-Q7L*7N6IkDM#}oOW@^^SV^k7{Jw|62Y2e}w9r*G{JV^ojX7kf zYxvF92WwyX8m6BUNJqq_gdnL*6$J{t>b!q-u5ThW>Rir8E7;OqzE)J36QUfI3m3$x zuwdBZ^Yk3@E)K5n`Vc911bz8mO#KOwJ01KyX4M|PrvDbIhWu|FTv{5foUFb2%1Gkx zW8nCAk5LKq>tD4^I>I%&y8fPZ{l83hOkx7pgX%dF8tF~Am z|7rApU!+jQct(b*Bt-y02F3e-122*yWJv!r+@!m{a-a6HfMA$lawI1z_Wv{R-cgO4 zcuWWl#Lq3pBCPZ6mg&{uwdma%rMAl^I^iTCHB1zOrBeU@DPtPfi!^FU)HV1!9icL( zH#z7HJ_-FG_scnLPY9C8XnE!zumzvHUWfH4neZ7LU)6UX7|RtTi$G!-1yA6%iTr~< zi^x_UfT;GB?&ieEs6fzckT&NHQG|@N$87Qkq6S!(`|Qlusm`IWvq$oW59wiRI1%@$ z*Vb~3r@2$_RAwJ!Bfs}!Zi4L52*+%P=ksABFgq@M(ti&Mzp~1LRS%Z?gMtZBPT%*n z#ok9SfbkBM)lgd5bIM!JFRQ#bhrZwbD@d}b2_L#~NieK>FUPi-pO(XGoGP0bsg{bl znbRza{M8>ZLeGcffBj1rphcB6^K}sM&kt{8Qz~Vxq5Rm%Gzjl(1a=ea6bU1qR6kRR zda~f~!iYI>D8V43O5ywHP#HI=%GO7&HW8%etzU?bV9rA1jNI(lwft`cO4;{tZo5I`E2C}Gb5r$kxUc(r!->zzOow_q4RKkS zxMXL$1hranO`~dm;M^Gj2^kI#)+)jKAGb4L!}N2P_xwU+o?Y)Fdd7O?Jo_ncvjTNtw!(Xa`kd4`}zJOF95*wm6#>+$a&o~`wV5L+CnZ{6xv(NGT8O5YC$CCK~D!*<>n4)i^&0bR`kV+li! zgb~6+QpmEbX_Fz#k7TsR1QEM6s@2U5^eXhCZxO3!0k=-{?H%1rxDzP}Nmifis+blq zVs=?Gs|2Nxpn)Gf+9#Ki5SSxCb2Wzkt_?f*ncjk#+AD_8zr{W`pRFQG&dc5Z*cD^r z$z6Q+mEqs9xnYk#b3<#Vr_+4Et%lgJ&~1q2ZH0uJ?g5Vd6f-feZ1VFZx>^5b#0j2aMF^xT>ey)z@;}4_U|a z!1?8ICN@!UKys*8D@_A|v)x9Ycs1aDA$+PO>3*{A1r+7+0DR;ZMt0$o_Zc`X$T)tX z1D^d*btH3gEgg_o4o$C8NX+OK{a?j>XH-;6)9#RmoO4bR1qqVV07DQ2L`mupB}*Q1 z&N)ezGz>_TBmy!>P!N?kL(U*UM#7LrK;q?`_k8!R_gn9ed)N2l_WrTEyQ;fuRqeIc z?&_*%b7(#5OV2enX4`xresY8-eo!v%qIA3~=E!z!en-_f_lWc9x7G(1gYCqFV++aU zAGsg=scLB1BMNq$U63Y=`Oz*LQf0?QHJjf;lFd)-u_TUMrUC7_69i9THi$5SW-?7?i505`Cb=Xt%1q~UAf6AIihpxk@>p%xOwWV+ z*N%Ad7cn_SB4e-7O7wGC&@8qKTn2dz5J)Lm9-w%!26;i5{T zPm*8XgbM|27Xec_R1^|1g6B0Y$=$6?giTKqThQCzHcJBy9#`-h7rSAOEs~Pb;xy%HYVu393c&j0qkXGV7q7e|Dbdh3vICCn#BuyW{ROFB=2wt6uJ8kVE z$Ac=X+otiYomyOFKoRj6*K3nf^VhC_`>Gx4w~@cY9NJ4Fdpr{LQ>;8wP0N<4*M*-$ z(=jR0*Q9Twc7xmv<9C}tk|RICgJ|peg%vV&S5DCcecOz5QfGg>3-`E}k@>gCM5spz zMc3bs`eRZYSu!Y{kf%B5g& z%?<(CR840__F0#I>`DnQZ-h4lVYHqi72bVhGTWq_luKSFH`m-M2pdtfyWbjHq5r-#hCkd?2 zfVKThpt`f*(z*Xy*FWAWupzaC1)kGfu2q$zLzi4j1$KWy{e9fXVY(6s) zkhjbMD&y;G|Y(u7ibg(ftVxb zQ+Tz%7+S|#3*QZwb&$2$MxZ5eYY^5KQHxDzPL&G_Y&+)rBW$-uWtr~W7yMNPRA1Lu z<>gL8E5jX<1nzR9q64SJt^zRS=%3doF@hQ2+jq4C>eA69Uj#!KmcDRU*OuJP6X}4P zZysGv+D~3>5ROIUp2*7kTT`Z)jmGc=Xz@@Ems0?L<-wEr5(sgU2=gNKYX&*zP6#?| zP`~yHEuh1!)iarrMhV?b{sZ-HeQI>!&;9+U5bpO3)V*B;jfJqKCl}!#P5g@D-a12o zu59N|r~x1_Hm?3td*FqYR2)oP6B@%^EH#K3ULcjVCl2 z^uauQG^0w>ovUTygP!#OHF7uaMRL?B0?yr);sjqvMTF{9;|SudLeRMi-@QoF*l9Fu zE6?tr4a(5vsefb(lk@H0w@IC+Pen9fx8mIJ5aal|ce4R!kwcP5j|O*+1`ZaqxXcz| zA25hejb8gzcu>@GDvXh!$Olxmz37g~ohubUKkdg+tPjReBRYKJskGK8qgB3^6Oh_5 zLSweS-$CXn)M(plFfRC&C0QQE!SBS%>BA_g8>~%#8Ghv2LGVvprx>LB)1qw`?L=|E zl|`;Q9j1g`RFh*vS&5IlK;c@KV|x=CcwM|W*1MJEKl%NWi$+&@_FbLNb~Oq>jU?;4 zw$2-|IE4eRgQ|oBOcnwFU3cCcYS3B>s+BIZFwuxZdA^z3^NtahEVG`tdt0h_FsT*HLc^ifty8cWWNgbHM(iXZ} z)Cq3j*-|LK$S;d{-0})Vu*FtDrO=irxxWZP`ma6eP@gJ)#l)YD8<0kyfJbPFW*b{y zyf+2pdLkDZti@OY8k4{o=qht;G2fjeedmrWogq_*a`zC+%GPlcLLbk!X96HFK{+0D zA%Xc&tL#g)QXfW_aVY}!$2)0C7$;w+7bG}{VwBeh-<1K{`;~X4Vo9L-sP?-`5Jww} zZE1EZBj^0L=ht685JL-Uvq|o!yY4SKGrsr&>oeTp>$Wc#mf7JfUf7qieAw5A7k5*! z-y<&8;HA$@*5u3ZVgwfc3z}XxX1Km^cFNy_&p9=>mne=LdnDlfJT!>KJ1~&^xs~O0 zKasC{@S3>dR@(v>8UCZOSxJ%g!p}E1uJnuJ)$pm;NI~Kv$D#S9x#Oq|tLNBYC0JcC*R7O$f2bl4WlNajup7bbIv3A z?0~9+eR{jF{^sT>GQlJxNb7ZC+$3I7Sk}`XPi{E3-`;Z?y2uK@(mT#w=n|*wAumnN zN7~tR4G*<+O!B*f3nI-0!^+Xrq-(!}*=!PD9XZ~#CCsExk}|BJG;g@JUf#Y$$^>`E zPKDcEewF!7*epcjB%{N-eDmv!m_e81n^^3_QJx&FQT7!d%*-Q2-}IVPTv>Xjq#uks z-jK)S^_JS>OR%wv$p%~mS0;k>`QaBRx@O_|kL+_f^eqGmrg(jjB|Nv7XEYD#>U^@h zAx3!4-AXeML7G`SZPgGQ==>Y4gJ8w}%6QsEh@M->3ET=lRKL$2v?k+7;hi4Q!1h9M zOYSV6;!0awr}0g0G}ag<&Xzq8;ln1q(ikk!UU)l$!Yd4cvbRw;KAK{#cW^pPHkjv& z?JX#a8$<8lm}>w4+q%>xriWkIE#CnArG4{GdFk1X;@x7vKFwL}noSoSnpy|fnt&@E z!1&r1tVxsI>3c4-;{Io^({x|O`Q!TvZ8fV1o?M=VMuR*+m*!62G*?@fgT3U<)6bcC zb4&{j!;}%rF6QO(0U6!$X%b$$E8L=?xg@hM=_-{9Nn%JNOUkMxBF3cD*m2z5r|Y#^ zaVM4#l$`GE3x((K`N;8Q=h^^h z#1ZtZY?hs(rVdB{ zGc&SQoKL%a#^0`pSrdWM?=@;gxEX(A1VGwVtpZ!AFZ~Gdwz8O~*B2H8mm4S}moW~+ z-HgyT#{O4kb}5D^zi5hDHH*(d5=a6yvNNt$KRo}o2Er^}t}5U5nS~v*&`_t}m{+6R z!(nWx@yJnweQX5Y?EJfmG0QIOd>Cxnc_hUCz+ zdzcsaT&YnMeXuH-demd`dk`Sh4c6W+_X1zedHN9*9y$;bcJZTYdHJVL*WxP%JcmeM zDySYFLzyhImu#0kuJ-br!Q1f(np6(%41S%Z>$;R%vyGA9%cCccDc2~}xOsnW^ z$<%}RUmWBG&2&Y&*B4g;hk%}sTii?d1gS7;H`qfzDbD5n?cyxUTHSk;QI^iIEoLrD z9Bj(*&f!RPY+87Qs(&GI0?R^cK9L$@Tjzw|b5wk{{2lt>l^(1Gi;|H@KR6HQErg`a zpqo_^bO3&M*D|VcKBX`f`j@q8aaG8oN^qn>Pe|`s;XrBicsL1{g0yAWgO+7l9K}QN zu|~6Xexrxm>=Vu5F*UcK43_-QNwAMyhM3TUmMS+W=`!A5mdMm5vyTG;>%#BI1F9w6 zR6SK*Qz-isk}AqeQJnvYPOb4zbL{6lH+wF$lv{b#WWaa<+!bmCtu7u~z&Wu#<9)Eg zfPkb9LUb9O_Ix}eyNd#L(oL+S(q#aoTKdZK%IEoI+0FOhuj3vy2RkS{KpQ-P^{jN-O ziT)AiaLW3dYnvJ?fY9L6KY}byRo}I(-Xw-GH5m@g+TTUrwX19%TRl>HYxYLr)+dEK z6VoZW9yEVVhIy)H&N~e=3ya9BN&oF{_1g||Q@q+V^byfxo8K;v_J05D&Q%Atq-PQy zW(_%e-1u<8gZ$QK)R>WIX&3bLCWa`)T;AELl@J2{`mA!ZW1j`P3^mgr>vBQ1H0B&2BUycnC4WiPktE5L)^YFN>= zlDCM%v-IbQ3d8CZ$8-A^~FZn@ImW}Klp!bFBdaD3&W*H8{V{1vNwA^OjEZn!>f zvb#h5%zI$DqtPmMKYOLTSN=Q^CX@uhA4ai4*oEC#GSK_vmfqcb%8y~YGFzt=@mbzk z#}~yMm&;p!9eDsb|3RY!WZby&R@eSpX(A%}8=g|_x-k{@ZJK?y4*QkKR^L~N9y$N^xUT+k zOzLRzYeR9p0uT>}sU(%}MKjIH4aD%_o&_u^j%ClQ+qIzZhX5Z_D|R#WMiHcEm5ba= zLP|-mOPKCL^umV*l-UM{p3XV{N(SzHC}W(3*Om+hFNpctQHb;ot#AgDo6 zQc!<)pbVA}N=v>oYFsvhbhOU?EeG5ALDkjQ`_6I_nMVbBBbGC9!jSc`!%v*;D=N(# z_R0w@m0?3l>v@1I;=IQ+8+9KWs$TkvPgHmQ`ff*I{{{!%k<9aD*hH1>OQnTEFkOvpcAOzgXrQj+EhCyhneGWI^UcuIPQSmOv8 zV~F!TIxcJ*86K5a(ovz*N3DD=b5Kz>CZ~iwB21ga&-D)@XIJ6DezB@k3;=7C`bHsf z-o3f=k`Rg9R}sgWNMkLwfLFWHP;!Vf+N`R~Dm5-lm*srQ37uC_W;Mci0pc+}2O z;iKaN9Y@{Q7GQ_`4=T;B;&tS=`_(u{K58MvtX5?*Ap(8T^Mbvwjj*n8jY-0%`ytJ% zsTW}>vDAnMKnQD01C9C&VOd>;1XkflXUyuV{~!H5k#`^<2Wv)??~e z5aNn1DAjNKjpc(d%lp%u-}T~#MUDH$VdN-BgJ{p_KTi%RAEb=R#ya9Qm(BF3%W{tk zBWw*#pR2}0jBm{K*TNl2iq!7ML_U4csS#K;Z|nP?=Q2t8F$d~nByRZ(|q4Q(Ex^Oohe4C?!y;*G?iKO@sLDWHr&-X#1n%bS*# zGzdFGavmZCDP$AQ`d805eOWrUarC!H9%#(+y5%@QnPKWz0ICM1>7*oKaiSFBH5@)DP6Ks>LTrr0_eX-EPHW$_O7aGHpLH`SUx11{#IwzjxL< zPJ~>)Sjka-?GhmwL3?xn=53CUr14e$%=(8W?SA1-PpcxjbsK z(?A%ehwMs%?c46-F^U#mZMHCuHshj8K^}{F+wAZwVr& zhv`sBC_%&-F?KL)nG?ait-yppYpmQ+1}cD7@UR)Njd{~@Eb$%Xt7ry?M&sUP2Koc8g1_1Dh>hdJNos81J8K2%UIY-q3R=Nk z>I$Dc`Tk+_Iklq|-pne&upp@P3qj!n8x#DcRG3F}32}@CeeLTiWDmBvQ$MWLuWk0i zB4m-`%mHmIzam%+>-8#Z2u&QiemtTB zA`0V?Z>Y3;R4_xgN&CdNh9( z#C-Im(oybS?k8{jr4bEuqyzsko04->SO{Tb60+jAADZq)G;3wC`P&lUEAhGL{dLPG z+zfW}T3CD&+pUOH3LIfiVpp|E&Od9nJZJlrvkbGPHvu>Zk8&U)4bsm8JsM8cwJX== z&ipXL!1INRVr>u|EHIErIlxORkFaX3;0kRkp4IL&wIExf3p}SqYX>rQbBspdU+rCu zmU|xjW)A&PZt;rPkJQdY>3fe{mWRZ=iS?c%H~QFilZ|BHD4!SzJTL!XRhrA6)|An~ z$Io~ma9HG~qf}+q23cPwPO7t#X7^`Y5P>3Iqn0NYw!0b63!3R(FjW#9kYx~?qefxD zKSQSA1;bx-ub18i-UyWRpg5xmUJN?Le4H*u$^#9UFCXIIh4Z5AYW9ly5Ww>|m75sgxoQN(C%-NH zP`%P{b^I$;HKGzp6Am47X3)y`Rw)(eh7lS6`QAp8N>uloF;(uUYb%&XGR$N9*brS< z9Bg4jl~8ss#6c2ja~QRM(?swo?l9_&m_o(PTn#8p5> zHk`#qP(WcKVch>Oq-)=#;umc7%^NQSoL4)K>eWkkiw%tT*Ns%Kcz*p@7p*z=QuuKH z;%ru&vhb^2N%AxQq!cw(-BR3*n$oIFRU|uhL+H2Dt9R)ZucqvDOZMu6=EQP$nioH| zTAcujUmgh{M^rO9)2=l}r{MgYGdcXZ6z+e#-z9I_V>b)iPj0`1vnBxS=u!eSK3e=_ z^cJp!3D_6zewHF+^yKAGTDIolh3ZBV<3x-bKkHn!nu^7$#>kSm318+K{Cuzi`dF{oWCiBoagJ=Z=$xRd?ATxN+(UmZ0T-VI?Q&_C2D^BLcIULxqVJ4pE;ge=&8$C-AGT(wth8ELdlPFPvSkFNcC$SA7@>zPuWKz*&Cv&(wr_|aR2RaMFhxWUjPr5LL|i;H8R?B? z0uPu_tj<~JoMbn$A}Lj#T<*a%0twniQ&i~_=$<~^k}tgPF*+HuU5Acj%38IrvvAVP z#w0JpRnJ^)-6^K|QM~-z8QKH*W;USV{yGz^06k=ihQ`Y`EbBoPW;0#Nsj3k!g8RT1 zhtf8&!c!Oo-z`NXzxHCk(=MYqQX~s^EB`XSEH{J$&XhkU82eh9E8leUWA^hqb9y+eOlMp{6MA zGT}c$3Y3ORBBb^>_~Rw&G=poPkb2uvmf=eMXfl{k1i4Y7(wRF(E2$1WPfQuGmc3YI zsx)ykY1}<|RI5~v20bxD{rPG8eCO5q(}8#}VDimtd=2_XEEQmS0@)@vwtS+MkrDU^ z+;xkLidPb86g}ESU z=``W^Q6E;1SE)PXlN$u#hy-%$mo6P#4m{Js=PgN?<0wam(BnvEP5qB!g~X4NGLc@M z-DA=F)<;o?_tw2nJck=3DcaU~fhpj@`(r$k%i76U}=VL#1#O^#{G8bUr3s zi?1HHF^ybYC*;{I!#PhEY)MA7^#^{`=SQ7ROeA0T(ymd5$BHIh*|e}SVxVGe0++bg zeP)^9+iW4#wl9C00`t>D9~B+YcGA*Y9iJ2z`z(3U5`IR9NaZRY5j;D)T4~*TH>bWx z2YmU8yofV*-b8d@L$2H4a3o&%oz#L5b6KztivCo?f3z(lmRNbOs0t$Z?YaxBE$vSO@;7?q#7{k*lxCYtYl#iL;zD)RR&@cJ zq`5&C{E+T)iFbCvzpFjO5K7Ws-jU@~_w+>&ft{_%c?=M1Cs~CjEOyjNBkLmPhpIWw zsyw?w=On09Qowr#!^yS#6G0!3BvJJeKfl9SzXGz8!^Ke=Fi8E8bQB6j6Ed1*qh@%4 z`cw=TXIR3IDApM<+H$tO=%j`o!-Kz{Y1|*9T{<$mOt>!Aj2|Yl(j1qx3(g;C=Fj2B z?!;$9XoPZq0z-^Yp*6#;P!UbWYLOzGw9i1dbm+W^6-D2jA4REGne{Ou%E zvt7pr;}Fv8^QgVCvG*3du3S>pz3jC!PTU~~vjtbFMjyRNwGs}(Pv$Z6B5SIi?@G}q zqFoZcrYYq`Xq>TzQ<+@Iz{eUAHA6C|lf;~UuC)sf`EEY*y^Ys|x1U9bM_JuLaB1O7 zg;>IBAl0#*vQ5mW(1H9TG8C=L$4k#MxM%IsBh7TCOqrz7b`d+vQ&V=W{@cW#frKU< zECrjko3n}D#QO{n8VEp8B%}DT+SNLEU;0V^p}Q9@rzSRv*e?qmB{A`=f_Wgf4As~3nrvfFX0{}GQ~d8jW`3M3eTn}2Ph8(1Wg(KKa^)3lfv>9Cj7jwRNr^(AWO&g)tqBaI70VXb19xmf%_J}Y`Y)q8&ZJ;2? zr}{i!9)SZ>N+{6~6!sX({i{oizF5_YR@MqTBCx)D13tBamqSU^ zI7EY3d&mxls5SioJn|ul%O0!<-ZKux1WQ2m9#qf}#X1g#+QkisC2NkE^`Jv}5oXsV zEtua&t*bwXcWJ{=sRGRM`#>W-wyICgHDXO^w>%n|^{s;j*_Jq=X&8EkgpVN!gN1D~0Oo6dsxJ3g z%b~vV{4%BX85Slr>4-aa!oAYBan{mxn2zEsqKe-o+OKJg7pJ(B&CGqrYq9oIivs7IUsI*9X9hF2?*vB!8(?71Y@DX3+8@K?rU06!GjJ2K0k;NPuDwB8odRz4uJPlmPSj^@^ zVCCLeGdQyFY?;nNQ&ReX)>!w=_dVq)e?(W?1}f-JD*w~F2<_+Q1-%W1N;Vs^SHb)x z-`+6*m-;Uq9>x_UY}3gny+1{@xAdSbWsK)9&PoqO=FjSf4~5}dCxPBDcCQ1s?zTXM zO%FZ(O@W$<7hFBHX!DVVnhG|ohWCab{oHuF4OM{rpses*lC#texX`ct1ZSoy5*va^hnJ+9A&dTqq?@ z_+EY;U)2q*;w2R@pFIDQ$he?xSpbZ1L23rud{Pw*JzyWB_f$Os!%6SN)rnSHc1HqR zLLbn|CUe-so`0bfgV3tpyg&(YL*J8jf4*NL@e|=Lt)a;^ZnfI*xc9c&p^@x3wu3xihU~Qg3MJmf7&0R0~3(RP@>8|d}C!yol zO`fgMT`^w#Zu@-i_U}CJn@t&ie@6(nNqf1EcK`x-r3R3?jl3M zX_eLlvpQXFEJ#AdLw0pZLsJEL-=m2f{U4QSf6OIo%U89p(tN3BaDQ8}m*r}8cRBzY zH8%NOuj`f7<&?xEcc}Ny2x9C;3Cg+0AV8!Gt>3;}sSoDgSTOxiqwfZH%@*bU%MEO{ZC?n%lSQE%#&F??zZi7E2AU1()=~cp3%K}n literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/cuav_x25-super/x25-super_pinouts_02.png b/docs/assets/flight_controller/cuav_x25-super/x25-super_pinouts_02.png new file mode 100644 index 0000000000000000000000000000000000000000..2c0f2eed59655395c6dad28095a4269b2f83c47b GIT binary patch literal 35123 zcmZ^~1yCGM@IQLEySr;}hu|8VAi;tYH24wV@Ze4Y1c$@j5-dk>OVB$cI0Oi=NFam* z!UcJJ|NmF7>i2)|b#2W~@AUTc^vq{_s-`!|$Uut-pB^6s0ugCHQ#S^IFaQt;ixL;( z@k!|2*Yw9*ppl-b#>2ydzP^5be*VG#!sY>Qf6VdSw*V%1@|SIzfzw9)3^;_SO+dRz)TDHS7dsZZ`-UvzI=@SE2|CE)wY z$n+5@C&RKF05+u1XR|YW4*UlDYp#pUeY;^zGBG#$D2|L%y0|1~F;LZdU$DsV0jbJq zZAjNbXZUkT_{QkRqOg-*Wq}BtTeh$zYu1CxvPJXL#4~VLu`URF!6xC z#*`TG9Z5;kGZZ+te80>VwbxT%+!Jflaa9bZqf^dTLl>C|IMg#!?tOwYfc2*S5}@=V zB!*UyCfzuFW%ttnZ#493yV(QJAW82QyR~04{ouB_oIK*e<_$-C_A6QSt>C}@%S+?z z!uf%K)5H-=GrcT}R{5)1nX*H6a@V zc@7((X*HD$<$VINVoY-dGkCU&sIkfJ{$e;N{;GMn`YT0GsoE!$w8{}^-7`iJ)cTzc zKd)C;a6yd*iFt607tfU4)EJsAWJ;OnV)rDz6#rqZ&nxtHKBRRuNR+-V6i$_k`6K94r zN`B@rl1_mZtQl4>j;tn3oAnSKM`o4sJ~Vn{^)(^ybb{af7JA%-w=EUREaMXTuE?Dj z(3>wcY9!)} zX2lr3-{8L4kRrujS5v8><5gOg?b+*Ap~bHtz=lVmJ$!j+kV0Rfe`eEldD7Um_mZ=a zcZCcmd??tf#Zd0XPC%z02lCO*>M0!YenPib*`MAws~bWDM5~Y>k1)ZL;||XQAq2qd zw#BRzCg8-AMDCagnlh?V#f*FzZ0j=R@sC+~Z>OBw67kRW810MNSIKhoC`;wsmCw&d zO*SmAeSo9SelDUIQ-OE0)a<=3FR6&%RKZE%l2LO3%p8gv<%|A! zkepx2E%l%FNvWfzzfgiVrN2{!#)!kk<0ez(LEz4AA$u4`?}Q>ga${$gra)nO4>!E| zsr$rSJDPQZa&&1=F&lyg+~GWNlfCw6=6VGL9;7QM{h~1xI}OB|@c!uPACpzY#;hoqTrn#r<6s^q)VvYuSErj`c** z%^7qyOo65^QiCRirehWQqOJS910!6jG8hN>k2-fGHRsc5Ew}F4_O!K4qQA|+=c;DF zU`)7$stIe%Eoy*EoNc5D=gxo%hpH->3k|Jz0_E{nXNsjm{HcdLZUg5Rvg6OpCk&rJ zdeaWeDp65FXVoPYpv4P99AMk$8Yqz0xVD0u)#HZ7RxH)}Kymh8B1XQ@f!k;mA~$K6 zd$nj%o-jbPqGcu|%28fAPYsC+qEZ-_L%rRmc#~g>y{h+qD@1Kl&0P7|w^SCx@rmbV zQRBA5II2Q`$>2Oyl&$j8F+<4YrdIcqVtS9h;fDHa9Ru{K*TS)KZn&u}=>RobtPhld zwf0%Gu6N2l6ZD$e+D0%!3P>2`Y(E^(G+!0lH{i2+DOExCn+a-XEzqZkgEUF8IYK`+i|SD(#>kpH?~ z-~lhlv-^q9KzFN-=a(wbQmd0TqS`FwLU4S&-dEWb>40y43E*c|0(c@7cf3niqdz|# zH&j_r*H(lUWW3LxRq6L>;{<(g7l3tSk2P9Y>(7U*hpx3#{z?0zbzy;a>-x62ny~Sf zZPo=Juin_GpUvkU{Bn3lJf(O{q16UkeZF_C`_%d*RhBO;MItQ(p5PoL8MnB4nZ-Ql zf^^I^geWd6IiFuqeO-MJurD0QxerZAi2whfh*lh&|Fxx1zHdo`*8dM0nxX5EBEWnO z{v?hca_Npx2Ob`>SUj$uAY@js3yK@A<)>08=Y|#F)m*Wps<>>A#TQm>FYFDDQKOhE zFHTdo&a?8e)cGf;NSo7b&P2?@yEg4AxSeyyzxwtU!1=V#vt%`;-W^*#tCcc@FF7sB zgjSAL!ql_nNGn8RPBV+?CgQWWI9xxs*g07`Gs3- zADc~h!l|hrwu&DfVR)dOFM}M;liSZNhx3a8fGw3PDP`^e+`P*^{?a_p=a8^W^}0+Z z2HG7v8y~SGS%*dtUf^&^wQnu2RtvY`onhs@r+foQEpghH&5Fn3hZnG!0?d^EDKUDA z6tUH8h1bwI#wkvd@`G`b#c`8$YndUL;6N%^re^-+m~3;R?E6xQLYBnlS5_C6nYD>=oN z6eXEd1OG*0XYBV|YqOVSWA6}u<8GMn?at#xE+4Dd%XYwnd`R4)x?jgx*nRZmqlJ;U zPmy^GKiTJLs$1&Ijxpi*yRTj(P|6iJ#^0~OxoCeL=-1Q11b#I7X6KVR#6cgOSQ^WW zDkvKl+=0ZAcLm$9)$Tm+3^sciRR}-6PiJ0o1NRQq`sp7B#?>YZ!^WC+NE{-6tJmZY z`T%R@dtq_b*53cksTwCOubR>>e%)V|P}lNx7?Ij@D3MO)UVYVk;Hvw-hb@cfa>4Nq z&!u#7UPN(7bv8{%wkKnLIq1)YJI>wvzF^8z>PW?3(9#KPF%zf8*9;(WZC6SN$Dhpw zCcEn<{}kcR4UAxl?JOWG`aW0vVHk>&OP7Upf;PYk;?|^jkv60h3x8mV!{E`Ar)5O@ z!VoR)N@HprHfl2p%~G3+@DKorps_h}FIQrM-S3<1Mmfa49bw(AU9dS6jbyy_76GZJ zN6}jG(nk@GOQ#N9JijjWeILS!udk5$GS<|CRyE;y+h`E%-j9*nWWYd8-d|+}4*bT)^G-vlAQncy_`Y zqKe-=(%4MoCY|DdKMW$+x3qB}7-5Md1ju64#Xzr?n3QpTyV=KBl~j}-)4_XnO?^Q_ zZ8ikrIVZP;THDgDcREEs^HzjyUhXSV1axD7wLpkGTsKsEZ24eUs;UJTQ$dtO>o`yL z?%Pz*TV^JR%#EhG=Q&Z3`N!_)8Gnd=v};NN0~F^q!^q$b2aqYX64H->j6_?X|0tE*XCt&+~~@6;*dEF&sas@149d5eI^L^9Vjgj839cR-oCEw?;qEN5WxZs zGObS$iozQ4G8GDktf|PqlapK>TNt48LRwUN)J!QAn5?J=c`dzld;4d)f6-Ay zl}c1xfco?4aCv4@YmMhyexY9h>KNFEq{%-OF~Q}`hwp7;X4ZM097NFSJ$G&UynU(_ zeIGNWB-CJiT?Q~U5kc7S;gm^07fTY**BpA#7&u(lVI|nNeF}pv9qVV6t?c+# z9D6gF6?*=LfCZDEuK(odda5i;9#|uEhh#uR&WOz80Y&v19H=1lyTd^l-erniT&gk& zC6FWIiPn+>jCKaa~AN-u9afBV1+{@phb=I0;@5&eKS;_od zP|l$Jo~}waO3#eVM0iPw_LD`uzW2S*Pyw`NWa^#_UQx6sqx2nMrFEP0Jbx9mgdLt4 zJ(Qq~Gk;*p9;@<3CyF%^#oa$^j?RRlL_?nm<0(?f;Oh;i^cGaQ=n?$s`X8q5Z~#N+ zG0U-R-#nG;^eA8BwopoMcKo0erBZ76D;zs&1!CCO1W|N#yDkp(Z>?(;z8ufHt#5DI zqaxBzC$arEu6c_(tiMR6oWY4v%y9>+f|~`SL2fwV8AAcTs9PM`@|_KjJSxamzAt}% zx3#MJ=N~bO-MZ+Q1JgwaTb)DA%)UhcABUPKnhRGK2V;=)Dp|0TE2S6IR#NS{LL8I1 zfRnd(Gc9-(dFL>t26b{g7EkqYmC+K&xKD2yx9;N6|m^(F2RS!MPX%yxy0?S zSs~ysR!IDG*XyY4yKX=@g#<*f)BR&t5Oq{5uI!~vB3g2Qu5C+sES=w{ZgbfiDUyV- zAAhXFv45d_;1v4Fc35Cekf+Cq$^b5D+t*H>24bWde&hJeB=%F+z!(Gnw^ATwp^xtH z=NJkft>74a=*1tsrk}vIFn_@?Q5SgP@^w$IgdOzqs%=Ikv&~N4V#)B?(CUmVE9y7B zsxQ{{7ce>6len}hitiM4`C7((TJGag8g(C`As9x1RNZSo-V{r>cFIiLf4EFi={W`U zK4tPsoHr1jXSw46mh)$b67H+C3Z%wJ1e+$N`ul%Ns^l<{KnIzCoIBF_H+-5bKs`QCDTHOTz~e-q83Wy|C;{+-NrEA;|~67 z`wv~~MtJ*v`|%8_AI^e(cXsHJxYQD-c_O1;F}R6Qdj?w*DHSH-?BbuXuh^CM#-!f`f@+`OZ0nV_f?u z0;yj|W-vGm@tZ^g<{>Rdr7cb14BM|nHPY`phYg+rKg1oGk2?ggqJ$P%%FPK;^4Z1z z=%`xgz`q5qAdR#=Gtl-sS%AHwLNA9{yg-wm@|B&l6~%!|Gwhe9QFEZ?215B@r|np% zR;0l&53QBVpi0*3_$~5)Q}8MxFogwP0Ocw9$%4)#BMCpgT^3&8L|WU#DDU&JO9Q^vh>Rg3jcxDqgL$6Gz^w}3u3!r4tuiL0 z0{-kH*y2Z<ZUQ6*5@ zoCd#=v|fLWh5IZAT4qLymCz!-n;6JB#rPq7&l$}k@@kD36%Hj3FWHx3gw(?FQoTT?}(ALT0F)w+oR0Y z7%~`|h7NJ%rw6KWU55#zym);+_~N$^?DN$8%H*s15xEJ|wT~^u_Z}A+=)D^Yghe9f zB4>v!wim`yK4^#Jz-s-H6_-fV^vqD1fK|ol!K-?;=s9!q{0AZk)iJM$*JR%u4cgs9 zOK<1;Lf%cv_}f=^mjI|O0B>DN*)UZ@N`8m;Usm#>o1cYu>T3L|gi_9rwx&8p{^WH;)m%e1_Rg=Nm;68~lQ=&Z({aRp5#69HUFE zfu_6`f_;)z_al66yXYi@x)wWmNRWr=53Fjk87{*{=c z%+^cV=cz8<`gbgmkf;pMpSkp>&F=7Y%*ZqOuKy+L-t`wYs`BSIOIz@_bpy*Q*`;k& zJrfFaahH9VOjh7FGHPy;?Xv1=2rJ32XCW*J80+7OQJ1{g*&nyJc}KK=A|^Wt&d?z` zQztASCZ5YTGji?u(3}YV&cBL5mjWMyr`E4#($M9KjR_Xd3yLlNE~0Uut7m(q5&%u^ zXHM%jm1oeF_aaV+;cXRr-=VZH}-6QrTYA9R>)ig0%W1JY^#4PRA1Hf%aZ z>j4E~WaFf%rs>9(OAXqeeG>WQjW%l1l!1HDGRk)69j*(Xpa~P%0L-EB^J$&XUc=JP z(~ZSX1xKO*YazlGVoUufi=T0rIm;47OmG^Y#~4c3qT-_^)=|2_v43DW!Zjiz zA6R%&k~SE%6CmJ>3Y9qO`N-~u8;0Ij-m^ZL!f!S-Mhz0#@2BUJO($h4dY)1_7H zjC(^FLHHkzp=%?)*7VB#FRCGaB^8&-N_Rx_8hED5tktMxlxBVLj`4AnI3{e>ooJl+ zA4Sg!ecynhs;=hL*#l(67SI}>R)z7`nLld8h0M>j-0Hs1ecW{NP8aJ;V%rz<#$LqI zS-xFWB#k>kgPy@`-%N;{F+6_gsDhL<49Jsq;&kJ1C4ig3?zKk^c&P7lo%WvjerunC zal)D4KC=Ps{{@DA6H|9{wr)*u&M?;&N%U)T~> z$!5yQ>{)dJ4-XkC7U>F7wqu%plcyIT17k>Hz2Qn?-yD}CsRCyo{=Ayzj+sn#LT1yD zMNRN4#H2x>tR8Z-bJ3hK0?#Iy?l4s88i$hHKHw1V7b#N%up;^aOtpGKyIQU#J^G~I z_DLGK;Qj-IB&R@Qd@Ln>zO;kvo;GG9s@Y#{Ul+|e(G1D;%zT@?T_eLg+1#)NZGds5 z_ISq>GF?D!df~2|PVYZLuEPnghBTJ*FznO~N#twqk}1IWY(HalDieq|kuLHfRO&W? zSqwe2&L%+%Ebybsu90)<=Tt7=)IW@HK*CJE_}5m6SHA<%Pm*8QK$;4?pCSSzuI!cP z-}1w#t#o+mOKEz^DY&!|*Ui5T8v<_#Ub zpmH^n7}uvztu#3;{iD}otVH6){@}PdZ}!)}`KQ#6LX=G6FrxX99eKou)Ztc0yIA!M z*W{(OU{#;1hz7qQK=-g?10(Zg+dtyb)?kaVdlC8P{Z`x@sk<8GG?N=|!-dphbFM0ZwWLc%AxF)mAp*JvA_6_=wZnTJ< z+NyR6sfFhNarqR2BrQXJaETAGSwB5y-J4+J;-e&FHgdQfD6$aRnLQAr-Z)R0f06?;`4eu_ai zz9rHy(>w3HZhpGYO>?SgqjGiWj5J&?s1*=^q?&wz=uuUD+5|F4;Wl^*2!iA6| z3WU&j9GMMm6{W-?cMMI{`b7p@)%3iFJK(KSuKx5UGeDYBiiB09uf0N041vAO=CkqL>>^u_++wNe7qH4v!uQw%rAo5Q8U%+EO^{2ADYtd zTRI@l$nMf-WV{#%h`$-`PqC9FZkk(I2AN+JUzPXzf)sxg>6TC9gyB@+F z2p$Fm31doa9d(oAlM-fu)>eVg_0#aNJOvk;u5%2CX3Ww=SSs{VXg=| zdd#G{8KzU6oB+(;Fdc*jqh!)M%FSO%EY({!i{*f71p|{?Md6iE9Ayqe)R3^akcd%uN zR;(3pP+wA;I786M{a0ndlAaQYeRO4_kmhNs6YpU8mM|(5lE@^HGGoM^3U~~mQ%)>~ zIvz>!cwb zFvFdaxJNZS6*`FsptG(win829NV_kc%vGlfn(+=0mSq@cm1q7}W&Ct{04G>6jzia5 zwf!gC$0+$rvPD(cS(gf5#15!>U8joXA`heaScQ+3cP`fazuqY-%WZq)Md)y-NaakG z0VA|BHLO_T{}}rcc+Wm>JX`vkaM1O{Hq+fr_TRo0P4)g1+?ZD1Tmeg4d&tb z2&Qd-m|}_sHEh?fb_Np~wLD7iV}S{GrJo)$q9PRJ378Z&3gIkvH>H!^izq(9e=m3SdS>Qy7Q;UWfxk{R!D(oSpJ0e*<`Ewg2P9~lZx2#&xwq|*+eZ!on4x?#IkuuS^k1QQ}Oy&4Ls6T4K5VwzHldr1iLC#n91dJG= z?t9Lqq&3PjJOQ<*9PWye5ORAPP5ymg6t$-D@+);8R;94jx7p|CE182t7fg^Gic`*0 z^v@(OYkOpWq`y5LJ}l3)D<^_tT9MT8gJLHkMA$Thu9@~XYI|7!?)a5RR_`fm-YZ{6BX&)#bg3HxRykEiDI z!=di%%iHDamo&mH!XZ2A;_L-UFKOj+AhRd)WWT6a4PJYQ$H2$E8WD7x&(uduIp<&M ztUi_0Vdwwe@Wc|GY2w+sY8=tnVqAQcpT(TOgP(EtL9Q~O<3=8&jVh}n-4+U4B7$y2kTgJj zs)fFnDtDLK_2R0d-bR7e2u)n?SZ=!0U|#>jCrl}FA=-Zam=`u4?u;MWJtH!^57T^e=Wx+k5it>gA7ZvxsTsqNIWf2dgs)3Kt6ir29c zO(mgqK&ay-wsX~KVDUJSN@ju!NC0IL{`AD;L05@(x7=ctVau75Y6z8T!zE!UZnB_} zir7gY8IH1(@8uRP(*^m)j(iQ*pYKF1&q(B7Oh2EtXxi14!k1uA@vOk4cVUXt>4l7> z@=7nrRkP%@Q*yHnez3ckHc}l!VN?-`Ur*1cHN*5cG@%Y5YLiM|RwbU3E*AVWy#&ii zK2K9VPVj6qKW}$Y`d4j3MsWC{ZG-wR@dsEWyW>Pv#eUVStu!PXAtt2slrX-l-blD! z^{qR)tyygw`=6I$3&ry8jJ2+*5!SfsG4Ifbb*-*LOI^T{^x;%_Dn+!hy&-*we|l}o z%;cSk)gW*IbOYG5_r-LLLC^fTv8ikq8Ik=-wK6qNUfy0QSd%BQqXOOH7wg>^@ch9! zLIj4Oa<5N)M^(UnZYzB>tr_Hqgu@!Afnvm61!7SKL0hEk^pYL+)%a&^rB+3xXvM$S zywx(}H-w=Vb_^SW`L%ve9E~m0gruuKI1lNx`*K$xI{vJ;=&mvTI^^kd@4A1R(-fMg z*>Y^SQK4(@VVX(BNvPZ}3WKtw_Oa@ZVv9Q-?xZ*lhnn%GXt$dAye`DY34!=E9o|+l zoBX*{B}Ys)-?mm>xFHV|P;a+?u`Xvf-}s~{stqPXP`B*MQhy8YM&RbTTC(Tz83+JP zGzKCCTP1!U%G#4lRRO zUUV*4Mth7C+|`9<9bocfG)4OzFMs6bPpqS}nQYR~nP&wD^x=)p z=rfLcZS)f6L1!`jR2<)4d5hoH{hS8qTz=V~n!OeQYqBsOUmB2PAoRC(_y%%)f2CDx z94NBG%&&p^7wf<6!B1+&&p3sO9f-uR;tCN>gT5AXx37`% z0@N5(G0!o_ysVzvT)eEv$XUnM1ney)bSHl(t#lHS4xjh`jh*(=lzxF~G57P{<(8f2J--Km!83MbcQy4 z9TidDm-!>WuZ{#Rg^Hiap%IuQp-63P_EL_n;iird7-C${ zBfCq8GWz+gpZyq>SXal*QDcsE+x`og}@wc=A4y!1O~nP;EWQ8B7IjhXiH>3jNcvEuy8la_R-5_=l8}qs-GOvhH5OZhn;~5lACDu4$8~1T> z0SXQn?mmww$TNggGe$Uo^YnF5Si~lxPw=?6+E-ZL>0bRVrDX~m(nN9FG5&n9tB!*) zPfP2-E|dG*Lsj6nwfsuo4f^;8i&kWZkuC3^bN&xjwmM`F*k>+H2WQAT`^t|q$$hvl z&r^nz=j7^qz{>$EIuYr~K96aX{|80123^+^4I6x- zSpnFF%u{<2Qf{LEugu8f-|zO94_Wf;edb8l;u#zK@r7BL0@m_8(?tc!=iZ`4TJ zOWZphKtZ+NMw$vj=&IV1-#_Z4$Pj1C^8Egs56MurG};w*)}9Q%*yBf@CdNi^A>&)X zXT6NEect~FdT;$mQD5Ny40c(OW@|QpiEgk(IIwlHKA0ZEN*d*0uSwBdqzTmzd&pf+ zZ0g}l-l!xJ|8;8~Dnijm+TqdW@#ig+!SJW7T82>-T!|3HUMvgt4OF)!1@Bf&hn3mc zEK*XTwuJuD5)DCx=R(w!Ryl5z`-}Rg#VQA=QMM*Vz_fg{2#^BygQtL{;C@jrUTG`q zyoZKP;P>d&Wy^sxPTOI&RxTVz6x)BEfIEu26R7v}f8tSco(0^q)Qt60*dQ%Z$egBJ4f zB3(+ND3H_G<7UAirWyWzq{$K1#^PX&%5^psYK2Hv5gy_rjRP;;Fn1CLoc0)*=E=^Q zcVd4DG)n*Mqk&cMaAQgY#ii@MFWY_LrkdalpLQ~!1WWvS@k2aZ6ddfLig6iB?CD?D zBX~>+Q3A%e;xBq&0-G8BFd1_PIL5up=X6?Vh-q1A8ZH$|HwYm$hC~=gD@|r>TV)*K!N=BERcCqBn5Y1G0 zEGLLRic*4)8c48$vcyN!)UOl?5-Lh-6B}Pz=jnx6K$W7K=f-5=G0q@>)i{Xb1?z>p z67n%#5h?KB$9!j6byottZlAUhLSD`{oX)w3cN%el5bWwh-EmbC1V{xqftg0BchA47 z)31q5143nhh-3DB_QPq&`^KK8%zU^w#XEY^D;{O*obA;kP0j{w2GCZe{()*x6%`ts z+)Jg5Gv?_bwYLFguh_}^iE%%I!w_TFDwNb^B7ZjusZ(+^W2ms@Ov** zS=yNYRJ(0D*^j_%Ia2A+kT_i7rtpH(>uMH$sPTsoN!)Xo{A^~jmo`@$uUkFQyDT+V zMF^!H>5J|>M+m=7zLgBevVaP_?SqKgxy25IyIZwP83Ldsxkl z;x?%aZw$`LDrP8Dj-`-c@W?_-1y6z;Dvkje#ZEKLFVe`f(rPr43`(otkHbmI{pY+M zJwtLgv%0UMHKAK29MpGKM&n$<*xY!bqLsr=`Ud{axhq+;Dx)*bRTjYqQpc1qb&vHX zK=L7%UWx~BlnUBWIGObKKR7-+SBm|lJjI9a-}lYaV_!BJih%jk;Jg3k6Foyw2f zrHY+1A&qy?!(-YO(eKU^tHILdzZ?IVz23HjR=g{BpE?UO!QFRe+g3~eD;(+y+mj(u z-?rW$t0K4R^(`nKzPisyGAu!8{lKt?I z?Dbcn=Z$_5E0Pi2^hcj$30{=6f&n7Q2KSY7r`8f-lq}h&t^fM41#2VPnWL7dqZXNY zgLG*~F4Y>O5iLG>-^}qcTIipP7QacgZj+bN8K%fRM;5#-|Ah#rxcd-KhgWv+9T&=r z_Tx_vZ`x+}CMRW{6v8L5j-F?r4N$1k6e$l(9ith{f6aX0=}q0+Sm9G1$qF&TxW`jB zU-9z;IZm+Tr}9%w!Q@|;+Yxu%e#p=^f7l=ww5j~gtOV1lASvd7O{3I2bMy+>@x!{~ zu@|Vyw^r$btSs%FQHxkhLWvOp!>P<}Q3kGZ$Y|A=XnLpmvf*beWK07KSsM(^Yx>B^ z@`s!tqKLKPvcXs)?1^kgMv6RvSVsIRo~lG<^ojACg2FQ(Th_h%a%%m4Z0Zw`%TM5K zH3x4WdXsOMv?+4&&j3#*d%A@W& zfcUE=c}Le~$`3K+#pTNR`WBD;{oK5e$z<}T*r&Vx@(Yky@6oINt}5S-Q5m22xy~Xf zr`m&L57uDb-7*Ri#%4TuR^7xBirAwt?2GUmR(_~%iTwBRj`D}kYrTk5`Dp=|SSTXj zieLc+l(1vV7lirgjk~@~cj5!0pic*A8VPaNgr0(WC0(zr`_+sGBt3 zcvP{QDCN;KjX&u}@M0qgLEBGLEC_0PQWD4fQ2sXWD5$07sBp=Ic&nL+p1d{?-Ba&q zi4R32(4QXhlFOHSFbk`7%zr&D5UgO|Lc=6?qH(52A~h}NTE@@3sRE|gVcR+}P$_%K z3VKbGhJ|u|`?@@Gd!~DrU&U9MVuHjyut!07g-+|`Ty_=!=+NHbxo)#F7)Jg59mXk| zHb3iC9(hA;Vd<21*C*I|CF{EF_&9s?m6)uR0BA*h3$oEb+PiNw$#+c3l-?+*;_j%` zlw5tJb)Df<&sBPK5HaCL89WUtz)YO`56(}h!*gdr;0JT?-Y1a4ZFe14gOq34cY2e> zBnGdOzS57W{MahVyGrAtbKEFy)O2~zf>cPhJBtO{0CB6kQVUPovO+k)3A(6R6R1+= z+GPK^D!*AtCE7tS#UqZd!Z-A596>*-oy4D}9!h4(8IKqH=_vIAsNkB&sxfh~TQ5;F ztO1I%e|!f4j0#o8T{n|PWb@+t!vH=c0j3Ls@6Ou-$35#7o*Mmd+SB)b-!g`aKGZ?1ZnFG|W zI`cf3bKa>barxc!x(<$?D~2G4iPb&g6#Qt^`)^Jp0oEw*2^QgMq()N+xFYHhL;B|+ zrVoA9xX?4k1gl4Y&Ou^E?`! z`({6<_0+hjA-94KX$95bz^M*Uoe>D(QPZT_y^07OcCl|xDhT1y48>ehwS*~(y7>bsI7lFMLXl zkj-c|&?udwc?5;4BkSHbr&F#R=sVs3eh5{u-@J?Nm_xED8Fsz5S+`KNl?JndVhmtT zy_J{s{A95YR5ou zqhuWkpvPK>8l*;Vd1T@|#s-ah^xfWG9>bg`OyaM_A6(*OF%OFHGI^B51lVN?|1(@< z7{k8`Fxf0mjQG3wh?oPk&`*GP*8$>s%M%d5lNT5Lr;m*L1GJ*tuH_mtxt{J;YCG-z zMJ~Ni*vs$hO1xh(y13onqol+nbsQKKatH-K;D;as59U}Ju{y^r|MDTGzx6~fVnpt< z++E)Q#KrG!qiN~PZp_2BCCt_emcNM@F|+EJv!h~KlOobbHTrvxP6^Z4W+_FVU(2D! zMa?{|PGdBg^~_c4{zFe8fWfS_AdHI3^SE~l5jY5z8UOF$gCOec#_yUQ;jXM-cu&_= z3mh1FSeg)=CL?D+_V+vGkpc06SFlq3mOF(7yu;Vh zhsUFNN9!IAS)$rf2(9mJU*4o!IX(VVAj6?t2&xsfT|@0%GR|_K5=6}mQx$sM(L@$o z)9+;jmPIPCbqITT7b<*PkOeQ2tpc$%t7}LXEhecy+8ZR%*(GM^*;D}pBc@L1tULe0 zFCX180C7GKmEye41@N9*QTJ|;kpsou@u+F2 z#|VxB@h($uvhDSuK1TX$yv3#uaT)qAuz{peiS8EQNLADz`Dg1-wHOVSjZ#x2fv6es z-7{+$6YQwEWaO&pQ_NM~Umgq_G--7+2NgBTM{zFO&pGcC3X}cbP%^Q-ODz{ROSSF- zcJcSwMa{^Zzx? z+rM-!U0n{WeM-E4uGjHh9+q6skc-VIX(3AB&84A|@!g_4BHB_$e0E4FZ^c%ez>Jn< zMMGSZn);5neonpv;ON*#n3*=6gE-YcZ5pr7jdKS*2PGAYMX({vMF<|$kcPJLEK-Ow zi$HU^Sv!zT=IkF~#i!hk4RRhvahHA!=wRrDTS|R&86`O*U@3fEC;a5m ztNKV2gs_SH!*hjH;QLMh?wQu-0N0mfOcSXWU6$LQ0Xr2iHRuf}gdhrf|sKXFp3ZSAi zVU{~Vh~jf<5^3!^elWj@c^!m2puS_w;70uj37qsazlK#*EX*?T>P3~qty0~po`S91 zInxMbeH?e&lJ3{b`%~pV0!m-*jJM=aM28)Ubh}rN!lV=v^p~8ls zXm(Y=`1ji{g~8T!fN*>0__eW<>-u8GsUqHh^J8%HhZNMSQWvKzPdwWl^N>IPpw;r( zp?W@l#vLuQfJe!k7^y}dB zaSz(0vn4v$z-V(8EjuIdB$4E6uJ*l$*_7n_wxOP-w$ay*(_5})ocL`xFiR!MYqyMc zN!EE{%d6d;PPrxRO;qRgaUjh;Y2K?#KP1-$Ft3(ZHAe3A9I^F=<$TwZ&&w+a$!~2h z%h6H21Zs-D97nXwR*(pfv_CZrV3(t(kQ3lX8Md%+tOV5EFx@3-EYYQKcuZ7el(#6Q z_x)v3pdk7{c_%h{(L=NQMmS#|8EJBP15^OV85NP5$oTxN{`D|huxl!;0eF-#->|dO zltLKRJIx%)n_~AaO&_oKcvRf-MnBc%dF)HL4=*%{q$Pl0$k+cr2Juc zb3>>GFV=xJ!q)y%51|0dPO2pLe8%BTsbi0FQkJO%J0k7?72`FhL>y$cywnTUGn*8F zt}>_fuF0cFVMGy(3hP|0HRQ?f0fm&O3CzV=oCxiVOEcq(j5-fGY|}#1VJfUHXGb8n zS7uWd>C9e4qYUJx*LkQYL627d7XKtHE=wSV_@2sD*JIs9c?kX18-@EYp%f#A;pWH9 zPW4uBlG=Jj@G#tm5#%- zo#IFHzb(FNGiWd@9WBy&n1h>nq#pX@NX3^WIB_By|GMib9^`qr#G{$LmcEzaL)Jan zow5sYVFbPI#QpvZFuAsEK&35-f!v7)M35qwiq*;1&4Jey%*0jbuvvO3xP~}Knc;^1 zV(k=5GX8Qkb=3O4fS#r{c`+;D9hqAHT^_%;Om8(-2|t=C14s@|b@rb)OE0B%0IT5| zO;A%dZe_+DId;kqif<0_6(Z)^-)bYy~X+GSf1Uz&rE-yG<}-PvP75r z{zDmURt)nNL{+I@39@Rc_(wm^3y=0(Vn}>zRAx3AyI$XRh{A}Jnhq6Mitzg0w7inM zA)#D-ta?m}GymvLmR>!=4gNKKL1*IyLIuu?*wZ7qLJSLw#Gdh%9?%R%& zVP|GRYg=Oco_@FwP54~??rFLmIm*_~`rF?u#g^zgRL1M*vk|o; zhwFNE^xhra=MD3+>NXq-n}2iIxd-BYb?Uuv{P9^?DLg$^G4NGUQv-boG4iuzlV$bN z1ol^=Y&5ZNYw(MOp=04UX88QmppNshwRYGyOL?zXMUw0c1OwX3uIFD(kWgLwLnU-v zg$+V$i2+{0U!)9>d@#wpgGQquzq~RKWiz(+Jl>#-&I94P1)GfO>fUKN{>nNL8hIib>q}=2BY>R{R)!yl?;D1U)%L zWlkkeGr#>NOr?#uk0}#gV05at%ty2K8+WQFe&G=u;t*YZ(kCQiE`skicar6L926v z|2nmuCFi4@{~fGgdR0&{qzxhBS99pJR$X*vh;BR`Fha@e^#Uvi9f6(PI)aF0cUn^l z5lU_^X@8?B>Z-vb{tS-WO>AmeHHQx5SY7#n&oMucdZJUC7L0{k10;&h071l>JDsTy z!6rN3OSs<}4WhevAL&VBM;cnyF{bqM?$U1Mn~Z)Cg4(urt6n3_UahU}3mwL>B#-W7^=UvI-%yD3{-rMHPutV~b&!0^i6CoB;Jy z5__P}b=4pzH?Cq{7L!VrWQ`pzd-R(|7AE?a3+~Evd6W%Z{CJ296O}LJUzVfkU2Alq z6N9+jH~@w_&YR3(gAlU#9bC%~?8avL$Gj5?L7?9H@7__4ils?0xmWAQ{b$XYfkAmWafc&uCSW7PWH{*|BBw(50qJ>8{C-dH1|Q)fr3 z-`LN6Iv`e<*j&j7EoGtT@o@no>#SfP#WjF2Kp`5}^ZS^)yx)Ub@_^vb>L2vxG!i0K zeKfJaqQn>b+|0g3uxFx%PqjyLb)0Qua2YZUSz|z`IRK9b2=0ZT=ks(If+S7xtdFARB?0?GrCogW%#3 zYl#z5zRfIXMz-vlni=~{?_NJgC*57*h?sTyhc(zmOPqa!kSLiCOV#Fr&g!>R*m-|FDsn z#cQv0`6`>7PL^zl#@?0WM>NW5Z^@OLH3NK|w6=zGAG7bfw61*t(onmuC}T@yJ=Ox& zN#&efzS)uE{7^_2+}m=4{|*0ntsD$?ZOQ9<#3LD1*oBZ@~No(*dM6%LIH{QZpSwu#_lezxtA z#YKTtu4c6;hhlENO+|5rA{jgS(R28dq*XtCyeF*iO1??v&I!ZHySbG_)GYBNHx0QB ziO_`3CBxqz(2jn-xPQGqVAnueS&uV8jX}h>Xj>?`}EQyW^6*$F!@kZLn?Z%h3fZ> z6Z{gtmw!8@{qN$f6FiB3ab6|}69@hiZ6&6WNcxJi080biH-DsJnR%_P1&yV`HvMEb z`-A;NfJAuIK{X?EYD=q{LCz$GlY0^6kPZP!RxA>0R^074|dx~@}Zn?H#S z&oxOh%X-SE8yxO*?ieJKhWuRu=)AoEk6}TyNXfidW+np*Hzzm`?aMh;Y-yM5W(`Xe zr5b~kkU})g{SSeyp^e$y#G0UovUtp@=~wzx${Y7PB3%ip$B9?QZ(v%!*&{E>_I=DUu-wf3FB*7ZFivHKpDoM>8oVKfo&E9dtQT9)zAN}b~jQ%STP4XATDX8p22F?#;{3D;Z|1+l-h-OHw_P+4Y5$HS2VxKYHj9hw$rr!s#Ov--34r|XlS}%`PkbP zr)h{h#=xfYwD_vfYR8-Uijx;P90j}9#v>%(hApP1pUm>F>hqBM+I${^2=fgqr9JfL zx;ngPXEj#Iy9h~DwqyCoFBJh2l3Fp_kAn*%{{T%t`jXBb6wE zDx5D_iwRIpb$8QE^rP-6UK3j+6tm-N@)o1L_mWn9>p4B!J0K~SvX}RpwjCADn>-Ls zv)8gy=}eZuQQ{Svsq2o#-BqSS;P&S1|I&j+9J3-)N_h8ij>ykR`Q^{k#~~EnioDj4%val*ht! z!Q7H|Oh;VY}1Fl$vaJFc~;!>04G`oT9)42 zQ$u+yB6Z^x)zV`E^gATk==)IG?D!kd%iD(RTDHKUkFg4LllY_fO^po8f=8Gea&Hd~b3$b)Gj+)2N?n)-2{tF+{ z^od{i202(u%+)+PF}hL{%XXb1sItQmu1mleN!JJ=H7{4xJzu_H_j;mX#^w&2rf{mE>p9?+4(w5zg-Y0`97Nj$*;Gt|of=Dj=s z?;0LhffNcI+O3tAgAecM{3DPD;8mBC`N95?hM{utW}Jz$Z_;#3#!J4ca821F^ zP+lA;d2PTEKUsmF?)=;({`IV{lU=}8g;P<;BNkYq+kcH@pwppp*@9HonZetcIs^q}S|2pD_91i_CR^=?*D zJ68^thb(?$XT{}@Eq*oAo@gr62}6v}`aHG?>dlvDYs~_3?uJH$%ZWky&J{5ecVFVS z6EWraV@FVXYFVf(X5F%48h^Z)Dz`wiiLvx!JN0p=WdnwV^(sUn`0IdxrGH~oXCE9)WBBrvE?-*3d z!`JvB5&GLbUeN=11Ew#gQIpEcSec=bH4qa^eBeosKtuT1?MVPu6?1g5W5w2LQq*0l z@9+@$q;0B0RNz`}A^!0A>YrcgJz4nR6o?86#8-VHg)pc67wBNaj+=foGIS#>k8S*O zK6p){uL3^G$Fnw+Z|$l>UM@h5WhT=H?FYu*Kmulr7PiB3uW6+QC>7EDn?Q^JT`ykuyfz{7GH!DrH(ejV*$mE3H82Ie3?U~ zS>09665uRFF8=_?R6L{XQ8+0;_3%(&^a~3ZtkX#yri>0oCNMxRSk{NS_?-f_Nw+s+ zn4k@tgD_wj4xNTYtV?<33?&H02cSr&;1j%Xl6p(zrT-qvR3dkSXoCrBu2Qc zYhFzX5W@xx%yH-o79LT-1Y$E#h)9#2H4Vd|WCX>Gp+A@coC9qeH@4sFLKQ}PmS2BZS1U|P=89Le_f-G~ zwKMp3910lp;vk)ACJ6Ne33f{3+a3veMNLNwRo_tl_KG89QB?K_3IfK%OsgaO#Zz+U ziPdDoqVI zk|YORqmnDsb^SKb`FZH_^YL-?DXFAi4l$1CSxEsi=|)eF)9CrxGAUQtkkmA;Y8s@5 z%hc5Y{$^EE$SRrbh@zBwm}ZB0HgC1q8C44w%!{p;Y=)pZ`XplNl`3c$g{3v@% z-)3A-AUE(ao;v!82U-#ctL}-Vd%aR`4m@JSjedc_3C(`cfIVtQ zHP(Z$J@f@bfBL}0kQPN}+hTWD7|d8K=>)xcA~)q>+1Zw@b1}n0A{O|xVGXZO^)I>U zTwf0DB3aAn=>g`S#|$(A#{R>UFqjF69hSsbI`1}sMxP{0Ff}8iGo8L8C1cEbm>jnC zA<4J&3qNA;>!Q?5`z|JKF{n^5d7Vw1bMhkj0sr{pJ8}jMo{IkUw-dPKj2l~Y>JIl~ z)MD=_?C=6IezNvjRIO{P%tBmxzJ%V!Q(CRiJkct9cf3j^`*r@-G$qmvzhU=G*t;U; zE;TX&zd^DTvtf2l!23DQTM)KDXG6iu=DRg@CN}L7HiaXeq{x(BkPXQWQsu=kOWG9E6A=Dd)67 z&6(%@0RuKhUm-B`vCJC2GH#Yll!Nl#gp9;)<;#{e`@0h0rv<4g#gvw#2SbjeRjZa3 z#VHHo@`+f&B{el6K?wZZm1~Lr6TcB71WWJP_8*SDi45)U!)vnuD-*l=&S1#V17|3l z3$$3KrKNu>?KVY>xj;D7M{DQnNcNE~<-yBy)<;Pw^o3d;FG6&cm}ffg3s;q9^u%Fb z&0;@sRMUt|R(4~J#%cR8f)K)BQW2Oes7`73Az)1QSKukP@IjRqs_yM4)(-_CQsK#t z(X|{ykt*=x!W`c8_asR=ItvgZq?u}7OP@s0RVcw}EbC{uZoe_@i`mzv*TAgwi*L%B zl+l@P-JeYP{j}cXeqsPkjG429X1?<5Bh=PR!!US)b8qL zSSV-bUnHyrQt47pu4uvRr?(sfV0-W);k<)>Cjq`KNU5Ji;w(3{tzn zEODZ43W?ZBku24+DU9UUmRm+}xagEp-$FM!={m{Zu zxoLEy%P`j>WCvKs^u^gSMU-sax~$x(OzL5qrT!RhBizlWGAbg!vPFK!@>2C+gf- zLmoS92b+kl-ROz+%aVGe3CY&+Reo!L)t;>dr92!5Oxhci`buj@vqIwxeiNXosRrk` zxY?Lk8h#;Q7ML}$7Rm5wZucRvJK^VWL)A)wl0UWbd|FO|?E!wa03j?hgSP~Ib^3OC zy75idV==8wxvZj3Ilv>yKxFJSFGQDVIQ8s&401O>mf@!0cUbk(^x9bxU3Q^ePHk8s zO@wK>PasF&CGl52k_bl~h~I8LucM7UUo7FD_o$Xr##qAkC+2H%W}p7uyXyL0lo}I6 zSG35f=O&oY7&*?!;bKsPs3AU?2i4Nr|4{zp8k8ve&*#qRrkzO92VNxIFi9FB8OmA zsX?<1=OwxlN(GB&Y;n(g7~h|2%tE3}z&=4rR!@`zDv@bLLzplBWDO0Y6>v>ux8~s7 zT_h`Z4O`HAE?0!Y=A6|H1s2!4NbZGZd;azVjauy*S|}`NZ9p54sAmbD4y*2je7B=@ z7tbW`DQH41Dw+3c1Hx8{QL**6l314xlN7a2SP2-V8?06p3j6&6`=Ao_miL?2&+Jsv z5kiokZQv8JcXO4Qa+Y+1JZj&wK|_{$f#hqv^ZL8Ar6zx;OtAB;T`wWX|1UMbRBjXwfh5j&6K4)xLO;V zWstVLg3ATS%bY!hXQ<;S!mos24ux{ILcNZ(3W6x5IVjK2My2&RpR*8^eAcIRMufoq z4?IO&=bu!NRRZ-klu}5Afjsx^lvbIIXv9BJ3C@t94C9Q$_Jequ%LA zB~)7{k$Z;MmFKvC^s|#k6cHFalF%6h2MPzmV&06H^)WZ%aS(h%QGE|SvQx+QB{hxT ze8wY`&yt@&@;XlVQfg*tcIiv?i%GK1-r75l3m^uuQcHSk ze8l&^K9f<`B~*wo;-VQ10pohi)d-k8qWfis;~Q^T(+_d)IAoQ=(tRcQ^u-M-SYe~f zMZCFt;EKsnYq;$Bea8Azur;6BrBpjy&WIE_>nPG0vdwK;Kr^yBN_S?f!b;qz!n< z81eo&ELTp)Efi(V7Cy>TK#@9V`_?%W@|bJjVVP>6;Ju3QEP)v2T!Vt-lq?0}UL11W zX8^3~13hF;^1gzI5MIiA@p-a)-6vwAe2Tsim@gDl9~ddd&GM%fCNtP+CBZLeAWG?g z<+zy)i->mwrm$pcWCpEz6j$|>>m<+3vq{4H;x@pL4KWEXaZICqMd&IUQ0BCXNVy=E z)^wV!Wcu?Jf;~3lOLWE5eE$X8w|UPhH5Ki;xVIV4UlcNKzV#e*db{T!i!BNZOjzo^ zq;TW)Dbg0pCsg47bg@L>^imjqg8TKdG22t-eJZQKj@}3umCc|@TCQrLou&X!Y~1kI z`ja>PKV8)w8g%V{KL>d*@r+IK-@ZEL8$0@)M%G|#fJUAJJg3j2lYN$?#y5`EG4aBA zh9^Bk8jA1?0JuO7zy4Gec^X092bJ^*a!3#oTcS5Fqzo!~Jx%Xl5I}^=v_6E27@#{X zA&!jTc-NYR2JAKCA2|mp6tG)Dq>?hef!27f4fFQWfNpD#x01BDHj1mJ@XD?oH<$w- z$-Ntwa*#26h>0)M)~7-!b=J)C^Faa{=?_ISc+@YcVp^XDYonj@MwE@Q* zZ~u$$z78H{O&i!S8NXWea_w@(G7x-Wn_((1;$EX8X)rjmaQoKF4Pw|Lb~1Gj(}cMQ z{!AT~sq_t3AVt}FMr_wj>YZvfIhZoXjR-gsoZgkWx1W|kY)7;nMDcsTn5a!9Tvfv5 z2+<${rlF+{2bDmy*SUx6mJx#?D`MPgXv#Ci|1?)26L~`{2W&f*DC`g@)#A{bhbRx! zHnv_)^uwo1q0T@eglR7Poe_NfBDC&=3I2D>{Mv)~eo9`J#Lb0=<-Djro}9h^o0j3* z%2#}{kk;GTr$(BJw8nU4Y(_eFE zApJZ_d3T*JX=frhAt%B@_69$Qf7igK;}h`w<$c`lfqogo|?Ey1y== zm?-2y7&a%88kx4Mu%N#%XIt4kJ@ZRj-GSi(!Fzm^w!+qwpx4yG zO(u#*FmB(G7xD@8CiS7WcVtC$h>usH@^NlgD;{?*MXbaq2JbPKg<8kR0uU+@ci3kbO2;P*GikCL{8MyEBt0zpWK`E7GLzS zLLXsN>y;}TJfy$q*GPKXE-ssUqf$8GhW-hW^T?DWss5>_FdyL4EG$BmDU@vZw}k3Y zODLe`_j=%H@P=_Mff3n`4PGI|vZ~1iFP2b4Ryz6JQFRSS!e1N!N(qC-hx)|W?l=+d z1JJKaA;Z_OLgaYRFQt`_^u05U^oV^CzPN{?O;w>(uLwU?Md7yp?p5J4bgMHQh!Wz@5pQ^LRu1ArMGeg(vTV*??N@~(l?y=A$Iog-tD zxUz(4s&uITJ$LPm>gn_lmMRx`^&B!z6?#UbkL*fZZK$c|uX%a^QN&IvG&lb#5Q**n z)APHp98EFrh)d%zG7Mh(aGQ>|3fkp~ckfd9gC0Xmf9toM#U{a8)WDD5ZUMn0+4t}& zyg#mdStOdkLm1q1qu*fQRQ>4!sqBj`Bh{b?h*EuMmz4AOdT@u99TVXeQ#3m1KF(TH z=0k73MIfu;T)?wgqWJn-J?sKm(2wkp5PxalFupI4q zoM?$9D1*G=m_*(Bg6NTIcpYEXJCJH&=knADhLS#d>n2`l+lewO4#NaW1v(A)v=Aj6 zVQL5{;|ZQ1g+9s(W=747v!};pNcxOk@%RI?0^RsV6khqtbe^a*R1Hw3cdyu(0&Yt_HT~aJyX3DaPpr<$tNeK=>%{r1!)C|>+B2~rS-lFI|iG#)@{iQ}| z&mng{0cAb<3OOuqWZQUX3<0rh7OE)N1GWluZP`R$64@+vWQj7MjP>8w$qZ&j zk0W#~r^oA3q1yO{Z22iKQ}};=V_}mhEHLXcGcgA0i)-dSLSF8N$3_uGy@2FJy$_+E zpnCKF&rRO{6#lJ}q<^aI>e;Bzk^PZjEJv$1>DHGXQs%66o;1yP$#Ye;D|{V#^m3BL zVPy50u~4@2LRT!$mBr$g0oK zV|^zY_V}y5QqJ0y_u*pcJNUTtVArjarnc@cgDNtAUy%ka8DdS&_%WY%NYmdOP?#)L z0!)blua=@BW8g@t+2YT?7ct=iB-pHL6@gjld{aK-d8cxhwmoJhi5uGb4aJNcfX~bv zf&b^2_BgVUgpZ>tC84XYRynaM1Hkf&4TytP9fN5n2wuM8!t-&V3 zDqRM@0dGbG`W%==cv25ErH0l-;j#@yX1N8m=9f&r)&ZY=RkUt{fbS#L8Thn+B;+u9 zafBGaWAg-to~&JSt9a0#bj*t(hW2+jdgRd|5_a|arSO4gFo8s0n!<@D!<_wi+Ry?8nIIB8WxXOTmhTf? z(LYP=zk*P;`qyQ|LGNGDr`o!C*#a-?8IMiZIQ3;qC<`)m({Nv4OpK#)C9hD`t-BQB zF{Jt4qE)`*=)@`ze`p`Us4pXe;I_ms>#AcsWkm@xKo>iE`f~S2Vb#~K{SkN(%pa2Q z65a-gzpHG?e7BPRsNT{7rof}n$J+gQMIRqvv>r-Ic^HWLR=h>@b<)2 z=ldFVNr7*X?qGp80ag~TDs6^spThG$2Q}x$DZ?8SmgU+M%z1x`%56q0M(WRy zfECcV@7uUq(DDoR13&9swzOzXb6Q!%pEWWI=-l(yX5oK}0aGcxB(?Gy4 zwv+pPk`~qlnlw?E<#g@OsqfwnCpO}Un_JvuftMq5X=Q02mABV-+F*NmeY40xscB>d zvu-#vsD7S{?f1ST)bMkdFXNnv28({ri@Us1+EPnbT%%Fw{0f$ot+A-2AlXxf*15-| zTA}PxMwF%PMcchYI@e?xTcL3Iel(()Z!EaWIBoQA6_n&aUr`Q+SHtd0VS)96_mcqq zVkO~(QU(FY(#cO!W%m+yM$tA+q|G-Ihw5i214=CW6G(i`4w^~r-J4ES#GT>;_TjQ| zU}a(Hh=#uY@SvzHot=1@pfEzkne)?Mo@57Kc$vu#x%8H8uMj1USu`<CIPo--;tRMXhAns6OyJr{4I@nU@n3Kbn$vJ`;E&V_XD|YuuTGV_;%WX*(|_z(VOchfC88 z&hRUT`bL_CWfv|vbe+%5$QSQT%egk%#mU@p571tS$>#I^siD0;-mpjiUVt~Vwves8 zxfCSy#d_6ctpY{fc1Z{~x{A@ek9>oPedUF>oau5?SXLUtExZ48(VMqPV9C%H2dk|C zj>vQveoLLZ1j#|f;rGa3uGKwzO@gI@oFC@*dhfiz=adY`hhCMrk`flhv~TZD+@$Z? znC10Mh5I&KQYO6I@ejCdGe;gc_9^2$`%X9v=D3pIRDE3CjoYe(VLs+ltUulMg%?t= zN-}!rp@&-TuM}i&_Q9+#xadk%$8-qcURI}E>aUvP#b^)6$*u-)?I{+~braVgJALBT zr=EYcX`$MyQdw#WE8=kC5NOxDw(l{`oSgi`EcE$DpO~M(8RFyLZMSFdD`9dZ6J9Y> zQkD2jKH%bp<)Y=G(GA7gIA_uvp40gq4!Ysp`1Sbf+?#HK^l)*+;gBkI5}b)9Lih#; ztm@(1J5ICn3YjQ&EVrc;J_dCZzNy*DF)Ci)Ze}9Hip9o#dc1Z1$x)b^04w(Y|8MXk zGUF32nlX8T-@!I>?ie+tDk|O5pNC8Ww`AlTtpBec{g`0> zgk;Vr?JY&Q*kCS7Ihk*qFb!KRSwxMv>dUH_-={{fCk!@|pdV(Ogpa=Y5&=7R%@Tu4Se*@CW>jdt=hi5d z3zC<+=5b7;VdNXAB~WvSrI-t6FLMJ(4)0(ji^=aB%SHANvn!fEE54&v%bYX=ILVaH z;vcg6J*h)~v8}5gW7W!=9@xIy>0q=2HjwMc0|JF}l4ij`so&EdI|pokUcp=KH4j#A z*&Sb3WaiO;0kYno!tid*{@%HVYJ7*@uwq7r)kL^4pkiM9n;-mqs+m9zEN3AlhZjNZ zKU1L;r@CmXeon1=U3JP2o*bOQl7aJtto`DKJB>UF!9TY3k&iA1qPeR8gWv{e^VZN) zTdy^11j%Q+50TlloPj6Kqa?rg@Ge;*dnM z$#bmgf+C`nK9}=lN5;^`L{hUFaO|PuxVep;30Pdq&bUyCqO>!n|3{O^{lNO3*_3FeYXEo{fprG7P5}O8@ zTP>&P+CwM;L7(LdyZ2m+_8-X@AvQPjGkdTn8b&? z%82lXU(mWamuo}A|J^w zG$=gdDV=i$@wR;aHA+M_N*Wxj0+uhbe@*!a$r9|HTE#O2C&=!m^Ri>bSu2130XOF+ z2NAJut3ZHCh>M|6uj$&=d0pLIRh>uDN$vehq918T$e@!bWr`-v=TWh4%$C#4F)Mof z2o3etP0-^|QYGLgRs{&85LT2a5s7PfiJIDAI%3+qWJVAONxeBRWm9pInlrb`m!ev0 zAbiIDN`Is<*|*<9hM7?=AV&D5uX_lHDN~xDfJgQsA(-G$(MDW}Zpi%3Cg|AX2BkO~ zJI$+(SR&9Is2%J9>irH;EmO*@$0>Y1nRSu+Pnth(lTob9)TGA>5(*uCTUqJ2UvteD zZXh=6a|NN(Ed}x=#Jq9Yx-5K(11)LLo@rX|j6s+Vex%w5P`!L77UlJ-lzhOOwds>9 zzH%Ym8ICc$3u$0HE?W-h>u3@fETQ%`pB8wMCBMR4E&{CUUr z<&lIE;!QP{#lis468W4YlNh9A2tF{A=raRTJNUd*K99wo2yL3~Ot=Y#@#rfx&oACY z(8U#h^5kc_k}IVAhbLngRX@fRW*do};d*ZvT6xBBN=Yj>g2Wikjd;#UcHir6tI_Hg z>#e((Y;QE!{!gcxFhjB=V5u8z!Ukz&bO`V6{_j$;THuh%eO8Ecjax=@#R5JfTJ*}y z-JgVr43r6pS}Ho?9XKRi;&0Bx#`ucH#>kQq`3^D%PB_67!%RbnV{Iw+VQy93;h#WX#*D*+XCc|Gz7 zJXkSG5-P5vEoOOLi4W1P_}R$lT+QRw*Lu{*w`CP+|K`b^@$TyR%|v3_>EDN&Ld`R* zM-Ylj-M6*!+;WK(BV%*@SKHui-oJ0E54+|LQ6e1^L{k`_j-1BV0%O6ppWyReb%&K1 z*_9RRMw8eM9w*GMD8kF(+G2Ur#P^KjX6bC-yqW;@zi1p|%WXA4NzpX~Gs|WJw5#(?Cq&fbWU{#-y*;DQHfRL~I}eKL*Q$}7EK=(k4R{6Bj_15`$v270hBT0IM^$ce zwo3%$_*AJ%Z`qAoliW^rvchKk4cGzPrTd{LFPNTmY7>n zM5bVTv?x^N`O7p&j_g;Z+12s5dks}-4e)gLJ?-#)jQI-xEQb1`!3(D(ya;w#UJFR3 z)pl8TzFZ1=obH)23=?+vn8P}r-TR%TA7D%I6}#>OYf&BX>$<8?x{AN$jG*+ufN6%9 z=pw^q{E{o@hVdf^%OyG?QTO6mLU6acsnp2gc8iWc8<;N$FOk14&LP2s`iU}{>vuu5 z+P2TgL=%t^o9!&Lf$-v5jofwH+U6a?W6jm5~L7A*=jd`Tw&$T zO;$ykuh3oB+;TEK$Jq@W+(eJy7Y z!^)8`$T5X<@AfCZhY7S87iAmu#IE}?ZIh(@Q>EzXB>JXJB7R4%kjlh`h$ z0OO7w0&-^ZZxO2$I1d5&ksa!X@b~(Nj-KdbOXkP_QuK99Zuz<$4C6B17WiZ-J=OB) z&P?>fL|++Rfs9f|b0u zE5e;^^PdC#2>~k&;S>W+$iRdbskQbgn`uIb@pryI0<(a?`d~Gl=za|57B_p2^)1lj z2IM#`Z_@PHg3lyN!=#wbjs94v6B=8K4t%l4+e=P_QSmKf8_E6bq_nk;wD)%Bw`|pE z_EKvq#uUcW`P4E7z47NgTd^yFc5r^Fd`xx1?-V9H+Ed?CPe4)UBv#dS!Ek$~?muxP zCN$}J?B`go>76q;)<5Zjd1M2G5CpwQm=~UfptV11&#C04MZZzIe$uaA^L*9*0up=8 z)r;gp#QZnNZ;P`xIR4UgHBEgHS-?sIumbH~c3h-qP*1_|B>LW`HIibul zDVu<27g-v0LzP4DYyX7S?0i^sIhyoSK^ckPJKOB(Y=}SgC!JF^fku>MLLxf3e7=frKhw>Y2c?3zkwN z^La+h=F)u5W{qUUDIm;Yt+uU_m?y;dqR6=D7EUmnrGJcc^|+ z$_U49SennJT@hbZ3rHr?b!t7YLeH4C%FLc#sIWl{QwYJ$5!nEUJV#+AYke+k*(L0qa`>$=#4_qBXA+E3?5e^M=PE7-%Hn78J>DMuKa(UTH6FfsrTCRdEG z+HXxm_-gI(hNO2xU|$%z?9+C{|4B%6lpB63fk%JV4)S=qE#TjsVPDY8clf%U>b?Ph zF?OXqu)Ek$W$gy<;&>C#FNDf)z={ikxq7Q_FdKp6y_8QS{`?>%>$}~)JQD}1()lII zd6i#nkZ~15X)hR)4n3=FImJMlnlQ0lAbCj#K=vlhXy|Ml?jeN88fBRdCP}Ej zrYdy{{hGRtRNt1(Na=w+Tm{mFx&aJeyEpur=m*4r&(jCM;&TNDB=(}>VXpM^6z=Z) zh~FX$?*~ocEB<9lb25mpBIaGWn1;v)|E6;aBuFYmGouzyVi1s<>#<8a){zg;GZ)sb zQhEotfu|bOhd8Pc8z2YR>oxOh5tll9I0-JAtz#V|lg2ckF6EH};n}kp6z21*$kWnU zsMiGp_NAO791Aw5QU8FUqMW)(ur)MdW}`thaQ${G0{&5FHFf=59MTqc^_1K@>Gg6- zq^@4zh}yNNtXt2fw6K_c@>yEqiTu0jpAn;;i(aPW5e-F0MG$P`7q3xlU`*EA9#o|} zINsM3TL&*v2l)~Bmay^E+6?Z{Xw#dNhY8X!n2=~MKoTmLGWb+6ACMX~8vxkykXX%z zfgCgzZ|DOpQ>atc?@65tE5bSdDJhZa-W?VgT$+E;zZ;w}E3S43ifS8a_!0Lu74X}Z z_XrWmIAp#$4y&5j0x{)o^3l8DM8~ zV~S-X;Qtph(tpARlo{({KWqWtk_u_8?G-emh;Bg1qW%@gVjh&lIDlykCb8$65f(Tz zfH&*nK~oqDrXM7~3IAwc9}JCz`F|EmDbs1UTPkXQvw~LVJcR$!l(wgUDxu zn$ghfE7{P;m*8cm0e~OtW1oGjqy}!6cKPH)a(JV)xVR(?DuLkp)n< zlSmlM{0R=al}_9F2mC<$Fj!Ba^!FDHgJ=#8_V7NUnHM&}khG^$9>fvD=Uj<)S}3ir z;l@;-bIu@hbt7|Jhyoky`xgGmeupokVs zGY+DMYMbb8En)odFEpYN62L)`q*cQC!VG`Ya$1I zlNR$&%P z(gvIz{yz`Y{6@Yp^@>p{bDj8t9E1#BMTKe&jx9mD++mds7WeRVsr<*-9IraD6sr=# zVHN)9pXg`TFl5^M($9XgJ-jcYp#J)S8YHQ;F`XimFTSDn>*xrb7}-0GpocuSH?sCa z9XjO~N;FH8%Uh&AEAF15=MBc^Dkb~V>oMS~x8->e@zF|Yf^g4|+TW1Azx@xT`EODG zn4!x0Q5PE|Q?~FXjQ-I>i1&tu5MsI25ys?>w*aL(+Y6YmG>Dd?P?$6LL2cu~B{SB# zq1Yqt0b4Y?gvrHw0_jU#(z1EM3kU$){aa74D${`J2P`&s*v<~Qfyg#$sv;YcM0^Oa zL5?GnVKKVLH+uB9IB_`18h)ebo+!Fe@)!Q2!5}P8S@<@%!!!S<=K?hwV++uB#!@45 z?zSAo*GUsy!-cX(xx=#>H&Xo~j)cgB55artV+9wl7LJQd6kWkWnX5*TTn@&QTCsCB zmHwQBT}!d{=j`W!ukCJBkYbzg7(ZHzfN_zte0*wth=CWLCUP5K03sCXfRDdPVa1Z2HL4zanPD%fX;?4)pZC5FXyA8RD zSlRocxzoJs)&KM$7$>a=l<8OWd3~pBuHSKFK5Bdr<8S@BJxJ(0ci|ml4i)uu7-s52 zx9Nw3^`ub@lwvDooda2W!rH=h9zZ2&6`4 z@_4UV7r@EuL^6}qlA=U2q-ItF@gnx-2&Jl9be`koj{Vd7Zlg$FgrMkm(PkccBzh?$ z6frFOSNEek>pZS@_Fw;JPLcG-dJ#UqM=KWpCs(eUAZt_3D;?u+)Mo=JgIhZthHpQ& zNcngQ;c}&uJVwE87tNF+@YKxXcgybC(@8G2lW#Dj@+0e(*#;8(wOvN|L&IOcX&BA7 zHrT@X2d|4yJpD+VAT{{{uUYsXN}1k%=1U89l%vl-fycPODCYlzZ7X?unU5%~oPTDe zN8twlkqi$i^+)ArI!GlH|CbU1o}o2dQ+`Otmp&XEH1#>!QlPw_Pac}2eoPpPacBG} zJ>*w)Nok;7Qc$RNw6`u0jV$YK5}{m&G@%`(D8Z85wdh6BZ%h}RI37-c5Wi6fS?TKa zZ1+#}j${Y;rxXxZZxn20%uJu|E|dR+a)4veEcs*{lfGkUsqf8NdkiUxt#R2`FRYFnmB-iz%4F ziJF0tUJ)5+PXz4QLD@aH;JadrH6GBhT@%BbB5cTLWI6XjP9rha1q z)Xr2DNHj!}E(_J_I@o<8`mer3IO|bZ8PbDAI&-cuZHu&pQs2c9=A}Fl`#;zU*`1UA z4_jxnNVY^WBdz}Ke?C)76a^T+x^*h*V?!E2}5B@$-IGT;*OQeupVt-*b zWcK&f1rSHrFxy&aGHV}^$7=ae^ntifCYq95W)BjY#fS0 z{3wTT7=knMI)`Y+6KKkV|EKhkHg(=V!3EeEi_za2k?g!=2bb$170Qb=tN$+w)nYkx zE_z@494YcJ*UH)IUlKNpdro&E=Bn5h9+d2$ivTVjO5sccVEBmt)wf@=LSF1lfg<;J zkoC(hE>-L)r%$(e2f)H;p6y(KmSZ9^Ctnz-`BU-ou#{|z+T(Ix;aaB?cM3%FeXsy# zrwzA;QzB^$0pf9JX{inw)xpil{BzX{G9Hc|nN_$iG5SE;ySwxL_fX}jyQV63K*D-v zi5k&IA!hh!85GrxiLjO&+YLX0%9rq|T-=+|AD?Rqo7aBD`_w5b3Lbj?$sxjQNOSpv zVI+^_{eNMzTWLCmtvLGIS}sQ-KN`_?8NZAqO)xRR|0ax4I;05ZMtxB)({mA07bY7e z9dAzU*}%+PsoLLM4P5$*3RU%Z5`JG-lF4ReN>DvdOE*0i73#=^{~(q9qxVZ;@c7r$ zuC#Z;Ts;#nv^I;2h`xe<6he_;_i(mvOs|Jl=GuPI3_=ntY1{Gc1F{7%-+ur0)jmuW z8=2k1mT_GG7s%E`77&8rV)|?Er`w-63##;? z!NZ`7upTyWIm-S@7i_G#LX4g?m~-FM`|Sf==;_dN&+5GlXbf7Bt5RVqfggw5@+N7FXX<6D)^^aXpG6;Qs&?inXFMY zeFYK}7GtRK&d6!`58eNzVeaW6uQgMgmF7S$q^|zI&Hke3s{ZrXo+poYc4~&dXn*%? z$=2ZV;tNsc*1&Zp^Jh-KGHY`G!>aniSJK=6)|EK1|JzW`zPtBOf=H|Wwx26kn@pV{ z$;;9_<$L|fK&MrO+j~_x?C!5BslTFjpwv=~?d2^VKf_mYwNu!RPZ23lc_uBs{Pp&S zocZ$#Jsx8qZAq4f$=&#NQ?u14Coc!sAPHzF6=S@-MXCGoMpd z!=6tvha*u>wCei3T8-})@0Fg~dcW@HF)p16niaENRXxnBGPGd?mZPr(t>Av0cm5N< zyAfmccb{o8n>hA#q;Gn1Bjtgsfej<9#07>*nZ9ldpG^1GN!OmztRRb;q}>i*<@dJcxK>6>GYq#`s+CyuNlbg~mH){fitcB2Lu4$Vt#4<u~DkTn2k1Muk z+wWX^KCT+L7i7VL2_?qgo>`_On}3{h~0-^~HgOH*8#YPVn{I>BfKhzP!}zkFSAcR@s4?9V*`c zo%@5|`}R09xhK`ll$s7y<9P2!H=j&b<<{O!7uIq%w{H2F{^ecc1;(lJ?O*O~fA;v< z!g@?^8yEG{lcs}9eLLPsH-DuV2`ShQ&^Y1q9tyc4X zx0qRfk;{v_uZ~PEJm9y{fEg*){%tJ(zN?ohQKap>!Qpf@qq3$j?KAUTCjQ=kG`3lJ z^Q{n0!HkOeT)PXti*-D#i2rB*`rUsi4q1=Ruaiu+%zQGp(le|*V6A9Xq)%P#w+VZ$ z1Od-}myMY3TgZO;$?ZRNwhBp z46x&N@0J z^V4KEu+%qBy7MnZhTHhSJ3+AHWE@^{Ik5+o7ryg(;qZ#9d@r!f+41Aio#=f{*N>kU z0lNPD(gN+(ED7c3e(qX?drcZx=7E28fd`1C@Zx`V_zf(o6U3bg>O5L~zH9+Wdb;|# JtaD0e0swve#3TR! literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/cuav_x25-super/x25-super_size.png b/docs/assets/flight_controller/cuav_x25-super/x25-super_size.png new file mode 100644 index 0000000000000000000000000000000000000000..05b2d10bc9dbc7d05896fcb6ed52fefce6a4fd15 GIT binary patch literal 24265 zcmbSxRa6{ZuV|%<#T_%ScDJy|pzqJZz|?;qK;^ zni!7)LP$+X(bCXptgjCZ4ISw3zqmM;l$2y7BmVRI_u~8<4-1pEwY9|iceNGe5kUdo zuFjopt#d!;KFCOwmzCL>o2Dkj7v<&v0HCk0|E;MhIXOANKfu%7JvS$}rlOpIlxT8t zGA1TQMMhFbLt|}iZDnP})x{+vBcr;ydTewwG>VZA1TvXYl9kf&T|F8Id+`Sp3VEy~ zt$g+0^8fELzdo*euSJG6bjBKl&l2qvHqP^KF($ zy8l;2=+=ji8Esxffd&rM| z`x~M6|H$ceY*CWRbK&>?wu8q+X#sDg5Sc#dUs+)%ezposa(=sMS%Vk zvw_Ec+P}wAhN>uA{vr8aq)urQ|w;w8uPpgF{i-UL1AnKZMHX~w5ftQtfC z+gURgkDaftBzL{8OoL4qx6#E|YxM|3Q~-5o#Zv!ipfL@wh(W1D-<8`0IJ8ZDXNYW><-2p&@FyPi%?7#G@6w%>g?feriw{Dq8wJlNuX- z?@Zs&L~~(+%cAi-L5AlBk9XgR7F65@RubUzpVnjJ1~5d0I#qrFRYWlINO27diRN>_ z&v3rT_Kkj%n>`Iw9h9=qQ^EGsW*;E`<~s zR%t-0ZG7R*@XGN?rASZ5tgE84MWj?1_-pNVXQ7O>*X-36;l>{^zs8AR;(om9kcx5h zGSUBpiQ_ToV3bsVhv+oDCqEknLfJ)!@b1^4xJ*F5zh*yF zMkM3Ts%0vL729zYYjZbOAh3q6hQIE2K;KCN)WfcxZ#nL#5i+4?ZE_vggo*u9?#qraM`EMH}NX zV2#t#sT6>A_{i0J!Hu_HsTV7B$dB2?djR@NBh&dz!Yak;ksB<$y>E6F#n8l!E%;qM zkxk0zQaaU+Tam|@XIW!SNl>zEX)5#R^#*j5;2q?1o}){+Bh(^FDKl>z`O!fbtkhd;k&T z1LG|I{|N_2z`aW;@P|iIX<4{g){)awQjE$bR#>%!{|pK z7FQ@+H2F|G+OH5z{v%poCLK_Mzkh!t@ol9cd5EQt^{$dMa65>Xu`yE>FIYkvY<65V zWNTcLALwaLZaG0s{79Ad@0WO-IIlux6d&>)@zXM`w?y2u^i{iU0?qXPrRHp3a8Jx| z&S(Dfr$bCfYoF!5e?0FnN!cwGI1?Y>9gkzzoR;@TJI9w9tg|6ap57`|gKt46X77~p zCc$O!N3*M=gWv2Y#j(aZ$38K}%zt?48Da*|J>+-^6HtHVl>}UNj+H3fq}MO}LM#z6 z#9zyI-x{S|S^CnS<@{`jIlX%_aHpH78v}%SD<~U60UzX$8@iE`D2$Oy`Mse$+r7SgM}<`y zVx2tPH{xT8k`RIvN^*hss6>UgDY(!FFcURN|9$S5K^#C|SKj-)jePCF!)$^ssr{4w zj`!_ZtxZvb&+K2_wPfi%?S8&r{(FMpkaC)V&2~7Fdu%VQX{q{#Kv@{U^&4SkC&%F+ zeA0zy_Oj>rc~i&vj=%V~HXy7QSk@}jOe)fI6p~p3ex>8A=Z=s%=m|44F7Iw;kFa0X z=N&2Z@Js%yE%Z>S7@*6pK8QFc#C=#8x$`!?!g4mx(UtyuCd}imZ+>=DWQ9kg)94=- z^(hO_ZWn^aApISeR*rM~YB$F~AjVg3j?TfrKi|8mlkNklp!X7X;<%Wb^?`XG+F;F6 zCPgtoK!d&W;3i*|FD{b ztK?`kIa1U0Knwgcp#Z!DXXEJMZUG9g(XMuRo>FGg0S4|YEpkW|qPCEIYUDYmIC2*d znbAeG@xuaAy1Iqbv^=GeqsBn5r8=XvwF>vvc(cs zm=w+>SEL-UZx3x;k#fnx6U}KufvfGU=6fk-OdUv56-y}oE^F-4P({2;f3!*xDmu~t zW3BRCGq@WFx7zQL-8osIYR>JA?{kr!3c2EhzI++90X|)8ELhQ>Zv7;j{%L=+YHC{k zSF}lzCW*e1*^KTkd}3x)siWxs36XtWPd7p44@iHfaZEnf)}P8G1{U-^+ZW{YiUfIx z*2e$zDl7M9?_jF$pKgFCb=K`3HrY>{$6k~HeGHKD5Hwe(W%nPFGiBJ@VH{}IPO+2x zF)_%Ar>gug{C#ltyjD3Yv~Z7!@1rVlb?ML?v2LS7Y!wB0_52C!G#*U>HW$1(A_&Tv zSNAMkO>S?N0R{zi)|!iO%aG~#2$Sco{Tg;$gV=+PzjIg*;_WCSd!dCRX9?}RF>s~g zBHV;-eZf*-b;(60Z4~6o4s1=I!q@xr1gRc|?v*pP>A%(e3I6bV&2RFy*ZsSk0Xd|) zh~tX-FHM!f#1iA;vNmo@df2h%iKPgOuhr7ZXCpfnPg=p2j;nP zjC6{kUO^nX{5z78>wi#6`Vdb@=WhBFdIM%EVR21o7sT_s1UAJdkS37I^q@ZH+^&s_ zNm&vBGy(i@!JOcNYY|z0k^~%llX~HZG<6&AWe2Bd%izLh&~#^i-}`E#N#rJSfrDKb@nIpB$-^I}ZbtaOWk$*) z812Qqf;9s}B#-0m1A&p;Da;xKduZOAQ}78w?7#2_5Dp75Hz+ajLK%Ej05vt&9vIFe z4=hHoxb<@CpET77mZ*4H;Z}nn@w%eJzSTBl6NSe}H%<39WkU`*NaHH!E1boS}Hw zBIbz>NCF{YE4(jU{;lCyQUntNGofgti%C4Ex{s9!JB(IC(+LVG@fQt9XhVIXaQ;X| zW4(BV5JdBjZS_i%MiC|f-%*b5^2k7i;y?sM1sIGILVcof@ET-7sKAOsvhNK+27t6f+8BZW4K=Hx5#WkUB6g3{WktG{aSD&a22^50ZwRpm{_#WI9=$C zKrJcoe=(+;ry?TG-;Y$3p8_e5+d_j)HA!|}dwR*=2F`UY$>@EoS%aR!1eAF`YK=gT z5)>In$Z`^ILX$7GN2R?O>Z0xMHc{cBA4TBQck=9e@t=&XOfY;&0bPp`IidLBLugag zJFfpEv?=qvr=Fk2R^r@55!S%^grD;Y{Hn)d0VgP?S2I4v+E%%r{gByjy8sfwtT|F? ztZfBGDA4)R;1bg-^X!--L26RgTvJ&l-^Wp$ixD&?l)C$D-xN8rD6z(DNb<3SGK=a- zZX&J3D`J>1584*f`&`JCb`R0^`Pv0xHPjnwi=z3r7x;73di)xeFzeMwl~t`IUBr=# zFvHcb6RNOVqI@q5ZX02cZd;-T+xiEgOzAa+8*vCHFBG{(zmZ?SGE(2@(R}|+pETXq zKZ79wR{qsiRBW&WgB=_CQyVhc7Oh545jdgmZltSYGSc^rBqueeb_y*dcriDn%GwA} z`xw33Id8{9lEF-T2mbBW!UYY`Huw+#0voD^=l(ptLfyzYQ!Se1S;sJ$Umr{pdZ1E% z`kU?NCZP-4SA6e+zEQb2;g!R$R3(@&GaBybg9iiu;s1wFw)-xdcZVJD-s|J>MIMVhBf9cuX^;h^#?f zGuVDb$Mdi2u$@Ubb4hqkn?G@Y=ch_V7DD?ZNsFJ6{1?q{p-Z#8MH9EOB5>9CHYs(A zv)#qB4f&r1xzW^j^jlTi{yHbO9newS$y*VA$deiDBl0s>#lTk6G(h`q`Uze5UbR%@ zeV8|3S<9btn7YnOca8Q)8sO8m#*Y*E={D~dmdFDl+Gm1RR-yHX4J0E7YtJ)>k&*XL z!K;*fd1tLdIZUQlym-7q#nj>Kx@^z}5m*9OIArVfg(d!0!YZR0QP+qztg#*5<5>gq z5t_yyW$f9DyrqHOaInB!F@zJwYNoKXWu{Mfyzo=32Xh>R(StY&8tl9d1EZdhOxzgK z1Vh&0G*Gki^zjK*DOwxpElaHNThqB%g=aw{8a1h+(g03<{5W4q;P2t%hHnfz3AL~G zLpo&b$UUJ~1^9H06uwCWCcrPm?y>uRX;}ErX61{TObp>jc%xu9hCh`6w(sJ8m%5MH z4NS?qLjtW+DPP2;{042~Tage#(V?nTy`GdSbSl3JbVxG@Pb2`xH zW6jg@=F8xKWOaM4)1J)_NrZ?62HbjvD6lf+y?4QjerWx;4)%939jZB2eRP(p=lYLX zwm$O2C~Zr_A(#tXmrXIU)kupOuk`&FGLA;Hx(>01xeG{zxq#a;Q57x3=HM{=K&A;+RdqAFAO zY;O3D5xitkV<4+#3@s8-K59k{&OC35&dm_r;GPQTU%hT>jtccqL8lbLcs~jXLBn~0i$VNwjX674 zgbmqd_i>&6M8;ur17qjJ!;AGvrB)5K$tE4I#<uQZC!KlyhGJ13dfh9>-Ie{zbTa4pEvn05twNxXYx~g4CnYiJ=e%;}gq zh85pF0nRiV$>INoiKmDS5m&t=30xA3_ z#eT~kdH6jjmgeNO`ZV(K#&3fAzhNIZ_{?{8zUpUX!0*Bm>lH28dcItGe9XGf>m=7} z=Pimb)xzo3|Gw?<{RN96%OP&HZ!4X$E>s7r7b;09hYo3H5?Ws@4>RN}AZi-9JLK`X z!$O%I4L$3UJKO8jvY@z$=Od?`m*8*H%1=b_iUsY(8V6>@{xoFjc%|vIN_{R* zNK6fv$keAOaYBEqy&V`X2QrpCnTjkL_gI{pL+H#KhbwcGT$IJwT?fPWASBdyh*OW#NU@dCbNVwGSZcqfYfza@>qFZp7X=|<3H>9!;{?7; z?Md2>#NwOp4ZOxtP7_jx#Ydl3FJ+ThX*CC%^^i3CfJ_sV`_LZ45;pk2Duwqaxtw;Q z7#sfc4O>E{*NO~nXJEE!e}yc_y%n00tX3#}3demhMY8jpgz@mvynb5YQytE=UNa0T&KyLg`EgXf;?#BcV zdZi)~-Ug^Y@rnSxIqM0cw~DCdfVXvnZAZx7jG)r^iOLel7L%AO%8B;pYO#RW$v#y! z3xnRhYR3@=w#c33Y6-sPwNu!7?b|?{`!h z@&n|8RB7n?%MV&=V78L=S&)E23KSe?C+GEGJe;R^E8;kEkme!C!@O`?o0`N^s~MF} znf^24wiAVNJeoz_taM;+ z{nzYqVe^tadJuu)OPJ%E-(f7+Y+5ySFFI{O`;c@N9|kXx1GROge13$fFmfA^h_^nQ zcQS$k9UUsinPxMl+Z|!KIJ+_5DJ)5B19Z< zLu=rN;tq}QtS7J;aaSK&NQtpcAz9YNn@Z?|-kHP=dA|QUx6#&hjwt%-@Sjd4dePXC zn@Ux3gj4l)A|Z^j35g$Pd`YV4y3s70rm_A5%xF`3i$I_{nN|eDBoNo`n=>dUi}(%; zU>x+N5Uw808T+J7uqxw<;%g1DLozg*R+{8G^5M3^1$%Z;7a{b3c0qR=TY&;kA{Gw5 zGYN(djEhBKn}rach9PKrF<~u~;PWIQ3M!V~^H^{Am)pr$3dy&xj(&gb@^uUVuw}U+ zF}>1#Pd54Q^Cuh;=mLO&VJrwUgDuFof>?#wi=vot7vb!ubK4G>{0^<~iTe7OaU*eJ z$+#2OW#sGquf#lT@-wchQbhAw^19bkHZ6U&lnYwZ$fhNjf;9w%SvcGqW>k#D#CMti zeSuJk$jAznM8wHW{SQ8d3sCh;;@59=_-FSCP9A>QxIs0vk6z$71;|XktfB@=FsA$-MJ^-um0nTei2k)Su1M52ocQD_RdM$DxYWjT zqtVkp>q2qPV_eb%ut65;=ev1Tl%I@d>Cyb~@G^>VmioFzj>1o_W44uIAT->+BP0B8 z*w5j}`vId;IeGxAZhev~GPP8;C(GU*pDZ(H4zu=BHv9f-1ik!O=R{gcf4okV&VYe= zW{Fyd*@K9YojzmSm)DV1Ae>C$W-|01_DKk5j)A!GC!gtq((VH6oA4BNrfHyRgYuKuQEW? zjmPC<9Wu4c&9Z&Qw-u{`^A_}Pi?6TlD#czy?mspa2!N%&qWD|7e{P%|P)xB(F=o*KOgPH?jO8fBnU`)vP6CeY#_IwX0DjT)kf8kLK z^s1aKWk5!qm&{5MqYyo(Yg_K^rpKF$aZy^3yrEEN(d77qXuumN>=cHW|A{Fa$ib82 z2$;yEVnN;jys_X*DSk4fvQ~$Xp}4D!4cP;N>$7D7(4J9fa$@ag!WKZrvogrD^T zMkhLnC8TS?VRNUjAikbu=A~n>pC-?{nLy7$PRVmRuypisb3wxJPryC|5w%Ie2E8X~Pa62;Hzy|M z(!fz^k%>;NJMoDnYV4JEC{BGPH6;IS2JUbuv?%ncBS$*r4Oe9E$%!}w^RB><1}wON zW&WAxGe2Qi@&}9_^nzKl#aHG)8^}aHF~a4@zvnt8kF!p=<8Q;n;qv&>!z(CbC2-cE z116a_e+|Q)-InNBs>ad`hi;*O_2i|qN-=-zsFGN-k_IRD)+h1gmAD!>U?Ew5Ko)+* zjK$RKAvnoifDj$b2#X>^7nA$R^4*m#KYSLQsY6ETl3y<8d`SIAl^4Wh83l)+={p=A}`bA5&u^lNCni6%AAl@hT zZLal;Yl~b!w73dzKRN0Z`%h{sOI&xB2cEk$D>o>4d{2ZMa=Y*2uZ3wtCR~-r3lGBT z!RegEVSRmlLmC!QV+~*xK=p2(A(#o;%*tYncXUH(kiK| zv{$(XHabc(z*od>F4vEJj?&cOMDUluCoG1^fZjz-XaId6n+Ah-Rl&?imPwIufzl&X{g_+<+%93qQuY{=t3!p~10Qtwc z5fR?w(iLLpTKX?Z=`7fDi84^eqd7kT? zlrp1@uNx#*DV7~Lz{t@Hp_@S$PwS;ddA)gY$&eX}H~ti}F#=xiKcbsR_jy>z_6cAS zk8J0~XHL#?#4L>@Z{TbQXWGAU{OLO@n_?$fBn?J;lu={8YQOEddvrue<;jF?6-5Rg zi_%(`PRdZTvR$In2a^Kh%Nn&y&!4U|DdDqY;8h3*t_oFK)&5C0O5a{NtacOP(X_+7esxNjA0bAQ|zOQ306Uvmfo+{ zz*-&^i$!>pA~Zl%n0LIIQzx6vG9(jDUK9cA%7eshJ#jRRHwjA|e_x6@^$s~p-;gEv zr0B@%=R|ILGHovywMlW(g^T~?_wpf{=zWlT(<%0DTGDJijy@nPokYcX%GPMI{JaY{ zv`$(ql;(Bc&=-7c-h@BM5A5WcKBm;E`9+ReZ=LAanv2$vL75 z{+~$SuReDm6;4pX-fVjS@eWY*f|*E*S%Uqw#2X*MX+u{fqgRiW@L)&^_0SU3~6g3gOxaALQni8sX)YT>XQ4tWby~NO$YLam8I>eVqizXcTX0w z0t(j%@Q=4F@Je0VUkwXd)d5Z?!F?m)XXJBqmC${1e2D!kBKFUv7N#dz zpj$tr3|&_SdG`8{txL4AV*hVc-z8~6-hqFoDSM^Ki&uqbXF%3y{J$u?3> z(w;~o*7$-Soal7#0d%^oj%we;=#`%=4tdv@mXL1+8?^7%7-M!G10^Y;I5<`=J;YOO zH)jGN98*8@F}W-(jAs_A^1A-*#=Bm1z#cIg%zmiFZ(Jtjw}|PZKc*=f6yC+6<0-5S z?c1wu&kWC9wLwKt+=Rf|nhSFU?mqQLiAIjRqWLFYAuBlhGl3ynPD>{BurH||L4eoy z4Y9e+YZ}15Uo)M3Yn=%!Vg7rxX3MFB!2eW}r4WZ%Dv@)GT9MUdu$ahIhO}CNi+0wT za380BY89tm>|}9*@7INGt;@ggCe`~$m)GO;@LzMB`Sv$KMZOF<3I8}su3}FR3=r_L ze4=Sk#mD#XQBzzzWcU4Ew|9wa5N%VLP7g$UkUs6o295oU1U=ah(3Y&K?HtFTR3iKcXhhN;b%Quy!-$M7k z>J%#Q6;nysi;Y)OmT-W#lGwhY3ntlRTpC51wl_~IFa$4-3){&?5E0zH`6x|`JBrau znUxGMmR#k#&&@G6bdx+LuACeC%wpUU0iS?K^*%nGqyS^`{b6zi@=r*TEmKX)gpp$X z)h^RmQ%rEipoQ3KDL?ye%PjA(1t51)R$FF*0w z;ugiMxjJCZA$fR6eUGW{Se(TI&*B}OuSYQXCq!ka3REMTi3zFWby>2p@n<`jZCf^r~Xk;)edkuY-Sbz~@?n&zD z_OKKqf9<>gn+nu8IAGKeE4p z9*~fp@K*mmpnbWaEbsP&BNvJbEcVy#O^ay4PstNm|Ca5{|2wQmAgghIs)d>S3oVK8hMXye$3#3OE3S=?c{15ju zz}6rYY1Gphe1B*zCFUA+HG#(T&{cr^rajQOM{Nxtga_JSb=*7He380+`POFZ)aXeE#YQt~z)du_V{FJ!&8M!6@(L5+ zfjm=fFv53_x(v6TbekAW(EJyml-aX>u1qJtuCA_j-CrPmT_^Z=w<9tF?gFoj&Q0~F z)~vhqp%aJMEH6%X*@p+;slIVZzOiY#vRa?On6p|(dfd!~qzKx+oUW2l7oF;S33G)e zEMe%!Ac?>5?ZKH6q|du8W+}#=GAKMaBq{uaLG3HwBJrSUlsG!vzW)9t>XgXT1H}^c zlr<`=za-wTet7Ye5I*4*1hB|zje6>$t!3=VA3F&8e}J8mbQ)%zkalVwP9g$dp|5{s{^M|h)5$>c%ZuTIL%2A~-R%iU=STh!17HN% z+2n5N18i{%6<*3u%RXX^-I|kYS;{B%EDSRt$J)qiKn=RO?KI|Epsfd#|MJTC z8mu9up$H&~#Sf%9h0{02SbSNqVgbyMJ5yw!c}RVzVl}HT5xK;W{GuKhO-@@fIFrLU zA3IztDZn6@*{J3@IK#Z?75*d#VeAZpd4_L9Jn=cMWnFt+gF-j!%I?si0zLJs;&!up zx{&mY9azH2oMFp*LO4CF$Dd<^9sG6fE#OIaD&pD!|wPR`^MRmzkSwz8E`#8dC*jsEguv8Xp$~M>Vlt z^gD7uO{CjaF`#>&^Tui+NeXqX-koa0{f{Wl-ShzYUxI(qa!+<1<3edyPIt7wkRF-9 zB@0hW@4U&AlMX85hSy2Jgn8Tu1&d_z(yqlq&(1CDl41-herw;yfVhblIK0eU;<&Mv z$aC;xLmM)+GH%$Dv2lkZpeAca1^y~FZIhr$T8W7+eMfefLSCSG7HAgm8S=)^qqf zHJiU95L*gRP>|AXS9GDQY*M&dBK=2aw^Z3kw;$P|AzyEDr$nWm(cqrJe-|NhcmM`! z)5$OEmFcy8S4=Q_$R&)P!5-_yO$~L@h|TSAcIT(A)_ztR04XT^srR66?;a*VY7qE% zjn*G$b>Pv4B^Gav1^zt%aZAOk?M<+5pj*Zg%ycomG0>2VRID^Nh^;oE$_(J z$WcMuIPjP;Ux1HnC;rhFJ{4G41j}cB)SChbZ4?ffi~^J+G1}BCIG`|)jeaM77f*U{ z(*jjGX8cC%Eh4iE7Cd4`BQ(jYD`$5DA>)Jo{;(w$5G_6e+)sqd+hj z9(w#pGiQx@%_}(7*mapUswoMx+_vR{Z9-tgCabo(Fibk_(3hD8- z>i%KvD?}uDN|%znU!}3#a8db{D84hvk4Btmm-Wja^$~=$5lPzzfl*3IQw)%cgP@0P zy=qOUdn)!eGjfckQUvt9u03L@{JYTT^z4#8n^ObB5Cl?tP)X16i9ae zwtWrpOa`&xeR&00j;&^1e6=l2L~Rak1sKNnp)=K;H=ZMMiJ>Rs1LGYSr+Kqq=oM&q z3`Ql1xpV{iwY1+>;nzsFAXzy(nxbUW-nXY4z z;E1{euk4K1u+U1Xc$DL!o;FkSo|UPG9x7Y1haob-Xk5s#yU|{c|6W$ zR*@drz?1iFvzlHJn-rSM(p!E6453GBWrY^H?P^`8)YP5r2xAUlVgZnUL032G`R8ZBhh)x^5XCe3Qjj z2WNEq!_X|O{_hwXaexJJX?{fE(ZH{kR+AR)jiTM2#Qv8V5CiR&?nX$k)Ox4wFfkr( zcuMH+QukUU3kZWG1Pkx|HJn3uX-Z778C6-^FI@Z&anB(Vn69#rz&kZ|3BYItp-s7X z<;HItGP6(JS-y%DNU#Ab5kNg*P5zrPy@7%H;#}t!v0Ndjt`7g0f%gpjk`}K%fa|Ej zOsTB<<<(h8A?)$)wO|Zl79tsOK1uf+HJKUyIMmky1HMX`EPxCI5r`0P=!`zux{2hN zTI)HTMKONUld76(@Gv5VPyvmv@Pr*dtOfO{UM;;8vbH%5vWeIeG_YPbKj<&rFyg>& zqT@#ji~bBq%X`H%3o&f5A8Y4Q7-4Cp=ywf6j+bVUg|gqK)-2bML-ocH?HB~w4RwkU z8;qLRbXh_CM);S1)tRpnVAcF;-(uW(vZ)%1jyM~UH4;{6oR?^p#^p*5?`JP8zKqxd zV_4OBk+Q|AW7&}B-_z~TM%j9SmzG4=@oS;q{^ZUrqg<5BuipM{A^HGQmx)OdUtt@> z(Ji-xNio~6KDwy|+8Ea_&nJOb)rO+?sKA8F6~%H{oCI&BXkVGoSDHng$Wjr8mU?oc zn?yGgr*PMc0wC&bI13?&8N3m*&uidNhNppiP2$~H7Ka^Ts`r|$P1sOP1n;H> zdop9u?+k!5xmQg%bv|!574nSnQYE9CN8fw?ETxi*Ecj(UEraTSXOk(-;2kcG^pdev zCBS`)>)Lld8#%IUsEBmLCf|--QpM`>F=kgMJ7V9jr5wEn#4%^B-A0!a#bf&31OdiYZNj+!0a`2%bxP2OULWEsiyjl5HFo zE;3M<#^{4O7`)OR>@=@N+u;N=yZ7RXaqb^iIqRi>wAlAlBu`b&GG7}OE4sG_C(Aj` z>LwMGe`K&=1!QzLWPm7BMl}+SRzLh&X&y37tz|ExyzzG^E8K0#Nx@2ap6=Xc3ytP_zYE^i8CC|L5}Da;zj zDzaM#o3b(%4>E-DVqcy_d^G%yK)WpOx<7$)_mF}N@*>SreKLVb-3HCZKv@5J5W+oS z2{Mhe5xqD6x--?J_nH;53?_2x2SYQ8CyR6PM=L)p>a-|E;7WxYyWno{-z}|>-^4*8 z_q6aGnG-?9 z?N&z!=OJ|?3n5v)3B<#9{-~9VlRmPY#j9F6l&`$tfd4BJ{VvY-$8dJ_JHcE%ReVPm z@=khc|JGXyJa&v+7GSAMYr>Rkyt7~8E20?$@~^x#ArU7VawDNqCL1&NwfOK@`sP>Z zyak9j{MiAGGUcDu|I|hcHX|ekpgcTqfqVY!dqHhT7exNxXHo-C}A*Kc~ z)sy&#Ukyyf`HWw3s;D%67DLbiHB0b;#1t1S$ zkJ=MK#ny&l+RZ~~v1V`JWN(`98rH}h2R2{5Levi9nd+SNGq}SOt_tH>Q4Oga{+4JX z^uP_=VRqmLG!oiKhC`ziTNU5=-`~7>)O*CNJuh3y8<3#>+x@yn2uylNicbAqo7{!e z|43|xNI;Ds7t8@>I@pzNvkOyHOxQvu{d%N|0DF#ZiYTb@6TEVxwn<3Okif! zKgYGwONGaxLVNjxN+y_M04Zhxdb1Qvx^Uv+4bPiT5kSiB)DlUNh{>KDb;Nsh{WJWk{Q&g<@+A zyh}hCzm1qa6qp_Tsy^>Kp7$E+@0RSaPp?hf1J zt8<0P?zU0V+~VW?`I=$%7Gw0QCY+AF-I1w`An1fo#ALd_?$FS0 zJbi=R1fOoX?j!fLjXX=4l63Bj%5Dkw;X#R(@dvI`iA3N16Nn=fwGL>uF(DLbRmc3n zZq3Qe6=id8JgEjk^O2X1MH2X)3`|IGJ+~dztv;Ha6vL?Hjuh3~){GeW2o#K>5L$Fp z2Duo(*gMN#{9TA%kGmDM3T|FXM5(pMky2A#fOcRA5q(j?V8JYR(n2=y*Pa2Iot6V> z;0TUKF9YaB))8Pm5p`aZ#4y+wv4D5m2N8w~4io__g=knk8g)%T!VY2!u8E$K{_h-r zb92Vy^vJq=dHN(@7G;6-t6P}6f9z*^xT7@c)uqg(NQ{~_UZP3?i9!cc2e|ZW{K^z(OOUEKUvTQ8iz6Q#{#Td_|H|2VEJv`&z z^ANIy?)Z_` z!Co9K&jKb4W&o9@p1X@>VTaOv#xKAvXnGhqGA$pB2lb!*)=a^n9xNW%kQOlg_~zD8 z#w;+Uj}*kRb6(nMn{Ti#04{)J0DCYfqW9wm@51*OB`J56H|zgkUdCn#Nq#z5TgE+7 z(RDGsLAj-xvq*G`AYE~BFkibFFb(;=;su?_N}t{Li2rfm*v#eWXO<#g^4CO0j{!pT zof}$>BvLkk?@+R$?!M%J6je!70%a$?Ed)te{$bhj*#g_*ydTY#L1lCbN^ImY(oJ1&Ny zx0Iu8P)AK`d@?~3gFQ!j3e&OqTts1Jos?ujLxK^vipGM}NG>l19$I94u!IU1J$cnM8VRlnu1bV`*JX}s zdSqKjwc^t65FG9+(mQWZyoJ)YLz^p@$||APbI(or7M+H*de*}`D^Ax1A$c3YQzMsh zy34-ri@5bl{vPaeW0oX0&M41Y-Fn?KYgPmXTZpbii<|7_(U-hC`+E>2u;H_`fRBL2 z04co+mXaimStja#x=%f?@I?&m=)rz?ik=q4u}jjzJ2-%mHgTJO^M5uB$&gE`a*=M#}oM^5g?*d}EuBEe|yMKV=RW7(NI0jLQ;!j2iZ*_?9*1rpCNt$~L zemU!Rb<(u^X6X!YrKk5#+5moNdP#`kkLjAHIkKqp8@uKwV<(wWU;ZlTXJhqQPw+LK z+UK=P)n)+<-K-F$ia<&>G%&9EA#9btdej9_CYKY717E6)`H$|E&2Z(yjC}eeb0ZwptIMR1q6hAx2kQO7G)kP>19xJ_S3p0ef(Cx$30C z5w)1B&^cQeO!7tIUp5vKrrXi)Z28{4HszPnqI5tBgp6BK$@rkl_5J%3rY2>h}5O#L`z z=5j5O$YU%xU9fHA+G#F$NBxojYwa9zgGXWsxX4{%lnON_of7<}L|4zTSQ}!e54L|4 zJnI3<-#X!B%w0WzT!jeg=>g|zO;O?pO^ciySUkPzEHiW?8y)kuxs|T7qI6$mOqs-i~ zU1NkN17Fj-?QXj0^OC1#s!L&;FJt_1z$30$LPQ*-YgPtJhD?Nt|VCKS`;iRJmT8$A9^|Vmo<7 zk=hJ+0}Xv|oRzzNHD_06S{`-`+RJQ4a}FkKz%2@vu6=B(F_18J zK3?6`w^tGzxWJ)x-6GCccb7ge>F0>TVd)s=k<;=qkE9+nXcYV>8$mKeobA#;#d~5I z74$*HKlessr(*zNs0YE61I}O{9rXIzgo+MmhFB9daLalK<~__k^myGA2+k3RneC>*iNzv}~ zeo`1}B>f!Gg-VR9qTFaX-_`Zv-mPMedaC(47dj+e(nYGU>H2P}^St6fvN9Eb=UYeZ zJ4X^1IvD-Aj^6dnmWmi?pu**~J2OOk?wjS*OKuX8x6l0hhwM(~rO`nrI_8_kYL?Q} z1sp90{x4-DFq5^n5W;5&ZO)!n(EekVJyTvHbWuM6w?x543DQrN=tX$oJd6)nJe3%3 z+nHH#xN0%v-p>xS4GF9rY2r36rRBAI3k-OOnj~N3?fPD8CgF(Fa9=`3EzMhUEkp;b zgogK>-2X;#-Sb4CM2K^ao>q6Ca00_lk&|{A&n>H7&ul1n+^?P~5KG9pekPFfk-OOjX!w%w$6ekls_AoZ}zPv~5KPYdv#0h*814E6FR?pm-QMc-~IW3vl zC8EU)tWz*MOreJlY)f39&>?>!i+yGHQ&&T?3l^0S|3=20=hXL~_oO z2aq9WBr2##o*|=TBn??W$qXQZl5@PwswDP_n)qN`kr^HZoTT)@4kBx z2JYI{z@#rDp>I1}_3+`(D>s^%)3MwnS*6F-6N7_D`BDNeUS=ifjEWU0dAagTn!tcM zsK2E7bXhy!fnoCaTZLP|z$gFGc}HLR6HVal#olM@KPKk!J`Rvnx&)koIvhhRxtE+I zoIgo4u-9Mxx3R$gS?d3Px3KR{J)-z7POG7oV<4;!womXSL(bp1Xg}j*){ZRXblMg< z$Ns;2|34AM4ZO-P>+y18Qjk8BS<*m!25P2hE+PFw^F4i*o6N71$0aXHA3=7;H31>P z8_EO!(2(BSwdHh~qTlV>>up`P*5MZELC~3*1=(g8H6|smZO(%g@4L8SFBuV;HdXb; z@S*9!-DE)H+{?DN;iVNDJjds(+$FxpBtzfibOyq_cVb)#jThno1sHwqz=P#z$Sud{>7r zSqVeANXMWs_24oot}WGJf&xkmc5aAQkloStM#`U7q<8%INP6Qy$z98n@D5btyME1o z=oaEC(}UddhD_yp#R=#2Mp?wcSJ5NQzOP?0!zL-*3n3;4e`vrYv&fF_tYR1+N97E5)ym6t<^8wp^G30r zg0KAH4Z~Ib--Qxg!6OP4tIT#We-@g}acOI2E(asc;6g7Gp17|>a-%KP zo#%dpW7J?S9zpMvF*d|`&mR@AQ)7ddlFGIIN|!57tOY0gcw~NbV1575p##K7Oo_4T zdnx`kKkS|Iw%G%7 z_4~iVIWfm{piI>S%pD!^NFEFU0)ECQAMLR((L9P3_WK!vn>;}!4{lcAg)(`$?cY^{ z0vp0d?nlIR*p>ZnX98f~{A!D(lZ9jwpS~0}{)%)?O~k z-Z~{07pKh1gS*hZF#+UsHLXe6{9O(`MZN_|$mBPC9hArb80fK4BqEYmYZfF$DCBRo z;^o23KbD~K!twH~cr;Np+@uK5Usb*yybcpnl2BFDooRy%xFFyA_}|fss72+du>4hB z#mgoq0VpM!n+kpF#0|}abELt~WfTx?3ve;+-@>Old}>r^_W>LD z@Lj=Y+Mi-2JnydbtzM*(AI@g-Pu#+xRr3NZ{KHeiDI_Y89@a}%=cA5zy8z$HwCng} z?1mEf{N~{hrURZNv2n$O@J0AO!|U*fPDNq2+VOKY3D#Cv;0Rk*`HnI8$^hpwml`;r z2yOhQARL{n4mx$qw>RCi1_lb3#P;o3RLl5`DxYbIiM@IA*ksxz2y{GMdub-912c&1K6dgh;d z=_*zxfU5COtg7L6TFp84_c=b2s$DcYI1>0qsEv|Ue7MRE>zi57(<8ROTb*PJBjsOb zzPupxt00rWm&MgYrEMZep*>hX{tOA*>XgKy`jI%t$;LrAJpazHYRRwT??+xL3O!0f zjV71I;;~a~KG#xGJHSTUct6Ls8rmZWrK&TIG43BCqN)|Pj)4tzV=UP zf8ly00p;-U>s>;#%44f)YZHs} zj#^>cN}u5xg~+fXESpy*3g$HGbB<>C<#LCgdYzrEfU>bu9r2;oG=aHko|q=f3qP0i z{iZq;-tsAW83+VJ2CDTw_F*rBCYK z`S#3$aR&Udwle*qMDOQ`n~W!bd1G~lNMmC~-we(utt1@~Mwnh&!)ZE2#TA;c`O!M< zR7h>CF+53KEc|X+&JAB;`avg~@mL6IJZC3pQ6zsl9N_j!EM49SnUc9UY4r-YFUCfG z-@PSE0Kq!gwx?&B?~?O1ga8fXw8e(%x6t`krdhugD)h;w3ve)Ym>#yH?B*G+IhA(V zgk^mf5hf`UirqOXL)W#d(!qwQU&m3+_gG*#oY?o-apbbfLFKM+Dx+E;=^wk-Hz2SLNi%1rp;|9l}*HnHN#~b8YoGflw ze4qj`8YX>EE>7yhqn4AV!@KJhOHJs^)^PTq^b& znjQ?6r#mm57?OQ7cJ}nJon27Zbb^5%%k$y`H5RY`eb3WS9#ngtnlF%&@5#mtNy%M#WKbFeJZ zZ6_{l7`OjPsmKKmd_qe;91w~{k@)f^hXqd%ht|qfgGG_kk#<6XCu}6sLAu(fO^Tr6 z5`oPJ`VA4XkLgs3X45_MoyG!vkSOju;kq%y7dwxk5bqd zCM8{+*Rac4IslP5&3I%BMa-^9_^3&jQnQ`(m-*KZ~>Rb6(G;GUELIRqrLM8 zTTmkZ5cPo2M5Ok79sn0zeokOlUDd1fxspQ1#^v`%=g0i|KEV?e!G}Vv-++;Bz87~@ zE;u;_au(9|H!8n>>c0c6it!*_Z-XaHGN4m9a@ao_f@zhyoqywD6~*l_@?yn@tJ|7S z(Mpzyw0GPeBaE(0O7axn?ivAp_hP%w- z=M#CLsylGLWMKj$Tzfz$G_5THGfg<)*mGi_KU@Bk@$29-p}lXjgFPzU3~h!^r1`O0 zotC;Vntons4<{pC3Pf->0*wG2AJxs9h?EcQ&iV-wjGZ;koE`M{_jX@lpm$7dxh~(* zKFap0Ge7d4L-+AyD317GeN*pA`-Ej8`!Z`y$7?1_bYjj*!M0trP zgxHLB@C7NQdZP_1r4bh_Pyq9%3E3;$xS^*h6H>6o$V;wc5nrb&@N{YB@jI)eut+VZ z3;gv#gg6s6|G?ksNMLQo1DUwX%+(KB5#*on$&Eld*F?`c{kz1{!~NF?Fu1OpWLJbL z;-d0l_NMO|Z*Dai)X|hQN);4JW>s-Vchis+dCG!SJkmKuKelAw58Q{L|8>lyw$v{( z2qm_W-f8M6tlSF}L-H+`6m}`6M7ShdS=&v|(RsZ24ID$X6ao>4PID(WtTplpqKd_Zx~jJXh5T)`9@ycUZ=i}DKbWR2-|pBv zE+4S(q1&i0lw2z~#!cKwRMz~iQ8+hah~|lPSi(hhqyp>Z0A88tE^>DjcdD>maQx2X zgWyKQ7vA7P5I%}!#pf@(@-{y#ico_wrGE+tDC|90Cd0OD>o4#oYmj)WET|&_3z|47 zQ=CTdA^C^?R!0Lhs(2&69C9hQuN&J$EOgP7TjC-*6e$$sLxLYB$_jrK-gybF5qUnj z+$2vuY5C-}N3pEXq&}k1M)y7gxKD;Q`VIgkCmR@1Cwr?2ZCED^ko%S2s z;^*{)=D&FF+d7YRBCb5JF-+iGp;@DCZcWYh@R`#Ufvqi09V^o5JP@Sg8$7|}eBk9G z@`tm};K!!Vzo5m{Wf5WPS(_*^PU~#kzH2;2QoD0HKrLpDz*>j;S(H z(|!5UK`^B`Fysf)>5bcs=2F5xKiONpE`nxy{8Q!6MWU#nW_6Q?&N))wUY|NdWT!b@ zkswPc`fE(a&UU-yen5bDwzI@X9|*4(Th`~#S5A}?v$6#uglI1bGPeM3^FVEw`BR=_h!kw|-8Q30w`8tPS*x0X#v%3B~F?{4% zIn5NlO+3?d?zelaq(b{jsJ5NIb|u-?;?_rN=|T!^NzqvCgl28A`=+4ge1{7ii)4po zCZ^U-gH~EK7QPR!>xejDjci3)lz$v~ks*aq^Q-&~TyHVwjgO4ho7u=zyfWa$qEI&f zO6rcr{R;PTO3so(cB!`tgtmu+{Ap+BelVxqQ#Ma_?nHg-)R}a!RUL*Z7YuP4Y+^b& z4K^l&2bop35*eo3_GN=+*zm<{&Pd4Z$&jHpa=&s8kPKJg_ztF2-1`@by!DjO?3gtt z_{@wIdFa1s_{RMguls@eAx`CUPJ@HnV5pmtf|pGF#3&5VOSJNzOKtxJ*&|ZY-z+!! zxq&2$=zcwEv7F@rdkEF9PF#B);=M1v^MTwV*Wtb2quj6Yw{c zUIL%yma+DonJK`zDI^>!+=!b1uAWvHz(KgcqXeKuQ{hQ;g)Q-m(olbkP)N5OKAu=J zxHPUaoYYV!s+V>$@PWoUinYI4T+7W}1vP7fI z<2rM7ER!8#72k_J2?+##`4joPy>KKcqv$UQxnINeMskXBrRoL)d*JaV0$9w3(DB1{ zdLiPEXw;l;5SHC|@jD^T?3~aW?iUVCvlj4?%?<{r;C%L}$jG z4ateuJy0j4Z!3d{cM!*W?Ti;ed8Chu|FmP)>#61?Tf%M)j{Zf$>oJ!^=}|WwJU(Cj zfLR{0MCZ?jl(d64d4pLvxhMNdMfUMJ!t4S7qMWFd+`uS(Hp`z*=u)F?J~mDF&?|H~ zpTy1B;=(=;DB6~_Yd=%k(IcaT<&W*f=!wcVJ_=1<+VT%d#^+ZK$!{%}$Mq)F%uN)~ zqD1z;WXPy{+REvh$=2Kuq>-niM4wPfe9*^?$l?!nwm^CObBWpcq9arhNpxR%W`Y$S zM~rtg`PC`-fU5s16;9G$zSw=^k~)+wVf{gO&{X3uM zQ^GCvFe%Zh*#jLL0B#ORvjQ=Jz#e zd`yrOpUv0rAAER}t+XZE8B37wPaeZw_Gh_N>0Ru|A}^Spn7^pM zv(-OQu^#hl+q>DeqIp?cPOM(Zk=gIF+5?sSkKW8(aa0*&CQA(io)Z2RJyFrh>07=` zcPX(k`04aI0AVK?5}bA*>PdaYOzh@|g<3j#NYu4uDZ5wvX%Ig}cOf@~*gl3u=CF>b zmuh|DFFTavIP2UsYUs^22S)z8D+2Z2_*&Qy@9($9)Mma&hIMLZzkQgL^)g3Nieu9#G5u-=8m}5qUVM3W` z-EYsZBr=jCm7(kLYBB&h9r?YP<0-)cT!vPX2^tFYjlo&a0mlS4v_LA;iwC#2*mU<` z5|KoM+D!b|NCq?Xg7==}AzgGB0s6__`Jo+(90?v6iB_A5Qx-q@(x`^F^otC7Ko08_ zA-Ev}ge19LUce$#1sKr*+)i52)#Pkhm)OkYVqtcVaoKbdSqA3P)w*h9sqycj4o+LF zln@yd_DhJ}wsN6b*JHe3NqrFVR!Xq_YZ)l?ud><9UfPgk8Qa4>PrT?`!RRnkmcX9JtxGh*rX+ z3717L4l7V=PIqadWMXf=kIY`uIC1J7R*Qf4w_RXYc~ZMj1}?)oUbQR$U5cTcx77ZQ z_ywbI2M=_$51UAO{8!49^3!sENo-xp1H^qE=gO6*oX}T=FOX@Z-w4@O`8&iigbthH z@MHdgdT;I0EN^|=0$a%Be^ABfc|Happ4Z&?R44DWT&OUtuJ0_al100(j)^AG@he&2 z4c9LmbD>;NjwgLHMRU#O>II;s3rf@HWGEi!;pbP>N{4wV7ZW6WFAt0I4vlF29FN|{ z7j5fm9)7Mb-Xb`UqYy)!A3J)rXm3bY1_zC4p3fB^b?@VNj?~^5YB+0=d=aZpU}*vB zU5rJD(pRwle$ty8_>7Dk*&-U(L8@*k{JeERO>aDxn6~#ds>J`%t|jBP-TNWK>X4vR zI3p9($C50VArASf*!Pjav-iVtJK!ZUWbOa!-p0h$mwPV_kOPz(n{M9GLvHX7$ z^k1L7&T)Mv@Z(kNvzRc$;reT&7*u{!c!DhG6W_awm^8_V=7PPyzhGSnClJi5v%O*1c(X><^uu554eMpBG+IPe> zo7?iiXqfs;BgJq5S@Hn`6$ZaonUNS?r=cDRxHTj*{3A zJe7;1egPgO!de>2GB&08l$aRNLBtTV8~W59`Lz5zh1X(9BNfI{*-bk=$IBYS@4x(0)jB~Y zeKP0`ZQt!pAH$Hbs&C2Dv>a84{fBz$-*L@*b7&m_QEs%?QP%2Gvvs=V2FFBhu3`50 z@Y<%s42}VNkHC}AUY|*c>yEJUze^YTlHt#n_A-@iua>l2br$l^1=bUrEUT4q`o#)m*}$Zq#p7qt?GB`9i${oHu`ljeRdK)Pn@0%_wSISJtE zIFZ8Zw=;Tm{hxYz3aG*ka9%#DuiYxFF;sDzn8^(^M@wzf-;@!gnV`FpO%JC!C!AMu zu4#hCqGVbx-P_%h{)3E(T_jLw#tu_Y1(1s6$Qw3BEWkP)Y(DHWUyemKw8>FD1XyV`wa+}rdoKP% O`b1M-qZ(`z^*;a`7fn_G literal 0 HcmV?d00001 diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index aaca3ffd3e..1306bcb72c 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -174,6 +174,7 @@ - [CUAV V5 nano (FMUv5)](flight_controller/cuav_v5_nano.md) - [CUAV V5 nano Wiring Quickstart](assembly/quick_start_cuav_v5_nano.md) - [CUAV X25 EVO](flight_controller/cuav_x25-evo.md) + - [CUAV X25 SUPER](flight_controller/cuav_x25-super.md) - [CubePilot Cube Orange+ (CubePilot)](flight_controller/cubepilot_cube_orangeplus.md) - [CubePilot Cube Orange (CubePilot)](flight_controller/cubepilot_cube_orange.md) - [CubePilot Cube Yellow (CubePilot)](flight_controller/cubepilot_cube_yellow.md) diff --git a/docs/en/flight_controller/autopilot_manufacturer_supported.md b/docs/en/flight_controller/autopilot_manufacturer_supported.md index ea2e465295..4c33358f9f 100644 --- a/docs/en/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/en/flight_controller/autopilot_manufacturer_supported.md @@ -22,6 +22,7 @@ The boards in this category are: - [CUAV V5+](../flight_controller/cuav_v5_plus.md) (FMUv5) - [CUAV V5 nano](../flight_controller/cuav_v5_nano.md) (FMUv5) - [CUAV X25 EVO](../flight_controller/cuav_x25-evo.md) + [CUAV X25 SUPER](../flight_controller/cuav_x25-super.md) - [CubePilot Cube Orange+](../flight_controller/cubepilot_cube_orangeplus.md) - [CubePilot Cube Orange](../flight_controller/cubepilot_cube_orange.md) - [CubePilot Cube Yellow](../flight_controller/cubepilot_cube_yellow.md) diff --git a/docs/en/flight_controller/cuav_x25-super.md b/docs/en/flight_controller/cuav_x25-super.md new file mode 100644 index 0000000000..1c57baf08e --- /dev/null +++ b/docs/en/flight_controller/cuav_x25-super.md @@ -0,0 +1,172 @@ +# CUAV X25-SUPER + + + +::: warning +PX4 does not manufacture this (or any) autopilot. +Contact the [manufacturer](https://store.cuav.net/) for hardware support or compliance issues. +::: + +The _X25-SUPER_ is an advanced autopilot manufactured by CUAV®. + +The autopilot is recommended for commercial system integration but is also suitable for academic research and any other applications. + +![X25-SUPER AutoPilot - hero image](../../assets/flight_controller/cuav_x25-super/x25-super.png) + +The X25-SUPER brings you ultimate performance, stability, and reliability in every aspect. + +::: info +These flight controllers are [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +### Features + +- Arm® Cortex-M7® processor (STM32H743XI) with Floating-Point Unit (FPU), operating at 480MHz, and featuring 2MB Flash memory. Enables developers to enhance productivity and efficiency, allowing for more complex algorithms and models. +- Automotive-grade RM3100 compass. Designed for better stability and anti-interference capability. +- Triple-redundant IMUs and dual-redundant barometers located on separate buses. If the PX4 autopilot detects a sensor failure, the system seamlessly switches to another sensor to maintain flight control reliability. +- Independent LDO power control supplies power to each sensor group. A vibration isolation system filters high-frequency vibrations and reduces noise to ensure accurate readings, enabling better overall flight performance for the vehicle. +- Integrated Microchip Ethernet PHY for high-speed communication with onboard devices like mission computers via Ethernet. +- Dual temperature compensation systems, located on the IMU board and FMU board respectively. Temperature is controlled by onboard heating resistors to achieve the optimal operating temperature for the IMUs. +- PWM servo output voltage switchable between 3.3V or 5V. +- Modular design for DIY carrier boards. + +### Processors & Sensors + +- Main Processor: STM32H743XI + - 32-bit Arm® Cortex®-M7, 480MHz, 2MB Flash, 1MB RAM +- Onboard Sensors: + - Accel/Gyro: SCH16T + - Accel/Gyro: IIM42652 + - Accel/Gyro: IIM42653 + - Magnetometer: RM3100 + - Barometer: BMP581 + - Barometer: ICP-20100 + +### Electrical Data + +- Rated Voltage: + - Input Voltage: 10~18V + - USB Power Input: 4.75~5.25V + - Servo Rail Input: 0~9.9V +- Rated Current: + - Total Output Max Current: 10A + - TELEM1 and TELEM2 Output Current limiter: 4A + - CAN1 and CAN2 Output Current limiter: 2.4A + - Other Ports Output Current limiter: 1.5A + +### Interfaces + +- 16x PWM Servo Outputs +- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus +- 1x Analog/PWM RSSI Input +- 2x TELEM Ports (with full flow control) +- 1x UART4 Port +- 2x GPS Ports + - 1x Full GPS plus Safety Switch Port (GPS1) + - 1x Basic GPS Port (with I2C, GPS2) +- 1x USB Port (TYPE-C) +- 1x Ethernet Port + - Transformerless application + - 100Mbps +- 3x I2C Bus Ports +- 1x SPI Bus + - 1x Chip Select Line + - 1x Data Ready Line + - 1x SPI Reset Line +- 5x CAN Ports for CAN Peripherals + - 3x CAN1 Bus Multiplexed Ports + - 2x CAN2 Bus Multiplexed Ports +- 2x Power Input Ports + - DroneCAN/UAVCAN Power Input +- 2x AD Ports + - Analog Input (3.3V) + - Analog Input (6.6V - not supported) +- 1x Dedicated Debug Port + - FMU Debug + +### Mechanical Data + +- Size + - Flight controller + + ![CUAV X25-SUPER](../../assets/flight_controller/cuav_x25-super/x25-super_size.png) + +## Purchase Channels {#store} + +Order from [CUAV](https://store.cuav.net/). + +## Assembly/Setup + +- Not provided. + +## Pinouts + +![CUAV X25-SUPER Pinout_01](../../assets/flight_controller/cuav_x25-super/x25-super_pinouts_01.png) +![CUAV X25-SUPER Pinout_02](../../assets/flight_controller/cuav_x25-super/x25-super_pinouts_02.png) + +## Serial Port Mapping + +| UART | Device | Port | +| ------ | ---------- | ------------- | +| USART1 | /dev/ttyS0 | GPS1 | +| USART2 | /dev/ttyS1 | GPS2 | +| USART3 | /dev/ttyS2 | Debug Console | +| UART4 | /dev/ttyS3 | UART4 | +| UART5 | /dev/ttyS4 | TELEM2 | +| USART6 | /dev/ttyS5 | RC | +| UART7 | /dev/ttyS6 | TELEM1 | + +## RC Input + +The RC input pin is directly connected to the FMU UART6 TX. + +## Voltage Ratings + +The _X25-SUPER_ achieves triple redundancy on power supplies if three power sources are provided. The three power rails are POWERC1, POWERC2, and USB. + +- **POWER C1** and **POWER C2** are DroneCAN/UAVCAN battery interfaces. + +**Normal Operation Maximum Ratings** + +Under these conditions, all power sources will be used to power the system in the following order: + +1. **POWER C1** and **POWER C2** Inputs (10V to 18V) +2. USB Input (4.75V to 5.25V) + +**Voltage monitoring** + +Digital DroneCAN/UAVCAN battery monitoring is enabled by default. + +## Building Firmware + +::: tip +Most users will not need to build this firmware from PX4 v1.18. +It is pre-built and automatically installed by _QGroundControl_ when appropriate hardware is connected. +::: + +To [build PX4](../dev_setup/building_px4.md) for this target, execute: + +``` +make cuav_x25-super_default +``` + +## Debug Port {#debug_port} + +The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port. + +| Pin | Signal | Volt | +| ------- | -------------- | ----- | +| 1 (red) | 5V+ | +5V | +| 2 (blk) | DEBUG TX (OUT) | +3.3V | +| 3 (blk) | DEBUG RX (IN) | +3.3V | +| 4 (blk) | FMU_SWDIO | +3.3V | +| 5 (blk) | FMU_SWCLK | +3.3V | +| 6 (blk) | GND | GND | + +## Supported Platforms / Airframes +Any multicopter / airplane / rover or boat that can be controlled with normal RC servos or Futaba S-Bus servos. +The complete set of supported configurations can be seen in the [Airframes Reference](../airframes/airframe_reference.md). + +## Further info + +- [CUAV Docs](https://doc.cuav.net/)