From 3f21946d5037bd588684ab7abce0ec4093a6b1fd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 24 Mar 2023 11:22:49 +1100 Subject: [PATCH 001/287] Copter: stop setting motor output levels at boot We should not have different state in our motors library based on your RC stick positions at boot. this call is made anywhere we actually arm the motors anyway. --- ArduCopter/system.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index b2b8c95e07ed4e..1a7429558a9cb9 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -206,10 +206,7 @@ void Copter::init_ardupilot() ins.set_log_raw_bit(MASK_LOG_IMU_RAW); - // enable output to motors - if (arming.rc_calibration_checks(true)) { - motors->output_min(); // output lowest possible value to motors - } + motors->output_min(); // output lowest possible value to motors // attempt to set the intial_mode, else set to STABILIZE if (!set_mode((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED)) { From d8042a13257241a863432b36a415a4d4d14a3d94 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 25 Mar 2023 14:53:09 +0000 Subject: [PATCH 002/287] AP_HAL_ChibiOS: ensure the rcout TIM_UP DMA request source is re-instated after cancellation This fixes a bug in bdshot whereby dma cancellation could result in the wrong DMA channel being used for dshot output and hence motors stopping --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 53e2b002d084a7..ab5259a1eaf17b 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -1656,9 +1656,15 @@ void RCOutput::dma_cancel(pwm_group& group) chSysLock(); dmaStreamDisable(group.dma); #ifdef HAL_WITH_BIDIR_DSHOT - if (group.ic_dma_enabled()) { + if (group.ic_dma_enabled() && !group.has_shared_ic_up_dma()) { dmaStreamDisable(group.bdshot.ic_dma[group.bdshot.curr_telem_chan]); } +#if STM32_DMA_SUPPORTS_DMAMUX + // the DMA request source has been switched by the receive path, so reinstate the correct one + if (group.dshot_state == DshotState::RECV_START && group.has_shared_ic_up_dma()) { + dmaSetRequestSource(group.dma, group.dma_up_channel); + } +#endif #endif // normally the CCR registers are reset by the final 0 in the DMA buffer // since we are cancelling early they need to be reset to avoid infinite pulses From 5ecf7ff1fe000939e7f9d340fbab167783a958dd Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 25 Mar 2023 21:16:05 +0000 Subject: [PATCH 003/287] AP_HAL_ChibiOS: ensure that DMA source is correct on DMA send for rcout --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index ab5259a1eaf17b..5d81171f53d960 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -1582,7 +1582,9 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length) up with this great method. */ TOGGLE_PIN_DEBUG(54); - +#if STM32_DMA_SUPPORTS_DMAMUX + dmaSetRequestSource(group.dma, group.dma_up_channel); +#endif dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR)); stm32_cacheBufferFlush(group.dma_buffer, buffer_length); dmaStreamSetMemory0(group.dma, group.dma_buffer); From 9d9026ce15e544412752157fee241feecbf72181 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Mar 2023 09:41:18 +0900 Subject: [PATCH 004/287] Rover: 4.3.6-beta11 release notes --- Rover/release-notes.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Rover/release-notes.txt b/Rover/release-notes.txt index c2bfdaacef7541..dece73e4c834e2 100644 --- a/Rover/release-notes.txt +++ b/Rover/release-notes.txt @@ -1,5 +1,9 @@ Rover Release Notes: ------------------------------------------------------------------ +Rover 4.3.0-beta11 25-Mar-2023 +Changes from 4.3.0-beta10 +1) Bi-directional DShot fix for possible motor stop approx 72min after startup +------------------------------------------------------------------ Rover 4.3.0-beta10 01-Mar-2023 Changes from 4.3.0-beta9 1) Bug fixes From 71d02820a78f73bcb1ac83a22bd019055b646747 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Mar 2023 09:40:26 +0900 Subject: [PATCH 005/287] Copter: 4.3.6-beta release notes --- ArduCopter/ReleaseNotes.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index 5b5ae54095018d..7af3da0b2cf114 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,5 +1,9 @@ ArduPilot Copter Release Notes: ------------------------------------------------------------------ +Copter 4.3.6-beta1 25-Mar-2023 +Changes from 4.3.5 +1) Bi-directional DShot fix for possible motor stop approx 72min after startup +------------------------------------------------------------------ Copter Copter 4.3.5 14-Mar-2023 / 4.3.5-rc1 01-Mar-2023 Changes from 4.3.4 1) Bug fixes From 3d3cd435c2bb0c524cbc150b08e47e0b35fcc965 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Mar 2023 16:43:10 +1100 Subject: [PATCH 006/287] Plane: release notes for 4.3.5 --- ArduPlane/ReleaseNotes.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index 7fcb224184bfdb..70036d3c84690e 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,5 +1,5 @@ -Release 4.3.5beta1 24th March 2023 ------------------------------------ +Release 4.3.5 26th March 2023 +------------------------------ - fixed 32 bit microsecond wrap in BDShot code From 8c7fc012d465d408040aab6727bb018875cbd23f Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sat, 25 Mar 2023 10:44:51 +1100 Subject: [PATCH 007/287] AP_HAL: fix CANFrame initialization in constructor --- libraries/AP_HAL/CANIface.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL/CANIface.cpp b/libraries/AP_HAL/CANIface.cpp index e5a712390d1eb9..9f31fc6fd7e848 100644 --- a/libraries/AP_HAL/CANIface.cpp +++ b/libraries/AP_HAL/CANIface.cpp @@ -98,14 +98,15 @@ AP_HAL::CANFrame::CANFrame(uint32_t can_id, const uint8_t* can_data, uint8_t dat id(can_id), canfd(canfd_frame) { - if ((can_data == nullptr) || (data_len == 0) || (data_len > MaxDataLen)) { + const uint8_t data_len_max = canfd_frame ? MaxDataLen : NonFDCANMaxDataLen; + if ((can_data == nullptr) || (data_len == 0) || (data_len > data_len_max)) { + dlc = 0; + memset(data, 0, MaxDataLen); return; } memcpy(this->data, can_data, data_len); - if (data_len <= 8) { + if (data_len <= NonFDCANMaxDataLen) { dlc = data_len; - } else if (!canfd) { - dlc = 8; } else { /* Data Length Code 9 10 11 12 13 14 15 From 8c1e2546d8cefee50b5d534af1f4bcc906632962 Mon Sep 17 00:00:00 2001 From: murata Date: Sun, 16 May 2021 14:21:47 +0900 Subject: [PATCH 008/287] Copter: Add an element of NAV_CONTROLLER_OUTPUT to ZIGZAG mode --- ArduCopter/mode.h | 3 +++ ArduCopter/mode_zigzag.cpp | 25 +++++++++++++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 52ed6379802d8e..812b9eb332b253 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -1794,6 +1794,9 @@ class ModeZigZag : public Mode { const char *name() const override { return "ZIGZAG"; } const char *name4() const override { return "ZIGZ"; } + uint32_t wp_distance() const override; + int32_t wp_bearing() const override; + float crosstrack_error() const override; private: diff --git a/ArduCopter/mode_zigzag.cpp b/ArduCopter/mode_zigzag.cpp index ff186ff65ee777..1bb82aaadba4a5 100644 --- a/ArduCopter/mode_zigzag.cpp +++ b/ArduCopter/mode_zigzag.cpp @@ -583,4 +583,29 @@ void ModeZigZag::spray(bool b) #endif } +uint32_t ModeZigZag::wp_distance() const +{ + if (is_auto) { + return wp_nav->get_wp_distance_to_destination(); + } else { + return 0; + } +} +int32_t ModeZigZag::wp_bearing() const +{ + if (is_auto) { + return wp_nav->get_wp_bearing_to_destination(); + } else { + return 0; + } +} +float ModeZigZag::crosstrack_error() const +{ + if (is_auto) { + return wp_nav->crosstrack_error(); + } else { + return 0; + } +} + #endif // MODE_ZIGZAG_ENABLED == ENABLED From 7f66e35459a8544f985d8f41fb60b20c6933feee Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Mar 2023 07:33:42 +1100 Subject: [PATCH 009/287] AP_Periph: release notes for 1.5.0 --- Tools/AP_Periph/ReleaseNotes.txt | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/Tools/AP_Periph/ReleaseNotes.txt b/Tools/AP_Periph/ReleaseNotes.txt index d265eff2d41ca4..76666579839791 100644 --- a/Tools/AP_Periph/ReleaseNotes.txt +++ b/Tools/AP_Periph/ReleaseNotes.txt @@ -1,3 +1,16 @@ +Release 1.5.0 27th Mar 2023 +--------------------------- + +This is a major release with the following changes: + +- fixed airspeed bus default +- limit mag to 25Hz by default +- fixed send rate of GPS yaw +- fixed HW ESC telem temp units +- allow set of port for HW telem +- send GNSS heading message if available +- stop sending old GNSS Fix message + Release 1.4.1 27th Sep 2022 --------------------------- From e6d6848fb19e32692228be9cee10c97c9f992f24 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Mar 2023 07:36:19 +1100 Subject: [PATCH 010/287] AP_Periph: prepare for 1.5.0 release --- Tools/AP_Periph/version.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Tools/AP_Periph/version.h b/Tools/AP_Periph/version.h index 84aad587c28b2a..2cd4fb5bf0ab7d 100644 --- a/Tools/AP_Periph/version.h +++ b/Tools/AP_Periph/version.h @@ -2,15 +2,16 @@ #include -#define THISFIRMWARE "AP_Periph V1.5.0-dev" +#define THISFIRMWARE "AP_Periph V1.5.0" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 1,5,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 1,5,0,FIRMWARE_VERSION_TYPE_OFFICIAL #define FW_MAJOR 1 #define FW_MINOR 5 #define FW_PATCH 0 -#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV +#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL + From 1bc9c490a132fef2df2ce7d97decbd6e1b75b0c8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 26 Mar 2023 15:43:00 +1100 Subject: [PATCH 011/287] Tools: remove remove redundant install-apt-ci.sh this isn't referenced anywhere and is causing unnecessary maintenance overhead. Presumably overtaken by github docker install images and the devenv install scripts --- Tools/scripts/install-apt-ci.sh | 25 ------------------------- 1 file changed, 25 deletions(-) delete mode 100755 Tools/scripts/install-apt-ci.sh diff --git a/Tools/scripts/install-apt-ci.sh b/Tools/scripts/install-apt-ci.sh deleted file mode 100755 index 82a0d98bfc019f..00000000000000 --- a/Tools/scripts/install-apt-ci.sh +++ /dev/null @@ -1,25 +0,0 @@ -#!/bin/bash -# Install APT packages for CI build testing - -set -ex - -PKGS=" \ - build-essential \ - gawk \ - libc6-i386 \ - libxml2-dev \ - libxslt1-dev \ - python-pip \ - python-dev \ - zlib1g-dev \ - " - -read -r UBUNTU_CODENAME <<<$(lsb_release -c -s) - -sudo add-apt-repository ppa:ubuntu-toolchain-r/test -y - -#wget -q -O - http://llvm.org/apt/llvm-snapshot.gpg.key | sudo apt-key add - -#sudo add-apt-repository "deb http://llvm.org/apt/${UBUNTU_CODENAME}/ llvm-toolchain-${UBUNTU_CODENAME}-3.7 main" -y -sudo apt-get -qq -y --force-yes update -sudo apt-get -qq -y --force-yes remove clang llvm -sudo apt-get -y --force-yes install $PKGS From a91178d0e1dd297165e66d1c6361560afbee83ae Mon Sep 17 00:00:00 2001 From: tzarjakob Date: Wed, 22 Mar 2023 09:45:41 +0100 Subject: [PATCH 012/287] AC_PrecLand: configuration of Precision Landing for custom build server --- libraries/AC_PrecLand/AC_PrecLand.cpp | 9 ++++++- libraries/AC_PrecLand/AC_PrecLand.h | 8 +++++- libraries/AC_PrecLand/AC_PrecLand_Backend.h | 9 ++++++- .../AC_PrecLand/AC_PrecLand_Companion.cpp | 8 +++++- libraries/AC_PrecLand/AC_PrecLand_Companion.h | 9 ++++++- libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 8 +++++- libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 9 ++++++- libraries/AC_PrecLand/AC_PrecLand_SITL.cpp | 4 +-- libraries/AC_PrecLand/AC_PrecLand_SITL.h | 9 ++++--- .../AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp | 4 +-- .../AC_PrecLand/AC_PrecLand_SITL_Gazebo.h | 9 ++++--- .../AC_PrecLand/AC_PrecLand_StateMachine.cpp | 8 +++++- .../AC_PrecLand/AC_PrecLand_StateMachine.h | 7 +++++ libraries/AC_PrecLand/AC_PrecLand_config.h | 27 +++++++++++++++++++ 14 files changed, 110 insertions(+), 18 deletions(-) create mode 100644 libraries/AC_PrecLand/AC_PrecLand_config.h diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index cf23c855496d8f..b2e2212239cdae 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -1,7 +1,12 @@ +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + +#include "AC_PrecLand.h" #include #include #include -#include "AC_PrecLand.h" + #include "AC_PrecLand_Backend.h" #include "AC_PrecLand_Companion.h" #include "AC_PrecLand_IRLock.h" @@ -774,3 +779,5 @@ AC_PrecLand *ac_precland() } } + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 2f804f59c933d9..397739c9f7a661 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -1,7 +1,11 @@ #pragma once -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + #include +#include #include #include "PosVelEKF.h" #include @@ -231,3 +235,5 @@ class AC_PrecLand namespace AP { AC_PrecLand *ac_precland(); }; + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_Backend.h b/libraries/AC_PrecLand/AC_PrecLand_Backend.h index d816a85d8ddbb7..41facd0deb4a01 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Backend.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Backend.h @@ -1,8 +1,13 @@ #pragma once +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + +#include "AC_PrecLand.h" #include #include -#include "AC_PrecLand.h" + class AC_PrecLand_Backend { @@ -44,3 +49,5 @@ class AC_PrecLand_Backend const AC_PrecLand& _frontend; // reference to precision landing front end AC_PrecLand::precland_state &_state; // reference to this instances state }; + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index e65ff1d6861d3a..51d46feb777fec 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -1,6 +1,10 @@ +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_COMPANION_ENABLED + +#include "AC_PrecLand_Companion.h" #include #include -#include "AC_PrecLand_Companion.h" // perform any required initialisation of backend void AC_PrecLand_Companion::init() @@ -73,3 +77,5 @@ void AC_PrecLand_Companion::handle_msg(const mavlink_landing_target_t &packet, u _los_meas_time_ms = timestamp_ms; _have_los_meas = true; } + +#endif // AC_PRECLAND_COMPANION_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index 67af707a9bd0b3..892a5aa1f8265b 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -1,7 +1,11 @@ #pragma once -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_COMPANION_ENABLED + #include "AC_PrecLand_Backend.h" +#include /* * AC_PrecLand_Companion - implements precision landing using target vectors provided @@ -46,3 +50,6 @@ class AC_PrecLand_Companion : public AC_PrecLand_Backend uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured bool _wrong_frame_msg_sent; }; + + +#endif // AC_PRECLAND_COMPANION_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index 04b1126621300c..e58bb52e829655 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -1,5 +1,9 @@ -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_IRLOCK_ENABLED + #include "AC_PrecLand_IRLock.h" +#include // Constructor AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) @@ -50,3 +54,5 @@ uint32_t AC_PrecLand_IRLock::los_meas_time_ms() { bool AC_PrecLand_IRLock::have_los_meas() { return _have_los_meas; } + +#endif // AC_PRECLAND_IRLOCK_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index da2923b1265a7e..08831bc3625951 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -1,7 +1,12 @@ #pragma once -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_IRLOCK_ENABLED + #include +#include + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include #else @@ -46,3 +51,5 @@ class AC_PrecLand_IRLock : public AC_PrecLand_Backend bool _have_los_meas; // true if there is a valid measurement from the camera uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured }; + +#endif // AC_PRECLAND_IRLOCK_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp index b71a4d1c26b2d9..1d920818fb789f 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp @@ -1,7 +1,7 @@ #include #include "AC_PrecLand_SITL.h" -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AC_PRECLAND_SITL_ENABLED #include "AP_AHRS/AP_AHRS.h" // init - perform initialisation of this backend @@ -54,4 +54,4 @@ bool AC_PrecLand_SITL::get_los_body(Vector3f& ret) { return true; } -#endif +#endif // AC_PRECLAND_SITL_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.h b/libraries/AC_PrecLand/AC_PrecLand_SITL.h index ee6fd526edf55f..53b0c23aa69745 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.h @@ -1,8 +1,11 @@ #pragma once -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_SITL_ENABLED + #include +#include #include /* @@ -43,4 +46,4 @@ class AC_PrecLand_SITL : public AC_PrecLand_Backend float _distance_to_target; // distance to target in meters }; -#endif +#endif // AC_PRECLAND_SITL_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp index 2bf94759dc8a39..95d331d75ba78d 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.cpp @@ -3,7 +3,7 @@ extern const AP_HAL::HAL& hal; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AC_PRECLAND_SITL_GAZEBO_ENABLED // Constructor AC_PrecLand_SITL_Gazebo::AC_PrecLand_SITL_Gazebo(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) @@ -55,4 +55,4 @@ bool AC_PrecLand_SITL_Gazebo::have_los_meas() { return _have_los_meas; } -#endif +#endif // AC_PRECLAND_SITL_GAZEBO_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h index e7f1ab06ed1cae..dcddec958ebb2b 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h @@ -1,8 +1,11 @@ #pragma once -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL -#include +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_SITL_GAZEBO_ENABLED + #include +#include #include /* @@ -41,4 +44,4 @@ class AC_PrecLand_SITL_Gazebo : public AC_PrecLand_Backend uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured }; -#endif +#endif // AC_PRECLAND_SITL_GAZEBO_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp index e2d36156513231..c456288ca2d368 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp @@ -1,5 +1,9 @@ -#include "AC_PrecLand_StateMachine.h" +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + #include +#include "AC_PrecLand_StateMachine.h" #include #include @@ -274,3 +278,5 @@ AC_PrecLand_StateMachine::FailSafeAction AC_PrecLand_StateMachine::get_failsafe_ // should never reach here return FailSafeAction::DESCEND; } + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h index b72b0e8d72e268..8479be3c6abf7e 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h @@ -1,5 +1,10 @@ #pragma once +#include "AC_PrecLand_config.h" + +#if AC_PRECLAND_ENABLED + +#include #include // This class constantly monitors what the status of the landing target is @@ -101,3 +106,5 @@ class AC_PrecLand_StateMachine { uint32_t failsafe_start_ms; // timestamp of when failsafe was triggered }; + +#endif // AC_PRECLAND_ENABLED diff --git a/libraries/AC_PrecLand/AC_PrecLand_config.h b/libraries/AC_PrecLand/AC_PrecLand_config.h new file mode 100644 index 00000000000000..74a5043955d0b5 --- /dev/null +++ b/libraries/AC_PrecLand/AC_PrecLand_config.h @@ -0,0 +1,27 @@ +#pragma once + +#include + +#ifndef AC_PRECLAND_ENABLED +#define AC_PRECLAND_ENABLED 1 +#endif + +#ifndef AC_PRECLAND_BACKEND_DEFAULT_ENABLED +#define AC_PRECLAND_BACKEND_DEFAULT_ENABLED AC_PRECLAND_ENABLED +#endif + +#ifndef AC_PRECLAND_COMPANION_ENABLED +#define AC_PRECLAND_COMPANION_ENABLED AC_PRECLAND_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AC_PRECLAND_IRLOCK_ENABLED +#define AC_PRECLAND_IRLOCK_ENABLED AC_PRECLAND_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AC_PRECLAND_SITL_ENABLED +#define AC_PRECLAND_SITL_ENABLED (AC_PRECLAND_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#ifndef AC_PRECLAND_SITL_GAZEBO_ENABLED +#define AC_PRECLAND_SITL_GAZEBO_ENABLED (AC_PRECLAND_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif From bd50e3eacf242030d49cd137eb4a1f472aeb5cc5 Mon Sep 17 00:00:00 2001 From: tzarjakob Date: Wed, 22 Mar 2023 09:45:41 +0100 Subject: [PATCH 013/287] AP_HAL_ChibiOS: configuration of Precision Landing for custom build server --- libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/include/save_some_flash.inc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat index 81c2f5e50449e0..07270c07b55613 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat @@ -161,7 +161,7 @@ define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 define HAL_GENERATOR_ENABLED 0 define AC_OAPATHPLANNER_ENABLED 0 -define PRECISION_LANDING 0 +define AC_PRECLAND_ENABLED 0 define HAL_BARO_WIND_COMP_ENABLED 0 define AP_GRIPPER_ENABLED 0 define HAL_HOTT_TELEM_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/save_some_flash.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/save_some_flash.inc index 428ea63143b1f3..73a10ff1ea26c7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/save_some_flash.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/save_some_flash.inc @@ -1,7 +1,7 @@ # save some flash define HAL_GENERATOR_ENABLED 0 define AC_OAPATHPLANNER_ENABLED 0 -define PRECISION_LANDING 0 +define AC_PRECLAND_ENABLED 0 define AP_OPTICALFLOW_ENABLED 0 define AP_ICENGINE_ENABLED 0 define HAL_BARO_WIND_COMP_ENABLED 0 From 97b7e8d1d09e3c8d837ac768cee4dd4631c6ae54 Mon Sep 17 00:00:00 2001 From: tzarjakob Date: Wed, 22 Mar 2023 09:45:41 +0100 Subject: [PATCH 014/287] ArduCopter: configuration of Precision Landing for custom build server --- ArduCopter/APM_Config.h | 1 - ArduCopter/Copter.cpp | 2 +- ArduCopter/Copter.h | 5 +++-- ArduCopter/GCS_Copter.cpp | 2 +- ArduCopter/GCS_Mavlink.cpp | 2 +- ArduCopter/Parameters.cpp | 2 +- ArduCopter/RC_Channel.cpp | 2 +- ArduCopter/config.h | 6 ------ ArduCopter/mode.cpp | 10 +++++----- ArduCopter/mode.h | 8 ++++---- ArduCopter/mode_auto.cpp | 2 +- ArduCopter/mode_land.cpp | 2 +- ArduCopter/mode_loiter.cpp | 6 +++--- ArduCopter/mode_rtl.cpp | 2 +- ArduCopter/precision_landing.cpp | 2 +- ArduCopter/system.cpp | 2 +- 16 files changed, 25 insertions(+), 31 deletions(-) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index db60b9cfc754ed..d9c8f7afdcdca7 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -9,7 +9,6 @@ //#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles //#define PARACHUTE DISABLED // disable parachute release to save 1k of flash //#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands -//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor //#define BEACON_ENABLED DISABLED // disable beacon support //#define STATS_ENABLED DISABLED // disable statistics support //#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 293d1d38f5f094..bb80d616ad5e51 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -180,7 +180,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(three_hz_loop, 3, 75, 57), SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60), SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63), -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED SCHED_TASK(update_precland, 400, 50, 69), #endif #if FRAME_CONFIG == HELI_FRAME diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index be136776ede474..425e419cfc1cf8 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -69,6 +69,7 @@ #include // Crop sprayer library #include // ADS-B RF based collision avoidance module library #include // ArduPilot proximity sensor library +#include #include #include @@ -115,7 +116,7 @@ #if AP_GRIPPER_ENABLED # include #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED # include # include #endif @@ -529,7 +530,7 @@ class Copter : public AP_Vehicle { #endif // Precision Landing -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED AC_PrecLand precland; AC_PrecLand_StateMachine precland_statemachine; #endif diff --git a/ArduCopter/GCS_Copter.cpp b/ArduCopter/GCS_Copter.cpp index 7721e5e74665d9..02599b045d798f 100644 --- a/ArduCopter/GCS_Copter.cpp +++ b/ArduCopter/GCS_Copter.cpp @@ -114,7 +114,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) } #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED if (copter.precland.enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 28aebf0511093f..9250a7928404f2 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -640,7 +640,7 @@ void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg) */ void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED copter.precland.handle_msg(packet, timestamp_ms); #endif } diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 4e699f3655e23f..1092475d55be45 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -664,7 +664,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(optflow, "FLOW", AP_OpticalFlow), #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // @Group: PLND_ // @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp GOBJECT(precland, "PLND_", AC_PrecLand), diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index afcd65754cad28..03d398c67a3c42 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -391,7 +391,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi break; case AUX_FUNC::PRECISION_LOITER: -#if PRECISION_LANDING == ENABLED && MODE_LOITER_ENABLED == ENABLED +#if AC_PRECLAND_ENABLED && MODE_LOITER_ENABLED == ENABLED switch (ch_flag) { case AuxSwitchPos::HIGH: copter.mode_loiter.set_precision_loiter_enabled(true); diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 5a4704b14915d1..9900d7e39b5361 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -138,12 +138,6 @@ # define AUTOTUNE_ENABLED ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// Precision Landing with companion computer or IRLock sensor -#ifndef PRECISION_LANDING - # define PRECISION_LANDING ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // Parachute release #ifndef PARACHUTE diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 61b1cbb7561b11..516de29c84ce51 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -594,7 +594,7 @@ void Mode::land_run_vertical_control(bool pause_descent) // Constrain the demanded vertical velocity so that it is between the configured maximum descent speed and the configured minimum descent speed. cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(g.land_speed)); -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED const bool navigating = pos_control->is_active_xy(); bool doing_precision_landing = !copter.ap.land_repo_active && copter.precland.target_acquired() && navigating; @@ -668,7 +668,7 @@ void Mode::land_run_horizontal_control() AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE); } copter.ap.land_repo_active = true; -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED } else { // no override right now, check if we should allow precland if (copter.precland.allow_precland_after_reposition()) { @@ -681,7 +681,7 @@ void Mode::land_run_horizontal_control() // this variable will be updated if prec land target is in sight and pilot isn't trying to reposition the vehicle copter.ap.prec_land_active = false; -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED copter.ap.prec_land_active = !copter.ap.land_repo_active && copter.precland.target_acquired(); // run precision landing if (copter.ap.prec_land_active) { @@ -738,7 +738,7 @@ void Mode::land_run_horizontal_control() // pause_descent is true if vehicle should not descend void Mode::land_run_normal_or_precland(bool pause_descent) { -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED if (pause_descent || !copter.precland.enabled()) { // we don't want to start descending immediately or prec land is disabled // in both cases just run simple land controllers @@ -753,7 +753,7 @@ void Mode::land_run_normal_or_precland(bool pause_descent) #endif } -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // Go towards a position commanded by prec land state machine in order to retry landing // The passed in location is expected to be NED and in m void Mode::precland_retry_position(const Vector3f &retry_pos) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 812b9eb332b253..dc417f51c6c837 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -147,7 +147,7 @@ class Mode { // pause_descent is true if vehicle should not descend void land_run_normal_or_precland(bool pause_descent = false); -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // Go towards a position commanded by prec land state machine in order to retry landing // The passed in location is expected to be NED and in meters void precland_retry_position(const Vector3f &retry_pos); @@ -1181,7 +1181,7 @@ class ModeLoiter : public Mode { bool has_user_takeoff(bool must_navigate) const override { return true; } bool allows_autotune() const override { return true; } -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED void set_precision_loiter_enabled(bool value) { _precision_loiter_enabled = value; } #endif @@ -1194,14 +1194,14 @@ class ModeLoiter : public Mode { int32_t wp_bearing() const override; float crosstrack_error() const override { return pos_control->crosstrack_error();} -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED bool do_precision_loiter(); void precision_loiter_xy(); #endif private: -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED bool _precision_loiter_enabled; bool _precision_loiter_active; // true if user has switched on prec loiter #endif diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index b6be6d5cefb169..77be3560749f48 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -53,7 +53,7 @@ bool ModeAuto::init(bool ignore_checks) // reset flag indicating if pilot has applied roll or pitch inputs during landing copter.ap.land_repo_active = false; -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precland state machine copter.precland_statemachine.init(); #endif diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 4072e76c8b3a10..377bef5ee9253b 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -46,7 +46,7 @@ bool ModeLand::init(bool ignore_checks) copter.fence.auto_disable_fence_for_landing(); #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precland state machine copter.precland_statemachine.init(); #endif diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index 0198db443e5b4d..602aa52859a151 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -34,14 +34,14 @@ bool ModeLoiter::init(bool ignore_checks) pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); pos_control->set_correction_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED _precision_loiter_active = false; #endif return true; } -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED bool ModeLoiter::do_precision_loiter() { if (!_precision_loiter_enabled) { @@ -165,7 +165,7 @@ void ModeLoiter::run() // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED bool precision_loiter_old_state = _precision_loiter_active; if (do_precision_loiter()) { precision_loiter_xy(); diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index fc08b39b19e6c3..e6ae505e8214a6 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -28,7 +28,7 @@ bool ModeRTL::init(bool ignore_checks) // this will be set true if prec land is later active copter.ap.prec_land_active = false; -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precland state machine copter.precland_statemachine.init(); #endif diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index 076177667806bd..ad98c2fa75552d 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -4,7 +4,7 @@ #include "Copter.h" -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED void Copter::init_precland() { diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 1a7429558a9cb9..499c552a5882ca 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -132,7 +132,7 @@ void Copter::init_ardupilot() camera.init(); #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precision landing init_precland(); #endif From dc037b9825da55df40581a2b6fb86c2eecabfec6 Mon Sep 17 00:00:00 2001 From: tzarjakob Date: Wed, 22 Mar 2023 09:45:41 +0100 Subject: [PATCH 015/287] Blimp: configuration of Precision Landing for custom build server --- Blimp/config.h | 6 ------ 1 file changed, 6 deletions(-) diff --git a/Blimp/config.h b/Blimp/config.h index 0516a157c12d0c..10cac9ea72bf7b 100644 --- a/Blimp/config.h +++ b/Blimp/config.h @@ -137,12 +137,6 @@ # define AUTOTUNE_ENABLED ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// Precision Landing with companion computer or IRLock sensor -#ifndef PRECISION_LANDING -# define PRECISION_LANDING ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // Parachute release #ifndef PARACHUTE From caee9f271a6cd7db4cef2da0559bcde534275331 Mon Sep 17 00:00:00 2001 From: tzarjakob Date: Wed, 22 Mar 2023 09:45:41 +0100 Subject: [PATCH 016/287] Rover: configuration of Precision Landing for custom build server --- Rover/GCS_Mavlink.cpp | 2 +- Rover/Parameters.cpp | 2 +- Rover/Rover.cpp | 2 +- Rover/Rover.h | 7 ++++--- Rover/config.h | 8 +------- Rover/precision_landing.cpp | 2 +- Rover/system.cpp | 2 +- 7 files changed, 10 insertions(+), 15 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index acfa8699b98365..92d17426514e46 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -1063,7 +1063,7 @@ void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg) */ void GCS_MAVLINK_Rover::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) { -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED rover.precland.handle_msg(packet, timestamp_ms); #endif } diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 1de13e3f6bf3bc..89738d9caedd36 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -297,7 +297,7 @@ const AP_Param::Info Rover::var_info[] = { GOBJECT(camera, "CAM", AP_Camera), #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // @Group: PLND_ // @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp GOBJECT(precland, "PLND_", AC_PrecLand), diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index bb6f56120a65af..f264315234b883 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -98,7 +98,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { #if AP_GRIPPER_ENABLED SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69), #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED SCHED_TASK(update_precland, 400, 50, 70), #endif #if AP_RPM_ENABLED diff --git a/Rover/Rover.h b/Rover/Rover.h index b06a25703329c7..f11bae3d600f9d 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -42,6 +42,7 @@ #include #include #include +#include // Configuration #include "defines.h" @@ -61,10 +62,10 @@ #include "GCS_Mavlink.h" #include "GCS_Rover.h" #include "AP_Rally.h" -#include "RC_Channel.h" // RC Channel Library -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED #include #endif +#include "RC_Channel.h" // RC Channel Library #include "mode.h" @@ -145,7 +146,7 @@ class Rover : public AP_Vehicle { #if OSD_ENABLED || OSD_PARAM_ENABLED AP_OSD osd; #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED AC_PrecLand precland; #endif // GCS handling diff --git a/Rover/config.h b/Rover/config.h index 6983f9d122eed5..77b2981c5fbcc5 100644 --- a/Rover/config.h +++ b/Rover/config.h @@ -38,12 +38,6 @@ #define AP_RALLY ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// Precision Landing with companion computer or IRLock sensor -#ifndef PRECISION_LANDING - # define PRECISION_LANDING ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // NAVL1 // @@ -70,7 +64,7 @@ ////////////////////////////////////////////////////////////////////////////// // Dock mode - allows vehicle to dock to a docking target #ifndef MODE_DOCK_ENABLED -# define MODE_DOCK_ENABLED PRECISION_LANDING +# define MODE_DOCK_ENABLED AC_PRECLAND_ENABLED #endif diff --git a/Rover/precision_landing.cpp b/Rover/precision_landing.cpp index 12b33174ebbe5f..c62b499b6a3eca 100644 --- a/Rover/precision_landing.cpp +++ b/Rover/precision_landing.cpp @@ -4,7 +4,7 @@ #include "Rover.h" -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED void Rover::init_precland() { diff --git a/Rover/system.cpp b/Rover/system.cpp index c7a17b10d5ac99..78e4107254ded5 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -117,7 +117,7 @@ void Rover::init_ardupilot() camera.init(); #endif -#if PRECISION_LANDING == ENABLED +#if AC_PRECLAND_ENABLED // initialise precision landing init_precland(); #endif From 6fa14ffe87a4c6dc2d22328db2bd7f998139c497 Mon Sep 17 00:00:00 2001 From: tzarjakob Date: Wed, 22 Mar 2023 09:45:41 +0100 Subject: [PATCH 017/287] Tools: configuration of Precision Landing for custom build server --- Tools/autotest/common.py | 2 +- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 2 ++ 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 692fc408c27a16..e3158d623b7e16 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -2780,7 +2780,7 @@ def all_log_format_ids(self): continue if "#if FRAME_CONFIG == HELI_FRAME" in line: continue - if "#if PRECISION_LANDING == ENABLED" in line: + if "#if AC_PRECLAND_ENABLED" in line: continue if "#end" in line: continue diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index d5fca1208e6cc0..5e097ea0e9a019 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -284,6 +284,7 @@ def __init__(self, Feature('Actuators', 'RobotisServo', 'AP_ROBOTISSERVO_ENABLED', 'Enable RobotisServo Protocol', 0, None), Feature('Actuators', 'FETTecOneWire', 'AP_FETTEC_ONEWIRE_ENABLED', 'Enable FETTec OneWire ESCs', 0, None), + Feature('Precision Landing', 'PrecLand', 'AC_PRECLAND_ENABLED', 'Enable Precision Landing support', 0, None), ] BUILD_OPTIONS.sort(key=lambda x: (x.category + x.label)) diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index cb261eb1597f4e..394874ad2a5e26 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -39,6 +39,8 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_AIRSPEED_ENABLED', 'AP_Airspeed::AP_Airspeed',), ('AP_AIRSPEED_{type}_ENABLED', r'AP_Airspeed_(?P.*)::init',), + ('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',), + ('HAL_ADSB_ENABLED', 'AP_ADSB::AP_ADSB',), ('HAL_ADSB_{type}_ENABLED', r'AP_ADSB_(?P.*)::update',), ('HAL_ADSB_UCP_ENABLED', 'AP_ADSB_uAvionix_UCP::update',), From 81a73e9477dc34bf151c6579db4cff00033017d8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 26 Mar 2023 15:35:52 +1100 Subject: [PATCH 018/287] Tools: remove dead Tools/scripts/magfit_flashlog.py script place has been taken by things like magfit.py --- Tools/scripts/magfit_flashlog.py | 149 ------------------------------- 1 file changed, 149 deletions(-) delete mode 100755 Tools/scripts/magfit_flashlog.py diff --git a/Tools/scripts/magfit_flashlog.py b/Tools/scripts/magfit_flashlog.py deleted file mode 100755 index 3ec6aaf33b41d7..00000000000000 --- a/Tools/scripts/magfit_flashlog.py +++ /dev/null @@ -1,149 +0,0 @@ -#!/usr/bin/env python - -''' fit best estimate of magnetometer offsets from ArduCopter flashlog -using the algorithm from Bill Premerlani -''' - -import sys - -# command line option handling -from optparse import OptionParser -parser = OptionParser("magfit_flashlog.py [options]") -parser.add_option("--verbose", action='store_true', default=False, help="verbose offset output") -parser.add_option("--gain", type='float', default=0.01, help="algorithm gain") -parser.add_option("--noise", type='float', default=0, help="noise to add") -parser.add_option("--max-change", type='float', default=10, help="max step change") -parser.add_option("--min-diff", type='float', default=50, help="min mag vector delta") -parser.add_option("--history", type='int', default=20, help="how many points to keep") -parser.add_option("--repeat", type='int', default=1, help="number of repeats through the data") - -(opts, args) = parser.parse_args() - -from pymavlink.rotmat import Vector3 - -if len(args) < 1: - print("Usage: magfit_flashlog.py [options] ") - sys.exit(1) - -def noise(): - '''a noise vector''' - from random import gauss - v = Vector3(gauss(0, 1), gauss(0, 1), gauss(0, 1)) - v.normalize() - return v * opts.noise - -def find_offsets(data, ofs): - '''find mag offsets by applying Bills "offsets revisited" algorithm - on the data - - This is an implementation of the algorithm from: - http://gentlenav.googlecode.com/files/MagnetometerOffsetNullingRevisited.pdf - ''' - - # a limit on the maximum change in each step - max_change = opts.max_change - - # the gain factor for the algorithm - gain = opts.gain - - data2 = [] - for d in data: - d = d.copy() + noise() - d.x = float(int(d.x + 0.5)) - d.y = float(int(d.y + 0.5)) - d.z = float(int(d.z + 0.5)) - data2.append(d) - data = data2 - - history_idx = 0 - mag_history = data[0:opts.history] - - for i in range(opts.history, len(data)): - B1 = mag_history[history_idx] + ofs - B2 = data[i] + ofs - - diff = B2 - B1 - diff_length = diff.length() - if diff_length <= opts.min_diff: - # the mag vector hasn't changed enough - we don't get any - # information from this - history_idx = (history_idx+1) % opts.history - continue - - mag_history[history_idx] = data[i] - history_idx = (history_idx+1) % opts.history - - # equation 6 of Bills paper - delta = diff * (gain * (B2.length() - B1.length()) / diff_length) - - # limit the change from any one reading. This is to prevent - # single crazy readings from throwing off the offsets for a long - # time - delta_length = delta.length() - if max_change != 0 and delta_length > max_change: - delta *= max_change / delta_length - - # set the new offsets - ofs = ofs - delta - - if opts.verbose: - print(ofs) - return ofs - - -def plot_corrected_field(filename, data, offsets): - f = open(filename, mode='w') - for d in data: - corrected = d + offsets - f.write("%.1f\n" % corrected.length()) - f.close() - -def magfit(logfile): - '''find best magnetometer offset fit to a log file''' - - print("Processing log %s" % filename) - - # open the log file - flog = open(filename, mode='r') - - data = [] - data_no_motors = [] - mag = None - offsets = None - - # now gather all the data - for line in flog: - if not line.startswith('COMPASS,'): - continue - line = line.rstrip() - line = line.replace(' ', '') - a = line.split(',') - ofs = Vector3(float(a[4]), float(a[5]), float(a[6])) - if offsets is None: - initial_offsets = ofs - offsets = ofs - motor_ofs = Vector3(float(a[7]), float(a[8]), float(a[9])) - mag = Vector3(float(a[1]), float(a[2]), float(a[3])) - mag = mag - offsets - data.append(mag) - data_no_motors.append(mag - motor_ofs) - - print("Extracted %u data points" % len(data)) - print("Current offsets: %s" % initial_offsets) - - # run the fitting algorithm - ofs = initial_offsets - for r in range(opts.repeat): - ofs = find_offsets(data, ofs) - plot_corrected_field('plot.dat', data, ofs) - plot_corrected_field('initial.dat', data, initial_offsets) - plot_corrected_field('zero.dat', data, Vector3(0,0,0)) - plot_corrected_field('hand.dat', data, Vector3(-25,-8,-2)) - plot_corrected_field('zero-no-motors.dat', data_no_motors, Vector3(0,0,0)) - print('Loop %u offsets %s' % (r, ofs)) - sys.stdout.flush() - print("New offsets: %s" % ofs) - -total = 0.0 -for filename in args: - magfit(filename) From 51757a192e2254eb981ddc7de37cf421fe6742d0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 13 Feb 2023 17:28:55 +1100 Subject: [PATCH 019/287] AP_Mount: clarify attitude returned in get_attitude_quaternion method call --- libraries/AP_Mount/AP_Mount_Backend.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index f433d7aa187e6b..72acbdab802b36 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -49,7 +49,9 @@ class AP_Mount_Backend // returns true if this mount can control its pan (required for multicopters) virtual bool has_pan_control() const = 0; - // get attitude as a quaternion. returns true on success + // get attitude as a quaternion. returns true on success. + // att_quat will be an earth-frame quaternion rotated such that + // yaw is in body-frame. virtual bool get_attitude_quaternion(Quaternion& att_quat) = 0; // get mount's mode From f3eb86bfa9ba62b4bf2e33670295743407bf6d93 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 27 Mar 2023 08:54:41 +0900 Subject: [PATCH 020/287] Rover: 4.3.0-beta12 release notes --- Rover/release-notes.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Rover/release-notes.txt b/Rover/release-notes.txt index dece73e4c834e2..4a80f680be59b6 100644 --- a/Rover/release-notes.txt +++ b/Rover/release-notes.txt @@ -1,6 +1,6 @@ Rover Release Notes: ------------------------------------------------------------------ -Rover 4.3.0-beta11 25-Mar-2023 +Rover 4.3.0-beta11/beta12 27-Mar-2023 Changes from 4.3.0-beta10 1) Bi-directional DShot fix for possible motor stop approx 72min after startup ------------------------------------------------------------------ From e57a9cacb68b1e7d4ec8f3631a893d5300c88cef Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 27 Mar 2023 08:55:29 +0900 Subject: [PATCH 021/287] Copter: 4.3.6-beta2 release notes --- ArduCopter/ReleaseNotes.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index 7af3da0b2cf114..e6d1ae320a74a2 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,6 +1,6 @@ ArduPilot Copter Release Notes: ------------------------------------------------------------------ -Copter 4.3.6-beta1 25-Mar-2023 +Copter 4.3.6-beta1/beta2 27-Mar-2023 Changes from 4.3.5 1) Bi-directional DShot fix for possible motor stop approx 72min after startup ------------------------------------------------------------------ From 67f19c6ddbffc5542fab7c4c1683bd2a40ce4364 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 23 Mar 2023 19:01:47 -0500 Subject: [PATCH 022/287] AP_Mission: allow clearing mission in AUTO when disarmed --- libraries/AP_Mission/AP_Mission.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 82fa893fd75d80..143f485fd052b6 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -267,8 +267,8 @@ void AP_Mission::reset() /// returns true if mission was running so it could not be cleared bool AP_Mission::clear() { - // do not allow clearing the mission while it is running - if (_flags.state == MISSION_RUNNING) { + // do not allow clearing the mission while it is running unless disarmed + if (hal.util->get_soft_armed() && _flags.state == MISSION_RUNNING) { return false; } @@ -280,7 +280,7 @@ bool AP_Mission::clear() _do_cmd.index = AP_MISSION_CMD_INDEX_NONE; _flags.nav_cmd_loaded = false; _flags.do_cmd_loaded = false; - + _flags.state = MISSION_STOPPED; // return success return true; } From 09331259bf104dd90591eeb2f25a26521cb33027 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 23 Mar 2023 19:01:47 -0500 Subject: [PATCH 023/287] Rover: allow clearing mission in AUTO when disarmed --- Rover/AP_Arming.cpp | 3 +++ Rover/mode_auto.cpp | 6 ++++++ 2 files changed, 9 insertions(+) diff --git a/Rover/AP_Arming.cpp b/Rover/AP_Arming.cpp index 805f23d720a497..d043360700baa2 100644 --- a/Rover/AP_Arming.cpp +++ b/Rover/AP_Arming.cpp @@ -200,6 +200,9 @@ bool AP_Arming_Rover::mode_checks(bool report) if (!rover.control_mode->allows_arming()) { check_failed(report, "Mode not armable"); return false; + } else if (rover.control_mode == &rover.mode_auto && rover.mode_auto.mission.num_commands() <= 1) { + check_failed(report, "AUTO requires mission"); + return false; } return true; } diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index e9bdd4c6f09e9b..b7cf77163cf0b0 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -44,6 +44,12 @@ void ModeAuto::_exit() void ModeAuto::update() { + // check if mission exists (due to being cleared while disarmed in AUTO, + // if no mission, then stop...needs mode change out of AUTO, mission load, + // and change back to AUTO to run a mission at this point + if (!hal.util->get_soft_armed() && mission.num_commands() <= 1) { + start_stop(); + } // start or update mission if (waiting_to_start) { // don't start the mission until we have an origin From 7990e4f964c1796ed9eb356cad723c9afd7f1288 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Mar 2023 09:54:09 +1100 Subject: [PATCH 024/287] SimOnHW: correct compilation on CubeOrangePlus this was at 2 to reduce CPU load. But particularly when CubeOrangePlus is playing around with auxiliary IMUs we really want to be running on SimOnHardware just what we're running on the normal firmware. We can find CPU cycles elsewhere.... --- libraries/AP_HAL_ChibiOS/hwdef/include/SimOnHW.inc | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/SimOnHW.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/SimOnHW.inc index 1f90fd8397ad3d..63d09f3db949b6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/SimOnHW.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/SimOnHW.inc @@ -1,6 +1,5 @@ env SIM_ENABLED 1 -define INS_MAX_INSTANCES 2 define HAL_COMPASS_MAX_SENSORS 2 define HAL_NAVEKF2_AVAILABLE 0 From 3fada156813d6ae76d5ff11b82cb21369786ccfc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Mar 2023 09:58:56 +1100 Subject: [PATCH 025/287] AP_InertialSensor: correct access beyond array in Ins TCal --- libraries/AP_InertialSensor/AP_InertialSensor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 4e2b8b623bcd4b..f95e746c82f3a3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -723,7 +723,7 @@ class AP_InertialSensor : AP_AccelCal_Client // instance number for logging #if INS_AUX_INSTANCES uint8_t tcal_instance(const AP_InertialSensor_TCal &tc) const { - for (uint8_t i=0; i Date: Tue, 28 Mar 2023 17:01:21 +0900 Subject: [PATCH 026/287] Tools: allocate a board ID for AP_HW_JFB110 add JFB-110 board definition --- Tools/AP_Bootloader/board_types.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 5a019c4d33eba8..e98d4f3af1e1de 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -220,6 +220,8 @@ AP_HW_KakuteH7-Wing 1105 AP_HW_PixSurveyA-IND 1107 +AP_HW_JFB110 1110 + AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 From 3c09a9e8aa7832437836eea2f32e21a19ce77439 Mon Sep 17 00:00:00 2001 From: pedro-fuoco Date: Sun, 26 Mar 2023 13:07:20 -0300 Subject: [PATCH 027/287] AP_DDS: update readme bash scripts and tutorial order * Fix install java apt script * Fix text indentation * Add export PATH script for micro-XRCE-DDS-Gen * Comment on the option to change ardupilot parameters through GCS * Fix MicroROS PR 401 hyperlink * Change tutorial order so that the user runs the microROS agent first --- libraries/AP_DDS/README.md | 93 +++++++++++++++++++++----------------- 1 file changed, 51 insertions(+), 42 deletions(-) diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index 446b2df762b5d5..e45886c4845234 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -33,20 +33,25 @@ Currently, serial is the only supported transport, but there are plans to add IP While DDS support in Ardupilot is mostly through git submodules, another tool needs to be available on your system: Micro XRCE DDS Gen. -1. Go to a directory on your system to clone the repo (perhaps next to `ardupilot`) -1. Install java +- Go to a directory on your system to clone the repo (perhaps next to `ardupilot`) +- Install java ```console - sudo apt install java + sudo apt install default-jre ```` -1. Follow instructions [here](https://micro-xrce-dds.docs.eprosima.com/en/latest/installation.html#installing-the-micro-xrce-dds-gen-tool) to install the generator, but use `develop` branch instead of `master` (for now). +- Follow instructions [here](https://micro-xrce-dds.docs.eprosima.com/en/latest/installation.html#installing-the-micro-xrce-dds-gen-tool) to install the generator, but use `develop` branch instead of `master` (for now). ```console git clone -b develop --recurse-submodules https://github.com/eProsima/Micro-XRCE-DDS-Gen.git cd Micro-XRCE-DDS-Gen ./gradlew assemble ``` -1. Add the generator directory to $PATH, like [so](https://github.com/eProsima/Micro-XRCE-DDS-docs/issues/83). -1. Test it +- Add the generator directory to $PATH, like [so](https://github.com/eProsima/Micro-XRCE-DDS-docs/issues/83). + ```console + # Add this to ~/.bashrc + + export PATH=$PATH:/your/path/to/Micro-XRCE-DDS-Gen/scripts + ``` +- Test it ```console cd /path/to/ardupilot microxrceddsgen -version @@ -67,7 +72,7 @@ section, you should remove it and switch to local install. | Name | Description | | - | - | -| SERIAL1_BAUD | The serial baud rate for DDS | +| SERIAL1_BAUD | The serial baud rate for DDS, use 115 | | SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port | @@ -100,11 +105,7 @@ param set SERIAL1_BAUD 115 # See libraries/AP_SerialManager/AP_SerialManager.h AP_SerialManager SerialProtocol_DDS_XRCE param set SERIAL1_PROTOCOL 45 ``` - -# Start the sim now with the new params -``` -sim_vehicle.py -v ArduPlane -D --console --enable-dds -A "--uartC=uart:/dev/pts/1" -``` +Alternatively it is possible to change the parameters on a GCS ## Starting with microROS Agent @@ -116,9 +117,9 @@ Follow the steps to use the microROS Agent - Install and run the microROS agent (as descibed here). Make sure to use the `humble` branch. -- https://micro.ros.org/docs/tutorials/core/first_application_linux/ + - https://micro.ros.org/docs/tutorials/core/first_application_linux/ -Until this [PR](https://github.com/micro-ROS/micro-ROS.github.io) is merged, ignore the notes about `foxy`. It works on `humble`. +Until this [PR](https://github.com/micro-ROS/micro-ROS.github.io/pull/401) is merged, ignore the notes about `foxy`. It works on `humble`. Follow the instructions for the following: @@ -129,7 +130,7 @@ Follow the instructions for the following: * Do "Creating the micro-ROS agent" * Source your ROS workspace -- Run microROS agent with the following command +Run microROS agent with the following command to test the agent ```bash cd ardupilot/libraries/AP_DDS @@ -140,35 +141,43 @@ ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/pts/2 -r dds_ ### Using the ROS2 CLI to Read Ardupilot Data -If you have installed the microROS agent and ROS-2 Humble +If you have installed the microROS agent and ROS2 Humble - Source the ros2 installation - - ```source /opt/ros/humble/setup.bash``` - -- If SITL is running alongise MicroROS Agent, you should be able to see the agent here and view the data output. - - -``` -$ ros2 node list -/Ardupilot_DDS_XRCE_Client - -$ ros2 topic list -v -Published topics: - * /ROS2_Time [builtin_interfaces/msg/Time] 1 publisher - * /parameter_events [rcl_interfaces/msg/ParameterEvent] 1 publisher - * /rosout [rcl_interfaces/msg/Log] 1 publisher - -Subscribed topics: - -$ ros2 topic hz /ROS2_Time -average rate: 50.115 - min: 0.012s max: 0.024s std dev: 0.00328s window: 52 - -$ ros2 topic echo /ROS2_Time -sec: 1678668735 -nanosec: 729410000 ---- -``` + ```bash + source /opt/ros/humble/setup.bash + ``` +- Run the microROS agent + ```bash + cd ardupilot/libraries/AP_DDS + ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/pts/2 -r dds_xrce_profile.xml # (assuming we are using tty/pts/2 for Ardupilot) + ``` +- Run SITL + ```bash + sim_vehicle.py -v ArduPlane -D --console --enable-dds -A "--uartC=uart:/dev/pts/1" + ``` +- You should be able to see the agent here and view the data output. + ```bash + $ ros2 node list + /Ardupilot_DDS_XRCE_Client + + $ ros2 topic list -v + Published topics: + * /ROS2_Time [builtin_interfaces/msg/Time] 1 publisher + * /parameter_events [rcl_interfaces/msg/ParameterEvent] 1 publisher + * /rosout [rcl_interfaces/msg/Log] 1 publisher + + Subscribed topics: + + $ ros2 topic hz /ROS2_Time + average rate: 50.115 + min: 0.012s max: 0.024s std dev: 0.00328s window: 52 + + $ ros2 topic echo /ROS2_Time + sec: 1678668735 + nanosec: 729410000 + --- + ``` ## Adding DDS messages to Ardupilot From dfdd7cde1baa25881a8a82dd7ac38667db70c234 Mon Sep 17 00:00:00 2001 From: pedro-fuoco Date: Mon, 27 Mar 2023 10:27:19 -0300 Subject: [PATCH 028/287] AP_DDS: update readme with feedback provided --- libraries/AP_DDS/README.md | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index e45886c4845234..4342b8d6587240 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -45,7 +45,7 @@ While DDS support in Ardupilot is mostly through git submodules, another tool ne ./gradlew assemble ``` -- Add the generator directory to $PATH, like [so](https://github.com/eProsima/Micro-XRCE-DDS-docs/issues/83). +- Add the generator directory to $PATH. ```console # Add this to ~/.bashrc @@ -72,7 +72,7 @@ section, you should remove it and switch to local install. | Name | Description | | - | - | -| SERIAL1_BAUD | The serial baud rate for DDS, use 115 | +| SERIAL1_BAUD | The serial baud rate for DDS | | SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port | @@ -105,7 +105,6 @@ param set SERIAL1_BAUD 115 # See libraries/AP_SerialManager/AP_SerialManager.h AP_SerialManager SerialProtocol_DDS_XRCE param set SERIAL1_PROTOCOL 45 ``` -Alternatively it is possible to change the parameters on a GCS ## Starting with microROS Agent @@ -130,7 +129,7 @@ Follow the instructions for the following: * Do "Creating the micro-ROS agent" * Source your ROS workspace -Run microROS agent with the following command to test the agent +Run microROS agent with the following command ```bash cd ardupilot/libraries/AP_DDS @@ -141,7 +140,7 @@ ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/pts/2 -r dds_ ### Using the ROS2 CLI to Read Ardupilot Data -If you have installed the microROS agent and ROS2 Humble +If you have installed the microROS agent and ROS 2 Humble - Source the ros2 installation ```bash From cb628e68751168abc66ff3e813353c7f6798e938 Mon Sep 17 00:00:00 2001 From: pedro-fuoco Date: Mon, 27 Mar 2023 11:05:51 -0300 Subject: [PATCH 029/287] AP_DDS: update readme headers overhaul --- libraries/AP_DDS/README.md | 74 +++++++++++++++----------------------- 1 file changed, 29 insertions(+), 45 deletions(-) diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index 4342b8d6587240..1dbb8bf712e114 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -68,34 +68,24 @@ For now, avoid having simultaneous local and global installs. If you followed the [global install](https://fast-dds.docs.eprosima.com/en/latest/installation/sources/sources_linux.html#global-installation) section, you should remove it and switch to local install. -## Parameters for DDS +## Setup serial for SITL with DDS -| Name | Description | -| - | - | -| SERIAL1_BAUD | The serial baud rate for DDS | -| SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port | - - -## Testing with a UART - -On Linux, first create a virtual serial port for use with SITL like [this](https://stackoverflow.com/questions/52187/virtual-serial-port-for-linux) +On Linux, creating a virtual serial port will be necessary to use serial in SITL, because of that install socat. ``` sudo apt-get update sudo apt-get install socat ``` -Then, start a virtual serial port with socat. Take note of the two `/dev/pts/*` ports. If yours are different, substitute as needed. -``` -socat -d -d pty,raw,echo=0 pty,raw,echo=0 ->>> 2023/02/21 05:26:06 socat[334] N PTY is /dev/pts/1 ->>> 2023/02/21 05:26:06 socat[334] N PTY is /dev/pts/2 ->>> 2023/02/21 05:26:06 socat[334] N starting data transfer loop with FDs [5,5] and [7,7] -``` +## Setup ardupilot for SITL with DDS Set up your [SITL](https://ardupilot.org/dev/docs/setting-up-sitl-on-linux.html). -Run the simulator with the following command (assuming we are using /dev/pts/1 for Ardupilot SITL). Take note how two parameters need adjusting from default to use DDS. -``` +Run the simulator with the following command. Take note how two parameters need adjusting from default to use DDS. +| Name | Description | +| - | - | +| SERIAL1_BAUD | The serial baud rate for DDS | +| SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port | +```bash # Wipe params till you see "AP: ArduPilot Ready" # Select your favorite vehicle type sim_vehicle.py -w -v ArduPlane @@ -105,8 +95,7 @@ param set SERIAL1_BAUD 115 # See libraries/AP_SerialManager/AP_SerialManager.h AP_SerialManager SerialProtocol_DDS_XRCE param set SERIAL1_PROTOCOL 45 ``` - -## Starting with microROS Agent +## Setup ROS 2 and micro-ROS Follow the steps to use the microROS Agent @@ -115,45 +104,40 @@ Follow the steps to use the microROS Agent - https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html - Install and run the microROS agent (as descibed here). Make sure to use the `humble` branch. + - Follow [the instructions](https://micro.ros.org/docs/tutorials/core/first_application_linux/) for the following: - - https://micro.ros.org/docs/tutorials/core/first_application_linux/ + - Do "Installing ROS 2 and the micro-ROS build system" + - Skip the docker run command, build it locally instead + - Skip "Creating a new firmware workspace" + - Skip "Building the firmware" + - Do "Creating the micro-ROS agent" + - Source your ROS workspace Until this [PR](https://github.com/micro-ROS/micro-ROS.github.io/pull/401) is merged, ignore the notes about `foxy`. It works on `humble`. -Follow the instructions for the following: - -* Do "Installing ROS 2 and the micro-ROS build system" - * Skip the docker run command, build it locally instead -* Skip "Creating a new firmware workspace" -* Skip "Building the firmware" -* Do "Creating the micro-ROS agent" -* Source your ROS workspace - -Run microROS agent with the following command - -```bash -cd ardupilot/libraries/AP_DDS -ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/pts/2 -r dds_xrce_profile.xml # (assuming we are using tty/pts/2 for Ardupilot) -``` - -## Tutorial +## Using the ROS2 CLI to Read Ardupilot Data -### Using the ROS2 CLI to Read Ardupilot Data - -If you have installed the microROS agent and ROS 2 Humble +After your setups are complete, do the following: - Source the ros2 installation ```bash source /opt/ros/humble/setup.bash ``` +- Start a virtual serial port with socat. Take note of the two `/dev/pts/*` ports. If yours are different, substitute as needed. + ```bash + socat -d -d pty,raw,echo=0 pty,raw,echo=0 + >>> 2023/02/21 05:26:06 socat[334] N PTY is /dev/pts/1 + >>> 2023/02/21 05:26:06 socat[334] N PTY is /dev/pts/2 + >>> 2023/02/21 05:26:06 socat[334] N starting data transfer loop with FDs [5,5] and [7,7] + ``` - Run the microROS agent ```bash cd ardupilot/libraries/AP_DDS - ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/pts/2 -r dds_xrce_profile.xml # (assuming we are using tty/pts/2 for Ardupilot) + ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/pts/2 -r dds_xrce_profile.xml # (assuming we are using tty/pts/2 for DDS Application) ``` -- Run SITL +- Run SITL (remember to kill any terminals running ardupilot SITL beforehand) ```bash - sim_vehicle.py -v ArduPlane -D --console --enable-dds -A "--uartC=uart:/dev/pts/1" + sim_vehicle.py -v ArduPlane -D --console --enable-dds -A "--uartC=uart:/dev/pts/1" # (assuming we are using /dev/pts/1 for Ardupilot SITL) ``` - You should be able to see the agent here and view the data output. ```bash From 7067e9d91754c1a9d7a46c0e4f8ac73734f0b6c9 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 5 Jan 2023 12:09:23 +1100 Subject: [PATCH 030/287] AP_UAVCAN: move libuavcan to libcanard driver --- libraries/AP_UAVCAN/AP_Canard_iface.cpp | 309 ++++++++ libraries/AP_UAVCAN/AP_Canard_iface.h | 68 ++ libraries/AP_UAVCAN/AP_UAVCAN.cpp | 703 +++++++----------- libraries/AP_UAVCAN/AP_UAVCAN.h | 210 +++--- libraries/AP_UAVCAN/AP_UAVCAN_Clock.h | 59 -- libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp | 262 ++----- libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h | 43 +- libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp | 238 ------ libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.h | 75 -- libraries/AP_UAVCAN/AP_UAVCAN_pool.cpp | 90 --- libraries/AP_UAVCAN/AP_UAVCAN_pool.h | 60 -- .../UAVCAN_sniffer/UAVCAN_sniffer.cpp | 187 ++--- .../AP_UAVCAN/examples/UAVCAN_sniffer/wscript | 18 +- 13 files changed, 918 insertions(+), 1404 deletions(-) create mode 100644 libraries/AP_UAVCAN/AP_Canard_iface.cpp create mode 100644 libraries/AP_UAVCAN/AP_Canard_iface.h delete mode 100644 libraries/AP_UAVCAN/AP_UAVCAN_Clock.h delete mode 100644 libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp delete mode 100644 libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.h delete mode 100644 libraries/AP_UAVCAN/AP_UAVCAN_pool.cpp delete mode 100644 libraries/AP_UAVCAN/AP_UAVCAN_pool.h diff --git a/libraries/AP_UAVCAN/AP_Canard_iface.cpp b/libraries/AP_UAVCAN/AP_Canard_iface.cpp new file mode 100644 index 00000000000000..e415fa4afe48d1 --- /dev/null +++ b/libraries/AP_UAVCAN/AP_Canard_iface.cpp @@ -0,0 +1,309 @@ +#include "AP_Canard_iface.h" +#include +#include +#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#include +#include +extern const AP_HAL::HAL& hal; +#define LOG_TAG "DroneCANIface" + +#define DEBUG_PKTS 0 + +DEFINE_HANDLER_LIST_HEADS(); +DEFINE_TRANSFER_OBJECT_HEADS(); + +#if AP_TEST_DRONECAN_DRIVERS +CanardInterface* CanardInterface::canard_ifaces[] = {nullptr, nullptr, nullptr}; +CanardInterface CanardInterface::test_iface{2}; +uint8_t test_node_mem_area[1024]; +HAL_Semaphore test_iface_sem; +#endif + +CanardInterface::CanardInterface(uint8_t iface_index) : +Interface(iface_index) { +#if AP_TEST_DRONECAN_DRIVERS + if (iface_index < 3) { + canard_ifaces[iface_index] = this; + } + if (iface_index == 0) { + test_iface.init(test_node_mem_area, sizeof(test_node_mem_area), 125); + } +#endif +} + +void CanardInterface::init(void* mem_arena, size_t mem_arena_size, uint8_t node_id) { + canardInit(&canard, mem_arena, mem_arena_size, onTransferReception, shouldAcceptTransfer, this); + canardSetLocalNodeID(&canard, node_id); + initialized = true; +} + +bool CanardInterface::broadcast(const Canard::Transfer &bcast_transfer) { + if (!initialized) { + return false; + } + WITH_SEMAPHORE(_sem); +#if AP_TEST_DRONECAN_DRIVERS + if (this == &test_iface) { + test_iface_sem.take_blocking(); + } +#endif + + // do canard broadcast + bool success = canardBroadcast(&canard, + bcast_transfer.data_type_signature, + bcast_transfer.data_type_id, + bcast_transfer.inout_transfer_id, + bcast_transfer.priority, + bcast_transfer.payload, + bcast_transfer.payload_len, + AP_HAL::native_micros64() + (bcast_transfer.timeout_ms * 1000) +#if CANARD_MULTI_IFACE + , ((1< 0; +#if AP_TEST_DRONECAN_DRIVERS + if (this == &test_iface) { + test_iface_sem.give(); + } +#endif + return success; +} + +bool CanardInterface::request(uint8_t destination_node_id, const Canard::Transfer &req_transfer) { + if (!initialized) { + return false; + } + WITH_SEMAPHORE(_sem); + // do canard request + return canardRequestOrRespond(&canard, + destination_node_id, + req_transfer.data_type_signature, + req_transfer.data_type_id, + req_transfer.inout_transfer_id, + req_transfer.priority, + CanardRequest, + req_transfer.payload, + req_transfer.payload_len, + AP_HAL::native_micros64() + (req_transfer.timeout_ms * 1000) +#if CANARD_MULTI_IFACE + , ((1< 0; +} + +bool CanardInterface::respond(uint8_t destination_node_id, const Canard::Transfer &res_transfer) { + if (!initialized) { + return false; + } + WITH_SEMAPHORE(_sem); + // do canard respond + return canardRequestOrRespond(&canard, + destination_node_id, + res_transfer.data_type_signature, + res_transfer.data_type_id, + res_transfer.inout_transfer_id, + res_transfer.priority, + CanardResponse, + res_transfer.payload, + res_transfer.payload_len, + AP_HAL::native_micros64() + (res_transfer.timeout_ms * 1000) +#if CANARD_MULTI_IFACE + , ((1< 0; +} + +void CanardInterface::onTransferReception(CanardInstance* ins, CanardRxTransfer* transfer) { + CanardInterface* iface = (CanardInterface*) ins->user_reference; + iface->handle_message(*transfer); +} + +bool CanardInterface::shouldAcceptTransfer(const CanardInstance* ins, + uint64_t* out_data_type_signature, + uint16_t data_type_id, + CanardTransferType transfer_type, + uint8_t source_node_id) { + CanardInterface* iface = (CanardInterface*) ins->user_reference; + return iface->accept_message(data_type_id, *out_data_type_signature); +} + +#if AP_TEST_DRONECAN_DRIVERS +void CanardInterface::processTestRx() { + if (!test_iface.initialized) { + return; + } + WITH_SEMAPHORE(test_iface_sem); + for (const CanardCANFrame* txf = canardPeekTxQueue(&test_iface.canard); txf != NULL; txf = canardPeekTxQueue(&test_iface.canard)) { + if (canard_ifaces[0]) { + canardHandleRxFrame(&canard_ifaces[0]->canard, txf, AP_HAL::native_micros64()); + } + canardPopTxQueue(&test_iface.canard); + } +} +#endif + +void CanardInterface::processTx() { + WITH_SEMAPHORE(_sem); + + for (uint8_t iface = 0; iface < num_ifaces; iface++) { + if (ifaces[iface] == NULL) { + continue; + } + auto txq = canard.tx_queue; + if (txq == nullptr) { + return; + } + AP_HAL::CANFrame txmsg {}; + // scan through list of pending transfers + while (true) { + auto txf = &txq->frame; + txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len); + memcpy(txmsg.data, txf->data, txf->data_len); + txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF); +#if HAL_CANFD_SUPPORTED + txmsg.canfd = txf->canfd; +#endif + bool write = true; + bool read = false; + ifaces[iface]->select(read, write, &txmsg, 0); + if ((AP_HAL::native_micros64() < txf->deadline_usec) && (txf->iface_mask & (1U<send(txmsg, txf->deadline_usec, 0) > 0) { + txf->iface_mask &= ~(1U<next; + if (txq == nullptr) { + break; + } + } + } + + // purge expired transfers + for (const CanardCANFrame* txf = canardPeekTxQueue(&canard); txf != NULL; txf = canardPeekTxQueue(&canard)) { + if ((AP_HAL::native_micros64() >= txf->deadline_usec) || (txf->iface_mask == 0)) { + canardPopTxQueue(&canard); + } else { + break; + } + } +} + +void CanardInterface::processRx() { + AP_HAL::CANFrame rxmsg; + for (uint8_t i=0; iselect(read_select, write_select, nullptr, 0); + if (!read_select) { // No data pending + break; + } + CanardCANFrame rx_frame {}; + + //palToggleLine(HAL_GPIO_PIN_LED); + uint64_t timestamp; + AP_HAL::CANIface::CanIOFlags flags; + if (ifaces[i]->receive(rxmsg, timestamp, flags) <= 0) { + break; + } + rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc); + memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len); +#if HAL_CANFD_SUPPORTED + rx_frame.canfd = rxmsg.canfd; +#endif + rx_frame.id = rxmsg.id; +#if CANARD_MULTI_IFACE + rx_frame.iface_id = i; +#endif + { + WITH_SEMAPHORE(_sem); + +#if DEBUG_PKTS + const int16_t res = +#endif + canardHandleRxFrame(&canard, &rx_frame, timestamp); +#if DEBUG_PKTS + // hal.console->printf("DTID: %u\n", extractDataType(rx_frame.id)); + // hal.console->printf("Rx %d, IF%d %lx: ", res, i, rx_frame.id); + if (res < 0 && + res != -CANARD_ERROR_RX_NOT_WANTED && + res != -CANARD_ERROR_RX_WRONG_ADDRESS) { + hal.console->printf("Rx error %d, IF%d %lx: \n", res, i, rx_frame.id); + // for (uint8_t index = 0; index < rx_frame.data_len; index++) { + // hal.console->printf("%02x", rx_frame.data[index]); + // } + // hal.console->printf("\n"); + } +#endif + } + } + } +} + +void CanardInterface::process(uint32_t duration_ms) { +#if AP_TEST_DRONECAN_DRIVERS + const uint64_t deadline = AP_HAL::micros64() + duration_ms*1000; + while (AP_HAL::micros64() < deadline) { + processTestRx(); + hal.scheduler->delay_microseconds(1000); + } +#else + const uint64_t deadline = AP_HAL::native_micros64() + duration_ms*1000; + while (true) { + processRx(); + processTx(); + uint64_t now = AP_HAL::native_micros64(); + if (now < deadline) { + _event_handle.wait(deadline - now); + } else { + break; + } + } +#endif +} + +bool CanardInterface::add_interface(AP_HAL::CANIface *can_iface) +{ + if (num_ifaces > HAL_NUM_CAN_IFACES) { + AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Num Ifaces Exceeded\n"); + return false; + } + if (can_iface == nullptr) { + AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Iface Null\n"); + return false; + } + if (ifaces[num_ifaces] != nullptr) { + AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Iface already added\n"); + return false; + } + ifaces[num_ifaces] = can_iface; + if (ifaces[num_ifaces] == nullptr) { + AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Can't alloc uavcan::iface\n"); + return false; + } + if (!can_iface->set_event_handle(&_event_handle)) { + AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Setting event handle failed\n"); + return false; + } + AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "DroneCANIfaceMgr: Successfully added interface %d\n", int(num_ifaces)); + num_ifaces++; + return true; +} +#endif // #if HAL_ENABLE_LIBUAVCAN_DRIVERS diff --git a/libraries/AP_UAVCAN/AP_Canard_iface.h b/libraries/AP_UAVCAN/AP_Canard_iface.h new file mode 100644 index 00000000000000..9c88df8826e481 --- /dev/null +++ b/libraries/AP_UAVCAN/AP_Canard_iface.h @@ -0,0 +1,68 @@ +#pragma once +#include +#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#include + +class AP_UAVCAN; +class CanardInterface : public Canard::Interface { + friend class AP_UAVCAN; +public: + + /// @brief delete copy constructor and assignment operator + CanardInterface(const CanardInterface&) = delete; + CanardInterface& operator=(const CanardInterface&) = delete; + + CanardInterface(uint8_t driver_index); + + void init(void* mem_arena, size_t mem_arena_size, uint8_t node_id); + + /// @brief broadcast message to all listeners on Interface + /// @param bc_transfer + /// @return true if message was added to the queue + bool broadcast(const Canard::Transfer &bcast_transfer) override; + + /// @brief request message from + /// @param destination_node_id + /// @param req_transfer + /// @return true if request was added to the queue + bool request(uint8_t destination_node_id, const Canard::Transfer &req_transfer) override; + + /// @brief respond to a request + /// @param destination_node_id + /// @param res_transfer + /// @return true if response was added to the queue + bool respond(uint8_t destination_node_id, const Canard::Transfer &res_transfer) override; + + void processTx(); + void processRx(); + + void process(uint32_t duration); + + static void onTransferReception(CanardInstance* ins, CanardRxTransfer* transfer); + static bool shouldAcceptTransfer(const CanardInstance* ins, + uint64_t* out_data_type_signature, + uint16_t data_type_id, + CanardTransferType transfer_type, + uint8_t source_node_id); + + bool add_interface(AP_HAL::CANIface *can_drv); + +#if AP_TEST_DRONECAN_DRIVERS + static CanardInterface& get_test_iface() { return test_iface; } + static void processTestRx(); +#endif + + uint8_t get_node_id() const override { return canard.node_id; } +private: + CanardInstance canard; + AP_HAL::CANIface* ifaces[HAL_NUM_CAN_IFACES]; +#if AP_TEST_DRONECAN_DRIVERS + static CanardInterface* canard_ifaces[3]; + static CanardInterface test_iface; +#endif + uint8_t num_ifaces; + HAL_EventHandle _event_handle; + bool initialized; + HAL_Semaphore _sem; +}; +#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS \ No newline at end of file diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.cpp b/libraries/AP_UAVCAN/AP_UAVCAN.cpp index 41f1ef3ac6582c..44a599e3910af1 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN.cpp @@ -25,34 +25,13 @@ #include #include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#if AP_DRONECAN_SEND_GPS -#include -#include -#include -#include -#endif -#include -#include - #include +#include +#include #include +#include +#include +#include #include #include #include @@ -60,15 +39,14 @@ #include #include #include +#include #include -#include #include #include "AP_UAVCAN_DNA_Server.h" #include #include #include -#include "AP_UAVCAN_pool.h" -#include +#include #define LED_DELAY_US 50000 @@ -111,7 +89,7 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { // @Description: UAVCAN node should be set implicitly // @Range: 1 250 // @User: Advanced - AP_GROUPINFO("NODE", 1, AP_UAVCAN, _uavcan_node, 10), + AP_GROUPINFO("NODE", 1, AP_UAVCAN, _dronecan_node, 10), // @Param: SRV_BM // @DisplayName: Output channels to be transmitted as servo over UAVCAN @@ -172,60 +150,10 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { // set this to 1 to minimise resend of stale msgs #define CAN_PERIODIC_TX_TIMEOUT_MS 2 -// publisher interfaces -static uavcan::Publisher* act_out_array[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* esc_raw[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* rgb_led[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* buzzer[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* safety_state[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* arming_status[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -#if AP_DRONECAN_SEND_GPS -static uavcan::Publisher* gnss_fix2[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* gnss_auxiliary[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* gnss_heading[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* gnss_status[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -#endif -static uavcan::Publisher* rtcm_stream[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* notify_state[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -// Clients -UC_CLIENT_CALL_REGISTRY_BINDER(ParamGetSetCb, uavcan::protocol::param::GetSet); -static uavcan::ServiceClient* param_get_set_client[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::protocol::param::GetSet::Request param_getset_req[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -UC_CLIENT_CALL_REGISTRY_BINDER(ParamExecuteOpcodeCb, uavcan::protocol::param::ExecuteOpcode); -static uavcan::ServiceClient* param_execute_opcode_client[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::protocol::param::ExecuteOpcode::Request param_save_req[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - - -// subscribers - -// handler SafteyButton -UC_REGISTRY_BINDER(ButtonCb, ardupilot::indication::Button); -static uavcan::Subscriber *safety_button_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -// handler TrafficReport -UC_REGISTRY_BINDER(TrafficReportCb, ardupilot::equipment::trafficmonitor::TrafficReport); -static uavcan::Subscriber *traffic_report_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -// handler actuator status -UC_REGISTRY_BINDER(ActuatorStatusCb, uavcan::equipment::actuator::Status); -static uavcan::Subscriber *actuator_status_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED -UC_REGISTRY_BINDER(ActuatorStatusVolzCb, com::volz::servo::ActuatorStatus); -static uavcan::Subscriber *actuator_status_Volz_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -#endif - -// handler ESC status -UC_REGISTRY_BINDER(ESCStatusCb, uavcan::equipment::esc::Status); -static uavcan::Subscriber *esc_status_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -// handler DEBUG -UC_REGISTRY_BINDER(DebugCb, uavcan::protocol::debug::LogMessage); -static uavcan::Subscriber *debug_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -AP_UAVCAN::AP_UAVCAN() +AP_UAVCAN::AP_UAVCAN(const int driver_index) : +_driver_index(driver_index), +canard_iface(driver_index), +_dna_server(*this) { AP_Param::setup_object_defaults(this, var_info); @@ -250,120 +178,62 @@ AP_UAVCAN *AP_UAVCAN::get_uavcan(uint8_t driver_index) return static_cast(AP::can().get_driver(driver_index)); } -bool AP_UAVCAN::add_interface(AP_HAL::CANIface* can_iface) { - - if (_iface_mgr == nullptr) { - _iface_mgr = new uavcan::CanIfaceMgr(); - } - - if (_iface_mgr == nullptr) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: can't create UAVCAN interface manager\n\r"); - return false; - } - - if (!_iface_mgr->add_interface(can_iface)) { +bool AP_UAVCAN::add_interface(AP_HAL::CANIface* can_iface) +{ + if (!canard_iface.add_interface(can_iface)) { debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: can't add UAVCAN interface\n\r"); return false; } return true; } -#pragma GCC diagnostic push -#pragma GCC diagnostic error "-Wframe-larger-than=2200" void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) { - _driver_index = driver_index; - - if (_initialized) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: init called more than once\n\r"); - return; - } - - if (_iface_mgr == nullptr) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: can't get UAVCAN interface driver\n\r"); - return; - } - - _allocator = new AP_PoolAllocator(_pool_size); - - if (_allocator == nullptr || !_allocator->init()) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't allocate node pool\n"); + if (driver_index != _driver_index) { + debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: init called with wrong driver_index"); return; } - - _node = new uavcan::Node<0>(*_iface_mgr, uavcan::SystemClock::instance(), *_allocator); - - if (_node == nullptr) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't allocate node\n\r"); - return; - } - - if (_node->isStarted()) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: node was already started?\n\r"); + if (_initialized) { + debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: init called more than once\n\r"); return; } - { - uavcan::NodeID self_node_id(_uavcan_node); - _node->setNodeID(self_node_id); - - char ndname[20]; - snprintf(ndname, sizeof(ndname), "org.ardupilot:%u", driver_index); - - uavcan::NodeStatusProvider::NodeName name(ndname); - _node->setName(name); - } - { - uavcan::protocol::SoftwareVersion sw_version; // Standard type uavcan.protocol.SoftwareVersion - sw_version.major = AP_UAVCAN_SW_VERS_MAJOR; - sw_version.minor = AP_UAVCAN_SW_VERS_MINOR; - _node->setSoftwareVersion(sw_version); - - uavcan::protocol::HardwareVersion hw_version; // Standard type uavcan.protocol.HardwareVersion - hw_version.major = AP_UAVCAN_HW_VERS_MAJOR; - hw_version.minor = AP_UAVCAN_HW_VERS_MINOR; + node_info_rsp.name.len = snprintf((char*)node_info_rsp.name.data, sizeof(node_info_rsp.name.data), "org.ardupilot:%u", driver_index); - const uint8_t uid_buf_len = hw_version.unique_id.capacity(); - uint8_t uid_len = uid_buf_len; - uint8_t unique_id[uid_buf_len]; + node_info_rsp.software_version.major = AP_UAVCAN_SW_VERS_MAJOR; + node_info_rsp.software_version.minor = AP_UAVCAN_SW_VERS_MINOR; + node_info_rsp.hardware_version.major = AP_UAVCAN_HW_VERS_MAJOR; + node_info_rsp.hardware_version.minor = AP_UAVCAN_HW_VERS_MINOR; - - if (hal.util->get_system_id_unformatted(unique_id, uid_len)) { - //This is because we are maintaining a common Server Record for all UAVCAN Instances. - //In case the node IDs are different, and unique id same, it will create - //conflict in the Server Record. - unique_id[uid_len - 1] += _uavcan_node; - uavcan::copy(unique_id, unique_id + uid_len, hw_version.unique_id.begin()); - } - _node->setHardwareVersion(hw_version); - } - -#if UAVCAN_SUPPORT_CANFD +#if HAL_CANFD_SUPPORTED if (option_is_set(Options::CANFD_ENABLED)) { - _node->enableCanFd(); + canard_iface.set_canfd(true); } #endif - int start_res = _node->start(); - if (start_res < 0) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: node start problem, error %d\n\r", start_res); + uint8_t uid_len = sizeof(uavcan_protocol_HardwareVersion::unique_id); + uint8_t unique_id[sizeof(uavcan_protocol_HardwareVersion::unique_id)]; + + mem_pool = new uint32_t[_pool_size/sizeof(uint32_t)]; + if (mem_pool == nullptr) { + debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: Failed to allocate memory pool\n\r"); return; } + canard_iface.init(mem_pool, (_pool_size/sizeof(uint32_t))*sizeof(uint32_t), _dronecan_node); - _dna_server = new AP_UAVCAN_DNA_Server(this, StorageAccess(StorageManager::StorageCANDNA)); - if (_dna_server == nullptr) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't allocate DNA server\n\r"); + if (!hal.util->get_system_id_unformatted(unique_id, uid_len)) { return; } + unique_id[uid_len - 1] += _dronecan_node; + memcpy(node_info_rsp.hardware_version.unique_id, unique_id, uid_len); //Start Servers - if (!_dna_server->init()) { + if (!_dna_server.init(unique_id, uid_len, _dronecan_node)) { debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: Failed to start DNA Server\n\r"); return; } // Roundup all subscribers from supported drivers - AP_UAVCAN_DNA_Server::subscribe_msgs(this); AP_GPS_UAVCAN::subscribe_msgs(this); #if AP_COMPASS_UAVCAN_ENABLED AP_Compass_UAVCAN::subscribe_msgs(this); @@ -389,107 +259,71 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) AP_Proximity_DroneCAN::subscribe_msgs(this); #endif - act_out_array[driver_index] = new uavcan::Publisher(*_node); - act_out_array[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2)); - act_out_array[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest); + act_out_array.set_timeout_ms(2); + act_out_array.set_priority(CANARD_TRANSFER_PRIORITY_HIGH); - esc_raw[driver_index] = new uavcan::Publisher(*_node); - esc_raw[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2)); - esc_raw[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest); + esc_raw.set_timeout_ms(2); + esc_raw.set_priority(CANARD_TRANSFER_PRIORITY_HIGH); - rgb_led[driver_index] = new uavcan::Publisher(*_node); - rgb_led[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - rgb_led[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + rgb_led.set_timeout_ms(20); + rgb_led.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - buzzer[driver_index] = new uavcan::Publisher(*_node); - buzzer[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - buzzer[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + buzzer.set_timeout_ms(20); + buzzer.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - safety_state[driver_index] = new uavcan::Publisher(*_node); - safety_state[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - safety_state[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + safety_state.set_timeout_ms(20); + safety_state.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - arming_status[driver_index] = new uavcan::Publisher(*_node); - arming_status[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - arming_status[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + arming_status.set_timeout_ms(20); + arming_status.set_priority(CANARD_TRANSFER_PRIORITY_LOW); #if AP_DRONECAN_SEND_GPS - gnss_fix2[driver_index] = new uavcan::Publisher(*_node); - gnss_fix2[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - gnss_fix2[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest); + gnss_fix2.set_timeout_ms(20); + gnss_fix2.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - gnss_auxiliary[driver_index] = new uavcan::Publisher(*_node); - gnss_auxiliary[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - gnss_auxiliary[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest); + gnss_auxiliary.set_timeout_ms(20); + gnss_auxiliary.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - gnss_heading[driver_index] = new uavcan::Publisher(*_node); - gnss_heading[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - gnss_heading[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest); + gnss_heading.set_timeout_ms(20); + gnss_heading.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - gnss_status[driver_index] = new uavcan::Publisher(*_node); - gnss_status[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - gnss_status[driver_index]->setPriority(uavcan::TransferPriority::OneLowerThanHighest); + gnss_status.set_timeout_ms(20); + gnss_status.set_priority(CANARD_TRANSFER_PRIORITY_LOW); #endif - rtcm_stream[driver_index] = new uavcan::Publisher(*_node); - rtcm_stream[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - rtcm_stream[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + rtcm_stream.set_timeout_ms(20); + rtcm_stream.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - notify_state[driver_index] = new uavcan::Publisher(*_node); - notify_state[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - notify_state[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + notify_state.set_timeout_ms(20); + notify_state.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - param_get_set_client[driver_index] = new uavcan::ServiceClient(*_node, ParamGetSetCb(this, &AP_UAVCAN::handle_param_get_set_response)); + param_save_client.set_timeout_ms(20); + param_save_client.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - param_execute_opcode_client[driver_index] = new uavcan::ServiceClient(*_node, ParamExecuteOpcodeCb(this, &AP_UAVCAN::handle_param_save_response)); + param_get_set_client.set_timeout_ms(20); + param_get_set_client.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - safety_button_listener[driver_index] = new uavcan::Subscriber(*_node); - if (safety_button_listener[driver_index]) { - safety_button_listener[driver_index]->start(ButtonCb(this, &handle_button)); - } - - traffic_report_listener[driver_index] = new uavcan::Subscriber(*_node); - if (traffic_report_listener[driver_index]) { - traffic_report_listener[driver_index]->start(TrafficReportCb(this, &handle_traffic_report)); - } - - actuator_status_listener[driver_index] = new uavcan::Subscriber(*_node); - if (actuator_status_listener[driver_index]) { - actuator_status_listener[driver_index]->start(ActuatorStatusCb(this, &handle_actuator_status)); - } - -#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED - actuator_status_Volz_listener[driver_index] = new uavcan::Subscriber(*_node); - if (actuator_status_Volz_listener[driver_index]) { - actuator_status_Volz_listener[driver_index]->start(ActuatorStatusVolzCb(this, &handle_actuator_status_Volz)); - } -#endif + node_status.set_priority(CANARD_TRANSFER_PRIORITY_LOWEST); + node_status.set_timeout_ms(1000); - esc_status_listener[driver_index] = new uavcan::Subscriber(*_node); - if (esc_status_listener[driver_index]) { - esc_status_listener[driver_index]->start(ESCStatusCb(this, &handle_ESC_status)); - } + node_info_server.set_timeout_ms(20); - debug_listener[driver_index] = new uavcan::Subscriber(*_node); - if (debug_listener[driver_index]) { - debug_listener[driver_index]->start(DebugCb(this, &handle_debug)); - } - _led_conf.devices_count = 0; - /* - * Informing other nodes that we're ready to work. - * Default mode is INITIALIZING. - */ - _node->setModeOperational(); + // setup node status + node_status_msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; + node_status_msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; + node_status_msg.sub_mode = 0; // Spin node for device discovery - _node->spin(uavcan::MonotonicDuration::fromMSec(5000)); + for (uint8_t i = 0; i < 5; i++) { + send_node_status(); + canard_iface.process(1000); + } snprintf(_thread_name, sizeof(_thread_name), "uavcan_%u", driver_index); if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_UAVCAN::loop, void), _thread_name, UAVCAN_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_CAN, 0)) { - _node->setModeOfflineAndPublish(); debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't create thread\n\r"); return; } @@ -497,7 +331,6 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) _initialized = true; debug_uavcan(AP_CANManager::LOG_INFO, "UAVCAN: init done\n\r"); } -#pragma GCC diagnostic pop void AP_UAVCAN::loop(void) { @@ -507,12 +340,7 @@ void AP_UAVCAN::loop(void) continue; } - const int error = _node->spin(uavcan::MonotonicDuration::fromMSec(1)); - - if (error < 0) { - hal.scheduler->delay_microseconds(100); - continue; - } + canard_iface.process(1); if (_SRV_armed) { bool sent_servos = false; @@ -548,7 +376,8 @@ void AP_UAVCAN::loop(void) notify_state_send(); send_parameter_request(); send_parameter_save_request(); - _dna_server->verify_nodes(); + send_node_status(); + _dna_server.verify_nodes(); #if AP_OPENDRONEID_ENABLED AP::opendroneid().dronecan_send(this); #endif @@ -566,6 +395,26 @@ void AP_UAVCAN::loop(void) } +void AP_UAVCAN::send_node_status(void) +{ + const uint32_t now = AP_HAL::native_millis(); + if (now - _node_status_last_send_ms < 1000) { + return; + } + _node_status_last_send_ms = now; + node_status_msg.uptime_sec = now / 1000; + node_status.broadcast(node_status_msg); +} + +void AP_UAVCAN::handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req) +{ + node_info_rsp.status = node_status_msg; + node_info_rsp.status.uptime_sec = AP_HAL::native_millis() / 1000; + + node_info_server.respond(transfer, node_info_rsp); +} + + ///// SRV output ///// void AP_UAVCAN::SRV_send_actuator(void) @@ -577,12 +426,12 @@ void AP_UAVCAN::SRV_send_actuator(void) do { repeat_send = false; - uavcan::equipment::actuator::ArrayCommand msg; + uavcan_equipment_actuator_ArrayCommand msg; uint8_t i; // UAVCAN can hold maximum of 15 commands in one frame for (i = 0; starting_servo < UAVCAN_SRV_NUMBER && i < 15; starting_servo++) { - uavcan::equipment::actuator::Command cmd; + uavcan_equipment_actuator_Command cmd; /* * Servo output uses a range of 1000-2000 PWM for scaling. @@ -597,21 +446,21 @@ void AP_UAVCAN::SRV_send_actuator(void) cmd.actuator_id = starting_servo + 1; if (option_is_set(Options::USE_ACTUATOR_PWM)) { - cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_PWM; + cmd.command_type = UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM; cmd.command_value = _SRV_conf[starting_servo].pulse; } else { - cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_UNITLESS; + cmd.command_type = UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS; cmd.command_value = constrain_float(((float) _SRV_conf[starting_servo].pulse - 1000.0) / 500.0 - 1.0, -1.0, 1.0); } - msg.commands.push_back(cmd); + msg.commands.data[i] = cmd; i++; } } - + msg.commands.len = i; if (i > 0) { - if (act_out_array[_driver_index]->broadcast(msg) > 0) { + if (act_out_array.broadcast(msg) > 0) { _srv_send_count++; } else { _fail_send_count++; @@ -626,8 +475,8 @@ void AP_UAVCAN::SRV_send_actuator(void) void AP_UAVCAN::SRV_send_esc(void) { - static const int cmd_max = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::RawValueType::max(); - uavcan::equipment::esc::RawCommand esc_msg; + static const int cmd_max = ((1<<13)-1); + uavcan_equipment_esc_RawCommand esc_msg; uint8_t active_esc_num = 0, max_esc_num = 0; uint8_t k = 0; @@ -658,15 +507,16 @@ void AP_UAVCAN::SRV_send_esc(void) scaled = constrain_float(scaled, 0, cmd_max); - esc_msg.cmd.push_back(static_cast(scaled)); + esc_msg.cmd.data[k] = static_cast(scaled); } else { - esc_msg.cmd.push_back(static_cast(0)); + esc_msg.cmd.data[k] = static_cast(0); } k++; } + esc_msg.cmd.len = k; - if (esc_raw[_driver_index]->broadcast(esc_msg) > 0) { + if (esc_raw.broadcast(esc_msg)) { _esc_send_count++; } else { _fail_send_count++; @@ -701,7 +551,7 @@ void AP_UAVCAN::led_out_send() return; } - uavcan::equipment::indication::LightsCommand msg; + uavcan_equipment_indication_LightsCommand msg; { WITH_SEMAPHORE(_led_out_sem); @@ -709,19 +559,16 @@ void AP_UAVCAN::led_out_send() return; } - uavcan::equipment::indication::SingleLightCommand cmd; - + msg.commands.len = _led_conf.devices_count; for (uint8_t i = 0; i < _led_conf.devices_count; i++) { - cmd.light_id =_led_conf.devices[i].led_index; - cmd.color.red = _led_conf.devices[i].red >> 3; - cmd.color.green = _led_conf.devices[i].green >> 2; - cmd.color.blue = _led_conf.devices[i].blue >> 3; - - msg.commands.push_back(cmd); + msg.commands.data[i].light_id =_led_conf.devices[i].led_index; + msg.commands.data[i].color.red = _led_conf.devices[i].red >> 3; + msg.commands.data[i].color.green = _led_conf.devices[i].green >> 2; + msg.commands.data[i].color.blue = _led_conf.devices[i].blue >> 3; } } - rgb_led[_driver_index]->broadcast(msg); + rgb_led.broadcast(msg); _led_conf.last_update = now; } @@ -761,7 +608,7 @@ bool AP_UAVCAN::led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t // buzzer send void AP_UAVCAN::buzzer_send() { - uavcan::equipment::indication::BeepCommand msg; + uavcan_equipment_indication_BeepCommand msg; WITH_SEMAPHORE(_buzzer.sem); uint8_t mask = (1U << _driver_index); if ((_buzzer.pending_mask & mask) == 0) { @@ -770,7 +617,7 @@ void AP_UAVCAN::buzzer_send() _buzzer.pending_mask &= ~mask; msg.frequency = _buzzer.frequency; msg.duration = _buzzer.duration; - buzzer[_driver_index]->broadcast(msg); + buzzer.broadcast(msg); } // buzzer support @@ -791,82 +638,83 @@ void AP_UAVCAN::notify_state_send() return; } - ardupilot::indication::NotifyState msg; + ardupilot_indication_NotifyState msg; msg.vehicle_state = 0; if (AP_Notify::flags.initialising) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_INITIALISING; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_INITIALISING; } if (AP_Notify::flags.armed) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_ARMED; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_ARMED; } if (AP_Notify::flags.flying) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_FLYING; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FLYING; } if (AP_Notify::flags.compass_cal_running) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_MAGCAL_RUN; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_MAGCAL_RUN; } if (AP_Notify::flags.ekf_bad) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_EKF_BAD; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_EKF_BAD; } if (AP_Notify::flags.esc_calibration) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_ESC_CALIBRATION; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_ESC_CALIBRATION; } if (AP_Notify::flags.failsafe_battery) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_FAILSAFE_BATT; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_BATT; } if (AP_Notify::flags.failsafe_gcs) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_FAILSAFE_GCS; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_GCS; } if (AP_Notify::flags.failsafe_radio) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_FAILSAFE_RADIO; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_RADIO; } if (AP_Notify::flags.firmware_update) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_FW_UPDATE; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FW_UPDATE; } if (AP_Notify::flags.gps_fusion) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_GPS_FUSION; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_GPS_FUSION; } if (AP_Notify::flags.gps_glitching) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_GPS_GLITCH; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_GPS_GLITCH; } if (AP_Notify::flags.have_pos_abs) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_POS_ABS_AVAIL; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_POS_ABS_AVAIL; } if (AP_Notify::flags.leak_detected) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_LEAK_DET; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_LEAK_DET; } if (AP_Notify::flags.parachute_release) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_CHUTE_RELEASED; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_CHUTE_RELEASED; } if (AP_Notify::flags.powering_off) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_POWERING_OFF; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_POWERING_OFF; } if (AP_Notify::flags.pre_arm_check) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_PREARM; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_PREARM; } if (AP_Notify::flags.pre_arm_gps_check) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_PREARM_GPS; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_PREARM_GPS; } if (AP_Notify::flags.save_trim) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_SAVE_TRIM; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_SAVE_TRIM; } if (AP_Notify::flags.vehicle_lost) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_LOST; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_LOST; } if (AP_Notify::flags.video_recording) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_VIDEO_RECORDING; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_VIDEO_RECORDING; } if (AP_Notify::flags.waiting_for_throw) { - msg.vehicle_state |= 1 << ardupilot::indication::NotifyState::VEHICLE_STATE_THROW_READY; + msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_THROW_READY; } - msg.aux_data_type = ardupilot::indication::NotifyState::VEHICLE_YAW_EARTH_CENTIDEGREES; + msg.aux_data_type = ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES; uint16_t yaw_cd = (uint16_t)(360.0f - degrees(AP::ahrs().get_yaw()))*100.0f; const uint8_t *data = (uint8_t *)&yaw_cd; for (uint8_t i=0; i<2; i++) { - msg.aux_data.push_back(data[i]); + msg.aux_data.data[i] = data[i]; } - notify_state[_driver_index]->broadcast(msg); + msg.aux_data.len = 2; + notify_state.broadcast(msg); _last_notify_state_ms = AP_HAL::native_millis(); } @@ -885,16 +733,16 @@ void AP_UAVCAN::gnss_send_fix() send Fix2 packet */ - uavcan::equipment::gnss::Fix2 pkt {}; + uavcan_equipment_gnss_Fix2 pkt {}; const Location &loc = gps.location(); const Vector3f &vel = gps.velocity(); pkt.timestamp.usec = AP_HAL::native_micros64(); pkt.gnss_timestamp.usec = gps.time_epoch_usec(); if (pkt.gnss_timestamp.usec == 0) { - pkt.gnss_time_standard = uavcan::equipment::gnss::Fix2::GNSS_TIME_STANDARD_NONE; + pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_NONE; } else { - pkt.gnss_time_standard = uavcan::equipment::gnss::Fix2::GNSS_TIME_STANDARD_UTC; + pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_UTC; } pkt.longitude_deg_1e8 = uint64_t(loc.lng) * 10ULL; pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL; @@ -907,53 +755,53 @@ void AP_UAVCAN::gnss_send_fix() switch (gps.status()) { case AP_GPS::GPS_Status::NO_GPS: case AP_GPS::GPS_Status::NO_FIX: - pkt.status = uavcan::equipment::gnss::Fix2::STATUS_NO_FIX; - pkt.mode = uavcan::equipment::gnss::Fix2::MODE_SINGLE; - pkt.sub_mode = uavcan::equipment::gnss::Fix2::SUB_MODE_DGPS_OTHER; + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; break; case AP_GPS::GPS_Status::GPS_OK_FIX_2D: - pkt.status = uavcan::equipment::gnss::Fix2::STATUS_2D_FIX; - pkt.mode = uavcan::equipment::gnss::Fix2::MODE_SINGLE; - pkt.sub_mode = uavcan::equipment::gnss::Fix2::SUB_MODE_DGPS_OTHER; + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; break; case AP_GPS::GPS_Status::GPS_OK_FIX_3D: - pkt.status = uavcan::equipment::gnss::Fix2::STATUS_3D_FIX; - pkt.mode = uavcan::equipment::gnss::Fix2::MODE_SINGLE; - pkt.sub_mode = uavcan::equipment::gnss::Fix2::SUB_MODE_DGPS_OTHER; + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; break; case AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS: - pkt.status = uavcan::equipment::gnss::Fix2::STATUS_3D_FIX; - pkt.mode = uavcan::equipment::gnss::Fix2::MODE_DGPS; - pkt.sub_mode = uavcan::equipment::gnss::Fix2::SUB_MODE_DGPS_SBAS; + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_SBAS; break; case AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT: - pkt.status = uavcan::equipment::gnss::Fix2::STATUS_3D_FIX; - pkt.mode = uavcan::equipment::gnss::Fix2::MODE_RTK; - pkt.sub_mode = uavcan::equipment::gnss::Fix2::SUB_MODE_RTK_FLOAT; + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT; break; case AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED: - pkt.status = uavcan::equipment::gnss::Fix2::STATUS_3D_FIX; - pkt.mode = uavcan::equipment::gnss::Fix2::MODE_RTK; - pkt.sub_mode = uavcan::equipment::gnss::Fix2::SUB_MODE_RTK_FIXED; + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED; break; } - pkt.covariance.resize(6); + pkt.covariance.len = 6; float hacc; if (gps.horizontal_accuracy(hacc)) { - pkt.covariance[0] = pkt.covariance[1] = sq(hacc); + pkt.covariance.data[0] = pkt.covariance.data[1] = sq(hacc); } float vacc; if (gps.vertical_accuracy(vacc)) { - pkt.covariance[2] = sq(vacc); + pkt.covariance.data[2] = sq(vacc); } float sacc; if (gps.speed_accuracy(sacc)) { const float vc3 = sq(sacc); - pkt.covariance[3] = pkt.covariance[4] = pkt.covariance[5] = vc3; + pkt.covariance.data[3] = pkt.covariance.data[4] = pkt.covariance.data[5] = vc3; } - gnss_fix2[_driver_index]->broadcast(pkt); + gnss_fix2.broadcast(pkt); @@ -964,24 +812,24 @@ void AP_UAVCAN::gnss_send_fix() /* send aux packet */ - uavcan::equipment::gnss::Auxiliary pkt_auxiliary {}; + uavcan_equipment_gnss_Auxiliary pkt_auxiliary {}; pkt_auxiliary.hdop = gps.get_hdop() * 0.01; pkt_auxiliary.vdop = gps.get_vdop() * 0.01; - gnss_auxiliary[_driver_index]->broadcast(pkt_auxiliary); + gnss_auxiliary.broadcast(pkt_auxiliary); /* send Status packet */ - ardupilot::gnss::Status pkt_status {}; + ardupilot_gnss_Status pkt_status {}; pkt_status.healthy = gps.is_healthy(); if (gps.logging_present() && gps.logging_enabled() && !gps.logging_failed()) { - pkt_status.status |= ardupilot::gnss::Status::STATUS_LOGGING; + pkt_status.status |= ARDUPILOT_GNSS_STATUS_STATUS_LOGGING; } uint8_t idx; // unused if (pkt_status.healthy && !gps.first_unconfigured_gps(idx)) { - pkt_status.status |= ardupilot::gnss::Status::STATUS_ARMABLE; + pkt_status.status |= ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE; } uint32_t error_codes; @@ -989,7 +837,7 @@ void AP_UAVCAN::gnss_send_fix() pkt_status.error_codes = error_codes; } - gnss_status[_driver_index]->broadcast(pkt_status); + gnss_status.broadcast(pkt_status); } } @@ -1009,13 +857,13 @@ void AP_UAVCAN::gnss_send_yaw() _gnss.last_lib_yaw_time_ms = yaw_time_ms; - ardupilot::gnss::Heading pkt_heading {}; + ardupilot_gnss_Heading pkt_heading {}; pkt_heading.heading_valid = true; pkt_heading.heading_accuracy_valid = is_positive(yaw_acc_deg); pkt_heading.heading_rad = radians(yaw_deg); pkt_heading.heading_accuracy_rad = radians(yaw_acc_deg); - gnss_heading[_driver_index]->broadcast(pkt_heading); + gnss_heading.broadcast(pkt_heading); } #endif // AP_DRONECAN_SEND_GPS @@ -1034,20 +882,21 @@ void AP_UAVCAN::rtcm_stream_send() return; } _rtcm_stream.last_send_ms = now; - uavcan::equipment::gnss::RTCMStream msg; + uavcan_equipment_gnss_RTCMStream msg; uint32_t len = _rtcm_stream.buf->available(); if (len > 128) { len = 128; } - msg.protocol_id = uavcan::equipment::gnss::RTCMStream::PROTOCOL_ID_RTCM3; + msg.protocol_id = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_PROTOCOL_ID_RTCM3; for (uint8_t i=0; iread_byte(&b)) { return; } - msg.data.push_back(b); + msg.data.data[i] = b; } - rtcm_stream[_driver_index]->broadcast(msg); + msg.data.len = len; + rtcm_stream.broadcast(msg); } // SafetyState send @@ -1061,26 +910,26 @@ void AP_UAVCAN::safety_state_send() _last_safety_state_ms = now; { // handle SafetyState - ardupilot::indication::SafetyState safety_msg; + ardupilot_indication_SafetyState safety_msg; switch (hal.util->safety_switch_state()) { case AP_HAL::Util::SAFETY_ARMED: - safety_msg.status = ardupilot::indication::SafetyState::STATUS_SAFETY_OFF; + safety_msg.status = ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_OFF; break; case AP_HAL::Util::SAFETY_DISARMED: - safety_msg.status = ardupilot::indication::SafetyState::STATUS_SAFETY_ON; + safety_msg.status = ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON; break; default: // nothing to send break; } - safety_state[_driver_index]->broadcast(safety_msg); + safety_state.broadcast(safety_msg); } { // handle ArmingStatus - uavcan::equipment::safety::ArmingStatus arming_msg; - arming_msg.status = hal.util->get_soft_armed() ? uavcan::equipment::safety::ArmingStatus::STATUS_FULLY_ARMED : - uavcan::equipment::safety::ArmingStatus::STATUS_DISARMED; - arming_status[_driver_index]->broadcast(arming_msg); + uavcan_equipment_safety_ArmingStatus arming_msg; + arming_msg.status = hal.util->get_soft_armed() ? UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED : + UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_DISARMED; + arming_status.broadcast(arming_msg); } } @@ -1104,12 +953,12 @@ void AP_UAVCAN::send_RTCMStream(const uint8_t *data, uint32_t len) /* handle Button message */ -void AP_UAVCAN::handle_button(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ButtonCb &cb) +void AP_UAVCAN::handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg) { - switch (cb.msg->button) { - case ardupilot::indication::Button::BUTTON_SAFETY: { + switch (msg.button) { + case ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY: { AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton(); - if (brdconfig && brdconfig->safety_button_handle_pressed(cb.msg->press_time)) { + if (brdconfig && brdconfig->safety_button_handle_pressed(msg.press_time)) { AP_HAL::Util::safety_state state = hal.util->safety_switch_state(); if (state == AP_HAL::Util::SAFETY_ARMED) { hal.rcout->force_safety_on(); @@ -1125,7 +974,7 @@ void AP_UAVCAN::handle_button(AP_UAVCAN* ap_uavcan, uint8_t node_id, const Butto /* handle traffic report */ -void AP_UAVCAN::handle_traffic_report(AP_UAVCAN* ap_uavcan, uint8_t node_id, const TrafficReportCb &cb) +void AP_UAVCAN::handle_traffic_report(const CanardRxTransfer& transfer, const ardupilot_equipment_trafficmonitor_TrafficReport& msg) { #if HAL_ADSB_ENABLED AP_ADSB *adsb = AP::ADSB(); @@ -1134,7 +983,6 @@ void AP_UAVCAN::handle_traffic_report(AP_UAVCAN* ap_uavcan, uint8_t node_id, con return; } - const ardupilot::equipment::trafficmonitor::TrafficReport &msg = cb.msg[0]; AP_ADSB::adsb_vehicle_t vehicle; mavlink_adsb_vehicle_t &pkt = vehicle.info; @@ -1152,10 +1000,10 @@ void AP_UAVCAN::handle_traffic_report(AP_UAVCAN* ap_uavcan, uint8_t node_id, con } pkt.emitter_type = msg.traffic_type; - if (msg.alt_type == ardupilot::equipment::trafficmonitor::TrafficReport::ALT_TYPE_PRESSURE_AMSL) { + if (msg.alt_type == ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_PRESSURE_AMSL) { pkt.flags |= ADSB_FLAGS_VALID_ALTITUDE; pkt.altitude_type = ADSB_ALTITUDE_TYPE_PRESSURE_QNH; - } else if (msg.alt_type == ardupilot::equipment::trafficmonitor::TrafficReport::ALT_TYPE_WGS84) { + } else if (msg.alt_type == ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_WGS84) { pkt.flags |= ADSB_FLAGS_VALID_ALTITUDE; pkt.altitude_type = ADSB_ALTITUDE_TYPE_GEOMETRIC; } @@ -1193,15 +1041,15 @@ void AP_UAVCAN::handle_traffic_report(AP_UAVCAN* ap_uavcan, uint8_t node_id, con /* handle actuator status message */ -void AP_UAVCAN::handle_actuator_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ActuatorStatusCb &cb) +void AP_UAVCAN::handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg) { // log as CSRV message AP::logger().Write_ServoStatus(AP_HAL::native_micros64(), - cb.msg->actuator_id, - cb.msg->position, - cb.msg->force, - cb.msg->speed, - cb.msg->power_rating_pct); + msg.actuator_id, + msg.position, + msg.force, + msg.speed, + msg.power_rating_pct); } #if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED @@ -1226,27 +1074,27 @@ void AP_UAVCAN::handle_actuator_status_Volz(AP_UAVCAN* ap_uavcan, uint8_t node_i /* handle ESC status message */ -void AP_UAVCAN::handle_ESC_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ESCStatusCb &cb) +void AP_UAVCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg) { #if HAL_WITH_ESC_TELEM - const uint8_t esc_offset = constrain_int16(ap_uavcan->_esc_offset.get(), 0, UAVCAN_SRV_NUMBER); - const uint8_t esc_index = cb.msg->esc_index + esc_offset; + const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, UAVCAN_SRV_NUMBER); + const uint8_t esc_index = msg.esc_index + esc_offset; if (!is_esc_data_index_valid(esc_index)) { return; } TelemetryData t { - .temperature_cdeg = int16_t((KELVIN_TO_C(cb.msg->temperature)) * 100), - .voltage = cb.msg->voltage, - .current = cb.msg->current, + .temperature_cdeg = int16_t((KELVIN_TO_C(msg.temperature)) * 100), + .voltage = msg.voltage, + .current = msg.current, }; - ap_uavcan->update_rpm(esc_index, cb.msg->rpm, cb.msg->error_count); - ap_uavcan->update_telem_data(esc_index, t, - (isnan(cb.msg->current) ? 0 : AP_ESC_Telem_Backend::TelemetryType::CURRENT) - | (isnan(cb.msg->voltage) ? 0 : AP_ESC_Telem_Backend::TelemetryType::VOLTAGE) - | (isnan(cb.msg->temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE)); + update_rpm(esc_index, msg.rpm, msg.error_count); + update_telem_data(esc_index, t, + (isnan(msg.current) ? 0 : AP_ESC_Telem_Backend::TelemetryType::CURRENT) + | (isnan(msg.voltage) ? 0 : AP_ESC_Telem_Backend::TelemetryType::VOLTAGE) + | (isnan(msg.temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE)); #endif } @@ -1261,16 +1109,15 @@ bool AP_UAVCAN::is_esc_data_index_valid(const uint8_t index) { /* handle LogMessage debug */ -void AP_UAVCAN::handle_debug(AP_UAVCAN* ap_uavcan, uint8_t node_id, const DebugCb &cb) +void AP_UAVCAN::handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg) { #if HAL_LOGGING_ENABLED - const auto &msg = *cb.msg; if (AP::can().get_log_level() != AP_CANManager::LOG_NONE) { // log to onboard log and mavlink - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CAN[%u] %s", node_id, msg.text.c_str()); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CAN[%u] %s", transfer.source_node_id, msg.text.data); } else { // only log to onboard log - AP::logger().Write_MessageF("CAN[%u] %s", node_id, msg.text.c_str()); + AP::logger().Write_MessageF("CAN[%u] %s", transfer.source_node_id, msg.text.data); } #endif } @@ -1281,7 +1128,7 @@ void AP_UAVCAN::send_parameter_request() if (param_request_sent) { return; } - param_get_set_client[_driver_index]->call(param_request_node_id, param_getset_req[_driver_index]); + param_get_set_client.request(param_request_node_id, param_getset_req); param_request_sent = true; } @@ -1293,9 +1140,10 @@ bool AP_UAVCAN::set_parameter_on_node(uint8_t node_id, const char *name, float v //busy return false; } - param_getset_req[_driver_index].index = 0; - param_getset_req[_driver_index].name = name; - param_getset_req[_driver_index].value.to() = value; + param_getset_req.index = 0; + param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)-1); + param_getset_req.value.real_value = value; + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE; param_float_cb = cb; param_request_sent = false; param_request_node_id = node_id; @@ -1310,9 +1158,10 @@ bool AP_UAVCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32_t //busy return false; } - param_getset_req[_driver_index].index = 0; - param_getset_req[_driver_index].name = name; - param_getset_req[_driver_index].value.to() = value; + param_getset_req.index = 0; + param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)-1); + param_getset_req.value.integer_value = value; + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; param_int_cb = cb; param_request_sent = false; param_request_node_id = node_id; @@ -1327,9 +1176,9 @@ bool AP_UAVCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGe //busy return false; } - param_getset_req[_driver_index].index = 0; - param_getset_req[_driver_index].name = name; - param_getset_req[_driver_index].value.to(); + param_getset_req.index = 0; + param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)); + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY; param_float_cb = cb; param_request_sent = false; param_request_node_id = node_id; @@ -1344,50 +1193,49 @@ bool AP_UAVCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGe //busy return false; } - param_getset_req[_driver_index].index = 0; - param_getset_req[_driver_index].name = name; - param_getset_req[_driver_index].value.to(); + param_getset_req.index = 0; + param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)); + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY; param_int_cb = cb; param_request_sent = false; param_request_node_id = node_id; return true; } -void AP_UAVCAN::handle_param_get_set_response(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ParamGetSetCb &cb) +void AP_UAVCAN::handle_param_get_set_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_GetSetResponse& rsp) { - WITH_SEMAPHORE(ap_uavcan->_param_sem); - if (!ap_uavcan->param_int_cb && - !ap_uavcan->param_float_cb) { + WITH_SEMAPHORE(_param_sem); + if (!param_int_cb && + !param_float_cb) { return; } - uavcan::protocol::param::GetSet::Response rsp = cb.rsp->getResponse(); - if (rsp.value.is(uavcan::protocol::param::Value::Tag::integer_value) && ap_uavcan->param_int_cb) { - int32_t val = rsp.value.to(); - if ((*ap_uavcan->param_int_cb)(ap_uavcan, node_id, rsp.name.c_str(), val)) { + if ((rsp.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) && param_int_cb) { + int32_t val = rsp.value.integer_value; + if ((*param_int_cb)(this, transfer.source_node_id, (const char*)rsp.name.data, val)) { // we want the parameter to be set with val - param_getset_req[ap_uavcan->_driver_index].index = 0; - param_getset_req[ap_uavcan->_driver_index].name = rsp.name; - param_getset_req[ap_uavcan->_driver_index].value.to() = val; - ap_uavcan->param_int_cb = ap_uavcan->param_int_cb; - ap_uavcan->param_request_sent = false; - ap_uavcan->param_request_node_id = node_id; + param_getset_req.index = 0; + memcpy(param_getset_req.name.data, rsp.name.data, rsp.name.len); + param_getset_req.value.integer_value = val; + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + param_request_sent = false; + param_request_node_id = transfer.source_node_id; return; } - } else if (rsp.value.is(uavcan::protocol::param::Value::Tag::real_value) && ap_uavcan->param_float_cb) { - float val = rsp.value.to(); - if ((*ap_uavcan->param_float_cb)(ap_uavcan, node_id, rsp.name.c_str(), val)) { + } else if ((rsp.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE) && param_float_cb) { + float val = rsp.value.real_value; + if ((*param_float_cb)(this, transfer.source_node_id, (const char*)rsp.name.data, val)) { // we want the parameter to be set with val - param_getset_req[ap_uavcan->_driver_index].index = 0; - param_getset_req[ap_uavcan->_driver_index].name = rsp.name; - param_getset_req[ap_uavcan->_driver_index].value.to() = val; - ap_uavcan->param_float_cb = ap_uavcan->param_float_cb; - ap_uavcan->param_request_sent = false; - ap_uavcan->param_request_node_id = node_id; + param_getset_req.index = 0; + memcpy(param_getset_req.name.data, rsp.name.data, rsp.name.len); + param_getset_req.value.real_value = val; + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE; + param_request_sent = false; + param_request_node_id = transfer.source_node_id; return; } } - ap_uavcan->param_int_cb = nullptr; - ap_uavcan->param_float_cb = nullptr; + param_int_cb = nullptr; + param_float_cb = nullptr; } @@ -1397,7 +1245,7 @@ void AP_UAVCAN::send_parameter_save_request() if (param_save_request_sent) { return; } - param_execute_opcode_client[_driver_index]->call(param_save_request_node_id, param_save_req[_driver_index]); + param_save_client.request(param_save_request_node_id, param_save_req); param_save_request_sent = true; } @@ -1409,7 +1257,7 @@ bool AP_UAVCAN::save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb) return false; } - param_save_req[_driver_index].opcode = uavcan::protocol::param::ExecuteOpcode::Request::OPCODE_SAVE; + param_save_req.opcode = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_SAVE; param_save_request_sent = false; param_save_request_node_id = node_id; save_param_cb = cb; @@ -1417,15 +1265,14 @@ bool AP_UAVCAN::save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb) } // handle parameter save request response -void AP_UAVCAN::handle_param_save_response(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ParamExecuteOpcodeCb &cb) +void AP_UAVCAN::handle_param_save_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_ExecuteOpcodeResponse& rsp) { - WITH_SEMAPHORE(ap_uavcan->_param_save_sem); - if (!ap_uavcan->save_param_cb) { + WITH_SEMAPHORE(_param_save_sem); + if (!save_param_cb) { return; } - uavcan::protocol::param::ExecuteOpcode::Response rsp = cb.rsp->getResponse(); - (*ap_uavcan->save_param_cb)(ap_uavcan, node_id, rsp.ok); - ap_uavcan->save_param_cb = nullptr; + (*save_param_cb)(this, transfer.source_node_id, rsp.ok); + save_param_cb = nullptr; } // Send Reboot command @@ -1433,15 +1280,9 @@ void AP_UAVCAN::handle_param_save_response(AP_UAVCAN* ap_uavcan, uint8_t node_id // THIS IS NOT A THREAD SAFE API! void AP_UAVCAN::send_reboot_request(uint8_t node_id) { - if (_node == nullptr) { - return; - } - uavcan::protocol::RestartNode::Request request; - request.magic_number = uavcan::protocol::RestartNode::Request::MAGIC_NUMBER; - uavcan::ServiceClient client(*_node); - client.setCallback([](const uavcan::ServiceCallResult& call_result){}); - - client.call(node_id, request); + uavcan_protocol_RestartNodeRequest request; + request.magic_number = UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAGIC_NUMBER; + restart_node_client.request(node_id, request); } // check if a option is set and if it is then reset it to 0. @@ -1459,7 +1300,7 @@ bool AP_UAVCAN::check_and_reset_option(Options option) bool AP_UAVCAN::prearm_check(char* fail_msg, uint8_t fail_msg_len) const { // forward this to DNA_Server - return _dna_server->prearm_check(fail_msg, fail_msg_len); + return _dna_server.prearm_check(fail_msg, fail_msg_len); } /* diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.h b/libraries/AP_UAVCAN/AP_UAVCAN.h index cf11dcf773ffcc..ad2d2680605320 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN.h +++ b/libraries/AP_UAVCAN/AP_UAVCAN.h @@ -20,17 +20,20 @@ #if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include -#include "AP_UAVCAN_IfaceMgr.h" -#include "AP_UAVCAN_Clock.h" +#include "AP_Canard_iface.h" #include #include #include #include -#include -#include #include - +#include +#include +#include +#include +#include +#include "AP_UAVCAN_DNA_Server.h" +#include +#include #ifndef UAVCAN_SRV_NUMBER #define UAVCAN_SRV_NUMBER NUM_SERVO_CHANNELS @@ -49,63 +52,12 @@ #define AP_UAVCAN_MAX_LED_DEVICES 4 // fwd-declare callback classes -class ButtonCb; -class TrafficReportCb; -class ActuatorStatusCb; -class ActuatorStatusVolzCb; -class ESCStatusCb; -class DebugCb; -class ParamGetSetCb; -class ParamExecuteOpcodeCb; -class AP_PoolAllocator; class AP_UAVCAN_DNA_Server; -#if defined(__GNUC__) && (__GNUC__ > 8) -#define DISABLE_W_CAST_FUNCTION_TYPE_PUSH \ - _Pragma("GCC diagnostic push") \ - _Pragma("GCC diagnostic ignored \"-Wcast-function-type\"") -#define DISABLE_W_CAST_FUNCTION_TYPE_POP \ - _Pragma("GCC diagnostic pop") -#else -#define DISABLE_W_CAST_FUNCTION_TYPE_PUSH -#define DISABLE_W_CAST_FUNCTION_TYPE_POP -#endif -#if defined(__GNUC__) && (__GNUC__ >= 11) -#define DISABLE_W_CAST_FUNCTION_TYPE_WITH_VOID (void*) -#else -#define DISABLE_W_CAST_FUNCTION_TYPE_WITH_VOID -#endif - -/* - Frontend Backend-Registry Binder: Whenever a message of said DataType_ from new node is received, - the Callback will invoke registry to register the node as separate backend. -*/ -#define UC_REGISTRY_BINDER(ClassName_, DataType_) \ - class ClassName_ : public AP_UAVCAN::RegistryBinder { \ - typedef void (*CN_Registry)(AP_UAVCAN*, uint8_t, const ClassName_&); \ - public: \ - ClassName_() : RegistryBinder() {} \ - DISABLE_W_CAST_FUNCTION_TYPE_PUSH \ - ClassName_(AP_UAVCAN* uc, CN_Registry ffunc) : \ - RegistryBinder(uc, (Registry)DISABLE_W_CAST_FUNCTION_TYPE_WITH_VOID ffunc) {} \ - DISABLE_W_CAST_FUNCTION_TYPE_POP \ - } - -#define UC_CLIENT_CALL_REGISTRY_BINDER(ClassName_, DataType_) \ - class ClassName_ : public AP_UAVCAN::ClientCallRegistryBinder { \ - typedef void (*CN_Registry)(AP_UAVCAN*, uint8_t, const ClassName_&); \ - public: \ - ClassName_() : ClientCallRegistryBinder() {} \ - DISABLE_W_CAST_FUNCTION_TYPE_PUSH \ - ClassName_(AP_UAVCAN* uc, CN_Registry ffunc) : \ - ClientCallRegistryBinder(uc, (ClientCallRegistry)DISABLE_W_CAST_FUNCTION_TYPE_WITH_VOID ffunc) {} \ - DISABLE_W_CAST_FUNCTION_TYPE_POP \ - } - class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { friend class AP_UAVCAN_DNA_Server; public: - AP_UAVCAN(); + AP_UAVCAN(const int driver_index); ~AP_UAVCAN(); static const struct AP_Param::GroupInfo var_info[]; @@ -117,13 +69,14 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { void init(uint8_t driver_index, bool enable_filters) override; bool add_interface(AP_HAL::CANIface* can_iface) override; - uavcan::Node<0>* get_node() { return _node; } uint8_t get_driver_index() const { return _driver_index; } FUNCTOR_TYPEDEF(ParamGetSetIntCb, bool, AP_UAVCAN*, const uint8_t, const char*, int32_t &); FUNCTOR_TYPEDEF(ParamGetSetFloatCb, bool, AP_UAVCAN*, const uint8_t, const char*, float &); FUNCTOR_TYPEDEF(ParamSaveCb, void, AP_UAVCAN*, const uint8_t, bool); + void send_node_status(); + ///// SRV output ///// void SRV_push_servos(void); @@ -138,7 +91,7 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { // Send Reboot command // Note: Do not call this from outside UAVCAN thread context, - // you can call this from uavcan callbacks and handlers. + // you can call this from dronecan callbacks and handlers. // THIS IS NOT A THREAD SAFE API! void send_reboot_request(uint8_t node_id); @@ -151,57 +104,6 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { // Save parameters bool save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb); - template - class RegistryBinder { - protected: - typedef void (*Registry)(AP_UAVCAN* _ap_uavcan, uint8_t _node_id, const RegistryBinder& _cb); - AP_UAVCAN* _uc; - Registry _ffunc; - - public: - RegistryBinder() : - _uc(), - _ffunc(), - msg() {} - - RegistryBinder(AP_UAVCAN* uc, Registry ffunc) : - _uc(uc), - _ffunc(ffunc), - msg(nullptr) {} - - void operator()(const uavcan::ReceivedDataStructure& _msg) { - msg = &_msg; - _ffunc(_uc, _msg.getSrcNodeID().get(), *this); - } - - const uavcan::ReceivedDataStructure *msg; - }; - - // ClientCallRegistryBinder - template - class ClientCallRegistryBinder { - protected: - typedef void (*ClientCallRegistry)(AP_UAVCAN* _ap_uavcan, uint8_t _node_id, const ClientCallRegistryBinder& _cb); - AP_UAVCAN* _uc; - ClientCallRegistry _ffunc; - public: - ClientCallRegistryBinder() : - _uc(), - _ffunc(), - rsp() {} - - ClientCallRegistryBinder(AP_UAVCAN* uc, ClientCallRegistry ffunc) : - _uc(uc), - _ffunc(ffunc), - rsp(nullptr) {} - - void operator()(const uavcan::ServiceCallResult& _rsp) { - rsp = &_rsp; - _ffunc(_uc, _rsp.getCallID().server_node_id.get(), *this); - } - const uavcan::ServiceCallResult *rsp; - }; - // options bitmask enum class Options : uint16_t { DNA_CLEAR_DATABASE = (1U<<0), @@ -221,9 +123,7 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { // 0. return true if it was set bool check_and_reset_option(Options option); - // This will be needed to implement if UAVCAN is used with multithreading - // Such cases will be firmware update, etc. - class RaiiSynchronizer {}; + CanardInterface& get_canard_iface() { return canard_iface; } private: void loop(void); @@ -270,7 +170,7 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { uint8_t param_save_request_node_id; // UAVCAN parameters - AP_Int8 _uavcan_node; + AP_Int8 _dronecan_node; AP_Int32 _servo_bm; AP_Int32 _esc_bm; AP_Int8 _esc_offset; @@ -279,14 +179,12 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { AP_Int16 _notify_state_hz; AP_Int16 _pool_size; - AP_PoolAllocator *_allocator; - AP_UAVCAN_DNA_Server *_dna_server; + uint32_t *mem_pool; - uavcan::Node<0> *_node; + AP_UAVCAN_DNA_Server _dna_server; uint8_t _driver_index; - uavcan::CanIfaceMgr* _iface_mgr; char _thread_name[13]; bool _initialized; ///// SRV output ///// @@ -355,22 +253,80 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { static HAL_Semaphore _telem_sem; + // node status send + uint32_t _node_status_last_send_ms; + // safety status send state uint32_t _last_safety_state_ms; // notify vehicle state uint32_t _last_notify_state_ms; + uavcan_protocol_NodeStatus node_status_msg; + + CanardInterface canard_iface; + Canard::Publisher node_status{canard_iface}; + Canard::Publisher act_out_array{canard_iface}; + Canard::Publisher esc_raw{canard_iface}; + Canard::Publisher rgb_led{canard_iface}; + Canard::Publisher buzzer{canard_iface}; + Canard::Publisher safety_state{canard_iface}; + Canard::Publisher arming_status{canard_iface}; + Canard::Publisher rtcm_stream{canard_iface}; + Canard::Publisher notify_state{canard_iface}; + +#if AP_DRONECAN_SEND_GPS + Canard::Publisher gnss_fix2{canard_iface}; + Canard::Publisher gnss_auxiliary{canard_iface}; + Canard::Publisher gnss_heading{canard_iface}; + Canard::Publisher gnss_status{canard_iface}; +#endif + // incoming messages + Canard::ObjCallback safety_button_cb{this, &AP_UAVCAN::handle_button}; + Canard::Subscriber safety_button_listener{safety_button_cb, _driver_index}; + + Canard::ObjCallback traffic_report_cb{this, &AP_UAVCAN::handle_traffic_report}; + Canard::Subscriber traffic_report_listener{traffic_report_cb, _driver_index}; + + Canard::ObjCallback actuator_status_cb{this, &AP_UAVCAN::handle_actuator_status}; + Canard::Subscriber actuator_status_listener{actuator_status_cb, _driver_index}; + + Canard::ObjCallback esc_status_cb{this, &AP_UAVCAN::handle_ESC_status}; + Canard::Subscriber esc_status_listener{esc_status_cb, _driver_index}; + + Canard::ObjCallback debug_cb{this, &AP_UAVCAN::handle_debug}; + Canard::Subscriber debug_listener{debug_cb, _driver_index}; + + // param client + Canard::ObjCallback param_get_set_res_cb{this, &AP_UAVCAN::handle_param_get_set_response}; + Canard::Client param_get_set_client{canard_iface, param_get_set_res_cb}; + + Canard::ObjCallback param_save_res_cb{this, &AP_UAVCAN::handle_param_save_response}; + Canard::Client param_save_client{canard_iface, param_save_res_cb}; + + // reboot client + void handle_restart_node_response(const CanardRxTransfer& transfer, const uavcan_protocol_RestartNodeResponse& msg) {} + Canard::ObjCallback restart_node_res_cb{this, &AP_UAVCAN::handle_restart_node_response}; + Canard::Client restart_node_client{canard_iface, restart_node_res_cb}; + + uavcan_protocol_param_ExecuteOpcodeRequest param_save_req; + uavcan_protocol_param_GetSetRequest param_getset_req; + + // Node Info Server + Canard::ObjCallback node_info_req_cb{this, &AP_UAVCAN::handle_node_info_request}; + Canard::Server node_info_server{canard_iface, node_info_req_cb}; + uavcan_protocol_GetNodeInfoResponse node_info_rsp; // incoming button handling - static void handle_button(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ButtonCb &cb); - static void handle_traffic_report(AP_UAVCAN* ap_uavcan, uint8_t node_id, const TrafficReportCb &cb); - static void handle_actuator_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ActuatorStatusCb &cb); - static void handle_actuator_status_Volz(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ActuatorStatusVolzCb &cb); - static void handle_ESC_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ESCStatusCb &cb); + void handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg); + void handle_traffic_report(const CanardRxTransfer& transfer, const ardupilot_equipment_trafficmonitor_TrafficReport& msg); + void handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg); + void handle_actuator_status_Volz(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg); + void handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg); static bool is_esc_data_index_valid(const uint8_t index); - static void handle_debug(AP_UAVCAN* ap_uavcan, uint8_t node_id, const DebugCb &cb); - static void handle_param_get_set_response(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ParamGetSetCb &cb); - static void handle_param_save_response(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ParamExecuteOpcodeCb &cb); + void handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg); + void handle_param_get_set_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_GetSetResponse& rsp); + void handle_param_save_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_ExecuteOpcodeResponse& rsp); + void handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req); }; #endif // #if HAL_ENABLE_LIBUAVCAN_DRIVERS diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_Clock.h b/libraries/AP_UAVCAN/AP_UAVCAN_Clock.h deleted file mode 100644 index eba4923a3c2f6c..00000000000000 --- a/libraries/AP_UAVCAN/AP_UAVCAN_Clock.h +++ /dev/null @@ -1,59 +0,0 @@ -/* - * This file is free software: you can redistribute it and/or modify it - * under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program. If not, see . - * - * Author: Siddharth Bharat Purohit - */ - - -#pragma once - -#include - -namespace uavcan -{ -class SystemClock: public uavcan::ISystemClock, uavcan::Noncopyable -{ -public: - SystemClock() = default; - - void adjustUtc(uavcan::UtcDuration adjustment) override - { - utc_adjustment_usec = adjustment.toUSec(); - } - - uavcan::MonotonicTime getMonotonic() const override - { - return uavcan::MonotonicTime::fromUSec(AP_HAL::native_micros64()); - } - - uavcan::UtcTime getUtc() const override - { - return uavcan::UtcTime::fromUSec(AP_HAL::native_micros64() + utc_adjustment_usec); - } - - int64_t getAdjustUsec() const - { - return utc_adjustment_usec; - } - - static SystemClock& instance() - { - static SystemClock inst; - return inst; - } - -private: - int64_t utc_adjustment_usec; -}; -} \ No newline at end of file diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp index 0e1b50cd035cdd..72c6019f833f3a 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp @@ -24,11 +24,10 @@ #include "AP_UAVCAN.h" #include #include -#include #include #include -#include "AP_UAVCAN_Clock.h" #include +#include extern const AP_HAL::HAL& hal; #define NODEDATA_MAGIC 0xAC01 @@ -37,56 +36,15 @@ extern const AP_HAL::HAL& hal; #define debug_uavcan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "UAVCAN", fmt, ##args); } while (0) -//Callback Object Definitions -UC_REGISTRY_BINDER(AllocationCb, uavcan::protocol::dynamic_node_id::Allocation); -UC_REGISTRY_BINDER(NodeStatusCb, uavcan::protocol::NodeStatus); -UC_CLIENT_CALL_REGISTRY_BINDER(GetNodeInfoCb, uavcan::protocol::GetNodeInfo); - -static uavcan::ServiceClient* getNodeInfo_client[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -static uavcan::Publisher* allocation_pub[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -AP_UAVCAN_DNA_Server::AP_UAVCAN_DNA_Server(AP_UAVCAN *ap_uavcan, StorageAccess _storage) : +AP_UAVCAN_DNA_Server::AP_UAVCAN_DNA_Server(AP_UAVCAN &ap_uavcan) : _ap_uavcan(ap_uavcan), - storage(_storage) + _canard_iface(ap_uavcan.canard_iface), + storage(StorageManager::StorageCANDNA), + allocation_sub(allocation_cb, _ap_uavcan.get_driver_index()), + node_status_sub(node_status_cb, _ap_uavcan.get_driver_index()), + node_info_client(_canard_iface, node_info_cb) {} -/* Subscribe to all the messages we are going to handle for -Server registry and Node allocation. */ -void AP_UAVCAN_DNA_Server::subscribe_msgs(AP_UAVCAN* ap_uavcan) -{ - if (ap_uavcan == nullptr) { - return; - } - - auto* node = ap_uavcan->get_node(); - //Register Allocation Message Handler - uavcan::Subscriber *AllocationListener; - AllocationListener = new uavcan::Subscriber(*node); - if (AllocationListener == nullptr) { - AP_BoardConfig::allocation_error("AP_UAVCAN_DNA: AllocationListener"); - } - const int alloc_listener_res = AllocationListener->start(AllocationCb(ap_uavcan, &trampoline_handleAllocation)); - if (alloc_listener_res < 0) { - AP_HAL::panic("Allocation Subscriber start problem\n\r"); - return; - } - //We allow anonymous transfers, as they are specifically for Node Allocation - AllocationListener->allowAnonymousTransfers(); - - //Register Node Status Listener - uavcan::Subscriber *NodeStatusListener; - NodeStatusListener = new uavcan::Subscriber(*node); - if (NodeStatusListener == nullptr) { - AP_BoardConfig::allocation_error("AP_UAVCAN_DNA: NodeStatusListener"); - } - const int nodestatus_listener_res = NodeStatusListener->start(NodeStatusCb(ap_uavcan, &trampoline_handleNodeStatus)); - if (nodestatus_listener_res < 0) { - AP_HAL::panic("NodeStatus Subscriber start problem\n\r"); - return; - } -} - /* Method to generate 6byte hash from the Unique ID. We return it packed inside the referenced NodeData structure */ void AP_UAVCAN_DNA_Server::getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const @@ -255,43 +213,10 @@ bool AP_UAVCAN_DNA_Server::isValidNodeDataAvailable(uint8_t node_id) Also resets the Server Record in case there is a mismatch between specified node id and unique id against the existing Server Record. */ -bool AP_UAVCAN_DNA_Server::init() +bool AP_UAVCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id) { - //Read the details from ap_uavcan - uavcan::Node<0>* _node = _ap_uavcan->get_node(); - uint8_t node_id = _node->getNodeID().get(); - uint8_t own_unique_id[16] = {0}; - uint8_t own_unique_id_len = 16; - - driver_index = _ap_uavcan->get_driver_index(); - - //copy unique id from node to uint8_t array - uavcan::copy(_node->getHardwareVersion().unique_id.begin(), - _node->getHardwareVersion().unique_id.end(), - own_unique_id); - + //Read the details from AP_UAVCAN server_state = HEALTHY; - - //Setup publisher for this driver index - allocation_pub[driver_index] = new uavcan::Publisher(*_node, true); - if (allocation_pub[driver_index] == nullptr) { - AP_BoardConfig::allocation_error("AP_UAVCAN_DNA: allocation_pub[%d]", driver_index); - } - - int res = allocation_pub[driver_index]->init(uavcan::TransferPriority::Default); - if (res < 0) { - return false; - } - allocation_pub[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(uavcan::protocol::dynamic_node_id::Allocation::FOLLOWUP_TIMEOUT_MS)); - - - //Setup GetNodeInfo Client - getNodeInfo_client[driver_index] = new uavcan::ServiceClient(*_node, GetNodeInfoCb(_ap_uavcan, &trampoline_handleNodeInfo)); - if (getNodeInfo_client[driver_index] == nullptr) { - AP_BoardConfig::allocation_error("AP_UAVCAN_DNA: getNodeInfo_client[%d]", driver_index); - } - - /* Go through our records and look for valid NodeData, to initialise occupation mask */ for (uint8_t i = 0; i <= MAX_NODE_ID; i++) { @@ -310,7 +235,7 @@ bool AP_UAVCAN_DNA_Server::init() //Its not there a reset should write it in the Storage reset(); } - if (_ap_uavcan->check_and_reset_option(AP_UAVCAN::Options::DNA_CLEAR_DATABASE)) { + if (_ap_uavcan.check_and_reset_option(AP_UAVCAN::Options::DNA_CLEAR_DATABASE)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UC DNA database reset"); reset(); } @@ -350,7 +275,7 @@ bool AP_UAVCAN_DNA_Server::init() addToSeenNodeMask(node_id); setVerificationMask(node_id); node_healthy_mask.set(node_id); - self_node_id[driver_index] = node_id; + self_node_id = node_id; return true; } @@ -422,7 +347,7 @@ seen list, So that we can raise issue if there are duplicates on the bus. */ void AP_UAVCAN_DNA_Server::verify_nodes() { - uint32_t now = uavcan::SystemClock::instance().getMonotonic().toMSec(); + uint32_t now = AP_HAL::millis(); if ((now - last_verification_request) < 5000) { return; } @@ -435,7 +360,7 @@ void AP_UAVCAN_DNA_Server::verify_nodes() //Check if we got acknowledgement from previous request //except for requests using our own node_id - if (curr_verifying_node == self_node_id[driver_index]) { + if (curr_verifying_node == self_node_id) { nodeInfo_resp_rcvd = true; } @@ -456,13 +381,16 @@ void AP_UAVCAN_DNA_Server::verify_nodes() //Find the next registered Node ID to be verified. for (uint8_t i = 0; i <= MAX_NODE_ID; i++) { curr_verifying_node = (curr_verifying_node + 1) % (MAX_NODE_ID + 1); + if ((curr_verifying_node == self_node_id) || (curr_verifying_node == 0)) { + continue; + } if (isNodeSeen(curr_verifying_node)) { break; } } - if (getNodeInfo_client[driver_index] != nullptr && isNodeIDOccupied(curr_verifying_node)) { - uavcan::protocol::GetNodeInfo::Request request; - getNodeInfo_client[driver_index]->call(curr_verifying_node, request); + if (isNodeIDOccupied(curr_verifying_node)) { + uavcan_protocol_GetNodeInfoRequest request; + node_info_client.request(curr_verifying_node, request); nodeInfo_resp_rcvd = false; } } @@ -470,63 +398,50 @@ void AP_UAVCAN_DNA_Server::verify_nodes() /* Handles Node Status Message, adds to the Seen Node list Also starts the Service call for Node Info to complete the Verification process. */ -void AP_UAVCAN_DNA_Server::handleNodeStatus(uint8_t node_id, const NodeStatusCb &cb) +void AP_UAVCAN_DNA_Server::handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg) { - if (node_id > MAX_NODE_ID) { + if (transfer.source_node_id > MAX_NODE_ID || transfer.source_node_id == 0) { return; } - if ((cb.msg->health != uavcan::protocol::NodeStatus::HEALTH_OK || - cb.msg->mode != uavcan::protocol::NodeStatus::MODE_OPERATIONAL) && - !_ap_uavcan->option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { + if ((msg.health != UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK || + msg.mode != UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL) && + !_ap_uavcan.option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { //if node is not healthy or operational, clear resp health mask, and set fault_node_id - fault_node_id = node_id; + fault_node_id = transfer.source_node_id; server_state = NODE_STATUS_UNHEALTHY; - node_healthy_mask.clear(node_id); + node_healthy_mask.clear(transfer.source_node_id); } else { - node_healthy_mask.set(node_id); + node_healthy_mask.set(transfer.source_node_id); if (node_healthy_mask == verified_mask) { server_state = HEALTHY; } } - if (!isNodeIDVerified(node_id)) { + if (!isNodeIDVerified(transfer.source_node_id)) { //immediately begin verification of the node_id - if (getNodeInfo_client[driver_index] != nullptr) { - uavcan::protocol::GetNodeInfo::Request request; - getNodeInfo_client[driver_index]->call(node_id, request); - } + uavcan_protocol_GetNodeInfoRequest request; + node_info_client.request(transfer.source_node_id, request); } //Add node to seen list if not seen before - addToSeenNodeMask(node_id); -} - -//Trampoline call for handleNodeStatus member method -void AP_UAVCAN_DNA_Server::trampoline_handleNodeStatus(AP_UAVCAN* ap_uavcan, uint8_t node_id, const NodeStatusCb &cb) -{ - if (ap_uavcan == nullptr) { - return; - } - - ap_uavcan->_dna_server->handleNodeStatus(node_id, cb); + addToSeenNodeMask(transfer.source_node_id); } - /* Node Info message handler Handle responses from GetNodeInfo Request. We verify the node info against our records. Marks Verification mask if already recorded, Or register if the node id is available and not recorded for the received Unique ID */ -void AP_UAVCAN_DNA_Server::handleNodeInfo(uint8_t node_id, uint8_t unique_id[], char name[], uint8_t major, uint8_t minor, uint32_t vcs_commit) +void AP_UAVCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp) { - if (node_id > MAX_NODE_ID) { + if (transfer.source_node_id > MAX_NODE_ID) { return; } /* if we haven't logged this node then log it now */ - if (!logged.get(node_id) && AP::logger().logging_started()) { - logged.set(node_id); + if (!logged.get(transfer.source_node_id) && AP::logger().logging_started()) { + logged.set(transfer.source_node_id); uint64_t uid[2]; - memcpy(uid, unique_id, sizeof(uid)); + memcpy(uid, rsp.hardware_version.unique_id, sizeof(rsp.hardware_version.unique_id)); // @LoggerMessage: CAND // @Description: Info from GetNodeInfo request // @Field: TimeUS: Time since system startup @@ -540,105 +455,82 @@ void AP_UAVCAN_DNA_Server::handleNodeInfo(uint8_t node_id, uint8_t unique_id[], AP::logger().Write("CAND", "TimeUS,NodeId,UID1,UID2,Name,Major,Minor,Version", "s#------", "F-------", "QBQQZBBI", AP_HAL::micros64(), - node_id, + transfer.source_node_id, uid[0], uid[1], - name, - major, - minor, - vcs_commit); + rsp.name.data, + rsp.software_version.major, + rsp.software_version.minor, + rsp.software_version.vcs_commit); } - if (isNodeIDOccupied(node_id)) { + if (isNodeIDOccupied(transfer.source_node_id)) { //if node_id already registered, just verify if Unique ID matches as well - if (node_id == getNodeIDForUniqueID(unique_id, 16)) { - if (node_id == curr_verifying_node) { + if (transfer.source_node_id == getNodeIDForUniqueID(rsp.hardware_version.unique_id, 16)) { + if (transfer.source_node_id == curr_verifying_node) { nodeInfo_resp_rcvd = true; } - setVerificationMask(node_id); - } else if (!_ap_uavcan->option_is_set(AP_UAVCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { + setVerificationMask(transfer.source_node_id); + } else if (!_ap_uavcan.option_is_set(AP_UAVCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { /* This is a device with node_id already registered for another device */ server_state = DUPLICATE_NODES; - fault_node_id = node_id; - memcpy(fault_node_name, name, sizeof(fault_node_name)); + fault_node_id = transfer.source_node_id; + memcpy(fault_node_name, rsp.name.data, sizeof(fault_node_name)); } } else { /* Node Id was not allocated by us, or during this boot, let's register this in our records Check if we allocated this Node before */ - uint8_t prev_node_id = getNodeIDForUniqueID(unique_id, 16); + uint8_t prev_node_id = getNodeIDForUniqueID(rsp.hardware_version.unique_id, 16); if (prev_node_id != 255) { //yes we did, remove this registration freeNodeID(prev_node_id); } //add a new server record - addNodeIDForUniqueID(node_id, unique_id, 16); + addNodeIDForUniqueID(transfer.source_node_id, rsp.hardware_version.unique_id, 16); //Verify as well - setVerificationMask(node_id); - if (node_id == curr_verifying_node) { + setVerificationMask(transfer.source_node_id); + if (transfer.source_node_id == curr_verifying_node) { nodeInfo_resp_rcvd = true; } } } -//Trampoline call for handleNodeInfo member call -void AP_UAVCAN_DNA_Server::trampoline_handleNodeInfo(AP_UAVCAN* ap_uavcan, uint8_t node_id, const GetNodeInfoCb& resp) -{ - uint8_t unique_id[16] = {0}; - char name[50] = {0}; - - //copy the unique id from message to uint8_t array - auto &r = resp.rsp->getResponse(); - uavcan::copy(r.hardware_version.unique_id.begin(), - r.hardware_version.unique_id.end(), - unique_id); - strncpy_noterm(name, r.name.c_str(), sizeof(name)-1); - - ap_uavcan->_dna_server->handleNodeInfo(node_id, unique_id, name, - r.software_version.major, - r.software_version.minor, - r.software_version.vcs_commit); -} - /* Handle the allocation message from the devices supporting dynamic node allocation. */ -void AP_UAVCAN_DNA_Server::handleAllocation(uint8_t node_id, const AllocationCb &cb) +void AP_UAVCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg) { - if (allocation_pub[driver_index] == nullptr) { - //init has not been called for this driver. - return; - } - if (!cb.msg->isAnonymousTransfer()) { + if (transfer.source_node_id != 0) { //Ignore Allocation messages that are not DNA requests return; } - uint32_t now = uavcan::SystemClock::instance().getMonotonic().toMSec(); + uint32_t now = AP_HAL::millis(); if (rcvd_unique_id_offset == 0 || (now - last_alloc_msg_ms) > 500) { - if (cb.msg->first_part_of_unique_id) { + if (msg.first_part_of_unique_id) { rcvd_unique_id_offset = 0; memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id)); } else { //we are only accepting first part return; } - } else if (cb.msg->first_part_of_unique_id) { + } else if (msg.first_part_of_unique_id) { // we are only accepting follow up messages return; } if (rcvd_unique_id_offset) { debug_uavcan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting Followup part! %u\n", - long(uavcan::SystemClock::instance().getMonotonic().toUSec()/1000), + (long int)AP_HAL::millis(), unsigned((now - last_alloc_msg_ms))); } else { debug_uavcan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting First part! %u\n", - long(uavcan::SystemClock::instance().getMonotonic().toUSec()/1000), + (long int)AP_HAL::millis(), unsigned((now - last_alloc_msg_ms))); } last_alloc_msg_ms = now; - if ((rcvd_unique_id_offset + cb.msg->unique_id.size()) > 16) { + if ((rcvd_unique_id_offset + msg.unique_id.len) > 16) { //This request is malformed, Reset! rcvd_unique_id_offset = 0; memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id)); @@ -646,50 +538,40 @@ void AP_UAVCAN_DNA_Server::handleAllocation(uint8_t node_id, const AllocationCb } //copy over the unique_id - for (uint8_t i=rcvd_unique_id_offset; i<(rcvd_unique_id_offset + cb.msg->unique_id.size()); i++) { - rcvd_unique_id[i] = cb.msg->unique_id[i - rcvd_unique_id_offset]; + for (uint8_t i=rcvd_unique_id_offset; i<(rcvd_unique_id_offset + msg.unique_id.len); i++) { + rcvd_unique_id[i] = msg.unique_id.data[i - rcvd_unique_id_offset]; } - rcvd_unique_id_offset += cb.msg->unique_id.size(); + rcvd_unique_id_offset += msg.unique_id.len; //send follow up message - uavcan::protocol::dynamic_node_id::Allocation msg; + uavcan_protocol_dynamic_node_id_Allocation rsp; /* Respond with the message containing the received unique ID so far or with node id if we successfully allocated one. */ - for (uint8_t i = 0; i < rcvd_unique_id_offset; i++) { - msg.unique_id.push_back(rcvd_unique_id[i]); - } + memcpy(rsp.unique_id.data, rcvd_unique_id, rcvd_unique_id_offset); + rsp.unique_id.len = rcvd_unique_id_offset; if (rcvd_unique_id_offset == 16) { //We have received the full Unique ID, time to do allocation uint8_t resp_node_id = getNodeIDForUniqueID((const uint8_t*)rcvd_unique_id, 16); if (resp_node_id == 255) { - resp_node_id = findFreeNodeID(cb.msg->node_id); + resp_node_id = findFreeNodeID(msg.node_id); if (resp_node_id != 255) { if (addNodeIDForUniqueID(resp_node_id, (const uint8_t*)rcvd_unique_id, 16)) { - msg.node_id = resp_node_id; + rsp.node_id = resp_node_id; } } else { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UC Node Alloc Failed!"); } } else { - msg.node_id = resp_node_id; + rsp.node_id = resp_node_id; } //reset states as well rcvd_unique_id_offset = 0; memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id)); } - allocation_pub[driver_index]->broadcast(msg); -} - -//Trampoline Call for handleAllocation member call -void AP_UAVCAN_DNA_Server::trampoline_handleAllocation(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AllocationCb &cb) -{ - if (ap_uavcan == nullptr) { - return; - } - ap_uavcan->_dna_server->handleAllocation(node_id, cb); + allocation_pub.broadcast(rsp, false); // never publish allocation message with CAN FD } //report the server state, along with failure message if any @@ -703,7 +585,7 @@ bool AP_UAVCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) co return false; } case DUPLICATE_NODES: { - if (_ap_uavcan->option_is_set(AP_UAVCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { + if (_ap_uavcan.option_is_set(AP_UAVCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { // ignore error return true; } @@ -715,7 +597,7 @@ bool AP_UAVCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) co return false; } case NODE_STATUS_UNHEALTHY: { - if (_ap_uavcan->option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { + if (_ap_uavcan.option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { // ignore error return true; } diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h index 5443423d1edcfe..0ba7a193f927b6 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h +++ b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h @@ -3,18 +3,17 @@ #include #if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include #include #include #include +#include +#include +#include +#include "AP_Canard_iface.h" +#include -//Forward declaring classes -class AllocationCb; -class NodeStatusCb; -class NodeInfoCb; -class GetNodeInfoCb; class AP_UAVCAN; - +//Forward declaring classes class AP_UAVCAN_DNA_Server { StorageAccess storage; @@ -34,7 +33,7 @@ class AP_UAVCAN_DNA_Server uint32_t last_verification_request; uint8_t curr_verifying_node; - uint8_t self_node_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; + uint8_t self_node_id; bool nodeInfo_resp_rcvd; Bitmask<128> occupation_mask; @@ -89,24 +88,30 @@ class AP_UAVCAN_DNA_Server //Look in the storage and check if there's a valid Server Record there bool isValidNodeDataAvailable(uint8_t node_id); - static void trampoline_handleNodeInfo(AP_UAVCAN* ap_uavcan, uint8_t node_id, const GetNodeInfoCb& resp); - static void trampoline_handleAllocation(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AllocationCb &cb); - static void trampoline_handleNodeStatus(AP_UAVCAN* ap_uavcan, uint8_t node_id, const NodeStatusCb &cb); + HAL_Semaphore storage_sem; + AP_UAVCAN &_ap_uavcan; + CanardInterface &_canard_iface; + Canard::Publisher allocation_pub{_canard_iface}; - HAL_Semaphore storage_sem; - AP_UAVCAN *_ap_uavcan; - uint8_t driver_index; + Canard::ObjCallback allocation_cb{this, &AP_UAVCAN_DNA_Server::handleAllocation}; + Canard::Subscriber allocation_sub; + + Canard::ObjCallback node_status_cb{this, &AP_UAVCAN_DNA_Server::handleNodeStatus}; + Canard::Subscriber node_status_sub; + + Canard::ObjCallback node_info_cb{this, &AP_UAVCAN_DNA_Server::handleNodeInfo}; + Canard::Client node_info_client; public: - AP_UAVCAN_DNA_Server(AP_UAVCAN *ap_uavcan, StorageAccess _storage); + AP_UAVCAN_DNA_Server(AP_UAVCAN &ap_uavcan); // Do not allow copies CLASS_NO_COPY(AP_UAVCAN_DNA_Server); //Initialises publisher and Server Record for specified uavcan driver - bool init(); + bool init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id); //Reset the Server Record void reset(); @@ -125,9 +130,9 @@ class AP_UAVCAN_DNA_Server bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const; //Callbacks - void handleAllocation(uint8_t node_id, const AllocationCb &cb); - void handleNodeStatus(uint8_t node_id, const NodeStatusCb &cb); - void handleNodeInfo(uint8_t node_id, uint8_t unique_id[], char name[], uint8_t major, uint8_t minor, uint32_t vcs_commit); + void handleAllocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg); + void handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg); + void handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp); //Run through the list of seen node ids for verification void verify_nodes(); diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp deleted file mode 100644 index bfa04b408432e0..00000000000000 --- a/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp +++ /dev/null @@ -1,238 +0,0 @@ - -/* - * This file is free software: you can redistribute it and/or modify it - * under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program. If not, see . - * - * Author: Siddharth Bharat Purohit - */ - -#include "AP_UAVCAN_IfaceMgr.h" - -#if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "AP_UAVCAN_Clock.h" -#include -#include -using namespace uavcan; -extern const AP_HAL::HAL& hal; -#define LOG_TAG "UAVCANIface" - -/***************************************************** - * * - * CAN Iface * - * * - * ***************************************************/ - -/** - * Non-blocking transmission. - * - * If the frame wasn't transmitted upon TX deadline, the driver should discard it. - * - * Note that it is LIKELY that the library will want to send the frames that were passed into the select() - * method as the next ones to transmit, but it is NOT guaranteed. The library can replace those with new - * frames between the calls. - * - * @return 1 = one frame transmitted, 0 = TX buffer full, negative for error. - */ -int16_t CanIface::send(const CanFrame& frame, MonotonicTime tx_deadline, CanIOFlags flags) -{ - if (can_iface_ == UAVCAN_NULLPTR) { - return -1; - } - return can_iface_->send(AP_HAL::CANFrame(frame.id, frame.data, AP_HAL::CANFrame::dlcToDataLength(frame.dlc), frame.isCanFDFrame()), tx_deadline.toUSec(), flags); -} - -/** - * Non-blocking reception. - * - * Timestamps should be provided by the CAN driver, ideally by the hardware CAN controller. - * - * Monotonic timestamp is required and can be not precise since it is needed only for - * protocol timing validation (transfer timeouts and inter-transfer intervals). - * - * UTC timestamp is optional, if available it will be used for precise time synchronization; - * must be set to zero if not available. - * - * Refer to @ref ISystemClock to learn more about timestamps. - * - * @param [out] out_ts_monotonic Monotonic timestamp, mandatory. - * @param [out] out_ts_utc UTC timestamp, optional, zero if unknown. - * @return 1 = one frame received, 0 = RX buffer empty, negative for error. - */ -int16_t CanIface::receive(CanFrame& out_frame, MonotonicTime& out_ts_monotonic, UtcTime& out_ts_utc, - CanIOFlags& out_flags) -{ - - if (can_iface_ == UAVCAN_NULLPTR) { - return -1; - } - AP_HAL::CANFrame frame; - uint64_t rx_timestamp; - uint16_t flags; - out_ts_monotonic = SystemClock::instance().getMonotonic(); - int16_t ret = can_iface_->receive(frame, rx_timestamp, flags); - if (ret < 0) { - return ret; - } - out_frame = CanFrame(frame.id, (const uint8_t*)frame.data, AP_HAL::CANFrame::dlcToDataLength(frame.dlc), frame.canfd); - out_flags = flags; - if (rx_timestamp != 0) { - out_ts_utc = uavcan::UtcTime::fromUSec(SystemClock::instance().getAdjustUsec() + rx_timestamp); - } else { - out_ts_utc = uavcan::UtcTime::fromUSec(0); - } - return ret; -} - -/** - * Number of available hardware filters. - */ -uint16_t CanIface::getNumFilters() const -{ - if (can_iface_ == UAVCAN_NULLPTR) { - return 0; - } - return can_iface_->getNumFilters(); -} - -/** - * Continuously incrementing counter of hardware errors. - * Arbitration lost should not be treated as a hardware error. - */ -uint64_t CanIface::getErrorCount() const -{ - if (can_iface_ == UAVCAN_NULLPTR) { - return 0; - } - return can_iface_->getErrorCount(); -} - -/***************************************************** - * * - * CAN Driver * - * * - * ***************************************************/ - -bool CanIfaceMgr::add_interface(AP_HAL::CANIface *can_iface) -{ - if (num_ifaces > HAL_NUM_CAN_IFACES) { - AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "UAVCANIfaceMgr: Num Ifaces Exceeded\n"); - return false; - } - if (can_iface == nullptr) { - AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "UAVCANIfaceMgr: Iface Null\n"); - return false; - } - if (ifaces[num_ifaces] != nullptr) { - AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "UAVCANIfaceMgr: Iface already added\n"); - return false; - } - ifaces[num_ifaces] = new CanIface(can_iface); - if (ifaces[num_ifaces] == nullptr) { - AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "UAVCANIfaceMgr: Can't alloc uavcan::iface\n"); - return false; - } - if (!ifaces[num_ifaces]->can_iface_->set_event_handle(&_event_handle)) { - AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "UAVCANIfaceMgr: Setting event handle failed\n"); - return false; - } - AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "UAVCANIfaceMgr: Successfully added interface %d\n", int(num_ifaces)); - num_ifaces++; - return true; -} -/** - * Returns an interface by index, or null pointer if the index is out of range. - */ -ICanIface* CanIfaceMgr::getIface(uint8_t iface_index) -{ - if (iface_index >= num_ifaces) { - return UAVCAN_NULLPTR; - } - return ifaces[iface_index]; -} - -/** - * Total number of available CAN interfaces. - * This value shall not change after initialization. - */ -uint8_t CanIfaceMgr::getNumIfaces() const -{ - return num_ifaces; -} - -CanSelectMasks CanIfaceMgr::makeSelectMasks(const CanSelectMasks in_mask, const CanFrame* (& pending_tx)[MaxCanIfaces]) const -{ - CanSelectMasks msk; - for (uint8_t i = 0; i < num_ifaces; i++) { - bool read = in_mask.read & (1 << i); - bool write = in_mask.write & (1 << i); - CanIface* iface = ifaces[i]; - if (iface == nullptr) { - continue; - } - if (pending_tx[i] == UAVCAN_NULLPTR) { - if (iface->can_iface_->select(read, write, nullptr, 0)) { - msk.read |= (read ? 1 : 0) << i; - msk.write |= (write ? 1 : 0) << i; - } - } else { - AP_HAL::CANFrame frame {pending_tx[i]->id, pending_tx[i]->data, AP_HAL::CANFrame::dlcToDataLength(pending_tx[i]->dlc)}; - if (iface->can_iface_->select(read, write, &frame, 0)) { - msk.read |= (read ? 1 : 0) << i; - msk.write |= (write ? 1 : 0) << i; - } - } - } - - return msk; -} - -/** - * Block until the deadline, or one of the specified interfaces becomes available for read or write. - * - * Iface masks will be modified by the driver to indicate which exactly interfaces are available for IO. - * - * Bit position in the masks defines interface index. - * - * Note that it is allowed to return from this method even if no requested events actually happened, or if - * there are events that were not requested by the library. - * - * The pending TX argument contains an array of pointers to CAN frames that the library wants to transmit - * next, per interface. This is intended to allow the driver to properly prioritize transmissions; many - * drivers will not need to use it. If a write flag for the given interface is set to one in the select mask - * structure, then the corresponding pointer is guaranteed to be valid (not UAVCAN_NULLPTR). - * - * @param [in,out] inout_masks Masks indicating which interfaces are needed/available for IO. - * @param [in] pending_tx Array of frames, per interface, that are likely to be transmitted next. - * @param [in] blocking_deadline Zero means non-blocking operation. - * @return Positive number of ready interfaces or negative error code. - */ -int16_t CanIfaceMgr::select(CanSelectMasks& inout_masks, - const CanFrame* (& pending_tx)[MaxCanIfaces], - const MonotonicTime blocking_deadline) -{ - const CanSelectMasks in_masks = inout_masks; - const uint64_t time = SystemClock::instance().getMonotonic().toUSec(); - - inout_masks = makeSelectMasks(in_masks, pending_tx); // Check if we already have some of the requested events - if ((inout_masks.read & in_masks.read) != 0 || - (inout_masks.write & in_masks.write) != 0) { - return 1; - } - if (time < blocking_deadline.toUSec()) { - _event_handle.wait(blocking_deadline.toUSec() - time); // Block until timeout expires or any iface updates - } - - inout_masks = makeSelectMasks(in_masks, pending_tx); // Return what we got even if none of the requested events are set - return 1; // Return value doesn't matter as long as it is non-negative -} -#endif //HAL_ENABLE_LIBUAVCAN_DRIVERSs diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.h b/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.h deleted file mode 100644 index 0c3b23ba18f1b9..00000000000000 --- a/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.h +++ /dev/null @@ -1,75 +0,0 @@ -/* - * This file is free software: you can redistribute it and/or modify it - * under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program. If not, see . - * - * Author: Siddharth Bharat Purohit - */ -#pragma once - -#include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - -#include - -namespace uavcan -{ - -class CanDriver; - -class CanIface : public ICanIface, Noncopyable -{ - friend class CanIfaceMgr; - AP_HAL::CANIface* can_iface_; -public: - CanIface(AP_HAL::CANIface *can_iface) : can_iface_(can_iface) {} - - virtual int16_t send(const CanFrame& frame, MonotonicTime tx_deadline, - CanIOFlags flags) override; - - virtual int16_t receive(CanFrame& out_frame, MonotonicTime& out_ts_monotonic, - UtcTime& out_ts_utc, CanIOFlags& out_flags) override; - - virtual int16_t configureFilters(const CanFilterConfig* filter_configs, - uint16_t num_configs) override { - return 0; - } - - uint16_t getNumFilters() const override; - - uint64_t getErrorCount() const override; -}; - -/** - * Generic CAN driver. - */ -class CanIfaceMgr : public ICanDriver, Noncopyable -{ - CanIface* ifaces[HAL_NUM_CAN_IFACES]; - uint8_t num_ifaces; - HAL_EventHandle _event_handle; -public: - bool add_interface(AP_HAL::CANIface *can_drv); - - ICanIface* getIface(uint8_t iface_index) override; - - uint8_t getNumIfaces() const override; - - CanSelectMasks makeSelectMasks(const CanSelectMasks in_mask, const CanFrame* (& pending_tx)[MaxCanIfaces]) const; - - int16_t select(CanSelectMasks& inout_masks, - const CanFrame* (& pending_tx)[MaxCanIfaces], - const MonotonicTime blocking_deadline) override; -}; - -} -#endif diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_pool.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_pool.cpp deleted file mode 100644 index 152381c3b829de..00000000000000 --- a/libraries/AP_UAVCAN/AP_UAVCAN_pool.cpp +++ /dev/null @@ -1,90 +0,0 @@ -/* - * This file is free software: you can redistribute it and/or modify it - * under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program. If not, see . - * - */ -/* - based on dynamic_memory.hpp which is: - Copyright (C) 2014 Pavel Kirienko - */ - -#include - -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - -#include "AP_UAVCAN.h" -#include "AP_UAVCAN_pool.h" -#include - -AP_PoolAllocator::AP_PoolAllocator(uint16_t _pool_size) : - num_blocks(_pool_size / UAVCAN_NODE_POOL_BLOCK_SIZE) -{ -} - -bool AP_PoolAllocator::init(void) -{ - WITH_SEMAPHORE(sem); - pool_nodes = (Node *)calloc(num_blocks, UAVCAN_NODE_POOL_BLOCK_SIZE); - if (pool_nodes == nullptr) { - return false; - } - for (uint16_t i=0; i<(num_blocks-1); i++) { - pool_nodes[i].next = &pool_nodes[i+1]; - } - free_list = &pool_nodes[0]; - return true; -} - -void* AP_PoolAllocator::allocate(std::size_t size) -{ - WITH_SEMAPHORE(sem); - if (free_list == nullptr || size > UAVCAN_NODE_POOL_BLOCK_SIZE) { - return nullptr; - } - Node *ret = free_list; - const uint32_t blk = ret - pool_nodes; - if (blk >= num_blocks) { - INTERNAL_ERROR(AP_InternalError::error_t::mem_guard); - return nullptr; - } - free_list = free_list->next; - - used++; - if (used > max_used) { - max_used = used; - } - - return ret; -} - -void AP_PoolAllocator::deallocate(const void* ptr) -{ - if (ptr == nullptr) { - return; - } - WITH_SEMAPHORE(sem); - - Node *p = reinterpret_cast(const_cast(ptr)); - const uint32_t blk = p - pool_nodes; - if (blk >= num_blocks) { - INTERNAL_ERROR(AP_InternalError::error_t::mem_guard); - return; - } - p->next = free_list; - free_list = p; - - used--; -} - -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS - diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_pool.h b/libraries/AP_UAVCAN/AP_UAVCAN_pool.h deleted file mode 100644 index 2549526bb7912b..00000000000000 --- a/libraries/AP_UAVCAN/AP_UAVCAN_pool.h +++ /dev/null @@ -1,60 +0,0 @@ -/* - * This file is free software: you can redistribute it and/or modify it - * under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program. If not, see . - * - */ -/* - based on dynamic_memory.hpp which is: - Copyright (C) 2014 Pavel Kirienko - */ - -#pragma once - -#include "AP_UAVCAN.h" - -#ifndef UAVCAN_NODE_POOL_BLOCK_SIZE -#if HAL_CANFD_SUPPORTED -#define UAVCAN_NODE_POOL_BLOCK_SIZE 128 -#else -#define UAVCAN_NODE_POOL_BLOCK_SIZE 64 -#endif -#endif - -class AP_PoolAllocator : public uavcan::IPoolAllocator -{ -public: - AP_PoolAllocator(uint16_t _pool_size); - - bool init(void); - void *allocate(std::size_t size) override; - void deallocate(const void* ptr) override; - - uint16_t getBlockCapacity() const override { - return num_blocks; - } - -private: - const uint16_t num_blocks; - - union Node { - uint8_t data[UAVCAN_NODE_POOL_BLOCK_SIZE]; - Node* next; - }; - - Node *free_list; - Node *pool_nodes; - HAL_Semaphore sem; - - uint16_t used; - uint16_t max_used; -}; diff --git a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp index bf2c76257cf047..0c5d625f0156df 100644 --- a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp +++ b/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp @@ -4,42 +4,18 @@ #include #include -#if HAL_MAX_CAN_PROTOCOL_DRIVERS +#if HAL_ENABLE_LIBUAVCAN_DRIVERS #include #include -#include - -#include - -#include -#include - -#include -#include -#include -#include - -#include -#include -#include - -#include -#include -#include -#include - -#include - -#include - #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL #include #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include #include #endif @@ -49,10 +25,8 @@ void loop(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define UAVCAN_NODE_POOL_SIZE 8192 -#ifdef UAVCAN_NODE_POOL_BLOCK_SIZE -#undef UAVCAN_NODE_POOL_BLOCK_SIZE -#endif -#define UAVCAN_NODE_POOL_BLOCK_SIZE 256 + +static uint8_t node_memory_pool[UAVCAN_NODE_POOL_SIZE]; #define debug_uavcan(fmt, args...) do { hal.console->printf(fmt, ##args); } while (0) @@ -67,22 +41,6 @@ class UAVCAN_sniffer { private: uint8_t driver_index = 0; - uavcan::Node<0> *_node; - - // This will be needed to implement if UAVCAN is used with multithreading - // Such cases will be firmware update, etc. - class RaiiSynchronizer { - public: - RaiiSynchronizer() - { - } - - ~RaiiSynchronizer() - { - } - }; - - uavcan::HeapBasedPoolAllocator _node_allocator; AP_CANManager can_mgr; }; @@ -108,20 +66,35 @@ static void count_msg(const char *name) } #define MSG_CB(mtype, cbname) \ - static void cb_ ## cbname(const uavcan::ReceivedDataStructure& msg) { count_msg(msg.getDataTypeFullName()); } - -MSG_CB(uavcan::protocol::NodeStatus, NodeStatus) -MSG_CB(uavcan::equipment::gnss::Fix2, Fix2) -MSG_CB(uavcan::equipment::gnss::Auxiliary, Auxiliary) -MSG_CB(uavcan::equipment::ahrs::MagneticFieldStrength, MagneticFieldStrength) -MSG_CB(uavcan::equipment::ahrs::MagneticFieldStrength2, MagneticFieldStrength2); -MSG_CB(uavcan::equipment::air_data::StaticPressure, StaticPressure) -MSG_CB(uavcan::equipment::air_data::StaticTemperature, StaticTemperature) -MSG_CB(uavcan::equipment::power::BatteryInfo, BatteryInfo); -MSG_CB(uavcan::equipment::actuator::ArrayCommand, ArrayCommand) -MSG_CB(uavcan::equipment::esc::RawCommand, RawCommand) -MSG_CB(uavcan::equipment::indication::LightsCommand, LightsCommand); -MSG_CB(com::hex::equipment::flow::Measurement, Measurement); + static void cb_ ## cbname(const CanardRxTransfer &transfer, const mtype& msg) { count_msg(#mtype); } + +MSG_CB(uavcan_protocol_NodeStatus, NodeStatus) +MSG_CB(uavcan_equipment_gnss_Fix2, Fix2) +MSG_CB(uavcan_equipment_gnss_Auxiliary, Auxiliary) +MSG_CB(uavcan_equipment_ahrs_MagneticFieldStrength, MagneticFieldStrength) +MSG_CB(uavcan_equipment_ahrs_MagneticFieldStrength2, MagneticFieldStrength2); +MSG_CB(uavcan_equipment_air_data_StaticPressure, StaticPressure) +MSG_CB(uavcan_equipment_air_data_StaticTemperature, StaticTemperature) +MSG_CB(uavcan_equipment_power_BatteryInfo, BatteryInfo); +MSG_CB(uavcan_equipment_actuator_ArrayCommand, ArrayCommand) +MSG_CB(uavcan_equipment_esc_RawCommand, RawCommand) +MSG_CB(uavcan_equipment_indication_LightsCommand, LightsCommand); +MSG_CB(com_hex_equipment_flow_Measurement, Measurement); + + +uavcan_protocol_NodeStatus node_status; +uavcan_protocol_GetNodeInfoResponse node_info; +CanardInterface *_uavcan_iface_mgr; +Canard::Publisher *node_status_pub; +Canard::Server *node_info_srv; + +static void cb_GetNodeInfoRequest(const CanardRxTransfer &transfer, const uavcan_protocol_GetNodeInfoRequest& msg) +{ + if (node_info_srv == nullptr) { + return; + } + node_info_srv->respond(transfer, node_info); +} void UAVCAN_sniffer::init(void) { @@ -137,7 +110,7 @@ void UAVCAN_sniffer::init(void) debug_uavcan("Can not initialised\n"); return; } - uavcan::CanIfaceMgr *_uavcan_iface_mgr = new uavcan::CanIfaceMgr; + _uavcan_iface_mgr = new CanardInterface{driver_index}; if (_uavcan_iface_mgr == nullptr) { return; @@ -148,74 +121,63 @@ void UAVCAN_sniffer::init(void) return; } - _node = new uavcan::Node<0>(*_uavcan_iface_mgr, uavcan::SystemClock::instance(), _node_allocator); + _uavcan_iface_mgr->init(node_memory_pool, sizeof(node_memory_pool), 9); - if (_node == nullptr) { + node_status_pub = new Canard::Publisher{*_uavcan_iface_mgr}; + if (node_status_pub == nullptr) { return; } - if (_node->isStarted()) { + node_info_srv = new Canard::Server{*_uavcan_iface_mgr, *Canard::allocate_static_callback(cb_GetNodeInfoRequest)}; + if (node_info_srv == nullptr) { return; } - uavcan::NodeID self_node_id(9); - _node->setNodeID(self_node_id); - - char ndname[20]; - snprintf(ndname, sizeof(ndname), "org.ardupilot:%u", driver_index); - - uavcan::NodeStatusProvider::NodeName name(ndname); - _node->setName(name); + node_info.name.len = snprintf((char*)node_info.name.data, sizeof(node_info.name.data), "org.ardupilot:%u", driver_index); - uavcan::protocol::SoftwareVersion sw_version; // Standard type uavcan.protocol.SoftwareVersion - sw_version.major = AP_UAVCAN_SW_VERS_MAJOR; - sw_version.minor = AP_UAVCAN_SW_VERS_MINOR; - _node->setSoftwareVersion(sw_version); + node_info.software_version.major = AP_UAVCAN_SW_VERS_MAJOR; + node_info.software_version.minor = AP_UAVCAN_SW_VERS_MINOR; - uavcan::protocol::HardwareVersion hw_version; // Standard type uavcan.protocol.HardwareVersion - - hw_version.major = AP_UAVCAN_HW_VERS_MAJOR; - hw_version.minor = AP_UAVCAN_HW_VERS_MINOR; - _node->setHardwareVersion(hw_version); - - int start_res = _node->start(); - if (start_res < 0) { - debug_uavcan("UAVCAN: node start problem\n\r"); - return; - } + node_info.hardware_version.major = AP_UAVCAN_HW_VERS_MAJOR; + node_info.hardware_version.minor = AP_UAVCAN_HW_VERS_MINOR; -#define START_CB(mtype, cbname) (new uavcan::Subscriber(*_node))->start(cb_ ## cbname) +#define START_CB(mtype, cbname) Canard::allocate_sub_static_callback(cb_ ## cbname,driver_index) - START_CB(uavcan::protocol::NodeStatus, NodeStatus); - START_CB(uavcan::equipment::gnss::Fix2, Fix2); - START_CB(uavcan::equipment::gnss::Auxiliary, Auxiliary); - START_CB(uavcan::equipment::ahrs::MagneticFieldStrength, MagneticFieldStrength); - START_CB(uavcan::equipment::ahrs::MagneticFieldStrength2, MagneticFieldStrength2); - START_CB(uavcan::equipment::air_data::StaticPressure, StaticPressure); - START_CB(uavcan::equipment::air_data::StaticTemperature, StaticTemperature); - START_CB(uavcan::equipment::power::BatteryInfo, BatteryInfo); - START_CB(uavcan::equipment::actuator::ArrayCommand, ArrayCommand); - START_CB(uavcan::equipment::esc::RawCommand, RawCommand); - START_CB(uavcan::equipment::indication::LightsCommand, LightsCommand); - START_CB(com::hex::equipment::flow::Measurement, Measurement); - - - /* - * Informing other nodes that we're ready to work. - * Default mode is INITIALIZING. - */ - _node->setModeOperational(); + START_CB(uavcan_protocol_NodeStatus, NodeStatus); + START_CB(uavcan_equipment_gnss_Fix2, Fix2); + START_CB(uavcan_equipment_gnss_Auxiliary, Auxiliary); + START_CB(uavcan_equipment_ahrs_MagneticFieldStrength, MagneticFieldStrength); + START_CB(uavcan_equipment_ahrs_MagneticFieldStrength2, MagneticFieldStrength2); + START_CB(uavcan_equipment_air_data_StaticPressure, StaticPressure); + START_CB(uavcan_equipment_air_data_StaticTemperature, StaticTemperature); + START_CB(uavcan_equipment_power_BatteryInfo, BatteryInfo); + START_CB(uavcan_equipment_actuator_ArrayCommand, ArrayCommand); + START_CB(uavcan_equipment_esc_RawCommand, RawCommand); + START_CB(uavcan_equipment_indication_LightsCommand, LightsCommand); + START_CB(com_hex_equipment_flow_Measurement, Measurement); debug_uavcan("UAVCAN: init done\n\r"); } +static void send_node_status() +{ + uavcan_protocol_NodeStatus msg; + msg.uptime_sec = AP_HAL::millis() / 1000; + msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; + msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; + msg.sub_mode = 0; + msg.vendor_specific_status_code = 0; + node_status_pub->broadcast(msg); +} + +uint32_t last_status_send = 0; void UAVCAN_sniffer::loop(void) { - if (_node == nullptr) { - return; + if (AP_HAL::millis() - last_status_send > 1000) { + last_status_send = AP_HAL::millis(); + send_node_status(); } - - _node->spin(uavcan::MonotonicDuration::fromMSec(1)); + _uavcan_iface_mgr->process(1); } void UAVCAN_sniffer::print_stats(void) @@ -233,8 +195,7 @@ void UAVCAN_sniffer::print_stats(void) static UAVCAN_sniffer sniffer; -UAVCAN_sniffer::UAVCAN_sniffer() : - _node_allocator(UAVCAN_NODE_POOL_SIZE, UAVCAN_NODE_POOL_SIZE) +UAVCAN_sniffer::UAVCAN_sniffer() {} UAVCAN_sniffer::~UAVCAN_sniffer() diff --git a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/wscript b/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/wscript index 719ec151ba9d4b..3e81beeee182a4 100644 --- a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/wscript +++ b/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/wscript @@ -1,7 +1,21 @@ #!/usr/bin/env python # encoding: utf-8 +from waflib.TaskGen import after_method, before_method, feature def build(bld): - bld.ap_example( - use='ap', + vehicle = bld.path.name + + bld.ap_stlib( + name=vehicle + '_libs', + ap_vehicle='UNKNOWN', + dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', + ap_libraries=bld.ap_common_vehicle_libraries() + [ + 'AP_OSD', + 'AP_RCMapper', + 'AP_Arming' + ], + ) + bld.ap_program( + program_groups=['tool'], + use=[vehicle + '_libs'], ) From 0e80802f694661742ba6bde3a1597c92fe2e20aa Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Fri, 6 Jan 2023 00:07:00 +1100 Subject: [PATCH 031/287] waf: replace libuavcan with libcanard for vehicle builds --- Tools/ardupilotwaf/ardupilotwaf.py | 3 +++ Tools/ardupilotwaf/boards.py | 41 +++++++++++++++++++----------- Tools/ardupilotwaf/chibios.py | 12 +++++++-- Tools/ardupilotwaf/dronecangen.py | 8 +++--- Tools/ardupilotwaf/uavcangen.py | 8 +++--- wscript | 25 ++++++++++++++++-- 6 files changed, 70 insertions(+), 27 deletions(-) diff --git a/Tools/ardupilotwaf/ardupilotwaf.py b/Tools/ardupilotwaf/ardupilotwaf.py index 78ca6aab34f2f8..4ef709a99051ce 100644 --- a/Tools/ardupilotwaf/ardupilotwaf.py +++ b/Tools/ardupilotwaf/ardupilotwaf.py @@ -325,6 +325,9 @@ def ap_stlib(bld, **kw): for l in kw['ap_libraries']: bld.ap_library(l, kw['ap_vehicle']) + if 'dynamic_source' not in kw: + kw['dynamic_source'] = 'modules/DroneCAN/libcanard/dsdlc_generated/src/**.c' + kw['features'] = kw.get('features', []) + ['cxx', 'cxxstlib'] kw['target'] = kw['name'] kw['source'] = [] diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index f39c31e3fad341..0ed397d2d176bd 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -429,15 +429,26 @@ def configure_env(self, cfg, env): ] if self.with_can and not cfg.env.AP_PERIPH: - env.AP_LIBRARIES += [ - 'AP_UAVCAN', - 'modules/uavcan/libuavcan/src/**/*.cpp' - ] + if not cfg.env.SITL32BIT and cfg.env.BOARD == 'sitl': + env.DEFINES.update( + HAL_ENABLE_LIBUAVCAN_DRIVERS = 0 + ) + else: + env.AP_LIBRARIES += [ + 'AP_UAVCAN', + 'modules/DroneCAN/libcanard/*.c', + ] + if cfg.options.enable_dronecan_tests: + env.DEFINES.update( + AP_TEST_DRONECAN_DRIVERS = 1 + ) env.DEFINES.update( UAVCAN_CPP_VERSION = 'UAVCAN_CPP03', UAVCAN_NO_ASSERTIONS = 1, - UAVCAN_NULLPTR = 'nullptr' + UAVCAN_NULLPTR = 'nullptr', + DRONECAN_CXX_WRAPPERS = 1, + CANARD_ENABLE_DEADLINE = 1, ) @@ -638,6 +649,9 @@ def configure_env(self, cfg, env): cfg.define('HAL_NUM_CAN_IFACES', 2) cfg.define('UAVCAN_EXCEPTIONS', 0) cfg.define('UAVCAN_SUPPORT_CANFD', 1) + env.DEFINES.update(CANARD_MULTI_IFACE=1, + CANARD_IFACE_ALL = 0x3, + CANARD_ENABLE_CANFD = 1) env.CXXFLAGS += [ '-Werror=float-equal' @@ -1069,16 +1083,13 @@ def configure_env(self, cfg, env): ('10','2','1'), ] - if cfg.env.AP_PERIPH: - if cfg.env.HAL_CANFD_SUPPORTED: - env.DEFINES.update(CANARD_ENABLE_CANFD=1) - else: - env.DEFINES.update(CANARD_ENABLE_TAO_OPTION=1) - if not cfg.options.bootloader: - if int(cfg.env.HAL_NUM_CAN_IFACES) > 1: - env.DEFINES.update(CANARD_MULTI_IFACE=1) - else: - env.DEFINES.update(CANARD_MULTI_IFACE=0) + if cfg.env.HAL_CANFD_SUPPORTED: + env.DEFINES.update(CANARD_ENABLE_CANFD=1) + else: + env.DEFINES.update(CANARD_ENABLE_TAO_OPTION=1) + if not cfg.options.bootloader and cfg.env.HAL_NUM_CAN_IFACES: + if int(cfg.env.HAL_NUM_CAN_IFACES) >= 1: + env.DEFINES.update(CANARD_IFACE_ALL=(1< Date: Tue, 10 Jan 2023 00:37:50 +1100 Subject: [PATCH 032/287] AP_CANManager: replace libuavcan with libcanard based driver --- libraries/AP_CANManager/AP_CANDriver.cpp | 2 ++ libraries/AP_CANManager/AP_CANManager.cpp | 7 +++++-- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_CANManager/AP_CANDriver.cpp b/libraries/AP_CANManager/AP_CANDriver.cpp index 5e602b1a789c6b..ed5ee7f66665da 100644 --- a/libraries/AP_CANManager/AP_CANDriver.cpp +++ b/libraries/AP_CANManager/AP_CANDriver.cpp @@ -36,9 +36,11 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = { // @RebootRequired: True AP_GROUPINFO("PROTOCOL", 1, AP_CANManager::CANDriver_Params, _driver_type, AP_CANManager::Driver_Type_UAVCAN), +#if HAL_ENABLE_LIBUAVCAN_DRIVERS // @Group: UC_ // @Path: ../AP_UAVCAN/AP_UAVCAN.cpp AP_SUBGROUPPTR(_uavcan, "UC_", 2, AP_CANManager::CANDriver_Params, AP_UAVCAN), +#endif #if (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)) // @Group: KDE_ diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index b84a749c053df2..ab6c437e04f617 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -202,8 +202,9 @@ void AP_CANManager::init() } // Allocate the set type of Driver +#if HAL_ENABLE_LIBUAVCAN_DRIVERS if (drv_type[drv_num] == Driver_Type_UAVCAN) { - _drivers[drv_num] = _drv_param[drv_num]._uavcan = new AP_UAVCAN; + _drivers[drv_num] = _drv_param[drv_num]._uavcan = new AP_UAVCAN(drv_num); if (_drivers[drv_num] == nullptr) { AP_BoardConfig::allocation_error("uavcan %d", i + 1); @@ -211,7 +212,9 @@ void AP_CANManager::init() } AP_Param::load_object_from_eeprom((AP_UAVCAN*)_drivers[drv_num], AP_UAVCAN::var_info); - } else if (drv_type[drv_num] == Driver_Type_KDECAN) { + } else +#endif + if (drv_type[drv_num] == Driver_Type_KDECAN) { #if (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)) // To be replaced with macro saying if KDECAN library is included _drivers[drv_num] = _drv_param[drv_num]._kdecan = new AP_KDECAN; From 310a307c10bb64a1f5ae8789dbc4ee3667ba9b0b Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Tue, 10 Jan 2023 00:33:30 +1100 Subject: [PATCH 033/287] AP_HAL: add define AP_TEST_DRONECAN_DRIVERS --- libraries/AP_HAL/AP_HAL_Boards.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 3934350e3a3e90..e62c415f74fc7d 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -222,6 +222,10 @@ #define HAL_ENABLE_LIBUAVCAN_DRIVERS HAL_CANMANAGER_ENABLED #endif +#ifndef AP_TEST_DRONECAN_DRIVERS +#define AP_TEST_DRONECAN_DRIVERS 0 +#endif + #ifndef AP_AIRSPEED_BACKEND_DEFAULT_ENABLED #define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 1 #endif From 09de24f3d2af58ece8f2baf32a7afd69e193ddbe Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Tue, 10 Jan 2023 00:44:10 +1100 Subject: [PATCH 034/287] AP_GPS: replace libuavcan with libcanard based driver --- libraries/AP_GPS/AP_GPS_UAVCAN.cpp | 244 +++++++++++------------------ libraries/AP_GPS/AP_GPS_UAVCAN.h | 39 ++--- 2 files changed, 110 insertions(+), 173 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp index c108f64d961899..21ae0987d61f0e 100644 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp @@ -27,15 +27,7 @@ #include -#include -#include -#include -#include -#if GPS_MOVING_BASELINE -#include -#include -#endif - +#include #include #define GPS_PPS_EMULATION 0 @@ -59,15 +51,6 @@ extern const AP_HAL::HAL& hal; #define LOG_TAG "GPS" -UC_REGISTRY_BINDER(Fix2Cb, uavcan::equipment::gnss::Fix2); -UC_REGISTRY_BINDER(AuxCb, uavcan::equipment::gnss::Auxiliary); -UC_REGISTRY_BINDER(HeadingCb, ardupilot::gnss::Heading); -UC_REGISTRY_BINDER(StatusCb, ardupilot::gnss::Status); -#if GPS_MOVING_BASELINE -UC_REGISTRY_BINDER(MovingBaselineDataCb, ardupilot::gnss::MovingBaselineData); -UC_REGISTRY_BINDER(RelPosHeadingCb, ardupilot::gnss::RelPosHeading); -#endif - #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #define NATIVE_TIME_OFFSET (AP_HAL::micros64() - AP_HAL::native_micros64()) #else @@ -106,67 +89,28 @@ void AP_GPS_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) return; } - auto* node = ap_uavcan->get_node(); - - uavcan::Subscriber *gnss_fix2; - gnss_fix2 = new uavcan::Subscriber(*node); - if (gnss_fix2 == nullptr) { - AP_BoardConfig::allocation_error("gnss_fix2"); - } - const int gnss_fix2_start_res = gnss_fix2->start(Fix2Cb(ap_uavcan, &handle_fix2_msg_trampoline)); - if (gnss_fix2_start_res < 0) { - AP_HAL::panic("UAVCAN GNSS subscriber start problem\n\r"); - } - - uavcan::Subscriber *gnss_aux; - gnss_aux = new uavcan::Subscriber(*node); - if (gnss_aux == nullptr) { - AP_BoardConfig::allocation_error("gnss_aux"); - } - const int gnss_aux_start_res = gnss_aux->start(AuxCb(ap_uavcan, &handle_aux_msg_trampoline)); - if (gnss_aux_start_res < 0) { - AP_HAL::panic("UAVCAN GNSS subscriber start problem\n\r"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_fix2_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); } - uavcan::Subscriber *gnss_heading; - gnss_heading = new uavcan::Subscriber(*node); - if (gnss_heading == nullptr) { - AP_BoardConfig::allocation_error("gnss_heading"); - } - const int gnss_heading_start_res = gnss_heading->start(HeadingCb(ap_uavcan, &handle_heading_msg_trampoline)); - if (gnss_heading_start_res < 0) { - AP_HAL::panic("UAVCAN GNSS subscriber start problem\n\r"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_aux_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); } - uavcan::Subscriber *gnss_status; - gnss_status = new uavcan::Subscriber(*node); - if (gnss_status == nullptr) { - AP_BoardConfig::allocation_error("gnss_status"); - } - const int gnss_status_start_res = gnss_status->start(StatusCb(ap_uavcan, &handle_status_msg_trampoline)); - if (gnss_status_start_res < 0) { - AP_HAL::panic("UAVCAN GNSS subscriber start problem\n\r"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_heading_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); } -#if GPS_MOVING_BASELINE - uavcan::Subscriber *gnss_moving_baseline; - gnss_moving_baseline = new uavcan::Subscriber(*node); - if (gnss_moving_baseline == nullptr) { - AP_BoardConfig::allocation_error("gnss_moving_baseline"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_status_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); } - const int gnss_moving_baseline_start_res = gnss_moving_baseline->start(MovingBaselineDataCb(ap_uavcan, &handle_moving_baseline_msg_trampoline)); - if (gnss_moving_baseline_start_res < 0) { - AP_HAL::panic("UAVCAN GNSS subscriber start problem\n\r"); +#if GPS_MOVING_BASELINE + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_moving_baseline_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("moving_baseline_sub"); } - uavcan::Subscriber *gnss_relposheading; - gnss_relposheading = new uavcan::Subscriber(*node); - if (gnss_relposheading == nullptr) { - AP_BoardConfig::allocation_error("gnss_relposheading"); - } - const int gnss_relposheading_start_res = gnss_relposheading->start(RelPosHeadingCb(ap_uavcan, &handle_relposheading_msg_trampoline)); - if (gnss_relposheading_start_res < 0) { - AP_HAL::panic("UAVCAN GNSS subscriber start problem\n\r"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_relposheading_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("relposheading_sub"); } #endif } @@ -374,7 +318,7 @@ AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t n */ void AP_GPS_UAVCAN::handle_velocity(const float vx, const float vy, const float vz) { - if (!uavcan::isNaN(vx)) { + if (!isnanf(vx)) { const Vector3f vel(vx, vy, vz); interim_state.velocity = vel; velocity_to_speed_course(interim_state); @@ -389,28 +333,28 @@ void AP_GPS_UAVCAN::handle_velocity(const float vx, const float vy, const float } } -void AP_GPS_UAVCAN::handle_fix2_msg(const Fix2Cb &cb) +void AP_GPS_UAVCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec) { bool process = false; seen_fix2 = true; WITH_SEMAPHORE(sem); - if (cb.msg->status == uavcan::equipment::gnss::Fix2::STATUS_NO_FIX) { + if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX) { interim_state.status = AP_GPS::GPS_Status::NO_FIX; } else { - if (cb.msg->status == uavcan::equipment::gnss::Fix2::STATUS_TIME_ONLY) { + if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_TIME_ONLY) { interim_state.status = AP_GPS::GPS_Status::NO_FIX; - } else if (cb.msg->status == uavcan::equipment::gnss::Fix2::STATUS_2D_FIX) { + } else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX) { interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_2D; process = true; - } else if (cb.msg->status == uavcan::equipment::gnss::Fix2::STATUS_3D_FIX) { + } else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX) { interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D; process = true; } - if (cb.msg->gnss_time_standard == uavcan::equipment::gnss::Fix2::GNSS_TIME_STANDARD_UTC) { - uint64_t epoch_ms = uavcan::UtcTime(cb.msg->gnss_timestamp).toUSec(); + if (msg.gnss_time_standard == UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_UTC) { + uint64_t epoch_ms = msg.gnss_timestamp.usec; if (epoch_ms != 0) { epoch_ms /= 1000; uint64_t gps_ms = epoch_ms - UNIX_OFFSET_MSEC; @@ -420,12 +364,12 @@ void AP_GPS_UAVCAN::handle_fix2_msg(const Fix2Cb &cb) } if (interim_state.status == AP_GPS::GPS_Status::GPS_OK_FIX_3D) { - if (cb.msg->mode == uavcan::equipment::gnss::Fix2::MODE_DGPS) { + if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS) { interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS; - } else if (cb.msg->mode == uavcan::equipment::gnss::Fix2::MODE_RTK) { - if (cb.msg->sub_mode == uavcan::equipment::gnss::Fix2::SUB_MODE_RTK_FLOAT) { + } else if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK) { + if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT) { interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT; - } else if (cb.msg->sub_mode == uavcan::equipment::gnss::Fix2::SUB_MODE_RTK_FIXED) { + } else if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED) { interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED; } } @@ -434,39 +378,39 @@ void AP_GPS_UAVCAN::handle_fix2_msg(const Fix2Cb &cb) if (process) { Location loc = { }; - loc.lat = cb.msg->latitude_deg_1e8 / 10; - loc.lng = cb.msg->longitude_deg_1e8 / 10; - loc.alt = cb.msg->height_msl_mm / 10; + loc.lat = msg.latitude_deg_1e8 / 10; + loc.lng = msg.longitude_deg_1e8 / 10; + loc.alt = msg.height_msl_mm / 10; interim_state.have_undulation = true; - interim_state.undulation = (cb.msg->height_msl_mm - cb.msg->height_ellipsoid_mm) * 0.001; + interim_state.undulation = (msg.height_msl_mm - msg.height_ellipsoid_mm) * 0.001; interim_state.location = loc; - handle_velocity(cb.msg->ned_velocity[0], cb.msg->ned_velocity[1], cb.msg->ned_velocity[2]); + handle_velocity(msg.ned_velocity[0], msg.ned_velocity[1], msg.ned_velocity[2]); - if (cb.msg->covariance.size() == 6) { - if (!uavcan::isNaN(cb.msg->covariance[0])) { - interim_state.horizontal_accuracy = sqrtf(cb.msg->covariance[0]); + if (msg.covariance.len == 6) { + if (!isnanf(msg.covariance.data[0])) { + interim_state.horizontal_accuracy = sqrtf(msg.covariance.data[0]); interim_state.have_horizontal_accuracy = true; } else { interim_state.have_horizontal_accuracy = false; } - if (!uavcan::isNaN(cb.msg->covariance[2])) { - interim_state.vertical_accuracy = sqrtf(cb.msg->covariance[2]); + if (!isnanf(msg.covariance.data[2])) { + interim_state.vertical_accuracy = sqrtf(msg.covariance.data[2]); interim_state.have_vertical_accuracy = true; } else { interim_state.have_vertical_accuracy = false; } - if (!uavcan::isNaN(cb.msg->covariance[3]) && - !uavcan::isNaN(cb.msg->covariance[4]) && - !uavcan::isNaN(cb.msg->covariance[5])) { - interim_state.speed_accuracy = sqrtf((cb.msg->covariance[3] + cb.msg->covariance[4] + cb.msg->covariance[5])/3); + if (!isnanf(msg.covariance.data[3]) && + !isnanf(msg.covariance.data[4]) && + !isnanf(msg.covariance.data[5])) { + interim_state.speed_accuracy = sqrtf((msg.covariance.data[3] + msg.covariance.data[4] + msg.covariance.data[5])/3); interim_state.have_speed_accuracy = true; } else { interim_state.have_speed_accuracy = false; } } - interim_state.num_sats = cb.msg->sats_used; + interim_state.num_sats = msg.sats_used; } else { interim_state.have_vertical_velocity = false; interim_state.have_vertical_accuracy = false; @@ -478,18 +422,18 @@ void AP_GPS_UAVCAN::handle_fix2_msg(const Fix2Cb &cb) if (!seen_aux) { // if we haven't seen an Aux message then populate vdop and // hdop from pdop. Some GPS modules don't provide the Aux message - interim_state.hdop = interim_state.vdop = cb.msg->pdop * 100.0; + interim_state.hdop = interim_state.vdop = msg.pdop * 100.0; } - if ((cb.msg->timestamp.usec > cb.msg->gnss_timestamp.usec) && (cb.msg->gnss_timestamp.usec > 0)) { + if ((msg.timestamp.usec > msg.gnss_timestamp.usec) && (msg.gnss_timestamp.usec > 0)) { // we have a valid timestamp based on gnss_timestamp timescale, we can use that to correct our gps message time - interim_state.last_corrected_gps_time_us = jitter_correction.correct_offboard_timestamp_usec(cb.msg->timestamp.usec, (cb.msg->getUtcTimestamp().toUSec() + NATIVE_TIME_OFFSET)); + interim_state.last_corrected_gps_time_us = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, (timestamp_usec + NATIVE_TIME_OFFSET)); interim_state.last_gps_time_ms = interim_state.last_corrected_gps_time_us/1000U; - interim_state.last_corrected_gps_time_us -= cb.msg->timestamp.usec - cb.msg->gnss_timestamp.usec; + interim_state.last_corrected_gps_time_us -= msg.timestamp.usec - msg.gnss_timestamp.usec; // this is also the time the message was received on the UART on other end. interim_state.corrected_timestamp_updated = true; } else { - interim_state.last_gps_time_ms = jitter_correction.correct_offboard_timestamp_usec(cb.msg->timestamp.usec, cb.msg->getUtcTimestamp().toUSec() + NATIVE_TIME_OFFSET)/1000U; + interim_state.last_gps_time_ms = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, timestamp_usec + NATIVE_TIME_OFFSET)/1000U; } #if GPS_PPS_EMULATION @@ -507,7 +451,7 @@ void AP_GPS_UAVCAN::handle_fix2_msg(const Fix2Cb &cb) static uint64_t next_toggle, last_toggle; - next_toggle = (cb.msg->timestamp.usec) + (1000000ULL - ((cb.msg->timestamp.usec) % 1000000ULL)); + next_toggle = (msg.timestamp.usec) + (1000000ULL - ((msg.timestamp.usec) % 1000000ULL)); next_toggle += jitter_correction.get_link_offset_usec(); if (next_toggle != last_toggle) { @@ -528,22 +472,22 @@ void AP_GPS_UAVCAN::handle_fix2_msg(const Fix2Cb &cb) } } -void AP_GPS_UAVCAN::handle_aux_msg(const AuxCb &cb) +void AP_GPS_UAVCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg) { WITH_SEMAPHORE(sem); - if (!uavcan::isNaN(cb.msg->hdop)) { + if (!isnanf(msg.hdop)) { seen_aux = true; - interim_state.hdop = cb.msg->hdop * 100.0; + interim_state.hdop = msg.hdop * 100.0; } - if (!uavcan::isNaN(cb.msg->vdop)) { + if (!isnanf(msg.vdop)) { seen_aux = true; - interim_state.vdop = cb.msg->vdop * 100.0; + interim_state.vdop = msg.vdop * 100.0; } } -void AP_GPS_UAVCAN::handle_heading_msg(const HeadingCb &cb) +void AP_GPS_UAVCAN::handle_heading_msg(const ardupilot_gnss_Heading& msg) { #if GPS_MOVING_BASELINE if (seen_relposheading && gps.mb_params[interim_state.instance].type.get() != 0) { @@ -556,33 +500,33 @@ void AP_GPS_UAVCAN::handle_heading_msg(const HeadingCb &cb) WITH_SEMAPHORE(sem); if (interim_state.gps_yaw_configured == false) { - interim_state.gps_yaw_configured = cb.msg->heading_valid; + interim_state.gps_yaw_configured = msg.heading_valid; } - interim_state.have_gps_yaw = cb.msg->heading_valid; - interim_state.gps_yaw = degrees(cb.msg->heading_rad); + interim_state.have_gps_yaw = msg.heading_valid; + interim_state.gps_yaw = degrees(msg.heading_rad); if (interim_state.have_gps_yaw) { interim_state.gps_yaw_time_ms = AP_HAL::millis(); } - interim_state.have_gps_yaw_accuracy = cb.msg->heading_accuracy_valid; - interim_state.gps_yaw_accuracy = degrees(cb.msg->heading_accuracy_rad); + interim_state.have_gps_yaw_accuracy = msg.heading_accuracy_valid; + interim_state.gps_yaw_accuracy = degrees(msg.heading_accuracy_rad); } -void AP_GPS_UAVCAN::handle_status_msg(const StatusCb &cb) +void AP_GPS_UAVCAN::handle_status_msg(const ardupilot_gnss_Status& msg) { WITH_SEMAPHORE(sem); seen_status = true; - healthy = cb.msg->healthy; - status_flags = cb.msg->status; - if (error_code != cb.msg->error_codes) { + healthy = msg.healthy; + status_flags = msg.status; + if (error_code != msg.error_codes) { AP::logger().Write_MessageF("GPS %d: error changed (0x%08x/0x%08x)", (unsigned int)(state.instance + 1), error_code, - cb.msg->error_codes); - error_code = cb.msg->error_codes; + msg.error_codes); + error_code = msg.error_codes; } } @@ -590,7 +534,7 @@ void AP_GPS_UAVCAN::handle_status_msg(const StatusCb &cb) /* handle moving baseline data. */ -void AP_GPS_UAVCAN::handle_moving_baseline_msg(const MovingBaselineDataCb &cb, uint8_t node_id) +void AP_GPS_UAVCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id) { WITH_SEMAPHORE(sem); if (role != AP_GPS::GPS_ROLE_MB_BASE) { @@ -601,15 +545,15 @@ void AP_GPS_UAVCAN::handle_moving_baseline_msg(const MovingBaselineDataCb &cb, u if (rtcm3_parser == nullptr) { return; } - for (const auto &c : cb.msg->data) { - rtcm3_parser->read(c); + for (int i=0; i < msg.data.len; i++) { + rtcm3_parser->read(msg.data.data[i]); } } /* handle relposheading message */ -void AP_GPS_UAVCAN::handle_relposheading_msg(const RelPosHeadingCb &cb, uint8_t node_id) +void AP_GPS_UAVCAN::handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id) { WITH_SEMAPHORE(sem); @@ -617,13 +561,13 @@ void AP_GPS_UAVCAN::handle_relposheading_msg(const RelPosHeadingCb &cb, uint8_t seen_relposheading = true; // push raw heading data to calculate moving baseline heading states if (calculate_moving_base_yaw(interim_state, - cb.msg->reported_heading_deg, - cb.msg->relative_distance_m, - cb.msg->relative_down_pos_m)) { - if (cb.msg->reported_heading_acc_available) { - interim_state.gps_yaw_accuracy = cb.msg->reported_heading_acc_deg; + msg.reported_heading_deg, + msg.relative_distance_m, + msg.relative_down_pos_m)) { + if (msg.reported_heading_acc_available) { + interim_state.gps_yaw_accuracy = msg.reported_heading_acc_deg; } - interim_state.have_gps_yaw_accuracy = cb.msg->reported_heading_acc_available; + interim_state.have_gps_yaw_accuracy = msg.reported_heading_acc_available; } } @@ -649,64 +593,64 @@ void AP_GPS_UAVCAN::clear_RTCMV3(void) #endif // GPS_MOVING_BASELINE -void AP_GPS_UAVCAN::handle_fix2_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const Fix2Cb &cb) +void AP_GPS_UAVCAN::handle_fix2_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); if (driver != nullptr) { - driver->handle_fix2_msg(cb); + driver->handle_fix2_msg(msg, transfer.timestamp_usec); } } -void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AuxCb &cb) +void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); if (driver != nullptr) { - driver->handle_aux_msg(cb); + driver->handle_aux_msg(msg); } } -void AP_GPS_UAVCAN::handle_heading_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const HeadingCb &cb) +void AP_GPS_UAVCAN::handle_heading_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); if (driver != nullptr) { - driver->handle_heading_msg(cb); + driver->handle_heading_msg(msg); } } -void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const StatusCb &cb) +void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); if (driver != nullptr) { - driver->handle_status_msg(cb); + driver->handle_status_msg(msg); } } #if GPS_MOVING_BASELINE // Moving Baseline msg trampoline -void AP_GPS_UAVCAN::handle_moving_baseline_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MovingBaselineDataCb &cb) +void AP_GPS_UAVCAN::handle_moving_baseline_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); if (driver != nullptr) { - driver->handle_moving_baseline_msg(cb, node_id); + driver->handle_moving_baseline_msg(msg, transfer.source_node_id); } } // RelPosHeading msg trampoline -void AP_GPS_UAVCAN::handle_relposheading_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const RelPosHeadingCb &cb) +void AP_GPS_UAVCAN::handle_relposheading_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); if (driver != nullptr) { - driver->handle_relposheading_msg(cb, node_id); + driver->handle_relposheading_msg(msg, transfer.source_node_id); } } #endif @@ -798,7 +742,7 @@ bool AP_GPS_UAVCAN::logging_healthy(void) const return true; } - return (status_flags & ardupilot::gnss::Status::STATUS_LOGGING) != 0; + return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_LOGGING) != 0; } bool AP_GPS_UAVCAN::is_configured(void) const @@ -808,7 +752,7 @@ bool AP_GPS_UAVCAN::is_configured(void) const return true; } - return (status_flags & ardupilot::gnss::Status::STATUS_ARMABLE) != 0; + return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE) != 0; } /* diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.h b/libraries/AP_GPS/AP_GPS_UAVCAN.h index 9ac0894bb6de94..6911e892c70acf 100644 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.h +++ b/libraries/AP_GPS/AP_GPS_UAVCAN.h @@ -14,27 +14,18 @@ */ // -// UAVCAN GPS driver +// DroneCAN GPS driver // #pragma once #include #include +#if HAL_ENABLE_LIBUAVCAN_DRIVERS #include "AP_GPS.h" #include "GPS_Backend.h" #include "RTCM3_Parser.h" #include -class FixCb; -class Fix2Cb; -class AuxCb; -class HeadingCb; -class StatusCb; -#if GPS_MOVING_BASELINE -class MovingBaselineDataCb; -class RelPosHeadingCb; -#endif - class AP_GPS_UAVCAN : public AP_GPS_Backend { public: AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role role); @@ -53,13 +44,14 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { static void subscribe_msgs(AP_UAVCAN* ap_uavcan); static AP_GPS_Backend* probe(AP_GPS &_gps, AP_GPS::GPS_State &_state); - static void handle_fix2_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const Fix2Cb &cb); - static void handle_aux_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AuxCb &cb); - static void handle_heading_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const HeadingCb &cb); - static void handle_status_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const StatusCb &cb); + static void handle_fix2_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg); + + static void handle_aux_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg); + static void handle_heading_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg); + static void handle_status_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg); #if GPS_MOVING_BASELINE - static void handle_moving_baseline_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MovingBaselineDataCb &cb); - static void handle_relposheading_msg_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const RelPosHeadingCb &cb); + static void handle_moving_baseline_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg); + static void handle_relposheading_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg); #endif static bool backends_healthy(char failure_msg[], uint16_t failure_msg_len); void inject_data(const uint8_t *data, uint16_t len) override; @@ -90,15 +82,15 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { // returns true once configuration has finished bool do_config(void); - void handle_fix2_msg(const Fix2Cb &cb); - void handle_aux_msg(const AuxCb &cb); - void handle_heading_msg(const HeadingCb &cb); - void handle_status_msg(const StatusCb &cb); + void handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec); + void handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg); + void handle_heading_msg(const ardupilot_gnss_Heading& msg); + void handle_status_msg(const ardupilot_gnss_Status& msg); void handle_velocity(const float vx, const float vy, const float vz); #if GPS_MOVING_BASELINE - void handle_moving_baseline_msg(const MovingBaselineDataCb &cb, uint8_t node_id); - void handle_relposheading_msg(const RelPosHeadingCb &cb, uint8_t node_id); + void handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id); + void handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id); #endif static bool take_registry(); @@ -147,3 +139,4 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { bool handle_param_get_set_response_float(AP_UAVCAN* ap_uavcan, const uint8_t node_id, const char* name, float &value); void handle_param_save_response(AP_UAVCAN* ap_uavcan, const uint8_t node_id, bool success); }; +#endif From 7112d156edbee0d05085e438f2da8678c0a184ba Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 4 Jan 2023 13:04:50 +1100 Subject: [PATCH 035/287] AP_Compass: replace libuavcan with libcanard based driver --- libraries/AP_Compass/AP_Compass.cpp | 2 +- libraries/AP_Compass/AP_Compass.h | 5 ++ libraries/AP_Compass/AP_Compass_UAVCAN.cpp | 67 +++++++++++----------- libraries/AP_Compass/AP_Compass_UAVCAN.h | 9 +-- 4 files changed, 43 insertions(+), 40 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index c3f8625533c499..4456927f83e815 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -1286,7 +1286,7 @@ void Compass::_detect_backends(void) } #endif -#if AP_COMPASS_SITL_ENABLED +#if AP_COMPASS_SITL_ENABLED && !AP_TEST_DRONECAN_DRIVERS ADD_BACKEND(DRIVER_SITL, new AP_Compass_SITL()); #endif diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index 59e91e932faab0..cae86595cab0bc 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -246,6 +246,11 @@ friend class AP_Compass_Backend; _board_orientation = orientation; } + // get overall board orientation + enum Rotation get_board_orientation(void) const { + return _board_orientation; + } + /// Set the motor compensation type /// /// @param comp_type 0 = disabled, 1 = enabled use throttle, 2 = enabled use current diff --git a/libraries/AP_Compass/AP_Compass_UAVCAN.cpp b/libraries/AP_Compass/AP_Compass_UAVCAN.cpp index 9a3fe29688f337..75cefff4dd6851 100644 --- a/libraries/AP_Compass/AP_Compass_UAVCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_UAVCAN.cpp @@ -21,16 +21,12 @@ #include #include - -#include -#include +#include +#include extern const AP_HAL::HAL& hal; #define LOG_TAG "COMPASS" -// Frontend Registry Binders -UC_REGISTRY_BINDER(MagCb, uavcan::equipment::ahrs::MagneticFieldStrength); -UC_REGISTRY_BINDER(Mag2Cb, uavcan::equipment::ahrs::MagneticFieldStrength2); AP_Compass_UAVCAN::DetectedModules AP_Compass_UAVCAN::_detected_modules[]; HAL_Semaphore AP_Compass_UAVCAN::_sem_registry; @@ -48,23 +44,12 @@ void AP_Compass_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) if (ap_uavcan == nullptr) { return; } - - auto* node = ap_uavcan->get_node(); - - uavcan::Subscriber *mag_listener; - mag_listener = new uavcan::Subscriber(*node); - const int mag_listener_res = mag_listener->start(MagCb(ap_uavcan, &handle_magnetic_field)); - if (mag_listener_res < 0) { - AP_HAL::panic("UAVCAN Mag subscriber start problem\n\r"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_magnetic_field, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("mag_sub"); } - uavcan::Subscriber *mag2_listener; - mag2_listener = new uavcan::Subscriber(*node); - const int mag2_listener_res = mag2_listener->start(Mag2Cb(ap_uavcan, &handle_magnetic_field_2)); - if (mag2_listener_res < 0) { - AP_HAL::panic("UAVCAN Mag subscriber start problem\n\r"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_magnetic_field_2, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("mag2_sub"); } } @@ -87,6 +72,23 @@ AP_Compass_Backend* AP_Compass_UAVCAN::probe(uint8_t index) _detected_modules[index].node_id, _detected_modules[index].ap_uavcan->get_driver_index(), _detected_modules[index].sensor_id); +#if AP_TEST_DRONECAN_DRIVERS + // Scroll through the registered compasses, and set the offsets + if (driver->_compass.get_offsets(index).is_zero()) { + driver->_compass.set_offsets(index, AP::sitl()->mag_ofs[index]); + } + + // we want to simulate a calibrated compass by default, so set + // scale to 1 + AP_Param::set_default_by_name("COMPASS_SCALE", 1); + AP_Param::set_default_by_name("COMPASS_SCALE2", 1); + AP_Param::set_default_by_name("COMPASS_SCALE3", 1); + driver->save_dev_id(index); + driver->set_rotation(index, ROTATION_NONE); + + // make first compass external + driver->set_external(index, true); +#endif } } return driver; @@ -170,31 +172,31 @@ void AP_Compass_UAVCAN::handle_mag_msg(const Vector3f &mag) accumulate_sample(raw_field, _instance); } -void AP_Compass_UAVCAN::handle_magnetic_field(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MagCb &cb) +void AP_Compass_UAVCAN::handle_magnetic_field(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg) { WITH_SEMAPHORE(_sem_registry); Vector3f mag_vector; - AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, 0); + AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, 0); if (driver != nullptr) { - mag_vector[0] = cb.msg->magnetic_field_ga[0]; - mag_vector[1] = cb.msg->magnetic_field_ga[1]; - mag_vector[2] = cb.msg->magnetic_field_ga[2]; + mag_vector[0] = msg.magnetic_field_ga[0]; + mag_vector[1] = msg.magnetic_field_ga[1]; + mag_vector[2] = msg.magnetic_field_ga[2]; driver->handle_mag_msg(mag_vector); } } -void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_UAVCAN* ap_uavcan, uint8_t node_id, const Mag2Cb &cb) +void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg) { WITH_SEMAPHORE(_sem_registry); Vector3f mag_vector; - uint8_t sensor_id = cb.msg->sensor_id; - AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, sensor_id); + uint8_t sensor_id = msg.sensor_id; + AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, sensor_id); if (driver != nullptr) { - mag_vector[0] = cb.msg->magnetic_field_ga[0]; - mag_vector[1] = cb.msg->magnetic_field_ga[1]; - mag_vector[2] = cb.msg->magnetic_field_ga[2]; + mag_vector[0] = msg.magnetic_field_ga[0]; + mag_vector[1] = msg.magnetic_field_ga[1]; + mag_vector[2] = msg.magnetic_field_ga[2]; driver->handle_mag_msg(mag_vector); } } @@ -203,5 +205,4 @@ void AP_Compass_UAVCAN::read(void) { drain_accumulated_samples(_instance); } - #endif // AP_COMPASS_UAVCAN_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_UAVCAN.h b/libraries/AP_Compass/AP_Compass_UAVCAN.h index 8eb57d9884198d..b68860c4e2e1e3 100644 --- a/libraries/AP_Compass/AP_Compass_UAVCAN.h +++ b/libraries/AP_Compass/AP_Compass_UAVCAN.h @@ -8,9 +8,6 @@ #include -class MagCb; -class Mag2Cb; - class AP_Compass_UAVCAN : public AP_Compass_Backend { public: AP_Compass_UAVCAN(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id, uint32_t devid); @@ -20,13 +17,13 @@ class AP_Compass_UAVCAN : public AP_Compass_Backend { static void subscribe_msgs(AP_UAVCAN* ap_uavcan); static AP_Compass_Backend* probe(uint8_t index); static uint32_t get_detected_devid(uint8_t index) { return _detected_modules[index].devid; } - static void handle_magnetic_field(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MagCb &cb); - static void handle_magnetic_field_2(AP_UAVCAN* ap_uavcan, uint8_t node_id, const Mag2Cb &cb); + static void handle_magnetic_field(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg); + static void handle_magnetic_field_2(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg); private: bool init(); - // callback for UAVCAN messages + // callback for DroneCAN messages void handle_mag_msg(const Vector3f &mag); static AP_Compass_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id); From 54df802d59fce134d343b7cc7f3ae6d5623a51ff Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 4 Jan 2023 12:44:30 +1100 Subject: [PATCH 036/287] AP_Baro: replace libuavcan with libcanard based driver --- libraries/AP_Baro/AP_Baro.cpp | 3 ++ libraries/AP_Baro/AP_Baro.h | 1 + libraries/AP_Baro/AP_Baro_SITL.cpp | 16 +++++------ libraries/AP_Baro/AP_Baro_SITL.h | 12 ++++---- libraries/AP_Baro/AP_Baro_UAVCAN.cpp | 42 +++++++++------------------- libraries/AP_Baro/AP_Baro_UAVCAN.h | 14 ++++++---- 6 files changed, 39 insertions(+), 49 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 2d7371ae43c860..9c1f3665d52801 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -605,10 +605,13 @@ void AP_Baro::init(void) if (sitl == nullptr) { AP_HAL::panic("No SITL pointer"); } +#if !AP_TEST_DRONECAN_DRIVERS + // use dronecan instances instead of SITL instances for(uint8_t i = 0; i < sitl->baro_count; i++) { ADD_BACKEND(new AP_Baro_SITL(*this)); } #endif +#endif #if AP_BARO_UAVCAN_ENABLED // Detect UAVCAN Modules, try as many times as there are driver slots diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index 3d423164cd1ecb..d61a43b9b1d478 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -28,6 +28,7 @@ class AP_Baro { friend class AP_Baro_Backend; friend class AP_Baro_SITL; // for access to sensors[] + friend class AP_Baro_UAVCAN; // for access to sensors[] public: AP_Baro(); diff --git a/libraries/AP_Baro/AP_Baro_SITL.cpp b/libraries/AP_Baro/AP_Baro_SITL.cpp index 1dd4e0e15be7a4..9b41e336459d72 100644 --- a/libraries/AP_Baro/AP_Baro_SITL.cpp +++ b/libraries/AP_Baro/AP_Baro_SITL.cpp @@ -29,17 +29,17 @@ AP_Baro_SITL::AP_Baro_SITL(AP_Baro &baro) : void AP_Baro_SITL::temperature_adjustment(float &p, float &T) { const float tsec = AP_HAL::millis() * 0.001f; - const float T_sensor = T + _sitl->temp_board_offset; - const float tconst = _sitl->temp_tconst; + const float T_sensor = T + AP::sitl()->temp_board_offset; + const float tconst = AP::sitl()->temp_tconst; if (tsec < 23 * tconst) { // time which past the equation below equals T_sensor within approx. 1E-9 - const float T0 = _sitl->temp_start; + const float T0 = AP::sitl()->temp_start; T = T_sensor - (T_sensor - T0) * expf(-tsec / tconst); } else { T = T_sensor; } - const float baro_factor = _sitl->temp_baro_factor; + const float baro_factor = AP::sitl()->temp_baro_factor; const float Tzero = 30.0f; // start baro adjustment at 30C if (is_positive(baro_factor)) { // this produces a pressure change with temperature that @@ -129,7 +129,7 @@ void AP_Baro_SITL::_timer() #endif // add in correction for wind effects - p += wind_pressure_correction(); + p += wind_pressure_correction(_instance); _recent_press = p; _recent_temp = T; @@ -157,12 +157,12 @@ void AP_Baro_SITL::update(void) /* return pressure correction for wind based on SIM_BARO_WCF parameters */ -float AP_Baro_SITL::wind_pressure_correction(void) +float AP_Baro_SITL::wind_pressure_correction(uint8_t instance) { - const auto &bp = _sitl->baro[_instance]; + const auto &bp = AP::sitl()->baro[instance]; // correct for static pressure position errors - const Vector3f &airspeed_vec_bf = _sitl->state.velocity_air_bf; + const Vector3f &airspeed_vec_bf = AP::sitl()->state.velocity_air_bf; float error = 0.0; const float sqx = sq(airspeed_vec_bf.x); diff --git a/libraries/AP_Baro/AP_Baro_SITL.h b/libraries/AP_Baro/AP_Baro_SITL.h index 5fe90a985cc724..68ba04d016ac0b 100644 --- a/libraries/AP_Baro/AP_Baro_SITL.h +++ b/libraries/AP_Baro/AP_Baro_SITL.h @@ -14,6 +14,12 @@ class AP_Baro_SITL : public AP_Baro_Backend { void update() override; + // adjust for simulated board temperature + static void temperature_adjustment(float &p, float &T); + + // adjust for wind effects + static float wind_pressure_correction(uint8_t instance); + protected: void update_healthy_flag(uint8_t instance) override { _frontend.sensors[instance].healthy = healthy(instance); }; @@ -32,12 +38,6 @@ class AP_Baro_SITL : public AP_Baro_Backend { static const uint8_t _buffer_length = 50; VectorN _buffer; - // adjust for simulated board temperature - void temperature_adjustment(float &p, float &T); - - // adjust for wind effects - float wind_pressure_correction(void); - // is the barometer usable for flight bool healthy(uint8_t instance); diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp index 0c7c46e5cc8a95..0a2a41ca802ffe 100644 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp @@ -3,19 +3,14 @@ #if AP_BARO_UAVCAN_ENABLED #include -#include - -#include -#include +#include +#include "AP_Baro_SITL.h" +#include extern const AP_HAL::HAL& hal; #define LOG_TAG "Baro" -//UAVCAN Frontend Registry Binder -UC_REGISTRY_BINDER(PressureCb, uavcan::equipment::air_data::StaticPressure); -UC_REGISTRY_BINDER(TemperatureCb, uavcan::equipment::air_data::StaticTemperature); - AP_Baro_UAVCAN::DetectedModules AP_Baro_UAVCAN::_detected_modules[]; HAL_Semaphore AP_Baro_UAVCAN::_sem_registry; @@ -31,23 +26,12 @@ void AP_Baro_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) if (ap_uavcan == nullptr) { return; } - - auto* node = ap_uavcan->get_node(); - - uavcan::Subscriber *pressure_listener; - pressure_listener = new uavcan::Subscriber(*node); - // Msg Handler - const int pressure_listener_res = pressure_listener->start(PressureCb(ap_uavcan, &handle_pressure)); - if (pressure_listener_res < 0) { - AP_HAL::panic("UAVCAN Baro subscriber start problem\n\r"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_pressure, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("pressure_sub"); } - uavcan::Subscriber *temperature_listener; - temperature_listener = new uavcan::Subscriber(*node); - // Msg Handler - const int temperature_listener_res = temperature_listener->start(TemperatureCb(ap_uavcan, &handle_temperature)); - if (temperature_listener_res < 0) { - AP_HAL::panic("UAVCAN Baro subscriber start problem\n\r"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_temperature, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("temperature_sub"); } } @@ -137,36 +121,36 @@ void AP_Baro_UAVCAN::_update_and_wrap_accumulator(float *accum, float val, uint8 } } -void AP_Baro_UAVCAN::handle_pressure(AP_UAVCAN* ap_uavcan, uint8_t node_id, const PressureCb &cb) +void AP_Baro_UAVCAN::handle_pressure(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg) { AP_Baro_UAVCAN* driver; { WITH_SEMAPHORE(_sem_registry); - driver = get_uavcan_backend(ap_uavcan, node_id, true); + driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, true); if (driver == nullptr) { return; } } { WITH_SEMAPHORE(driver->_sem_baro); - _update_and_wrap_accumulator(&driver->_pressure, cb.msg->static_pressure, &driver->_pressure_count, 32); + _update_and_wrap_accumulator(&driver->_pressure, msg.static_pressure, &driver->_pressure_count, 32); driver->new_pressure = true; } } -void AP_Baro_UAVCAN::handle_temperature(AP_UAVCAN* ap_uavcan, uint8_t node_id, const TemperatureCb &cb) +void AP_Baro_UAVCAN::handle_temperature(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg) { AP_Baro_UAVCAN* driver; { WITH_SEMAPHORE(_sem_registry); - driver = get_uavcan_backend(ap_uavcan, node_id, false); + driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, false); if (driver == nullptr) { return; } } { WITH_SEMAPHORE(driver->_sem_baro); - driver->_temperature = KELVIN_TO_C(cb.msg->static_temperature); + driver->_temperature = KELVIN_TO_C(msg.static_temperature); } } diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.h b/libraries/AP_Baro/AP_Baro_UAVCAN.h index 2edcc2e871cb59..38c73eb2d8f39e 100644 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.h +++ b/libraries/AP_Baro/AP_Baro_UAVCAN.h @@ -5,9 +5,9 @@ #if AP_BARO_UAVCAN_ENABLED #include - -class PressureCb; -class TemperatureCb; +#if AP_TEST_DRONECAN_DRIVERS +#include +#endif class AP_Baro_UAVCAN : public AP_Baro_Backend { public: @@ -19,9 +19,11 @@ class AP_Baro_UAVCAN : public AP_Baro_Backend { static AP_Baro_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, bool create_new); static AP_Baro_Backend* probe(AP_Baro &baro); - static void handle_pressure(AP_UAVCAN* ap_uavcan, uint8_t node_id, const PressureCb &cb); - static void handle_temperature(AP_UAVCAN* ap_uavcan, uint8_t node_id, const TemperatureCb &cb); - + static void handle_pressure(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg); + static void handle_temperature(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg); +#if AP_TEST_DRONECAN_DRIVERS + void update_healthy_flag(uint8_t instance) override { _frontend.sensors[instance].healthy = !AP::sitl()->baro[instance].disable; }; +#endif private: static void _update_and_wrap_accumulator(float *accum, float val, uint8_t *count, const uint8_t max_count); From 0d90e0377ae70aa4802b032b5a455aa31f7c9f0f Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 4 Jan 2023 22:25:39 +1100 Subject: [PATCH 037/287] AP_Airspeed: replace libuavcan with libcanard based driver --- libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp | 50 ++++++-------------- libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h | 7 +-- 2 files changed, 17 insertions(+), 40 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp index deea83c2aa58ad..d905dc132b96df 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp @@ -4,22 +4,12 @@ #include #include +#include -#include -#if AP_AIRSPEED_HYGROMETER_ENABLE -#include -#endif extern const AP_HAL::HAL& hal; #define LOG_TAG "AirSpeed" -// Frontend Registry Binders -UC_REGISTRY_BINDER(AirspeedCb, uavcan::equipment::air_data::RawAirData); - -#if AP_AIRSPEED_HYGROMETER_ENABLE -UC_REGISTRY_BINDER(HygrometerCb, dronecan::sensors::hygrometer::Hygrometer); -#endif - AP_Airspeed_UAVCAN::DetectedModules AP_Airspeed_UAVCAN::_detected_modules[]; HAL_Semaphore AP_Airspeed_UAVCAN::_sem_registry; @@ -34,22 +24,13 @@ void AP_Airspeed_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) return; } - auto* node = ap_uavcan->get_node(); - - uavcan::Subscriber *airspeed_listener; - airspeed_listener = new uavcan::Subscriber(*node); - - const int airspeed_listener_res = airspeed_listener->start(AirspeedCb(ap_uavcan, &handle_airspeed)); - if (airspeed_listener_res < 0) { - AP_HAL::panic("DroneCAN Airspeed subscriber error \n"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_airspeed, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("airspeed_sub"); } #if AP_AIRSPEED_HYGROMETER_ENABLE - uavcan::Subscriber *hygrometer_listener; - hygrometer_listener = new uavcan::Subscriber(*node); - const int hygrometer_listener_res = hygrometer_listener->start(HygrometerCb(ap_uavcan, &handle_hygrometer)); - if (hygrometer_listener_res < 0) { - AP_HAL::panic("DroneCAN Hygrometer subscriber error\n"); + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_hygrometer, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("hygrometer_sub"); } #endif } @@ -128,18 +109,18 @@ AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, return nullptr; } -void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AirspeedCb &cb) +void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg) { WITH_SEMAPHORE(_sem_registry); - AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); if (driver != nullptr) { WITH_SEMAPHORE(driver->_sem_airspeed); - driver->_pressure = cb.msg->differential_pressure; - if (!isnan(cb.msg->static_air_temperature) && - cb.msg->static_air_temperature > 0) { - driver->_temperature = KELVIN_TO_C(cb.msg->static_air_temperature); + driver->_pressure = msg.differential_pressure; + if (!isnan(msg.static_air_temperature) && + msg.static_air_temperature > 0) { + driver->_temperature = KELVIN_TO_C(msg.static_air_temperature); driver->_have_temperature = true; } driver->_last_sample_time_ms = AP_HAL::millis(); @@ -147,16 +128,16 @@ void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, } #if AP_AIRSPEED_HYGROMETER_ENABLE -void AP_Airspeed_UAVCAN::handle_hygrometer(AP_UAVCAN* ap_uavcan, uint8_t node_id, const HygrometerCb &cb) +void AP_Airspeed_UAVCAN::handle_hygrometer(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg) { WITH_SEMAPHORE(_sem_registry); - AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); if (driver != nullptr) { WITH_SEMAPHORE(driver->_sem_airspeed); - driver->_hygrometer.temperature = KELVIN_TO_C(cb.msg->temperature); - driver->_hygrometer.humidity = cb.msg->humidity; + driver->_hygrometer.temperature = KELVIN_TO_C(msg.temperature); + driver->_hygrometer.humidity = msg.humidity; driver->_hygrometer.last_sample_ms = AP_HAL::millis(); } } @@ -213,5 +194,4 @@ bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &tempera return true; } #endif // AP_AIRSPEED_HYGROMETER_ENABLE - #endif // AP_AIRSPEED_UAVCAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h index ae67d77c61cb5a..83d99568b7d0e4 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h @@ -12,9 +12,6 @@ #include -class AirspeedCb; -class HygrometerCb; - class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { public: AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance); @@ -38,8 +35,8 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { private: - static void handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AirspeedCb &cb); - static void handle_hygrometer(AP_UAVCAN* ap_uavcan, uint8_t node_id, const HygrometerCb &cb); + static void handle_airspeed(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg); + static void handle_hygrometer(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg); static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id); From 6a1460efb047175b31711802360a37be3328d6a5 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 4 Jan 2023 22:11:32 +1100 Subject: [PATCH 038/287] AP_BattMonitor: replace libuavcan with libcanard based driver --- .../AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp | 145 ++++++------------ .../AP_BattMonitor/AP_BattMonitor_UAVCAN.h | 28 ++-- 2 files changed, 57 insertions(+), 116 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp index 2c1c7fbc8bfd3d..ce1d66ccf90f9a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp @@ -13,11 +13,6 @@ #include #include -#include -#include -#include -#include - #define LOG_TAG "BattMon" extern const AP_HAL::HAL& hal; @@ -36,13 +31,6 @@ const AP_Param::GroupInfo AP_BattMonitor_UAVCAN::var_info[] = { AP_GROUPEND }; -UC_REGISTRY_BINDER(BattInfoCb, uavcan::equipment::power::BatteryInfo); -UC_REGISTRY_BINDER(BattInfoAuxCb, ardupilot::equipment::power::BatteryInfoAux); -UC_REGISTRY_BINDER(MpptStreamCb, mppt::Stream); - -static void trampoline_handleOutputEnable(const uavcan::ServiceCallResult& resp); -static uavcan::ServiceClient* outputEnable_client[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - /// Constructor AP_BattMonitor_UAVCAN::AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params ¶ms) : AP_BattMonitor_Backend(mon, mon_state, params), @@ -61,43 +49,17 @@ void AP_BattMonitor_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) return; } - auto* node = ap_uavcan->get_node(); - - uavcan::Subscriber *battinfo_listener; - battinfo_listener = new uavcan::Subscriber(*node); - // Backend Msg Handler - const int battinfo_listener_res = battinfo_listener->start(BattInfoCb(ap_uavcan, &handle_battery_info_trampoline)); - if (battinfo_listener_res < 0) { - AP_BoardConfig::allocation_error("UAVCAN BatteryInfo subscriber start problem\n\r"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_battery_info_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("battinfo_sub"); } - uavcan::Subscriber *battinfo_aux_listener; - battinfo_aux_listener = new uavcan::Subscriber(*node); - // Backend Msg Handler - const int battinfo_aux_listener_res = battinfo_aux_listener->start(BattInfoAuxCb(ap_uavcan, &handle_battery_info_aux_trampoline)); - if (battinfo_aux_listener_res < 0) { - AP_BoardConfig::allocation_error("UAVCAN BatteryInfoAux subscriber start problem"); - return; - } - - uavcan::Subscriber *mppt_stream_listener; - mppt_stream_listener = new uavcan::Subscriber(*node); - // Backend Msg Handler - const int mppt_stream_listener_res = mppt_stream_listener->start(MpptStreamCb(ap_uavcan, &handle_mppt_stream_trampoline)); - if (mppt_stream_listener_res < 0) { - AP_BoardConfig::allocation_error("UAVCAN Mppt::Stream subscriber start problem"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_battery_info_aux_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("battinfo_aux_sub"); } - // set up callback to verify mppt::OutputEnable - const uint8_t driver_index = ap_uavcan->get_driver_index(); - outputEnable_client[driver_index] = new uavcan::ServiceClient(*node); - if (outputEnable_client[driver_index] == nullptr || outputEnable_client[driver_index]->init() < 0) { - AP_BoardConfig::allocation_error("UAVCAN Mppt::outputEnable client start problem"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_mppt_stream_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("mppt_stream_sub"); } - outputEnable_client[driver_index]->setCallback(trampoline_handleOutputEnable); } AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t battery_id) @@ -128,7 +90,6 @@ AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u batmon->_ap_uavcan = ap_uavcan; batmon->_node_id = node_id; batmon->_instance = i; - batmon->_node = ap_uavcan->get_node(); batmon->init(); AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, @@ -141,13 +102,13 @@ AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u return nullptr; } -void AP_BattMonitor_UAVCAN::handle_battery_info(const BattInfoCb &cb) +void AP_BattMonitor_UAVCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg) { - update_interim_state(cb.msg->voltage, cb.msg->current, cb.msg->temperature, cb.msg->state_of_charge_pct); + update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct); WITH_SEMAPHORE(_sem_battmon); - _remaining_capacity_wh = cb.msg->remaining_capacity_wh; - _full_charge_capacity_wh = cb.msg->full_charge_capacity_wh; + _remaining_capacity_wh = msg.remaining_capacity_wh; + _full_charge_capacity_wh = msg.full_charge_capacity_wh; } void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc) @@ -178,18 +139,18 @@ void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const floa _interim_state.healthy = true; } -void AP_BattMonitor_UAVCAN::handle_battery_info_aux(const BattInfoAuxCb &cb) +void AP_BattMonitor_UAVCAN::handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg) { WITH_SEMAPHORE(_sem_battmon); - uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), cb.msg->voltage_cell.size()); - float remaining_capacity_ah = _remaining_capacity_wh / cb.msg->nominal_voltage; - float full_charge_capacity_ah = _full_charge_capacity_wh / cb.msg->nominal_voltage; + uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len); + float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage; + float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage; - _cycle_count = cb.msg->cycle_count; + _cycle_count = msg.cycle_count; for (uint8_t i = 0; i < cell_count; i++) { - _interim_state.cell_voltages.cells[i] = cb.msg->voltage_cell[i] * 1000; + _interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000; } - _interim_state.is_powering_off = cb.msg->is_powering_off; + _interim_state.is_powering_off = msg.is_powering_off; _interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000; _interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh; _interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600); @@ -201,17 +162,17 @@ void AP_BattMonitor_UAVCAN::handle_battery_info_aux(const BattInfoAuxCb &cb) _has_battery_info_aux = true; } -void AP_BattMonitor_UAVCAN::handle_mppt_stream(const MpptStreamCb &cb) +void AP_BattMonitor_UAVCAN::handle_mppt_stream(const mppt_Stream &msg) { const bool use_input_value = option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value); - const float voltage = use_input_value ? cb.msg->input_voltage : cb.msg->output_voltage; - const float current = use_input_value ? cb.msg->input_current : cb.msg->output_current; + const float voltage = use_input_value ? msg.input_voltage : msg.output_voltage; + const float current = use_input_value ? msg.input_current : msg.output_current; // use an invalid soc so we use the library calculated one const uint8_t soc = 127; // convert C to Kelvin - const float temperature_K = isnan(cb.msg->temperature) ? 0 : C_TO_KELVIN(cb.msg->temperature); + const float temperature_K = isnan(msg.temperature) ? 0 : C_TO_KELVIN(msg.temperature); update_interim_state(voltage, current, temperature_K, soc); @@ -229,38 +190,38 @@ void AP_BattMonitor_UAVCAN::handle_mppt_stream(const MpptStreamCb &cb) } #if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG - if (_mppt.fault_flags != cb.msg->fault_flags) { - mppt_report_faults(_instance, cb.msg->fault_flags); + if (_mppt.fault_flags != msg.fault_flags) { + mppt_report_faults(_instance, msg.fault_flags); } #endif - _mppt.fault_flags = cb.msg->fault_flags; + _mppt.fault_flags = msg.fault_flags; } -void AP_BattMonitor_UAVCAN::handle_battery_info_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const BattInfoCb &cb) +void AP_BattMonitor_UAVCAN::handle_battery_info_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, cb.msg->battery_id); + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.battery_id); if (driver == nullptr) { return; } - driver->handle_battery_info(cb); + driver->handle_battery_info(msg); } -void AP_BattMonitor_UAVCAN::handle_battery_info_aux_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const BattInfoAuxCb &cb) +void AP_BattMonitor_UAVCAN::handle_battery_info_aux_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, cb.msg->battery_id); + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.battery_id); if (driver == nullptr) { return; } - driver->handle_battery_info_aux(cb); + driver->handle_battery_info_aux(msg); } -void AP_BattMonitor_UAVCAN::handle_mppt_stream_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MpptStreamCb &cb) +void AP_BattMonitor_UAVCAN::handle_mppt_stream_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const mppt_Stream &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, node_id); + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, transfer.source_node_id); if (driver == nullptr) { return; } - driver->handle_mppt_stream(cb); + driver->handle_mppt_stream(msg); } // read - read the voltage and current @@ -351,7 +312,7 @@ void AP_BattMonitor_UAVCAN::mppt_check_powered_state() // force should be true to force sending the state change request to the MPPT void AP_BattMonitor_UAVCAN::mppt_set_powered_state(bool power_on) { - if (_ap_uavcan == nullptr || _node == nullptr || !_mppt.is_detected) { + if (_ap_uavcan == nullptr || !_mppt.is_detected) { return; } @@ -360,48 +321,28 @@ void AP_BattMonitor_UAVCAN::mppt_set_powered_state(bool power_on) GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: powering %s%s", (unsigned)_instance+1, _mppt.powered_state ? "ON" : "OFF", (_mppt.powered_state_remote_ms == 0) ? "" : " Retry"); - // set up a request /w a status callback - mppt::OutputEnable::Request request; + mppt_OutputEnableRequest request; request.enable = _mppt.powered_state; request.disable = !request.enable; - _mppt.powered_state_remote_ms = AP_HAL::millis(); - const uint8_t driver_index = _ap_uavcan->get_driver_index(); - outputEnable_client[driver_index]->call(_node_id, request); -} - -// callback trampoline of outputEnable response to verify it is enabled or disabled -void trampoline_handleOutputEnable(const uavcan::ServiceCallResult& resp) -{ - uint8_t can_num_drivers = AP::can().get_num_drivers(); - for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i); - if (uavcan == nullptr) { - continue; + if (mppt_outputenable_client == nullptr) { + mppt_outputenable_client = new Canard::Client{_ap_uavcan->get_canard_iface(), mppt_outputenable_res_cb}; + if (mppt_outputenable_client == nullptr) { + return; } - - const uint8_t node_id = resp.getResponse().getSrcNodeID().get(); - AP_BattMonitor_UAVCAN* driver = AP_BattMonitor_UAVCAN::get_uavcan_backend(uavcan, node_id, node_id); - if (driver == nullptr) { - continue; - } - - const auto &response = resp.getResponse(); - const uint8_t nodeId = response.getSrcNodeID().get(); - const bool enabled = response.enabled; - driver->handle_outputEnable_response(nodeId, enabled); } + mppt_outputenable_client->request(_node_id, request); } // callback from outputEnable to verify it is enabled or disabled -void AP_BattMonitor_UAVCAN::handle_outputEnable_response(const uint8_t nodeId, const bool enabled) +void AP_BattMonitor_UAVCAN::handle_outputEnable_response(const CanardRxTransfer& transfer, const mppt_OutputEnableResponse& response) { - if (nodeId != _node_id) { + if (transfer.source_node_id != _node_id) { // this response is not from the node we are looking for return; } - if (enabled == _mppt.powered_state) { + if (response.enabled == _mppt.powered_state) { // we got back what we expected it to be. We set it on, it now says it on (or vice versa). // Clear the timer so we don't re-request _mppt.powered_state_remote_ms = 0; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h index ec1c517d4a961c..475d7210bb1119 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h @@ -2,9 +2,8 @@ #include "AP_BattMonitor.h" #include "AP_BattMonitor_Backend.h" - +#if HAL_ENABLE_LIBUAVCAN_DRIVERS #include -#include #define AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS 5000000 // sensor becomes unhealthy if no successful readings for 5 seconds @@ -12,10 +11,6 @@ #define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 #endif -class BattInfoCb; -class BattInfoAuxCb; -class MpptStreamCb; - class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend { public: @@ -53,16 +48,15 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend static void subscribe_msgs(AP_UAVCAN* ap_uavcan); static AP_BattMonitor_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t battery_id); - static void handle_battery_info_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const BattInfoCb &cb); - static void handle_battery_info_aux_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const BattInfoAuxCb &cb); - static void handle_mppt_stream_trampoline(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MpptStreamCb &cb); - void handle_outputEnable_response(const uint8_t nodeId, const bool enabled); + static void handle_battery_info_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg); + static void handle_battery_info_aux_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg); + static void handle_mppt_stream_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const mppt_Stream &msg); void mppt_set_powered_state(bool power_on) override; private: - void handle_battery_info(const BattInfoCb &cb); - void handle_battery_info_aux(const BattInfoAuxCb &cb); + void handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg); + void handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg); void update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc); static bool match_battery_id(uint8_t instance, uint8_t battery_id) { @@ -77,7 +71,7 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend OVER_CURRENT = (1U<<2), OVER_TEMPERATURE = (1U<<3), }; - void handle_mppt_stream(const MpptStreamCb &cb); + void handle_mppt_stream(const mppt_Stream &msg); void mppt_check_powered_state(); #if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG @@ -102,7 +96,7 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend bool _has_consumed_energy; bool _has_battery_info_aux; uint8_t _instance; // instance of this battery monitor - uavcan::Node<0> *_node; // UAVCAN node id + AP_Float _curr_mult; // scaling multiplier applied to current reports for adjustment // MPPT variables struct { @@ -112,4 +106,10 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend uint8_t fault_flags; // bits holding fault flags uint32_t powered_state_remote_ms; // timestamp of when request was sent, zeroed on response. Used to retry } _mppt; + + void handle_outputEnable_response(const CanardRxTransfer&, const mppt_OutputEnableResponse&); + + Canard::ObjCallback mppt_outputenable_res_cb{this, &AP_BattMonitor_UAVCAN::handle_outputEnable_response}; + Canard::Client *mppt_outputenable_client; }; +#endif From bcecda5c3f44454fd979dbaf833a6bcf3e0f08b0 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 4 Jan 2023 23:22:18 +1100 Subject: [PATCH 039/287] AP_Opticalflow: replace libuavcan with libcanard based driver --- .../AP_OpticalFlow_HereFlow.cpp | 31 ++++++------------- .../AP_OpticalFlow/AP_OpticalFlow_HereFlow.h | 4 +-- 2 files changed, 11 insertions(+), 24 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp index bbf37c87ade115..d3c506992da03d 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp @@ -6,14 +6,10 @@ #include #include - -#include +#include extern const AP_HAL::HAL& hal; -//UAVCAN Frontend Registry Binder -UC_REGISTRY_BINDER(MeasurementCb, com::hex::equipment::flow::Measurement); - uint8_t AP_OpticalFlow_HereFlow::_node_id = 0; AP_OpticalFlow_HereFlow* AP_OpticalFlow_HereFlow::_driver = nullptr; AP_UAVCAN* AP_OpticalFlow_HereFlow::_ap_uavcan = nullptr; @@ -36,20 +32,13 @@ void AP_OpticalFlow_HereFlow::subscribe_msgs(AP_UAVCAN* ap_uavcan) return; } - auto* node = ap_uavcan->get_node(); - - uavcan::Subscriber *measurement_listener; - measurement_listener = new uavcan::Subscriber(*node); - // Register method to handle incoming HereFlow measurement - const int measurement_listener_res = measurement_listener->start(MeasurementCb(ap_uavcan, &handle_measurement)); - if (measurement_listener_res < 0) { - AP_HAL::panic("UAVCAN Flow subscriber start problem\n\r"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_measurement, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("measurement_sub"); } } //updates driver states based on received HereFlow messages -void AP_OpticalFlow_HereFlow::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MeasurementCb &cb) +void AP_OpticalFlow_HereFlow::handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const com_hex_equipment_flow_Measurement &msg) { if (_driver == nullptr) { return; @@ -58,16 +47,16 @@ void AP_OpticalFlow_HereFlow::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t n //as we only handle one Here Flow at a time as of now if (_ap_uavcan == nullptr) { _ap_uavcan = ap_uavcan; - _node_id = node_id; + _node_id = transfer.source_node_id; } - if (_ap_uavcan == ap_uavcan && _node_id == node_id) { + if (_ap_uavcan == ap_uavcan && _node_id == transfer.source_node_id) { WITH_SEMAPHORE(_driver->_sem); _driver->new_data = true; - _driver->flowRate = Vector2f(cb.msg->flow_integral[0], cb.msg->flow_integral[1]); - _driver->bodyRate = Vector2f(cb.msg->rate_gyro_integral[0], cb.msg->rate_gyro_integral[1]); - _driver->integral_time = cb.msg->integration_interval; - _driver->surface_quality = cb.msg->quality; + _driver->flowRate = Vector2f(msg.flow_integral[0], msg.flow_integral[1]); + _driver->bodyRate = Vector2f(msg.rate_gyro_integral[0], msg.rate_gyro_integral[1]); + _driver->integral_time = msg.integration_interval; + _driver->surface_quality = msg.quality; } } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h index e279a118ebffb2..941fe26681b928 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h @@ -10,8 +10,6 @@ #include -class MeasurementCb; - class AP_OpticalFlow_HereFlow : public OpticalFlow_backend { public: AP_OpticalFlow_HereFlow(AP_OpticalFlow &flow); @@ -22,7 +20,7 @@ class AP_OpticalFlow_HereFlow : public OpticalFlow_backend { static void subscribe_msgs(AP_UAVCAN* ap_uavcan); - static void handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MeasurementCb &cb); + static void handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const com_hex_equipment_flow_Measurement &msg); private: From 805a8707da37dd281acf24b7042ad3af5db103f0 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 5 Jan 2023 11:19:01 +1100 Subject: [PATCH 040/287] AP_RangeFinder: replace libuavcan with libcanard based driver --- .../AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp | 40 +++++++------------ .../AP_RangeFinder/AP_RangeFinder_UAVCAN.h | 4 +- 2 files changed, 16 insertions(+), 28 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp index cba78545cbb2d7..4a5b89ffb028e5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp @@ -6,32 +6,20 @@ #include #include #include - -#include +#include extern const AP_HAL::HAL& hal; #define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0) -//UAVCAN Frontend Registry Binder -UC_REGISTRY_BINDER(MeasurementCb, uavcan::equipment::range_sensor::Measurement); - //links the rangefinder uavcan message to this backend void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) { if (ap_uavcan == nullptr) { return; } - - auto* node = ap_uavcan->get_node(); - - uavcan::Subscriber *measurement_listener; - measurement_listener = new uavcan::Subscriber(*node); - // Register method to handle incoming RangeFinder measurement - const int measurement_listener_res = measurement_listener->start(MeasurementCb(ap_uavcan, &handle_measurement)); - if (measurement_listener_res < 0) { - AP_HAL::panic("UAVCAN RangeFinder subscriber start problem\n\r"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_measurement, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("measurement_sub"); } } @@ -112,32 +100,32 @@ void AP_RangeFinder_UAVCAN::update() } //RangeFinder message handler -void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MeasurementCb &cb) +void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg) { //fetch the matching uavcan driver, node id and sensor id backend instance - AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id, cb.msg->sensor_id, true); + AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.sensor_id, true); if (driver == nullptr) { return; } WITH_SEMAPHORE(driver->_sem); - switch (cb.msg->reading_type) { - case uavcan::equipment::range_sensor::Measurement::READING_TYPE_VALID_RANGE: + switch (msg.reading_type) { + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE: { //update the states in backend instance - driver->_distance_cm = cb.msg->range*100.0f; + driver->_distance_cm = msg.range*100.0f; driver->_last_reading_ms = AP_HAL::millis(); driver->_status = RangeFinder::Status::Good; driver->new_data = true; break; } //Additional states supported by RFND message - case uavcan::equipment::range_sensor::Measurement::READING_TYPE_TOO_CLOSE: + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_CLOSE: { driver->_last_reading_ms = AP_HAL::millis(); driver->_status = RangeFinder::Status::OutOfRangeLow; break; } - case uavcan::equipment::range_sensor::Measurement::READING_TYPE_TOO_FAR: + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR: { driver->_last_reading_ms = AP_HAL::millis(); driver->_status = RangeFinder::Status::OutOfRangeHigh; @@ -149,18 +137,18 @@ void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t nod } } //copy over the sensor type of Rangefinder - switch (cb.msg->sensor_type) { - case uavcan::equipment::range_sensor::Measurement::SENSOR_TYPE_SONAR: + switch (msg.sensor_type) { + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_SONAR: { driver->_sensor_type = MAV_DISTANCE_SENSOR_ULTRASOUND; break; } - case uavcan::equipment::range_sensor::Measurement::SENSOR_TYPE_LIDAR: + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR: { driver->_sensor_type = MAV_DISTANCE_SENSOR_LASER; break; } - case uavcan::equipment::range_sensor::Measurement::SENSOR_TYPE_RADAR: + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_RADAR: { driver->_sensor_type = MAV_DISTANCE_SENSOR_RADAR; break; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h index 5a9282274486d2..18f320583610b3 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h @@ -3,7 +3,7 @@ #include "AP_RangeFinder_Backend.h" #ifndef AP_RANGEFINDER_UAVCAN_ENABLED -#define AP_RANGEFINDER_UAVCAN_ENABLED (HAL_CANMANAGER_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#define AP_RANGEFINDER_UAVCAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) #endif #if AP_RANGEFINDER_UAVCAN_ENABLED @@ -23,7 +23,7 @@ class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { static AP_RangeFinder_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t address, bool create_new); static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); - static void handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MeasurementCb &cb); + static void handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg); protected: virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { From 47e5337fbdbc1ffc59d88d313e85e320d5e4c4eb Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 5 Jan 2023 11:20:19 +1100 Subject: [PATCH 041/287] AP_Proximity: replace libuavcan with libcanard based driver --- .../AP_Proximity/AP_Proximity_DroneCAN.cpp | 33 +++++-------------- .../AP_Proximity/AP_Proximity_DroneCAN.h | 5 ++- 2 files changed, 11 insertions(+), 27 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp index dd94bca0746afa..80456962bd3c8f 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp @@ -23,12 +23,8 @@ #include #include -#include - extern const AP_HAL::HAL& hal; -//DroneCAN Frontend Registry Binder ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY -UC_REGISTRY_BINDER(MeasurementCb, ardupilot::equipment::proximity_sensor::Proximity); ObjectBuffer_TS AP_Proximity_DroneCAN::items(50); @@ -42,19 +38,8 @@ void AP_Proximity_DroneCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) return; } - auto* node = ap_uavcan->get_node(); - - uavcan::Subscriber *measurement_listener; - measurement_listener = new uavcan::Subscriber(*node); - if (measurement_listener == nullptr) { - AP_BoardConfig::allocation_error("DroneCAN_PRX"); - } - - // Register method to handle incoming Proximity measurement - const int measurement_listener_res = measurement_listener->start(MeasurementCb(ap_uavcan, &handle_measurement)); - if (measurement_listener_res < 0) { - AP_BoardConfig::allocation_error("DroneCAN Proximity subscriber start problem\n\r"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_measurement, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("measurement_sub"); } } @@ -169,20 +154,20 @@ float AP_Proximity_DroneCAN::distance_min() const } //Proximity message handler -void AP_Proximity_DroneCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MeasurementCb &cb) +void AP_Proximity_DroneCAN::handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg) { //fetch the matching DroneCAN driver, node id and sensor id backend instance - AP_Proximity_DroneCAN* driver = get_uavcan_backend(ap_uavcan, node_id, cb.msg->sensor_id, true); + AP_Proximity_DroneCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.sensor_id, true); if (driver == nullptr) { return; } WITH_SEMAPHORE(driver->_sem); - switch (cb.msg->reading_type) { - case ardupilot::equipment::proximity_sensor::Proximity::READING_TYPE_GOOD: { + switch (msg.reading_type) { + case ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_READING_TYPE_GOOD: { //update the states in backend instance driver->_last_update_ms = AP_HAL::millis(); driver->_status = AP_Proximity::Status::Good; - const ObstacleItem item = {cb.msg->yaw, cb.msg->pitch, cb.msg->distance}; + const ObstacleItem item = {msg.yaw, msg.pitch, msg.distance}; if (driver->items.space()) { // ignore reading if no place to put it in the queue @@ -191,12 +176,12 @@ void AP_Proximity_DroneCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t nod break; } //Additional states supported by Proximity message - case ardupilot::equipment::proximity_sensor::Proximity::READING_TYPE_NOT_CONNECTED: { + case ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_READING_TYPE_NOT_CONNECTED: { driver->_last_update_ms = AP_HAL::millis(); driver->_status = AP_Proximity::Status::NotConnected; break; } - case ardupilot::equipment::proximity_sensor::Proximity::READING_TYPE_NO_DATA: { + case ARDUPILOT_EQUIPMENT_PROXIMITY_SENSOR_PROXIMITY_READING_TYPE_NO_DATA: { driver->_last_update_ms = AP_HAL::millis(); driver->_status = AP_Proximity::Status::NoData; break; diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h index 3a1eab9a404079..00844c18a6a39e 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h @@ -5,11 +5,10 @@ #include #ifndef AP_PROXIMITY_DRONECAN_ENABLED -#define AP_PROXIMITY_DRONECAN_ENABLED (HAL_CANMANAGER_ENABLED && HAL_PROXIMITY_ENABLED) +#define AP_PROXIMITY_DRONECAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && HAL_PROXIMITY_ENABLED) #endif #if AP_PROXIMITY_DRONECAN_ENABLED -class MeasurementCb; class AP_Proximity_DroneCAN : public AP_Proximity_Backend { @@ -30,7 +29,7 @@ class AP_Proximity_DroneCAN : public AP_Proximity_Backend static void subscribe_msgs(AP_UAVCAN* ap_uavcan); - static void handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t node_id, const MeasurementCb &cb); + static void handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg); private: From 2ede296486c64f540f7aa4a8bc74cd9049afd99e Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 5 Jan 2023 11:20:51 +1100 Subject: [PATCH 042/287] AP_Notify: replace libuavcan with libcanard based driver --- libraries/AP_Notify/AP_Notify.cpp | 4 ++-- libraries/AP_Notify/MMLPlayer.cpp | 2 +- libraries/AP_Notify/UAVCAN_RGB_LED.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index 80103df72320be..b3b3b28cac09cb 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -348,9 +348,9 @@ void AP_Notify::add_backends(void) #endif break; case Notify_LED_UAVCAN: -#if HAL_CANMANAGER_ENABLED +#if HAL_ENABLE_LIBUAVCAN_DRIVERS ADD_BACKEND(new UAVCAN_RGB_LED(0)); -#endif // HAL_CANMANAGER_ENABLED +#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS break; case Notify_LED_Scripting: diff --git a/libraries/AP_Notify/MMLPlayer.cpp b/libraries/AP_Notify/MMLPlayer.cpp index a48fc1f127689a..68bf2e8164a368 100644 --- a/libraries/AP_Notify/MMLPlayer.cpp +++ b/libraries/AP_Notify/MMLPlayer.cpp @@ -64,7 +64,7 @@ void MMLPlayer::start_note(float duration, float frequency, float volume) _note_duration_us = duration*1e6; hal.util->toneAlarm_set_buzzer_tone(frequency, volume, _note_duration_us/1000U); -#if HAL_CANMANAGER_ENABLED +#if HAL_ENABLE_LIBUAVCAN_DRIVERS // support CAN buzzers too uint8_t can_num_drivers = AP::can().get_num_drivers(); diff --git a/libraries/AP_Notify/UAVCAN_RGB_LED.cpp b/libraries/AP_Notify/UAVCAN_RGB_LED.cpp index 3d21c095374c8a..5b705235a79127 100644 --- a/libraries/AP_Notify/UAVCAN_RGB_LED.cpp +++ b/libraries/AP_Notify/UAVCAN_RGB_LED.cpp @@ -17,7 +17,7 @@ #include #include -#if HAL_CANMANAGER_ENABLED +#if HAL_ENABLE_LIBUAVCAN_DRIVERS #include "UAVCAN_RGB_LED.h" #include From 1c2a464be0372dce5a628d446dfc4fb968cb4b11 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 5 Jan 2023 11:21:20 +1100 Subject: [PATCH 043/287] AP_EFI: replace libuavcan with libcanard based driver --- libraries/AP_EFI/AP_EFI_DroneCAN.cpp | 66 ++++++++++++---------------- libraries/AP_EFI/AP_EFI_DroneCAN.h | 7 +-- libraries/AP_EFI/AP_EFI_config.h | 2 +- 3 files changed, 30 insertions(+), 45 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp index 0df6d054841531..18332295e0d293 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp @@ -6,16 +6,12 @@ #include #include - -#include +#include extern const AP_HAL::HAL& hal; AP_EFI_DroneCAN *AP_EFI_DroneCAN::driver; -// DroneCAN Frontend Registry Binder -UC_REGISTRY_BINDER(EFIStatusCb, uavcan::equipment::ice::reciprocating::Status); - // constructor AP_EFI_DroneCAN::AP_EFI_DroneCAN(AP_EFI &_frontend) : AP_EFI_Backend(_frontend) @@ -29,16 +25,9 @@ void AP_EFI_DroneCAN::subscribe_msgs(AP_UAVCAN *ap_uavcan) if (ap_uavcan == nullptr) { return; } - auto* node = ap_uavcan->get_node(); - uavcan::Subscriber *status_listener; - status_listener = new uavcan::Subscriber(*node); - - // Register method to handle incoming status - const int status_listener_res = status_listener->start(EFIStatusCb(ap_uavcan, &trampoline_status)); - if (status_listener_res < 0) { - AP_HAL::panic("DroneCAN EFI subscriber start problem\n\r"); - return; + if (Canard::allocate_sub_arg_callback(ap_uavcan, &trampoline_status, ap_uavcan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); } } @@ -48,86 +37,85 @@ void AP_EFI_DroneCAN::update() } // EFI message handler -void AP_EFI_DroneCAN::trampoline_status(AP_UAVCAN *ap_uavcan, uint8_t node_id, const EFIStatusCb &cb) +void AP_EFI_DroneCAN::trampoline_status(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg) { if (driver == nullptr) { return; } - const uavcan::equipment::ice::reciprocating::Status &pkt = *cb.msg; - driver->handle_status(pkt); + driver->handle_status(msg); } /* handle reciprocating ICE status message from DroneCAN */ -void AP_EFI_DroneCAN::handle_status(const uavcan::equipment::ice::reciprocating::Status &pkt) +void AP_EFI_DroneCAN::handle_status(const uavcan_equipment_ice_reciprocating_Status &pkt) { auto &istate = internal_state; // state maps 1:1 from Engine_State istate.engine_state = Engine_State(pkt.state); - if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED)) { + if (!(pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED)) { istate.crankshaft_sensor_status = Crankshaft_Sensor_Status::NOT_SUPPORTED; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_CRANKSHAFT_SENSOR_ERROR) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR) { istate.crankshaft_sensor_status = Crankshaft_Sensor_Status::ERROR; } else { istate.crankshaft_sensor_status = Crankshaft_Sensor_Status::OK; } - if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_SUPPORTED)) { + if (!(pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED)) { istate.temperature_status = Temperature_Status::NOT_SUPPORTED; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_BELOW_NOMINAL) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_BELOW_NOMINAL) { istate.temperature_status = Temperature_Status::BELOW_NOMINAL; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_ABOVE_NOMINAL) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_ABOVE_NOMINAL) { istate.temperature_status = Temperature_Status::ABOVE_NOMINAL; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_OVERHEATING) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_OVERHEATING) { istate.temperature_status = Temperature_Status::OVERHEATING; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL) { istate.temperature_status = Temperature_Status::EGT_ABOVE_NOMINAL; } else { istate.temperature_status = Temperature_Status::OK; } - if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_FUEL_PRESSURE_SUPPORTED)) { + if (!(pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED)) { istate.fuel_pressure_status = Fuel_Pressure_Status::NOT_SUPPORTED; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_FUEL_PRESSURE_BELOW_NOMINAL) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_BELOW_NOMINAL) { istate.fuel_pressure_status = Fuel_Pressure_Status::BELOW_NOMINAL; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_FUEL_PRESSURE_ABOVE_NOMINAL) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_ABOVE_NOMINAL) { istate.fuel_pressure_status = Fuel_Pressure_Status::ABOVE_NOMINAL; } else { istate.fuel_pressure_status = Fuel_Pressure_Status::OK; } - if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_OIL_PRESSURE_SUPPORTED)) { + if (!(pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED)) { istate.oil_pressure_status = Oil_Pressure_Status::NOT_SUPPORTED; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_OIL_PRESSURE_BELOW_NOMINAL) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_BELOW_NOMINAL) { istate.oil_pressure_status = Oil_Pressure_Status::BELOW_NOMINAL; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_OIL_PRESSURE_ABOVE_NOMINAL) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_ABOVE_NOMINAL) { istate.oil_pressure_status = Oil_Pressure_Status::ABOVE_NOMINAL; } else { istate.oil_pressure_status = Oil_Pressure_Status::OK; } - if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_DETONATION_SUPPORTED)) { + if (!(pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_SUPPORTED)) { istate.detonation_status = Detonation_Status::NOT_SUPPORTED; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_DETONATION_OBSERVED) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_OBSERVED) { istate.detonation_status = Detonation_Status::OBSERVED; } else { istate.detonation_status = Detonation_Status::NOT_OBSERVED; } - if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_MISFIRE_SUPPORTED)) { + if (!(pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_SUPPORTED)) { istate.misfire_status = Misfire_Status::NOT_SUPPORTED; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_MISFIRE_OBSERVED) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_OBSERVED) { istate.misfire_status = Misfire_Status::OBSERVED; } else { istate.misfire_status = Misfire_Status::NOT_OBSERVED; } - if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_DEBRIS_SUPPORTED)) { + if (!(pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_SUPPORTED)) { istate.debris_status = Debris_Status::NOT_SUPPORTED; - } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_DEBRIS_DETECTED) { + } else if (pkt.flags & UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_DETECTED) { istate.debris_status = Debris_Status::DETECTED; } else { istate.debris_status = Debris_Status::NOT_DETECTED; @@ -152,8 +140,8 @@ void AP_EFI_DroneCAN::handle_status(const uavcan::equipment::ice::reciprocating: istate.spark_plug_usage = Spark_Plug_Usage(pkt.spark_plug_usage); // assume max one cylinder status - if (pkt.cylinder_status.size() > 0) { - const auto &cs = pkt.cylinder_status[0]; + if (pkt.cylinder_status.len > 0) { + const auto &cs = pkt.cylinder_status.data[0]; auto &c = istate.cylinder_status; c.ignition_timing_deg = cs.ignition_timing_deg; c.injection_time_ms = cs.injection_time_ms; diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.h b/libraries/AP_EFI/AP_EFI_DroneCAN.h index b84e4be1b0c9f7..fc695962be2139 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.h +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.h @@ -5,9 +5,6 @@ #if AP_EFI_DRONECAN_ENABLED #include -#include - -class EFIStatusCb; class AP_EFI_DroneCAN : public AP_EFI_Backend { public: @@ -16,10 +13,10 @@ class AP_EFI_DroneCAN : public AP_EFI_Backend { void update() override; static void subscribe_msgs(AP_UAVCAN* ap_uavcan); - static void trampoline_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const EFIStatusCb &cb); + static void trampoline_status(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg); private: - void handle_status(const uavcan::equipment::ice::reciprocating::Status &pkt); + void handle_status(const uavcan_equipment_ice_reciprocating_Status &pkt); // singleton for trampoline static AP_EFI_DroneCAN *driver; diff --git a/libraries/AP_EFI/AP_EFI_config.h b/libraries/AP_EFI/AP_EFI_config.h index 29f07638f74a52..0552d781a3c9f4 100644 --- a/libraries/AP_EFI/AP_EFI_config.h +++ b/libraries/AP_EFI/AP_EFI_config.h @@ -16,7 +16,7 @@ #endif #ifndef AP_EFI_DRONECAN_ENABLED -#define AP_EFI_DRONECAN_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED +#define AP_EFI_DRONECAN_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS #endif #ifndef AP_EFI_NWPWU_ENABLED From fcfc4ce88953bcc6f9bb208e6b2fd90810c8ca22 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 5 Jan 2023 11:24:34 +1100 Subject: [PATCH 044/287] SRV_Channel: replace libuavcan with libcanard based driver --- libraries/SRV_Channel/SRV_Channels.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SRV_Channel/SRV_Channels.cpp b/libraries/SRV_Channel/SRV_Channels.cpp index 5f0d47fc90bd6b..798b0830a51d85 100644 --- a/libraries/SRV_Channel/SRV_Channels.cpp +++ b/libraries/SRV_Channel/SRV_Channels.cpp @@ -534,7 +534,7 @@ void SRV_Channels::push() fetteconwire_ptr->update(); #endif -#if HAL_CANMANAGER_ENABLED +#if HAL_ENABLE_LIBUAVCAN_DRIVERS // push outputs to CAN uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { From 4262f506c107a40ab97dbde3626b6d06102270fb Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 5 Jan 2023 17:28:18 +1100 Subject: [PATCH 045/287] AP_OpenDroneID: replace libuavcan with libcanard based driver --- .../AP_OpenDroneID_DroneCAN.cpp | 75 ++++++++----------- 1 file changed, 31 insertions(+), 44 deletions(-) diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp b/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp index bd7a1df8647cfb..8d374ac108e26a 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp @@ -23,26 +23,15 @@ #include #if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include -#include -#include -#include -#include -#include - #include -static uavcan::Publisher* dc_location[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* dc_basic_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* dc_self_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* dc_system[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static uavcan::Publisher* dc_operator_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -// handle ArmStatus -UC_REGISTRY_BINDER(ArmStatusCb, dronecan::remoteid::ArmStatus); -static uavcan::Subscriber *arm_status_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static Canard::Publisher* dc_location[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static Canard::Publisher* dc_basic_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static Canard::Publisher* dc_self_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static Canard::Publisher* dc_system[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static Canard::Publisher* dc_operator_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static void handle_arm_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ArmStatusCb &cb); +static void handle_arm_status(AP_UAVCAN* ap_uavcan, const CanardRxTransfer &transfer, const dronecan_remoteid_ArmStatus &msg); void AP_OpenDroneID::dronecan_init(AP_UAVCAN *uavcan) { @@ -53,46 +42,45 @@ void AP_OpenDroneID::dronecan_init(AP_UAVCAN *uavcan) return; } - dc_location[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + dc_location[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); if (dc_location[driver_index] == nullptr) { goto alloc_failed; } - dc_location[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - dc_location[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + dc_location[driver_index]->set_timeout_ms(20); + dc_location[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - dc_basic_id[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + dc_basic_id[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); if (dc_basic_id[driver_index] == nullptr) { goto alloc_failed; } - dc_basic_id[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - dc_basic_id[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + dc_basic_id[driver_index]->set_timeout_ms(20); + dc_basic_id[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - dc_self_id[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + dc_self_id[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); if (dc_self_id[driver_index] == nullptr) { goto alloc_failed; } - dc_self_id[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - dc_self_id[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + dc_self_id[driver_index]->set_timeout_ms(20); + dc_self_id[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - dc_system[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + dc_system[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); if (dc_system[driver_index] == nullptr) { goto alloc_failed; } - dc_system[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - dc_system[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + dc_system[driver_index]->set_timeout_ms(20); + dc_system[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - dc_operator_id[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + dc_operator_id[driver_index] = new Canard::Publisher(uavcan->get_canard_iface()); if (dc_operator_id[driver_index] == nullptr) { goto alloc_failed; } - dc_operator_id[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); - dc_operator_id[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + dc_operator_id[driver_index]->set_timeout_ms(20); + dc_operator_id[driver_index]->set_priority(CANARD_TRANSFER_PRIORITY_LOW); - arm_status_listener[driver_index] = new uavcan::Subscriber(*uavcan->get_node()); - if (arm_status_listener[driver_index] == nullptr) { + if (Canard::allocate_sub_arg_callback(uavcan, &handle_arm_status, driver_index) == nullptr) + { goto alloc_failed; } - arm_status_listener[driver_index]->start(ArmStatusCb(uavcan, &handle_arm_status)); dronecan_done_init |= driver_mask; return; @@ -149,12 +137,12 @@ void AP_OpenDroneID::dronecan_send(AP_UAVCAN *uavcan) } #define ODID_COPY(name) msg.name = pkt.name -#define ODID_COPY_STR(name) do { for (uint8_t i = 0; i Date: Mon, 23 Jan 2023 11:22:52 +1100 Subject: [PATCH 046/287] Tools: add force-32bit option while building sitl for CAN test --- Tools/scripts/build_ci.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index a0cae745d78d76..f0303e757831f0 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -130,7 +130,7 @@ for t in $CI_BUILD_TARGET; do fi if [ "$t" == "sitltest-can" ]; then echo "Building SITL Periph GPS" - $waf configure --board sitl + $waf configure --board sitl --sitl-32bit $waf copter run_autotest "Copter" "build.SITLPeriphGPS" "test.CAN" continue From ac905caae96657928aa3abe60f692c5e57c920de Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Fri, 6 Jan 2023 23:03:34 +1100 Subject: [PATCH 047/287] AP_Common: add return to strncpy_noterm --- libraries/AP_Common/AP_Common.cpp | 4 +++- libraries/AP_Common/AP_Common.h | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Common/AP_Common.cpp b/libraries/AP_Common/AP_Common.cpp index cfc2e5379afa3c..19c403c353bf0d 100644 --- a/libraries/AP_Common/AP_Common.cpp +++ b/libraries/AP_Common/AP_Common.cpp @@ -74,14 +74,16 @@ bool hex_to_uint8(uint8_t a, uint8_t &res) /* strncpy without the warning for not leaving room for nul termination */ -void strncpy_noterm(char *dest, const char *src, size_t n) +size_t strncpy_noterm(char *dest, const char *src, size_t n) { size_t len = strnlen(src, n); + size_t ret = len; // return value is length of src if (len < n) { // include nul term if it fits len++; } memcpy(dest, src, len); + return ret; } /** diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index f9632eec01a179..8bd64286daac27 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -158,7 +158,7 @@ bool hex_to_uint8(uint8_t a, uint8_t &res); // return the uint8 value of an asc /* strncpy without the warning for not leaving room for nul termination */ -void strncpy_noterm(char *dest, const char *src, size_t n); +size_t strncpy_noterm(char *dest, const char *src, size_t n); // return the numeric value of an ascii hex character int16_t char_to_hex(char a); From 50bfa516bcf4d549456493b68ab13020149c8183 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 8 Jan 2023 14:46:36 +1100 Subject: [PATCH 048/287] waf: add support for dronecan on linux --- Tools/ardupilotwaf/boards.py | 45 ++++++++++++++++++++++++++++++++---- wscript | 14 +++++------ 2 files changed, 48 insertions(+), 11 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 0ed397d2d176bd..bf39ed7bc456db 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -429,7 +429,7 @@ def configure_env(self, cfg, env): ] if self.with_can and not cfg.env.AP_PERIPH: - if not cfg.env.SITL32BIT and cfg.env.BOARD == 'sitl': + if not cfg.env.FORCE32BIT and (cfg.env.BOARD == 'sitl' or cfg.env.BOARD == 'linux'): env.DEFINES.update( HAL_ENABLE_LIBUAVCAN_DRIVERS = 0 ) @@ -759,7 +759,7 @@ def configure_env(self, cfg, env): '-fno-slp-vectorize' # compiler bug when trying to use SLP ] - if cfg.options.sitl_32bit: + if cfg.options.force_32bit: # 32bit platform flags env.CXXFLAGS += [ '-m32', @@ -1134,7 +1134,15 @@ def get_name(self): return self.name class linux(Board): + def __init__(self): + if self.toolchain == 'native': + self.with_can = True + else: + self.with_can = False + def configure_env(self, cfg, env): + if cfg.options.board == 'linux' and cfg.options.force_32bit: + self.with_can = True super(linux, self).configure_env(cfg, env) env.DEFINES.update( @@ -1162,8 +1170,35 @@ def configure_env(self, cfg, env): 'AP_HAL_Linux', ] - if self.with_can: + if cfg.options.force_32bit: + env.DEFINES.update( + HAL_FORCE_32BIT = 1, + ) + # 32bit platform flags + cfg.env.CXXFLAGS += [ + '-m32', + ] + cfg.env.CFLAGS += [ + '-m32', + ] + cfg.env.LDFLAGS += [ + '-m32', + ] + else: + env.DEFINES.update( + HAL_FORCE_32BIT = 0, + ) + if self.with_can and cfg.options.board == 'linux' and cfg.options.force_32bit: + cfg.env.HAL_NUM_CAN_IFACES = 2 + cfg.define('HAL_NUM_CAN_IFACES', 2) cfg.define('UAVCAN_EXCEPTIONS', 0) + cfg.define('UAVCAN_SUPPORT_CANFD', 1) + cfg.define('HAL_CANFD_SUPPORTED', 1) + cfg.define('CANARD_ENABLE_CANFD', 1) + + if self.with_can: + env.DEFINES.update(CANARD_MULTI_IFACE=1, + CANARD_IFACE_ALL = 0x3) if cfg.options.apstatedir: cfg.define('AP_STATEDIR', cfg.options.apstatedir) @@ -1270,7 +1305,7 @@ def __init__(self): def configure_env(self, cfg, env): super(bbbmini, self).configure_env(cfg, env) - + cfg.env.HAL_NUM_CAN_IFACES = 1 env.DEFINES.update( CONFIG_HAL_BOARD_SUBTYPE = 'HAL_BOARD_SUBTYPE_LINUX_BBBMINI', ) @@ -1283,6 +1318,7 @@ def __init__(self): def configure_env(self, cfg, env): super(blue, self).configure_env(cfg, env) + cfg.env.HAL_NUM_CAN_IFACES = 1 env.DEFINES.update( CONFIG_HAL_BOARD_SUBTYPE = 'HAL_BOARD_SUBTYPE_LINUX_BLUE', @@ -1296,6 +1332,7 @@ def __init__(self): def configure_env(self, cfg, env): super(pocket, self).configure_env(cfg, env) + cfg.env.HAL_NUM_CAN_IFACES = 1 env.DEFINES.update( CONFIG_HAL_BOARD_SUBTYPE = 'HAL_BOARD_SUBTYPE_LINUX_POCKET', diff --git a/wscript b/wscript index 7a5d5e2c6ce623..263c0963497c9d 100644 --- a/wscript +++ b/wscript @@ -328,9 +328,9 @@ configuration in order to save typing. default=False, help="Enable SITL RGBLed") - g.add_option('--sitl-32bit', action='store_true', + g.add_option('--force-32bit', action='store_true', default=False, - help="Enable SITL 32bit") + help="Force 32bit build") g.add_option('--build-dates', action='store_true', default=False, @@ -440,7 +440,7 @@ def configure(cfg): cfg.env.BOARD = cfg.options.board cfg.env.DEBUG = cfg.options.debug cfg.env.COVERAGE = cfg.options.coverage - cfg.env.SITL32BIT = cfg.options.sitl_32bit + cfg.env.FORCE32BIT = cfg.options.force_32bit cfg.env.ENABLE_ASSERTS = cfg.options.enable_asserts cfg.env.BOOTLOADER = cfg.options.bootloader cfg.env.ENABLE_MALLOC_GUARD = cfg.options.enable_malloc_guard @@ -482,7 +482,7 @@ def configure(cfg): cfg.load('dronecangen') else: cfg.load('uavcangen') - if not (cfg.options.sitl_32bit and cfg.options.board != 'sitl'): + if cfg.options.force_32bit or (cfg.options.board != 'sitl' and cfg.options.board != 'linux'): cfg.load('dronecangen') cfg.env.SUBMODULE_UPDATE = cfg.options.submodule_update @@ -542,8 +542,8 @@ def configure(cfg): else: cfg.end_msg('disabled', color='YELLOW') - cfg.start_msg('SITL 32-bit build') - if cfg.env.SITL32BIT: + cfg.start_msg('Force 32-bit build') + if cfg.env.FORCE32BIT: cfg.end_msg('enabled') else: cfg.end_msg('disabled', color='YELLOW') @@ -680,7 +680,7 @@ def _build_dynamic_sources(bld): bld.srcnode.find_dir('modules/uavcan/libuavcan/include').abspath() ] ) - if (not bld.env.SITL32BIT) and bld.env.BOARD == 'sitl': + if (not bld.env.FORCE32BIT) and (bld.env.BOARD == 'sitl' or bld.env.BOARD == 'linux'): # remove generated files dronecan_dir = bld.bldnode.make_node('modules/DroneCAN/libcanard/dsdlc_generated/').abspath() if os.path.exists(dronecan_dir): From c90cf03619865788d8ba7a978f747d0f6e16c832 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Mon, 9 Jan 2023 09:56:33 +1100 Subject: [PATCH 049/287] autotest: replace sitl_32bit with force_32bit --- Tools/autotest/autotest.py | 6 +++--- Tools/autotest/common.py | 4 ++-- Tools/autotest/pysim/util.py | 18 +++++++++--------- Tools/autotest/sim_vehicle.py | 8 ++++---- 4 files changed, 18 insertions(+), 18 deletions(-) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index e6ece2b37aa745..dbff7d3cf83ace 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -444,7 +444,7 @@ def run_step(step): "postype_single": opts.postype_single, "extra_configure_args": opts.waf_configure_args, "coverage": opts.coverage, - "sitl_32bit" : opts.sitl_32bit, + "force_32bit" : opts.force_32bit, "ubsan" : opts.ubsan, "ubsan_abort" : opts.ubsan_abort, "num_aux_imus" : opts.num_aux_imus, @@ -958,10 +958,10 @@ def format_epilog(self, formatter): action="store_true", dest="ekf_single", help="force single precision EKF") - group_build.add_option("--sitl-32bit", + group_build.add_option("--force-32bit", default=False, action='store_true', - dest="sitl_32bit", + dest="force_32bit", help="compile sitl using 32-bit") group_build.add_option("", "--ubsan", default=False, diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index e3158d623b7e16..d00804de7ad175 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -1494,7 +1494,7 @@ def __init__(self, replay=False, sup_binaries=[], reset_after_every_test=False, - sitl_32bit=False, + force_32bit=False, ubsan=False, ubsan_abort=False, num_aux_imus=0, @@ -1521,7 +1521,7 @@ def __init__(self, self.speedup = self.default_speedup() self.sup_binaries = sup_binaries self.reset_after_every_test = reset_after_every_test - self.sitl_32bit = sitl_32bit + self.force_32bit = force_32bit self.ubsan = ubsan self.ubsan_abort = ubsan_abort self.build_opts = build_opts diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index 68b278138cdc55..e8df91561c23a3 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -112,7 +112,7 @@ def waf_configure(board, coverage=False, ekf_single=False, postype_single=False, - sitl_32bit=False, + force_32bit=False, extra_args=[], extra_hwdef=None, ubsan=False, @@ -130,8 +130,8 @@ def waf_configure(board, cmd_configure.append('--ekf-single') if postype_single: cmd_configure.append('--postype-single') - if sitl_32bit: - cmd_configure.append('--sitl-32bit') + if force_32bit: + cmd_configure.append('--force-32bit') if ubsan: cmd_configure.append('--ubsan') if ubsan_abort: @@ -174,7 +174,7 @@ def build_SITL( j=None, math_check_indexes=False, postype_single=False, - sitl_32bit=False, + force_32bit=False, ubsan=False, ubsan_abort=False, num_aux_imus=0, @@ -189,7 +189,7 @@ def build_SITL( ekf_single=ekf_single, postype_single=postype_single, coverage=coverage, - sitl_32bit=sitl_32bit, + force_32bit=force_32bit, ubsan=ubsan, ubsan_abort=ubsan_abort, extra_defines=extra_defines, @@ -209,7 +209,7 @@ def build_SITL( def build_examples(board, j=None, debug=False, clean=False, configure=True, math_check_indexes=False, coverage=False, - ekf_single=False, postype_single=False, sitl_32bit=False, ubsan=False, ubsan_abort=False, num_aux_imus=0, + ekf_single=False, postype_single=False, force_32bit=False, ubsan=False, ubsan_abort=False, num_aux_imus=0, extra_configure_args=[]): # first configure if configure: @@ -220,7 +220,7 @@ def build_examples(board, j=None, debug=False, clean=False, configure=True, math ekf_single=ekf_single, postype_single=postype_single, coverage=coverage, - sitl_32bit=sitl_32bit, + force_32bit=force_32bit, ubsan=ubsan, ubsan_abort=ubsan_abort, extra_args=extra_configure_args) @@ -258,7 +258,7 @@ def build_tests(board, coverage=False, ekf_single=False, postype_single=False, - sitl_32bit=False, + force_32bit=False, ubsan=False, ubsan_abort=False, num_aux_imus=0, @@ -273,7 +273,7 @@ def build_tests(board, ekf_single=ekf_single, postype_single=postype_single, coverage=coverage, - sitl_32bit=sitl_32bit, + force_32bit=force_32bit, ubsan=ubsan, ubsan_abort=ubsan_abort, extra_args=extra_configure_args) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 58c346a118b93b..43c4b2d4cd51f5 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -393,8 +393,8 @@ def do_build(opts, frame_options): if opts.ekf_single: cmd_configure.append("--ekf-single") - if opts.sitl_32bit: - cmd_configure.append("--sitl-32bit") + if opts.force_32bit: + cmd_configure.append("--force-32bit") if opts.ubsan: cmd_configure.append("--ubsan") @@ -1029,10 +1029,10 @@ def generate_frame_help(): action="store_true", dest="math_check_indexes", help="enable checking of math indexes") -group_build.add_option("", "--sitl-32bit", +group_build.add_option("", "--force-32bit", default=False, action='store_true', - dest="sitl_32bit", + dest="force_32bit", help="compile sitl using 32-bit") group_build.add_option("", "--configure-define", default=[], From d0b79959e7f48b8f2594d30b4be6964db3b1f8ad Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Mon, 9 Jan 2023 09:57:10 +1100 Subject: [PATCH 050/287] Tools: scripts: replace sitl-32bit with force-32bit --- Tools/scripts/build_ci.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index f0303e757831f0..357df28cb32684 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -130,7 +130,7 @@ for t in $CI_BUILD_TARGET; do fi if [ "$t" == "sitltest-can" ]; then echo "Building SITL Periph GPS" - $waf configure --board sitl --sitl-32bit + $waf configure --board sitl --force-32bit $waf copter run_autotest "Copter" "build.SITLPeriphGPS" "test.CAN" continue From 10fb5d6b21b77cbfe08d4649fba5745d12201b4b Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Mon, 9 Jan 2023 10:00:09 +1100 Subject: [PATCH 051/287] AP_HAL: enable virtual CAN for native built linux targets --- libraries/AP_HAL/board/linux.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_HAL/board/linux.h b/libraries/AP_HAL/board/linux.h index c36205d73759c6..989b768c539411 100644 --- a/libraries/AP_HAL/board/linux.h +++ b/libraries/AP_HAL/board/linux.h @@ -396,3 +396,10 @@ #ifndef HAL_GYROFFT_ENABLED #define HAL_GYROFFT_ENABLED 0 #endif + +#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NONE) && HAL_FORCE_32BIT +// we can use virtual CAN on native builds +#define HAL_LINUX_USE_VIRTUAL_CAN 1 +#else +#define HAL_LINUX_USE_VIRTUAL_CAN 0 +#endif From ee310433e590d95a25264e88f55a41d520da22c5 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Mon, 9 Jan 2023 10:00:52 +1100 Subject: [PATCH 052/287] AP_HAL_Linux: add option to use vitual CAN in linux --- libraries/AP_HAL_Linux/CANSocketIface.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_Linux/CANSocketIface.cpp b/libraries/AP_HAL_Linux/CANSocketIface.cpp index c2203afa39c508..3c5cbae9543309 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.cpp +++ b/libraries/AP_HAL_Linux/CANSocketIface.cpp @@ -462,8 +462,11 @@ void CANIface::_updateDownStatusFromPollResult(const pollfd& pfd) bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) { char iface_name[16]; +#if HAL_LINUX_USE_VIRTUAL_CAN + sprintf(iface_name, "vcan%u", _self_index); +#else sprintf(iface_name, "can%u", _self_index); - +#endif if (_initialized) { return _initialized; } From ef117dc3cf4c9af57e4659073f10f6c45e9f9969 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Mon, 9 Jan 2023 21:11:05 +1100 Subject: [PATCH 053/287] AP_Bootloader: fix bootloader build --- Tools/AP_Bootloader/wscript | 24 +++++++++++++----------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/Tools/AP_Bootloader/wscript b/Tools/AP_Bootloader/wscript index 22887ea9d30b0c..705e269182d381 100644 --- a/Tools/AP_Bootloader/wscript +++ b/Tools/AP_Bootloader/wscript @@ -9,16 +9,6 @@ def build(bld): flashiface_lib = ['AP_HAL', 'AP_FlashIface', 'AP_HAL_Empty'] else: flashiface_lib = [] - - # build external libcanard library - bld.stlib(source='../../modules/DroneCAN/libcanard/canard.c', - use='dronecan', - target='libcanard') - - bld.ap_program( - use=['ap','libcanard','AP_Bootloader_libs', 'dronecan'], - program_groups='bootloader' - ) bld.ap_stlib( name= 'AP_Bootloader_libs', @@ -27,5 +17,17 @@ def build(bld): ap_vehicle='AP_Bootloader', ap_libraries= flashiface_lib + [ 'AP_Math', - 'AP_CheckFirmware' + 'AP_CheckFirmware', + 'AP_HAL', ]) + + # build external libcanard library + bld.stlib(source='../../modules/DroneCAN/libcanard/canard.c', + name='libcanard', + use='dronecan', + target='libcanard') + + bld.ap_program( + use=['AP_Bootloader_libs', 'libcanard', 'dronecan'], + program_groups='bootloader' + ) From 6dc73b3d5494a775ebd57e8cf4e80aa994d66888 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 11 Jan 2023 18:37:17 +1100 Subject: [PATCH 054/287] AP_HAL: sitl: set default value of HAL_CAN_DRIVER_DEFAULT as 1 --- libraries/AP_HAL/board/sitl.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/board/sitl.h b/libraries/AP_HAL/board/sitl.h index 883d0a814a03de..3d288adc25a569 100644 --- a/libraries/AP_HAL/board/sitl.h +++ b/libraries/AP_HAL/board/sitl.h @@ -72,3 +72,7 @@ #ifndef HAL_WITH_EKF_DOUBLE #define HAL_WITH_EKF_DOUBLE HAL_HAVE_HARDWARE_DOUBLE #endif + +#ifndef HAL_CAN_DRIVER_DEFAULT +#define HAL_CAN_DRIVER_DEFAULT 1 +#endif From 530b9bdbaed144707dcd2f2781af82515cf60221 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Tue, 3 Jan 2023 18:54:38 +1100 Subject: [PATCH 055/287] modules: update dronecan_dsdlc --- modules/DroneCAN/dronecan_dsdlc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/DroneCAN/dronecan_dsdlc b/modules/DroneCAN/dronecan_dsdlc index 01586259d5a8b1..e3068c595a755d 160000 --- a/modules/DroneCAN/dronecan_dsdlc +++ b/modules/DroneCAN/dronecan_dsdlc @@ -1 +1 @@ -Subproject commit 01586259d5a8b11f9c4a034a976f886630ae4fb7 +Subproject commit e3068c595a755d827bd3350bd8192a0f0393e026 From 3ca65aae4f0881d76c2e76314d8b547f99e18e41 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Tue, 3 Jan 2023 19:09:08 +1100 Subject: [PATCH 056/287] modules: update libcanard --- modules/DroneCAN/libcanard | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/DroneCAN/libcanard b/modules/DroneCAN/libcanard index aec8028798e848..29886a8295e521 160000 --- a/modules/DroneCAN/libcanard +++ b/modules/DroneCAN/libcanard @@ -1 +1 @@ -Subproject commit aec8028798e8485851644e85093c50b1bd6e8ade +Subproject commit 29886a8295e5212b3688bf26406cbda9dd1f146c From 44e897cf2da7a390f4fec3979b3579686b9a8174 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 22 Jan 2023 18:31:16 +1100 Subject: [PATCH 057/287] AP_CANManager: setup CANManager for DroneCAN Driver tests --- libraries/AP_CANManager/AP_CANManager.cpp | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index ab6c437e04f617..72b45648c65c5d 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -115,6 +115,7 @@ AP_CANManager::AP_CANManager() _singleton = this; } +#if !AP_TEST_DRONECAN_DRIVERS void AP_CANManager::init() { WITH_SEMAPHORE(_sem); @@ -282,7 +283,26 @@ void AP_CANManager::init() _driver_type_cache[drv_num] = drv_type[drv_num]; } } +#else +void AP_CANManager::init() +{ + WITH_SEMAPHORE(_sem); + for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) { + if ((Driver_Type) _drv_param[i]._driver_type.get() == Driver_Type_UAVCAN) { + _drivers[i] = _drv_param[i]._uavcan = new AP_UAVCAN(i); + if (_drivers[i] == nullptr) { + AP_BoardConfig::allocation_error("uavcan %d", i + 1); + continue; + } + + AP_Param::load_object_from_eeprom((AP_UAVCAN*)_drivers[i], AP_UAVCAN::var_info); + _drivers[i]->init(i, true); + _driver_type_cache[i] = (Driver_Type) _drv_param[i]._driver_type.get(); + } + } +} +#endif /* register a new CAN driver */ From 50a760d8a5cf290a665ebf98285221a53b7f460a Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 22 Jan 2023 18:32:44 +1100 Subject: [PATCH 058/287] Tools: add --enable-dronecan-tests option to autotest --- Tools/autotest/autotest.py | 6 ++++++ Tools/autotest/common.py | 2 ++ Tools/autotest/pysim/util.py | 16 +++++++++++++--- 3 files changed, 21 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index dbff7d3cf83ace..a19bdf335300d5 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -448,6 +448,7 @@ def run_step(step): "ubsan" : opts.ubsan, "ubsan_abort" : opts.ubsan_abort, "num_aux_imus" : opts.num_aux_imus, + "dronecan_tests" : opts.dronecan_tests, } if opts.Werror: @@ -978,6 +979,11 @@ def format_epilog(self, formatter): default=0, type='int', help='number of auxiliary IMUs to simulate') + group_build.add_option("--enable-dronecan-tests", + default=False, + action='store_true', + dest="dronecan_tests", + help="enable dronecan tests") parser.add_option_group(group_build) group_sim = optparse.OptionGroup(parser, "Simulation options") diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index d00804de7ad175..02ec61791fa55b 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -1498,6 +1498,7 @@ def __init__(self, ubsan=False, ubsan_abort=False, num_aux_imus=0, + dronecan_tests=False, build_opts={}): self.start_time = time.time() @@ -1578,6 +1579,7 @@ def __init__(self, offline=self.terrain_in_offline_mode ) self.terrain_data_messages_sent = 0 # count of messages back + self.dronecan_tests = dronecan_tests def __del__(self): if self.rc_thread is not None: diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index e8df91561c23a3..2776488c8526aa 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -118,6 +118,7 @@ def waf_configure(board, ubsan=False, ubsan_abort=False, num_aux_imus=0, + dronecan_tests=False, extra_defines={}): cmd_configure = [relwaf(), "configure", "--board", board] if debug: @@ -138,6 +139,8 @@ def waf_configure(board, cmd_configure.append('--ubsan-abort') if num_aux_imus > 0: cmd_configure.append('--num-aux-imus=%u' % num_aux_imus) + if dronecan_tests: + cmd_configure.append('--enable-dronecan-tests') if extra_hwdef is not None: cmd_configure.extend(['--extra-hwdef', extra_hwdef]) for nv in extra_defines.items(): @@ -178,6 +181,7 @@ def build_SITL( ubsan=False, ubsan_abort=False, num_aux_imus=0, + dronecan_tests=False, ): # first configure @@ -194,6 +198,7 @@ def build_SITL( ubsan_abort=ubsan_abort, extra_defines=extra_defines, num_aux_imus=num_aux_imus, + dronecan_tests=dronecan_tests, extra_args=extra_configure_args,) # then clean @@ -209,7 +214,8 @@ def build_SITL( def build_examples(board, j=None, debug=False, clean=False, configure=True, math_check_indexes=False, coverage=False, - ekf_single=False, postype_single=False, force_32bit=False, ubsan=False, ubsan_abort=False, num_aux_imus=0, + ekf_single=False, postype_single=False, force_32bit=False, ubsan=False, ubsan_abort=False, + num_aux_imus=0, dronecan_tests=False, extra_configure_args=[]): # first configure if configure: @@ -223,7 +229,8 @@ def build_examples(board, j=None, debug=False, clean=False, configure=True, math force_32bit=force_32bit, ubsan=ubsan, ubsan_abort=ubsan_abort, - extra_args=extra_configure_args) + extra_args=extra_configure_args, + dronecan_tests=dronecan_tests) # then clean if clean: @@ -262,6 +269,7 @@ def build_tests(board, ubsan=False, ubsan_abort=False, num_aux_imus=0, + dronecan_tests=False, extra_configure_args=[]): # first configure @@ -276,7 +284,9 @@ def build_tests(board, force_32bit=force_32bit, ubsan=ubsan, ubsan_abort=ubsan_abort, - extra_args=extra_configure_args) + num_aux_imus=num_aux_imus, + dronecan_tests=dronecan_tests, + extra_args=extra_configure_args,) # then clean if clean: From b65c74940d80d127b73a963f756326200d698d2f Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 22 Jan 2023 18:33:55 +1100 Subject: [PATCH 059/287] AP_HAL_SITL: setup for DroneCAN driver test build --- libraries/AP_HAL_SITL/SITL_State.cpp | 4 +++- libraries/AP_HAL_SITL/system.cpp | 20 ++++++++++++++++++++ 2 files changed, 23 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 48cff7d1033479..1bf532972f971b 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -86,7 +86,9 @@ void SITL_State::_sitl_setup() sitl_model->set_precland(&_sitl->precland_sim); _sitl->i2c_sim.init(); sitl_model->set_i2c(&_sitl->i2c_sim); - +#if AP_TEST_DRONECAN_DRIVERS + sitl_model->set_dronecan_device(&_sitl->dronecan_sim); +#endif if (_use_fg_view) { fg_socket.connect(_fg_address, _fg_view_port); } diff --git a/libraries/AP_HAL_SITL/system.cpp b/libraries/AP_HAL_SITL/system.cpp index 8b1c35d7ddde37..518a2f3e168370 100644 --- a/libraries/AP_HAL_SITL/system.cpp +++ b/libraries/AP_HAL_SITL/system.cpp @@ -196,12 +196,20 @@ uint64_t millis64() uint32_t native_micros() { +#if AP_TEST_DRONECAN_DRIVERS + return micros(); +#else return native_micros64() & 0xFFFFFFFF; +#endif } uint32_t native_millis() { +#if AP_TEST_DRONECAN_DRIVERS + return millis(); +#else return native_millis64() & 0xFFFFFFFF; +#endif } /* @@ -209,28 +217,40 @@ uint32_t native_millis() */ uint16_t native_millis16() { +#if AP_TEST_DRONECAN_DRIVERS + return millis16(); +#else return native_millis64() & 0xFFFF; +#endif } uint64_t native_micros64() { +#if AP_TEST_DRONECAN_DRIVERS + return micros64(); +#else struct timeval tp; gettimeofday(&tp, nullptr); uint64_t ret = 1.0e6 * ((tp.tv_sec + (tp.tv_usec * 1.0e-6)) - (state.start_time.tv_sec + (state.start_time.tv_usec * 1.0e-6))); return ret; +#endif } uint64_t native_millis64() { +#if AP_TEST_DRONECAN_DRIVERS + return millis64(); +#else struct timeval tp; gettimeofday(&tp, nullptr); uint64_t ret = 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) - (state.start_time.tv_sec + (state.start_time.tv_usec*1.0e-6))); return ret; +#endif } From 5f2dd4ab5c018ec8de7c05712aec03db71f15feb Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 22 Jan 2023 18:35:53 +1100 Subject: [PATCH 060/287] SITL: add support for testing DroneCAN --- libraries/SITL/SIM_Aircraft.cpp | 6 + libraries/SITL/SIM_Aircraft.h | 7 +- libraries/SITL/SIM_DroneCANDevice.cpp | 238 ++++++++++++++++++++++++++ libraries/SITL/SIM_DroneCANDevice.h | 60 +++++++ libraries/SITL/SITL.h | 4 + 5 files changed, 314 insertions(+), 1 deletion(-) create mode 100644 libraries/SITL/SIM_DroneCANDevice.cpp create mode 100644 libraries/SITL/SIM_DroneCANDevice.h diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 24220c4f96b8c5..7c8082b460f719 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -1016,6 +1016,12 @@ void Aircraft::update_external_payload(const struct sitl_input &input) if (ie24) { ie24->update(input); } + +#if AP_TEST_DRONECAN_DRIVERS + if (dronecan) { + dronecan->update(); + } +#endif } void Aircraft::add_shove_forces(Vector3f &rot_accel, Vector3f &body_accel) diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 236630fbb17e0c..87deaec30ed1a0 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -147,7 +147,9 @@ class Aircraft { void set_gripper_epm(Gripper_EPM *_gripper_epm) { gripper_epm = _gripper_epm; } void set_precland(SIM_Precland *_precland); void set_i2c(class I2C *_i2c) { i2c = _i2c; } - +#if AP_TEST_DRONECAN_DRIVERS + void set_dronecan_device(DroneCANDevice *_dronecan) { dronecan = _dronecan; } +#endif float get_battery_voltage() const { return battery_voltage; } protected: @@ -335,6 +337,9 @@ class Aircraft { IntelligentEnergy24 *ie24; SIM_Precland *precland; class I2C *i2c; +#if AP_TEST_DRONECAN_DRIVERS + DroneCANDevice *dronecan; +#endif }; } // namespace SITL diff --git a/libraries/SITL/SIM_DroneCANDevice.cpp b/libraries/SITL/SIM_DroneCANDevice.cpp new file mode 100644 index 00000000000000..f550095f01a5d9 --- /dev/null +++ b/libraries/SITL/SIM_DroneCANDevice.cpp @@ -0,0 +1,238 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + base class for CAN simulated devices +*/ +#include "SIM_DroneCANDevice.h" +#if AP_TEST_DRONECAN_DRIVERS + +#include +#include +#include +#include +#include +#include +#include + + +using namespace SITL; + +void DroneCANDevice::update_baro() { + const uint64_t now = AP_HAL::micros64(); + if (((now - _baro_last_update_us) < 10000) && (_baro_last_update_us != 0)) { + return; + } + _baro_last_update_us = now; + const uint32_t now_ms = AP_HAL::millis(); + float sim_alt = AP::sitl()->state.altitude; + + if (AP::sitl()->baro_count < 1) { + // barometer is disabled + return; + } + + sim_alt += AP::sitl()->baro[0].drift * now_ms * 0.001f; + sim_alt += AP::sitl()->baro[0].noise * rand_float(); + + + // add baro glitch + sim_alt += AP::sitl()->baro[0].glitch; + + // add delay + uint32_t best_time_delta = 200; // initialise large time representing buffer entry closest to current time - delay. + uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay. + + // storing data from sensor to buffer + if (now_ms - _last_store_time >= 10) { // store data every 10 ms. + _last_store_time = now_ms; + if (_store_index > _buffer_length - 1) { // reset buffer index if index greater than size of buffer + _store_index = 0; + } + + // if freezed barometer, report altitude to last recorded altitude + if (AP::sitl()->baro[0].freeze == 1) { + sim_alt = _last_altitude; + } else { + _last_altitude = sim_alt; + } + + _buffer[_store_index].data = sim_alt; // add data to current index + _buffer[_store_index].time = _last_store_time; // add time_stamp to current index + _store_index = _store_index + 1; // increment index + } + + // return delayed measurement + const uint32_t delayed_time = now_ms - AP::sitl()->baro[0].delay; // get time corresponding to delay + + // find data corresponding to delayed time in buffer + for (uint8_t i = 0; i <= _buffer_length - 1; i++) { + // find difference between delayed time and time stamp in buffer + uint32_t time_delta = abs( + (int32_t)(delayed_time - _buffer[i].time)); + // if this difference is smaller than last delta, store this time + if (time_delta < best_time_delta) { + best_index = i; + best_time_delta = time_delta; + } + } + if (best_time_delta < 200) { // only output stored state if < 200 msec retrieval error + sim_alt = _buffer[best_index].data; + } + +#if !APM_BUILD_TYPE(APM_BUILD_ArduSub) + float sigma, delta, theta; + + AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); + float p = SSL_AIR_PRESSURE * delta; + float T = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta); + + AP_Baro_SITL::temperature_adjustment(p, T); + T = C_TO_KELVIN(T); +#else + float rho, delta, theta; + AP_Baro::SimpleUnderWaterAtmosphere(-sim_alt * 0.001f, rho, delta, theta); + float p = SSL_AIR_PRESSURE * delta; + float T = SSL_AIR_TEMPERATURE * theta; +#endif + + // add in correction for wind effects + p += AP_Baro_SITL::wind_pressure_correction(0); + static Canard::Publisher press_pub{CanardInterface::get_test_iface()}; + static Canard::Publisher temp_pub{CanardInterface::get_test_iface()}; + uavcan_equipment_air_data_StaticPressure press_msg {}; + press_msg.static_pressure = p; + press_pub.broadcast(press_msg); + uavcan_equipment_air_data_StaticTemperature temp_msg {}; + temp_msg.static_temperature = T; + temp_pub.broadcast(temp_msg); +} + +void DroneCANDevice::update_airspeed() { + const uint32_t now = AP_HAL::micros64(); + if ((now - _airspeed_last_update_us < 50000) && (_airspeed_last_update_us != 0)) { + return; + } + _airspeed_last_update_us = now; + uavcan_equipment_air_data_RawAirData msg {}; + msg.differential_pressure = AP::sitl()->state.airspeed_raw_pressure[0]; + + // this was mostly swiped from SIM_Airspeed_DLVR: + const float sim_alt = AP::sitl()->state.altitude; + + float sigma, delta, theta; + AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); + + // To Do: Add a sensor board temperature offset parameter + msg.static_air_temperature = SSL_AIR_TEMPERATURE * theta + 25.0; + + static Canard::Publisher raw_air_pub{CanardInterface::get_test_iface()}; + raw_air_pub.broadcast(msg); +} + +void DroneCANDevice::_setup_eliptical_correcion(uint8_t i) +{ + Vector3f diag = AP::sitl()->mag_diag[i].get(); + if (diag.is_zero()) { + diag = {1,1,1}; + } + const Vector3f &diagonals = diag; + const Vector3f &offdiagonals = AP::sitl()->mag_offdiag[i]; + + if (diagonals == _last_dia && offdiagonals == _last_odi) { + return; + } + + _eliptical_corr = Matrix3f(diagonals.x, offdiagonals.x, offdiagonals.y, + offdiagonals.x, diagonals.y, offdiagonals.z, + offdiagonals.y, offdiagonals.z, diagonals.z); + if (!_eliptical_corr.invert()) { + _eliptical_corr.identity(); + } + _last_dia = diag; + _last_odi = offdiagonals; +} + +void DroneCANDevice::update_compass() { + + // Sampled at 100Hz + const uint32_t now = AP_HAL::micros64(); + if ((now - _compass_last_update_us < 10000) && (_compass_last_update_us != 0)) { + return; + } + _compass_last_update_us = now; + + // calculate sensor noise and add to 'truth' field in body frame + // units are milli-Gauss + Vector3f noise = rand_vec3f() * AP::sitl()->mag_noise; + Vector3f new_mag_data = AP::sitl()->state.bodyMagField + noise; + + _setup_eliptical_correcion(0); + Vector3f f = (_eliptical_corr * new_mag_data) - AP::sitl()->mag_ofs[0].get(); + // rotate compass + f.rotate_inverse((enum Rotation)AP::sitl()->mag_orient[0].get()); + f.rotate(AP::compass().get_board_orientation()); + // scale the compass to simulate sensor scale factor errors + f *= AP::sitl()->mag_scaling[0]; + + static Canard::Publisher mag_pub{CanardInterface::get_test_iface()}; + uavcan_equipment_ahrs_MagneticFieldStrength mag_msg {}; + mag_msg.magnetic_field_ga[0] = f.x/1000.0f; + mag_msg.magnetic_field_ga[1] = f.y/1000.0f; + mag_msg.magnetic_field_ga[2] = f.z/1000.0f; + mag_msg.magnetic_field_covariance.len = 0; + mag_pub.broadcast(mag_msg); + static Canard::Publisher mag2_pub{CanardInterface::get_test_iface()}; + uavcan_equipment_ahrs_MagneticFieldStrength2 mag2_msg; + mag2_msg.magnetic_field_ga[0] = f.x/1000.0f; + mag2_msg.magnetic_field_ga[1] = f.y/1000.0f; + mag2_msg.magnetic_field_ga[2] = f.z/1000.0f; + mag2_msg.sensor_id = 0; + mag2_msg.magnetic_field_covariance.len = 0; + mag2_pub.broadcast(mag2_msg); +} + +void DroneCANDevice::update_rangefinder() { + + // Sampled at 100Hz + const uint32_t now = AP_HAL::micros64(); + if ((now - _rangefinder_last_update_us < 10000) && (_rangefinder_last_update_us != 0)) { + return; + } + _rangefinder_last_update_us = now; + static Canard::Publisher pub{CanardInterface::get_test_iface()}; + uavcan_equipment_range_sensor_Measurement msg; + msg.timestamp.usec = AP_HAL::micros64(); + msg.sensor_id = 0; + msg.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR; + const float dist = AP::sitl()->get_rangefinder(0); + if (is_positive(dist)) { + msg.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE; + msg.range = dist; + } else { + msg.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR; + msg.range = 0; + } + pub.broadcast(msg); +} + +void DroneCANDevice::update() +{ + update_baro(); + update_airspeed(); + update_compass(); + update_rangefinder(); +} + +#endif // AP_TEST_DRONECAN_DRIVERS \ No newline at end of file diff --git a/libraries/SITL/SIM_DroneCANDevice.h b/libraries/SITL/SIM_DroneCANDevice.h new file mode 100644 index 00000000000000..98e5c7c9e03787 --- /dev/null +++ b/libraries/SITL/SIM_DroneCANDevice.h @@ -0,0 +1,60 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + base class for CAN simulated devices +*/ + +#pragma once + +#include +#include +#include +#include + +#if AP_TEST_DRONECAN_DRIVERS +namespace SITL { + +class DroneCANDevice { +public: + void update(void); + +private: + // barometer delay buffer variables + struct readings_baro { + uint32_t time; + float data; + }; + uint8_t _store_index; + uint32_t _last_store_time; + static const uint8_t _buffer_length = 50; + VectorN _buffer; + float _last_altitude; + void update_baro(void); + + void update_airspeed(void); + void update_compass(void); + void update_rangefinder(void); + void _setup_eliptical_correcion(uint8_t i); + uint64_t _baro_last_update_us; + uint64_t _airspeed_last_update_us; + uint64_t _compass_last_update_us; + uint64_t _rangefinder_last_update_us; + Matrix3f _eliptical_corr; + Vector3f _last_dia; + Vector3f _last_odi; +}; + +} +#endif // AP_TEST_DRONECAN_DRIVERS \ No newline at end of file diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 3b273a25931d2e..1596f9f929017c 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -26,6 +26,7 @@ #include "SIM_IntelligentEnergy24.h" #include "SIM_Ship.h" #include "SIM_GPS.h" +#include "SIM_DroneCANDevice.h" namespace SITL { @@ -448,6 +449,9 @@ class SIM { RichenPower richenpower_sim; IntelligentEnergy24 ie24_sim; FETtecOneWireESC fetteconewireesc_sim; +#if AP_TEST_DRONECAN_DRIVERS + DroneCANDevice dronecan_sim; +#endif // ESC telemetry AP_Int8 esc_telem; From 56068e65c67292693080a754bedb744f534d3d2b Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 5 Feb 2023 14:38:49 +1100 Subject: [PATCH 061/287] waf: add support for multithreaded register/unregister of DroneCAN handlers --- Tools/ardupilotwaf/boards.py | 1 + Tools/ardupilotwaf/chibios.py | 1 + wscript | 1 + 3 files changed, 3 insertions(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index bf39ed7bc456db..6333444d5bac04 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -448,6 +448,7 @@ def configure_env(self, cfg, env): UAVCAN_NO_ASSERTIONS = 1, UAVCAN_NULLPTR = 'nullptr', DRONECAN_CXX_WRAPPERS = 1, + USE_USER_HELPERS = 1, CANARD_ENABLE_DEADLINE = 1, ) diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index c9b4d8a54e10b5..68c30fa6833c93 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -458,6 +458,7 @@ def setup_canmgr_build(cfg): if not env.AP_PERIPH: env.DEFINES += [ 'DRONECAN_CXX_WRAPPERS=1', + 'USE_USER_HELPERS=1', 'CANARD_ENABLE_DEADLINE=1', 'CANARD_MULTI_IFACE=1' ] diff --git a/wscript b/wscript index 263c0963497c9d..58ec32bbc74a29 100644 --- a/wscript +++ b/wscript @@ -695,6 +695,7 @@ def _build_dynamic_sources(bld): export_includes=[ bld.bldnode.make_node('modules/DroneCAN/libcanard/dsdlc_generated/include').abspath(), bld.srcnode.find_dir('modules/DroneCAN/libcanard/').abspath(), + bld.srcnode.find_dir('libraries/AP_UAVCAN/canard/').abspath(), ] ) elif bld.env.AP_PERIPH: From 3a38c2f1eb942cbba08169a1853c4433e59675e6 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 5 Feb 2023 14:40:28 +1100 Subject: [PATCH 062/287] AP_UAVCAN: allow multithreaded register/unregistering handlers --- libraries/AP_UAVCAN/AP_Canard_iface.cpp | 3 +++ libraries/AP_UAVCAN/canard/canard_helpers_user.h | 5 +++++ 2 files changed, 8 insertions(+) create mode 100644 libraries/AP_UAVCAN/canard/canard_helpers_user.h diff --git a/libraries/AP_UAVCAN/AP_Canard_iface.cpp b/libraries/AP_UAVCAN/AP_Canard_iface.cpp index e415fa4afe48d1..d3a9c63e478235 100644 --- a/libraries/AP_UAVCAN/AP_Canard_iface.cpp +++ b/libraries/AP_UAVCAN/AP_Canard_iface.cpp @@ -10,7 +10,10 @@ extern const AP_HAL::HAL& hal; #define DEBUG_PKTS 0 DEFINE_HANDLER_LIST_HEADS(); +DEFINE_HANDLER_LIST_SEMAPHORES(); + DEFINE_TRANSFER_OBJECT_HEADS(); +DEFINE_TRANSFER_OBJECT_SEMAPHORES(); #if AP_TEST_DRONECAN_DRIVERS CanardInterface* CanardInterface::canard_ifaces[] = {nullptr, nullptr, nullptr}; diff --git a/libraries/AP_UAVCAN/canard/canard_helpers_user.h b/libraries/AP_UAVCAN/canard/canard_helpers_user.h new file mode 100644 index 00000000000000..ff4e1d6c989165 --- /dev/null +++ b/libraries/AP_UAVCAN/canard/canard_helpers_user.h @@ -0,0 +1,5 @@ +#include // to include SEMAPHORE + +namespace Canard { +typedef ::HAL_Semaphore Semaphore; +} From 51f856e5c6fcbe94bba344d9b7957bb315338609 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 5 Feb 2023 14:41:21 +1100 Subject: [PATCH 063/287] modules: update libcanard --- modules/DroneCAN/libcanard | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/DroneCAN/libcanard b/modules/DroneCAN/libcanard index 29886a8295e521..149aa59bd04a00 160000 --- a/modules/DroneCAN/libcanard +++ b/modules/DroneCAN/libcanard @@ -1 +1 @@ -Subproject commit 29886a8295e5212b3688bf26406cbda9dd1f146c +Subproject commit 149aa59bd04a005803756e2fc3c20d8a3e9266f0 From 07532eaf2fba028f5278bb0e0f41ffec3ce944f9 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 10 Nov 2022 16:50:28 +0000 Subject: [PATCH 064/287] AP_Common: NOINLINE is now defined in ChibiOS --- libraries/AP_Common/AP_Common.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index 8bd64286daac27..fb2fdfc9ceb033 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -44,7 +44,9 @@ #define OPTIMIZE(level) __attribute__((optimize(level))) // sometimes we need to prevent inlining to prevent large stack usage +#ifndef NOINLINE #define NOINLINE __attribute__((noinline)) +#endif // used to ignore results for functions marked as warn unused #define IGNORE_RETURN(x) do {if (x) {}} while(0) From 788469477113054443a26c50080d027ab59542fe Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 11 Nov 2022 09:35:42 +0000 Subject: [PATCH 065/287] AP_Bootloader: fix virtual timer interface --- Tools/AP_Bootloader/bl_protocol.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/AP_Bootloader/bl_protocol.cpp b/Tools/AP_Bootloader/bl_protocol.cpp index c0b7171a2043a9..c4577cd2312e15 100644 --- a/Tools/AP_Bootloader/bl_protocol.cpp +++ b/Tools/AP_Bootloader/bl_protocol.cpp @@ -163,7 +163,7 @@ extern AP_FlashIface_JEDEC ext_flash; /* 1ms timer tick callback */ -static void sys_tick_handler(void *ctx) +static void sys_tick_handler(virtual_timer_t* vt, void *ctx) { chSysLockFromISR(); chVTSetI(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr); From 76b5915d5b400b103db4044904207b6a83c2363e Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 27 Nov 2022 15:56:15 +0000 Subject: [PATCH 066/287] AP_BoardConfig: ensure that debug pins are enabled if compiled with debug --- libraries/AP_BoardConfig/board_drivers.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_BoardConfig/board_drivers.cpp b/libraries/AP_BoardConfig/board_drivers.cpp index 40b2a30647075a..6d59ea32d61d3b 100644 --- a/libraries/AP_BoardConfig/board_drivers.cpp +++ b/libraries/AP_BoardConfig/board_drivers.cpp @@ -54,7 +54,7 @@ void AP_BoardConfig::board_init_safety() */ void AP_BoardConfig::board_init_debug() { -#ifndef HAL_BUILD_AP_PERIPH +#if !defined(HAL_BUILD_AP_PERIPH) && !defined(HAL_DEBUG_BUILD) if ((_options & BOARD_OPTION_DEBUG_ENABLE) == 0) { #ifdef HAL_GPIO_PIN_JTCK_SWCLK palSetLineMode(HAL_GPIO_PIN_JTCK_SWCLK, PAL_MODE_INPUT); @@ -63,7 +63,7 @@ void AP_BoardConfig::board_init_debug() palSetLineMode(HAL_GPIO_PIN_JTMS_SWDIO, PAL_MODE_INPUT); #endif } -#endif // HAL_BUILD_AP_PERIPH +#endif // HAL_BUILD_AP_PERIPH && HAL_DEBUG_BUILD } From c9382cd2212f14ce842052082b3c840b455e49e6 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 28 Nov 2022 09:33:50 +0000 Subject: [PATCH 067/287] AP_InertialSensor: HAL_WITH_DSP -> HAL_GYROFFT_ENABLED --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 6 +++--- libraries/AP_InertialSensor/AP_InertialSensor.h | 4 ++-- libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp | 8 ++++---- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index be46e9a2b50a46..a69a0c4fd3d222 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -840,7 +840,7 @@ AP_InertialSensor_Backend *AP_InertialSensor::_find_backend(int16_t backend_id, } bool AP_InertialSensor::set_gyro_window_size(uint16_t size) { -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED _gyro_window_size = size; // allocate FFT gyro window @@ -909,7 +909,7 @@ AP_InertialSensor::init(uint16_t loop_rate) batchsampler.init(); #endif -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED AP_GyroFFT* fft = AP::fft(); bool fft_enabled = fft != nullptr && fft->enabled(); if (fft_enabled) { @@ -954,7 +954,7 @@ AP_InertialSensor::init(uint16_t loop_rate) notch.num_dynamic_notches = 1; #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) if (notch.params.hasOption(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED if (notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) { notch.num_dynamic_notches = AP_HAL::DSP::MAX_TRACKED_PEAKS; // only 3 peaks supported currently } else diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index f95e746c82f3a3..4c4a839d8daf19 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -152,7 +152,7 @@ class AP_InertialSensor : AP_AccelCal_Client uint16_t get_accel_rate_hz(uint8_t instance) const { return uint16_t(_accel_raw_sample_rates[instance] * _accel_over_sampling[instance]); } // FFT support access -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED const Vector3f& get_gyro_for_fft(void) const { return _gyro_for_fft[_primary_gyro]; } FloatBuffer& get_raw_gyro_window(uint8_t instance, uint8_t axis) { return _gyro_window[instance][axis]; } FloatBuffer& get_raw_gyro_window(uint8_t axis) { return get_raw_gyro_window(_primary_gyro, axis); } @@ -501,7 +501,7 @@ class AP_InertialSensor : AP_AccelCal_Client LowPassFilter2pVector3f _gyro_filter[INS_MAX_INSTANCES]; Vector3f _accel_filtered[INS_MAX_INSTANCES]; Vector3f _gyro_filtered[INS_MAX_INSTANCES]; -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED // Thread-safe public version of _last_raw_gyro Vector3f _gyro_for_fft[INS_MAX_INSTANCES]; Vector3f _last_gyro_for_fft[INS_MAX_INSTANCES]; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index 54ad8504f1515a..88b780964e7911 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -181,7 +181,7 @@ void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f & void AP_InertialSensor_Backend::save_gyro_window(const uint8_t instance, const Vector3f &gyro, uint8_t phase) { -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED // capture gyro window for FFT analysis if (_imu._fft_window_phase == phase) { if (_imu._gyro_window_size > 0) { @@ -243,7 +243,7 @@ void AP_InertialSensor_Backend::apply_gyro_filters(const uint8_t instance, const // if the filtering failed in any way then reset the filters and keep the old value if (gyro_filtered.is_nan() || gyro_filtered.is_inf()) { _imu._gyro_filter[instance].reset(); -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED _imu._post_filter_gyro_filter[instance].reset(); #endif for (auto ¬ch : _imu.harmonic_notches) { @@ -756,7 +756,7 @@ void AP_InertialSensor_Backend::update_gyro(uint8_t instance) /* front end */ } if (_imu._new_gyro_data[instance]) { _publish_gyro(instance, _imu._gyro_filtered[instance]); -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED // copy the gyro samples from the backend to the frontend window for FFTs sampling at less than IMU rate _imu._gyro_for_fft[instance] = _imu._last_gyro_for_fft[instance]; #endif @@ -768,7 +768,7 @@ void AP_InertialSensor_Backend::update_gyro(uint8_t instance) /* front end */ if (_last_gyro_filter_hz != _gyro_filter_cutoff() || sensors_converging()) { _imu._gyro_filter[instance].set_cutoff_frequency(gyro_rate, _gyro_filter_cutoff()); -#if HAL_WITH_DSP +#if HAL_GYROFFT_ENABLED _imu._post_filter_gyro_filter[instance].set_cutoff_frequency(gyro_rate, _gyro_filter_cutoff()); #endif _last_gyro_filter_hz = _gyro_filter_cutoff(); From 1c14c8f043579d3cf1e9928a6f8ca154ff8a7f16 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 15 Jan 2023 15:22:21 +0000 Subject: [PATCH 068/287] AP_FlashIface: build fix for examples clearly document parameters of memory-mapped mode --- libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp | 6 +++--- .../AP_FlashIface/examples/jedec_test_bl/jedec_test.cpp | 3 ++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp b/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp index 2c3929f08db88c..47ed9198be06c8 100644 --- a/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp +++ b/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp @@ -929,13 +929,13 @@ bool AP_FlashIface_JEDEC::start_xip_mode(void** addr) { // Set QSPI module for XIP mode AP_HAL::QSPIDevice::CommandHeader cmd; - cmd.cmd = _desc.fast_read_ins; - cmd.alt = 0xA5; + cmd.cmd = _desc.fast_read_ins; // generally 0xEB for 1-4-4 access + cmd.alt = 0xF0; // add M0-7 bits in alt to make up 32-bit address phase cmd.cfg = AP_HAL::QSPI::CFG_ADDR_SIZE_24 | AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | AP_HAL::QSPI::CFG_ADDR_MODE_FOUR_LINES | AP_HAL::QSPI::CFG_DATA_MODE_FOUR_LINES | - AP_HAL::QSPI::CFG_ALT_MODE_FOUR_LINES | /* Always 4 lines, note.*/ + AP_HAL::QSPI::CFG_ALT_MODE_FOUR_LINES | AP_HAL::QSPI::CFG_ALT_SIZE_8; cmd.addr = 0; cmd.dummy = _desc.fast_read_dummy_cycles; diff --git a/libraries/AP_FlashIface/examples/jedec_test_bl/jedec_test.cpp b/libraries/AP_FlashIface/examples/jedec_test_bl/jedec_test.cpp index a6d4ed9241d118..cd9aeb6a0ef441 100644 --- a/libraries/AP_FlashIface/examples/jedec_test_bl/jedec_test.cpp +++ b/libraries/AP_FlashIface/examples/jedec_test_bl/jedec_test.cpp @@ -2,6 +2,7 @@ #include #include #include +#include AP_FlashIface_JEDEC jedec_dev; @@ -16,7 +17,7 @@ static UNUSED_FUNCTION void test_page_program() uprintf("Failed to allocate data for read"); } - // fill program data with its own adress + // fill program data with its own address for (uint32_t i = 0; i < jedec_dev.get_page_size(); i++) { data[i] = i; } From 4a8ce32f90bf76a0562d274cb3c57894681a96a1 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 16 Nov 2022 10:53:27 +0000 Subject: [PATCH 069/287] AP_HAL_ChibiOS: remove USART3 to match fmuv5 and save some flash remove UART7 on fmuv3 to save enough flash to fit in 16k --- libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat | 13 +++---------- 1 file changed, 3 insertions(+), 10 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat index eee65e240a73e0..002fbad6143b3c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat @@ -30,7 +30,7 @@ USB_STRING_MANUFACTURER "ArduPilot" define BOOTLOADER_BAUDRATE 115200 # uarts and USB to run bootloader protocol on -SERIAL_ORDER OTG1 USART2 USART3 UART7 +SERIAL_ORDER OTG1 USART2 # this is the pin that senses USB being connected. It is an input pin # setup as OPENDRAIN @@ -50,16 +50,9 @@ PD6 USART2_RX USART2 PD3 USART2_CTS USART2 PD4 USART2_RTS USART2 -# the telem2 USART, also with RTS/CTS available -# USART3 serial3 telem2 -PD8 USART3_TX USART3 -PD9 USART3_RX USART3 -PD11 USART3_CTS USART3 -PD12 USART3_RTS USART3 - # UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) -PE7 UART7_RX UART7 -PE8 UART7_TX UART7 +#PE7 UART7_RX UART7 +#PE8 UART7_TX UART7 # define a LED PE12 LED_BOOTLOADER OUTPUT From 667b38635612a335017aab660f4a392dfe765ed0 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 10 Nov 2022 16:49:54 +0000 Subject: [PATCH 070/287] AP_HAL_ChibiOS: port to ChibiOS 21.11.x convert RCOutput to new virtual timer interface cope with SDC vs SDMMC use new SPIv3 driver. Correct clocks for SDMMCv2. add STM32L431 support port ChibiOS config to version 8 support SPIv3 driver model v2 on H7 use currcore in debug options use new mmc API disable speed optimizations in the bootloader to save a little flash upgrade to halconf v8.4 relax constraints on QSP/flash clock. add support for disabling QSPI reset in main firmware --- libraries/AP_HAL_ChibiOS/I2CDevice.cpp | 2 +- libraries/AP_HAL_ChibiOS/QSPIDevice.cpp | 10 +- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 6 +- libraries/AP_HAL_ChibiOS/RCOutput.h | 8 +- libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp | 2 +- libraries/AP_HAL_ChibiOS/SPIDevice.cpp | 22 +- libraries/AP_HAL_ChibiOS/Util.cpp | 6 +- .../AP_HAL_ChibiOS/hwdef/common/chconf.h | 56 +++- .../hwdef/common/chibios_board.mk | 2 +- .../AP_HAL_ChibiOS/hwdef/common/crashdump.c | 2 +- .../AP_HAL_ChibiOS/hwdef/common/ffconf.h | 272 +++++++++--------- .../AP_HAL_ChibiOS/hwdef/common/halconf.h | 48 +++- .../AP_HAL_ChibiOS/hwdef/common/stm32_util.c | 2 +- .../hwdef/common/stm32h7_mcuconf.h | 43 ++- .../hwdef/common/stm32l4_mcuconf.h | 1 + .../hwdef/scripts/chibios_hwdef.py | 10 +- libraries/AP_HAL_ChibiOS/sdcard.cpp | 10 +- libraries/AP_HAL_ChibiOS/system.cpp | 6 +- 18 files changed, 323 insertions(+), 185 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp index cc50bbacad0aa5..e05a09883eafab 100644 --- a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp @@ -31,7 +31,7 @@ #include "hal.h" static const struct I2CInfo { - struct I2CDriver *i2c; + I2CDriver *i2c; uint8_t instance; uint8_t dma_channel_rx; uint8_t dma_channel_tx; diff --git a/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp b/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp index 4a7b7e681147e2..5ae2d69092198e 100644 --- a/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp @@ -48,13 +48,19 @@ QSPIDesc QSPIDeviceManager::device_table[] = { HAL_QSPI_DEVICE_LIST }; #define XSTR(x) STR(x) #define STR(x) #x +#if (STM32_QSPICLK < HAL_QSPI1_CLK) +#error "Flash speed must not be greater than QSPI Clock" +#endif #if (STM32_QSPICLK % HAL_QSPI1_CLK) -#error "QSPI Clock" XSTR(STM32_QSPICLK) " needs to be divisible by selected clock" XSTR(HAL_QSPI1_CLK) +#warning "QSPI clock not an integer multiple of flash speed" #endif #if defined(STM32_WSPI_USE_QUADSPI2) && STM32_WSPI_USE_QUADSPI2 +#if (STM32_QSPICLK < HAL_QSPI2_CLK) +#error "Flash speed must not be greater than QSPI Clock" +#endif #if (STM32_QSPICLK % HAL_QSPI2_CLK) -#error "QSPI Clock" XSTR(STM32_QSPICLK) " needs to be divisible by selected clock" XSTR(HAL_QSPI2_CLK) +#warning "QSPI clock not an integer multiple of flash speed" #endif #endif diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 5d81171f53d960..1acb4a43545eae 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -212,7 +212,7 @@ void RCOutput::rcout_thread() } } -__RAMFUNC__ void RCOutput::dshot_update_tick(void* p) +__RAMFUNC__ void RCOutput::dshot_update_tick(virtual_timer_t* vt, void* p) { chSysLockFromISR(); RCOutput* rcout = (RCOutput*)p; @@ -1614,7 +1614,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length) /* unlock DMA channel after a dshot send completes and no return value is expected */ -__RAMFUNC__ void RCOutput::dma_unlock(void *p) +__RAMFUNC__ void RCOutput::dma_unlock(virtual_timer_t* vt, void *p) { chSysLockFromISR(); pwm_group *group = (pwm_group *)p; @@ -1887,7 +1887,7 @@ void RCOutput::serial_bit_irq(void) /* timeout a byte read */ -void RCOutput::serial_byte_timeout(void *ctx) +void RCOutput::serial_byte_timeout(virtual_timer_t* vt, void *ctx) { chSysLockFromISR(); irq.timed_out = true; diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 6ee05e85cd1fd4..c259929704a8c5 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -602,12 +602,12 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput void dshot_send_groups(uint64_t time_out_us); void dshot_send(pwm_group &group, uint64_t time_out_us); bool dshot_send_command(pwm_group &group, uint8_t command, uint8_t chan); - static void dshot_update_tick(void* p); + static void dshot_update_tick(virtual_timer_t*, void* p); static void dshot_send_next_group(void* p); // release locks on the groups that are pending in reverse order void dshot_collect_dma_locks(uint64_t last_run_us); static void dma_up_irq_callback(void *p, uint32_t flags); - static void dma_unlock(void *p); + static void dma_unlock(virtual_timer_t*, void *p); void dma_cancel(pwm_group& group); bool mode_requires_dma(enum output_mode mode) const; bool setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high, @@ -627,7 +627,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput bool bdshot_decode_dshot_telemetry(pwm_group& group, uint8_t chan); static uint8_t bdshot_find_next_ic_channel(const pwm_group& group); static void bdshot_dma_ic_irq_callback(void *p, uint32_t flags); - static void bdshot_finish_dshot_gcr_transaction(void *p); + static void bdshot_finish_dshot_gcr_transaction(virtual_timer_t* vt, void *p); bool bdshot_setup_group_ic_DMA(pwm_group &group); static void bdshot_receive_pulses_DMAR(pwm_group* group); static void bdshot_config_icu_dshot(stm32_tim_t* TIMx, uint8_t chan, uint8_t ccr_ch); @@ -650,7 +650,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput bool serial_read_byte(uint8_t &b); void fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b , uint32_t bitval); static void serial_bit_irq(void); - static void serial_byte_timeout(void *ctx); + static void serial_byte_timeout(virtual_timer_t* vt, void *ctx); }; diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index fea8b8f16b97f3..33d6f2808cc812 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -372,7 +372,7 @@ void RCOutput::bdshot_config_icu_dshot(stm32_tim_t* TIMx, uint8_t chan, uint8_t /* unlock DMA channel after a bi-directional dshot transaction completes */ -__RAMFUNC__ void RCOutput::bdshot_finish_dshot_gcr_transaction(void *p) +__RAMFUNC__ void RCOutput::bdshot_finish_dshot_gcr_transaction(virtual_timer_t* vt, void *p) { pwm_group *group = (pwm_group *)p; chSysLockFromISR(); diff --git a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp index ae1b8da471d2c6..2367f3de36f869 100644 --- a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp @@ -205,7 +205,7 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len) // expect this timeout to trigger unless there is a severe MCU // error const uint32_t timeout_us = 20000U + len * 32U; - msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); + msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { ret = false; @@ -233,7 +233,7 @@ bool SPIDevice::clock_pulse(uint32_t n) acquire_bus(true, true); osalSysLock(); spiStartIgnoreI(spi_devices[device_desc.bus].driver, n); - msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); + msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[device_desc.bus].driver); @@ -246,7 +246,7 @@ bool SPIDevice::clock_pulse(uint32_t n) } osalSysLock(); spiStartIgnoreI(spi_devices[device_desc.bus].driver, n); - msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); + msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[device_desc.bus].driver); @@ -363,18 +363,20 @@ bool SPIDevice::acquire_bus(bool set, bool skip_cs) } else { bus.dma_handle->lock(); spiAcquireBus(spi_devices[device_desc.bus].driver); /* Acquire ownership of the bus. */ - bus.spicfg.end_cb = nullptr; bus.spicfg.ssport = PAL_PORT(device_desc.pal_line); bus.spicfg.sspad = PAL_PAD(device_desc.pal_line); + bus.spicfg.data_cb = nullptr; + bus.spicfg.error_cb = nullptr; + bus.spicfg.slave = false; #if defined(STM32H7) bus.spicfg.cfg1 = freq_flag; bus.spicfg.cfg2 = device_desc.mode; - if (bus.spicfg.dummytx == nullptr) { - bus.spicfg.dummytx = (uint32_t *)malloc_dma(4); - memset(bus.spicfg.dummytx, 0xFF, 4); + if (bus.spicfg.txsource == nullptr) { + bus.spicfg.txsource = (uint32_t *)malloc_dma(4); + memset(bus.spicfg.txsource, 0xFF, 4); } - if (bus.spicfg.dummyrx == nullptr) { - bus.spicfg.dummyrx = (uint32_t *)malloc_dma(4); + if (bus.spicfg.rxsink == nullptr) { + bus.spicfg.rxsink = (uint32_t *)malloc_dma(4); } #else bus.spicfg.cr1 = (uint16_t)(freq_flag | device_desc.mode); @@ -500,7 +502,7 @@ void SPIDevice::test_clock_freq(void) uint32_t t0 = AP_HAL::micros(); spiStartExchange(spi_devices[i].driver, len, buf1, buf2); chSysLock(); - msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->thread, chTimeMS2I(100)); + msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->sync_transfer, chTimeMS2I(100)); chSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[i].driver); diff --git a/libraries/AP_HAL_ChibiOS/Util.cpp b/libraries/AP_HAL_ChibiOS/Util.cpp index be69b924791016..81c8c0d92c9eab 100644 --- a/libraries/AP_HAL_ChibiOS/Util.cpp +++ b/libraries/AP_HAL_ChibiOS/Util.cpp @@ -417,7 +417,7 @@ bool Util::was_watchdog_reset() const __RAMFUNC__ void Util::thread_info(ExpandingString &str) { #if HAL_ENABLE_THREAD_STATISTICS - uint64_t cumulative_cycles = ch.kernel_stats.m_crit_isr.cumulative; + uint64_t cumulative_cycles = currcore->kernel_stats.m_crit_isr.cumulative; for (thread_t *tp = chRegFirstThread(); tp; tp = chRegNextThread(tp)) { if (tp->stats.best > 0) { // not run cumulative_cycles += (uint64_t)tp->stats.cumulative; @@ -430,8 +430,8 @@ __RAMFUNC__ void Util::thread_info(ExpandingString &str) str.printf("ThreadsV2\nISR PRI=255 sp=%p STACK=%u/%u LOAD=%4.1f%%\n", &__main_stack_base__, unsigned(stack_free(&__main_stack_base__)), - unsigned(isr_stack_size), 100.0f * float(ch.kernel_stats.m_crit_isr.cumulative) / float(cumulative_cycles)); - ch.kernel_stats.m_crit_isr.cumulative = 0U; + unsigned(isr_stack_size), 100.0f * float(currcore->kernel_stats.m_crit_isr.cumulative) / float(cumulative_cycles)); + currcore->kernel_stats.m_crit_isr.cumulative = 0U; #else str.printf("ThreadsV2\nISR PRI=255 sp=%p STACK=%u/%u\n", &__main_stack_base__, diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h index 195b0e521e3c57..f673dcc4b93f63 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h @@ -31,7 +31,7 @@ #include "hwdef.h" #define _CHIBIOS_RT_CONF_ -#define _CHIBIOS_RT_CONF_VER_6_1_ +#define _CHIBIOS_RT_CONF_VER_7_0_ /*===========================================================================*/ /** * @name System timers settings @@ -76,6 +76,27 @@ extern "C" { #define CH_DBG_STATISTICS FALSE #endif +/** + * @brief Handling of instances. + * @note If enabled then threads assigned to various instances can + * interact each other using the same synchronization objects. + * If disabled then each OS instance is a separate world, no + * direct interactions are handled by the OS. + */ +#if !defined(CH_CFG_SMP_MODE) +#define CH_CFG_SMP_MODE FALSE +#endif + +/** + * @brief Time Stamps APIs. + * @details If enabled then the time stamps APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_CFG_USE_TIMESTAMP) +#define CH_CFG_USE_TIMESTAMP TRUE +#endif + /** * @brief System time counter resolution. * @note Allowed values are 16 or 32 bits. @@ -803,6 +824,39 @@ extern "C" { /* Trace code here.*/ \ } +/** + * @brief System initialization hook. + * @details User initialization code added to the @p chSysInit() function + * just before interrupts are enabled globally. + */ +#define CH_CFG_SYSTEM_INIT_HOOK() { \ + /* Add system initialization code here.*/ \ +} + +/** + * @brief OS instance structure extension. + * @details User fields added to the end of the @p os_instance_t structure. + */ +#define CH_CFG_OS_INSTANCE_EXTRA_FIELDS \ + /* Add OS instance custom fields here.*/ + +/** + * @brief Runtime Faults Collection Unit hook. + * @details This hook is invoked each time new faults are collected and stored. + */ +#define CH_CFG_RUNTIME_FAULTS_HOOK(mask) { \ + /* Faults handling code here.*/ \ +} + +/** + * @brief OS instance initialization hook. + * + * @param[in] oip pointer to the @p os_instance_t structure + */ +#define CH_CFG_OS_INSTANCE_INIT_HOOK(oip) { \ + /* Add OS instance initialization code here.*/ \ +} + /** @} */ /*===========================================================================*/ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk index 14382747e7289f..29723c6866e0ea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk @@ -109,7 +109,7 @@ include $(CHIBIOS)/$(CHIBIOS_PLATFORM_MK) include $(CHIBIOS)/os/hal/osal/rt-nil/osal.mk # RTOS files (optional). include $(CHIBIOS)/os/rt/rt.mk -include $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/mk/port_v7m.mk +include $(CHIBIOS)/os/common/ports/ARMv7-M/compilers/GCC/mk/port.mk # Other files (optional). #include $(CHIBIOS)/test/rt/test.mk include $(CHIBIOS)/os/hal/lib/streams/streams.mk diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c b/libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c index 5eec28ba98f145..61093b69e0b696 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c @@ -99,7 +99,7 @@ const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void) // do a full dump if on serial static CrashCatcherMemoryRegion regions[60] = { {(uint32_t)&__ram0_start__, (uint32_t)&__ram0_end__, CRASH_CATCHER_BYTE}, - {(uint32_t)&ch, (uint32_t)&ch + sizeof(ch), CRASH_CATCHER_BYTE}}; + {(uint32_t)&ch_system, (uint32_t)&ch_system + sizeof(ch_system), CRASH_CATCHER_BYTE}}; uint32_t total_dump_size = dump_size + buf_off + REMAINDER_MEM_REGION_SIZE; // loop through chibios threads and add their stack info uint8_t curr_region = 2; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/ffconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/ffconf.h index abfa15e523b8b6..b0dbfa3fc55ea8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/ffconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/ffconf.h @@ -1,87 +1,95 @@ -#pragma once - -/* CHIBIOS FIX */ -#include "ch.h" +#include "hwdef.h" /*---------------------------------------------------------------------------/ -/ FatFs - FAT file system module configuration file +/ FatFs Functional Configurations /---------------------------------------------------------------------------*/ -#define FFCONF_DEF 80196 /* Revision ID */ +#define FFCONF_DEF 86631 /* Revision ID */ /*---------------------------------------------------------------------------/ / Function Configurations /---------------------------------------------------------------------------*/ -#define FF_FS_READONLY 0 +#define FF_FS_READONLY 0 /* This option switches read-only configuration. (0:Read/Write or 1:Read-only) / Read-only configuration removes writing API functions, f_write(), f_sync(), / f_unlink(), f_mkdir(), f_chmod(), f_rename(), f_truncate(), f_getfree() / and optional writing functions as well. */ -#define FF_FS_MINIMIZE 0 +#define FF_FS_MINIMIZE 0 /* This option defines minimization level to remove some basic API functions. / -/ 0: All basic functions are enabled. +/ 0: Basic functions are fully enabled. / 1: f_stat(), f_getfree(), f_unlink(), f_mkdir(), f_truncate() and f_rename() / are removed. / 2: f_opendir(), f_readdir() and f_closedir() are removed in addition to 1. / 3: f_lseek() function is removed in addition to 2. */ -#define FF_USE_STRFUNC 0 -/* This option switches string functions, f_gets(), f_putc(), f_puts() and -/ f_printf(). -/ -/ 0: Disable string functions. -/ 1: Enable without LF-CRLF conversion. -/ 2: Enable with LF-CRLF conversion. */ - - -#define FF_USE_FIND 0 +#define FF_USE_FIND 0 /* This option switches filtered directory read functions, f_findfirst() and / f_findnext(). (0:Disable, 1:Enable 2:Enable with matching altname[] too) */ -#ifndef FF_USE_MKFS -// f_mkfs() only supported on SDC so far -#define FF_USE_MKFS HAL_USE_SDC -#endif +#define FF_USE_MKFS HAL_USE_SDC /* This option switches f_mkfs() function. (0:Disable or 1:Enable) */ -#define FF_USE_FASTSEEK 0 +#define FF_USE_FASTSEEK 0 /* This option switches fast seek function. (0:Disable or 1:Enable) */ -#define FF_USE_EXPAND 0 +#define FF_USE_EXPAND 0 /* This option switches f_expand function. (0:Disable or 1:Enable) */ -#define FF_USE_CHMOD 1 +#define FF_USE_CHMOD 1 /* This option switches attribute manipulation functions, f_chmod() and f_utime(). -/ (0:Disable or 1:Enable) Also _FS_READONLY needs to be 0 to enable this option. */ +/ (0:Disable or 1:Enable) Also FF_FS_READONLY needs to be 0 to enable this option. */ -#define FF_USE_LABEL 0 +#define FF_USE_LABEL 0 /* This option switches volume label functions, f_getlabel() and f_setlabel(). / (0:Disable or 1:Enable) */ -#define FF_USE_FORWARD 0 +#define FF_USE_FORWARD 0 /* This option switches f_forward() function. (0:Disable or 1:Enable) */ +#define FF_USE_STRFUNC 0 +#define FF_PRINT_LLI 0 +#define FF_PRINT_FLOAT 0 +#define FF_STRF_ENCODE 0 +/* FF_USE_STRFUNC switches string functions, f_gets(), f_putc(), f_puts() and +/ f_printf(). +/ +/ 0: Disable. FF_PRINT_LLI, FF_PRINT_FLOAT and FF_STRF_ENCODE have no effect. +/ 1: Enable without LF-CRLF conversion. +/ 2: Enable with LF-CRLF conversion. +/ +/ FF_PRINT_LLI = 1 makes f_printf() support long long argument and FF_PRINT_FLOAT = 1/2 + makes f_printf() support floating point argument. These features want C99 or later. +/ When FF_LFN_UNICODE >= 1 with LFN enabled, string functions convert the character +/ encoding in it. FF_STRF_ENCODE selects assumption of character encoding ON THE FILE +/ to be read/written via those functions. +/ +/ 0: ANSI/OEM in current CP +/ 1: Unicode in UTF-16LE +/ 2: Unicode in UTF-16BE +/ 3: Unicode in UTF-8 +*/ + + /*---------------------------------------------------------------------------/ / Locale and Namespace Configurations /---------------------------------------------------------------------------*/ -#define FF_CODE_PAGE 850 +#define FF_CODE_PAGE 850 /* This option specifies the OEM code page to be used on the target system. -/ Incorrect setting of the code page can cause a file open failure. +/ Incorrect code page setting can cause a file open failure. / -/ 1 - ASCII (No extended character. Non-LFN cfg. only) / 437 - U.S. / 720 - Arabic / 737 - Greek @@ -103,53 +111,52 @@ / 936 - Simplified Chinese (DBCS) / 949 - Korean (DBCS) / 950 - Traditional Chinese (DBCS) +/ 0 - Include all code pages above and configured by f_setcp() */ -#define FF_USE_LFN 3 -#define FF_MAX_LFN 255 -/* The _USE_LFN switches the support of long file name (LFN). +#define FF_USE_LFN 3 +#define FF_MAX_LFN 255 +/* The FF_USE_LFN switches the support for LFN (long file name). / -/ 0: Disable support of LFN. _MAX_LFN has no effect. -/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe. +/ 0: Disable LFN. FF_MAX_LFN has no effect. +/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe. / 2: Enable LFN with dynamic working buffer on the STACK. / 3: Enable LFN with dynamic working buffer on the HEAP. / -/ To enable the LFN, Unicode handling functions (option/unicode.c) must be added -/ to the project. The working buffer occupies (_MAX_LFN + 1) * 2 bytes and -/ additional 608 bytes at exFAT enabled. _MAX_LFN can be in range from 12 to 255. -/ It should be set 255 to support full featured LFN operations. +/ To enable the LFN, ffunicode.c needs to be added to the project. The LFN function +/ requiers certain internal working buffer occupies (FF_MAX_LFN + 1) * 2 bytes and +/ additional (FF_MAX_LFN + 44) / 15 * 32 bytes when exFAT is enabled. +/ The FF_MAX_LFN defines size of the working buffer in UTF-16 code unit and it can +/ be in range of 12 to 255. It is recommended to be set it 255 to fully support LFN +/ specification. / When use stack for the working buffer, take care on stack overflow. When use heap / memory for the working buffer, memory management functions, ff_memalloc() and -/ ff_memfree(), must be added to the project. */ +/ ff_memfree() exemplified in ffsystem.c, need to be added to the project. */ -#define FF_LFN_UNICODE 0 -/* This option switches character encoding on the API. (0:ANSI/OEM or 1:UTF-16) -/ To use Unicode string for the path name, enable LFN and set _LFN_UNICODE = 1. -/ This option also affects behavior of string I/O functions. */ +#define FF_LFN_UNICODE 0 +/* This option switches the character encoding on the API when LFN is enabled. +/ +/ 0: ANSI/OEM in current CP (TCHAR = char) +/ 1: Unicode in UTF-16 (TCHAR = WCHAR) +/ 2: Unicode in UTF-8 (TCHAR = char) +/ 3: Unicode in UTF-32 (TCHAR = DWORD) +/ +/ Also behavior of string I/O functions will be affected by this option. +/ When LFN is not enabled, this option has no effect. */ + -#define FF_LFN_BUF 255 -#define FF_SFN_BUF 12 +#define FF_LFN_BUF 255 +#define FF_SFN_BUF 12 /* This set of options defines size of file name members in the FILINFO structure / which is used to read out directory items. These values should be suffcient for / the file names to read. The maximum possible length of the read file name depends / on character encoding. When LFN is not enabled, these options have no effect. */ -#define FF_STRF_ENCODE 3 -/* When _LFN_UNICODE == 1, this option selects the character encoding ON THE FILE to -/ be read/written via string I/O functions, f_gets(), f_putc(), f_puts and f_printf(). -/ -/ 0: ANSI/OEM -/ 1: UTF-16LE -/ 2: UTF-16BE -/ 3: UTF-8 -/ -/ This option has no effect when _LFN_UNICODE == 0. */ - -#define FF_FS_RPATH 1 -/* This option configures support of relative path. +#define FF_FS_RPATH 1 +/* This option configures support for relative path. / / 0: Disable relative path and remove related functions. / 1: Enable relative path. f_chdir() and f_chdrive() are available. @@ -161,99 +168,106 @@ / Drive/Volume Configurations /---------------------------------------------------------------------------*/ -#define FF_VOLUMES 1 -/* Number of volumes (logical drives) to be used. */ +#define FF_VOLUMES 1 +/* Number of volumes (logical drives) to be used. (1-10) */ -#define FF_STR_VOLUME_ID 0 -#define FF_VOLUME_STRS "RAM","NAND","CF","SD","SD2","USB","USB2","USB3" -/* _STR_VOLUME_ID switches string support of volume ID. -/ When _STR_VOLUME_ID is set to 1, also pre-defined strings can be used as drive -/ number in the path name. _VOLUME_STRS defines the drive ID strings for each -/ logical drives. Number of items must be equal to _VOLUMES. Valid characters for -/ the drive ID strings are: A-Z and 0-9. */ +#define FF_STR_VOLUME_ID 0 +#define FF_VOLUME_STRS "RAM","NAND","CF","SD","SD2","USB","USB2","USB3" +/* FF_STR_VOLUME_ID switches support for volume ID in arbitrary strings. +/ When FF_STR_VOLUME_ID is set to 1 or 2, arbitrary strings can be used as drive +/ number in the path name. FF_VOLUME_STRS defines the volume ID strings for each +/ logical drives. Number of items must not be less than FF_VOLUMES. Valid +/ characters for the volume ID strings are A-Z, a-z and 0-9, however, they are +/ compared in case-insensitive. If FF_STR_VOLUME_ID >= 1 and FF_VOLUME_STRS is +/ not defined, a user defined volume string table needs to be defined as: +/ +/ const char* VolumeStr[FF_VOLUMES] = {"ram","flash","sd","usb",... +*/ -#define FF_MULTI_PARTITION 0 -/* This option switches support of multi-partition on a physical drive. +#define FF_MULTI_PARTITION 0 +/* This option switches support for multiple volumes on the physical drive. / By default (0), each logical drive number is bound to the same physical drive / number and only an FAT volume found on the physical drive will be mounted. -/ When multi-partition is enabled (1), each logical drive number can be bound to +/ When this function is enabled (1), each logical drive number can be bound to / arbitrary physical drive and partition listed in the VolToPart[]. Also f_fdisk() / funciton will be available. */ -#define FF_MIN_SS 512 -#define FF_MAX_SS 512 -/* These options configure the range of sector size to be supported. (512, 1024, -/ 2048 or 4096) Always set both 512 for most systems, all type of memory cards and -/ harddisk. But a larger value may be required for on-board flash memory and some -/ type of optical media. When _MAX_SS is larger than _MIN_SS, FatFs is configured -/ to variable sector size and GET_SECTOR_SIZE command must be implemented to the -/ disk_ioctl() function. */ +#define FF_MIN_SS 512 +#define FF_MAX_SS 512 +/* This set of options configures the range of sector size to be supported. (512, +/ 1024, 2048 or 4096) Always set both 512 for most systems, generic memory card and +/ harddisk, but a larger value may be required for on-board flash memory and some +/ type of optical media. When FF_MAX_SS is larger than FF_MIN_SS, FatFs is configured +/ for variable sector size mode and disk_ioctl() function needs to implement +/ GET_SECTOR_SIZE command. */ -#define FF_LBA64 0 + +#define FF_LBA64 0 /* This option switches support for 64-bit LBA. (0:Disable or 1:Enable) / To enable the 64-bit LBA, also exFAT needs to be enabled. (FF_FS_EXFAT == 1) */ -#define FF_MIN_GPT 0x100000000 -/* Minimum number of sectors to switch GPT format to create partition in f_mkfs and +#define FF_MIN_GPT 0x100000000 +/* Minimum number of sectors to switch GPT as partitioning format in f_mkfs and / f_fdisk function. 0x100000000 max. This option has no effect when FF_LBA64 == 0. */ -#define FF_USE_TRIM 0 -/* This option switches support of ATA-TRIM. (0:Disable or 1:Enable) + +#define FF_USE_TRIM 0 +/* This option switches support for ATA-TRIM. (0:Disable or 1:Enable) / To enable Trim function, also CTRL_TRIM command should be implemented to the / disk_ioctl() function. */ -#define FF_FS_NOFSINFO 0 -/* If you need to know correct free space on the FAT32 volume, set bit 0 of this -/ option, and f_getfree() function at first time after volume mount will force -/ a full FAT scan. Bit 1 controls the use of last allocated cluster number. -/ -/ bit0=0: Use free cluster count in the FSINFO if available. -/ bit0=1: Do not trust free cluster count in the FSINFO. -/ bit1=0: Use last allocated cluster number in the FSINFO if available. -/ bit1=1: Do not trust last allocated cluster number in the FSINFO. -*/ - - /*---------------------------------------------------------------------------/ / System Configurations /---------------------------------------------------------------------------*/ -#define FF_FS_TINY 0 +#define FF_FS_TINY 0 /* This option switches tiny buffer configuration. (0:Normal or 1:Tiny) -/ At the tiny configuration, size of file object (FIL) is reduced _MAX_SS bytes. +/ At the tiny configuration, size of file object (FIL) is shrinked FF_MAX_SS bytes. / Instead of private sector buffer eliminated from the file object, common sector -/ buffer in the file system object (FATFS) is used for the file data transfer. */ +/ buffer in the filesystem object (FATFS) is used for the file data transfer. */ -#define FF_FS_EXFAT 1 -/* This option switches support of exFAT file system. (0:Disable or 1:Enable) -/ When enable exFAT, also LFN needs to be enabled. (_USE_LFN >= 1) -/ Note that enabling exFAT discards C89 compatibility. */ +#define FF_FS_EXFAT 1 +/* This option switches support for exFAT filesystem. (0:Disable or 1:Enable) +/ To enable exFAT, also LFN needs to be enabled. (FF_USE_LFN >= 1) +/ Note that enabling exFAT discards ANSI C (C89) compatibility. */ -#define FF_FS_NORTC 0 -#define FF_NORTC_MON 1 -#define FF_NORTC_MDAY 1 -#define FF_NORTC_YEAR 2016 -/* The option _FS_NORTC switches timestamp functiton. If the system does not have -/ any RTC function or valid timestamp is not needed, set _FS_NORTC = 1 to disable -/ the timestamp function. All objects modified by FatFs will have a fixed timestamp -/ defined by _NORTC_MON, _NORTC_MDAY and _NORTC_YEAR in local time. -/ To enable timestamp function (_FS_NORTC = 0), get_fattime() function need to be -/ added to the project to get current time form real-time clock. _NORTC_MON, -/ _NORTC_MDAY and _NORTC_YEAR have no effect. -/ These options have no effect at read-only configuration (_FS_READONLY = 1). */ +#define FF_FS_NORTC 0 +#define FF_NORTC_MON 1 +#define FF_NORTC_MDAY 1 +#define FF_NORTC_YEAR 2016 +/* The option FF_FS_NORTC switches timestamp functiton. If the system does not have +/ any RTC function or valid timestamp is not needed, set FF_FS_NORTC = 1 to disable +/ the timestamp function. Every object modified by FatFs will have a fixed timestamp +/ defined by FF_NORTC_MON, FF_NORTC_MDAY and FF_NORTC_YEAR in local time. +/ To enable timestamp function (FF_FS_NORTC = 0), get_fattime() function need to be +/ added to the project to read current time form real-time clock. FF_NORTC_MON, +/ FF_NORTC_MDAY and FF_NORTC_YEAR have no effect. +/ These options have no effect in read-only configuration (FF_FS_READONLY = 1). */ + + +#define FF_FS_NOFSINFO 0 +/* If you need to know correct free space on the FAT32 volume, set bit 0 of this +/ option, and f_getfree() function at first time after volume mount will force +/ a full FAT scan. Bit 1 controls the use of last allocated cluster number. +/ +/ bit0=0: Use free cluster count in the FSINFO if available. +/ bit0=1: Do not trust free cluster count in the FSINFO. +/ bit1=0: Use last allocated cluster number in the FSINFO if available. +/ bit1=1: Do not trust last allocated cluster number in the FSINFO. +*/ -#define FF_FS_LOCK 0 -/* The option _FS_LOCK switches file lock function to control duplicated file open -/ and illegal operation to open objects. This option must be 0 when _FS_READONLY +#define FF_FS_LOCK 0 +/* The option FF_FS_LOCK switches file lock function to control duplicated file open +/ and illegal operation to open objects. This option must be 0 when FF_FS_READONLY / is 1. / / 0: Disable file lock function. To avoid volume corruption, application program @@ -263,27 +277,27 @@ / lock control is independent of re-entrancy. */ -#define FF_FS_REENTRANT 0 -#define FF_FS_TIMEOUT chTimeMS2I(1000) -#define FF_SYNC_t semaphore_t* -/* The option _FS_REENTRANT switches the re-entrancy (thread safe) of the FatFs +/* #include // O/S definitions */ +#define FF_FS_REENTRANT 0 +#define FF_FS_TIMEOUT chTimeMS2I(1000) +#define FF_SYNC_t semaphore_t* +/* The option FF_FS_REENTRANT switches the re-entrancy (thread safe) of the FatFs / module itself. Note that regardless of this option, file access to different / volume is always re-entrant and volume control functions, f_mount(), f_mkfs() / and f_fdisk() function, are always not re-entrant. Only file/directory access / to the same volume is under control of this function. / -/ 0: Disable re-entrancy. _FS_TIMEOUT and _SYNC_t have no effect. +/ 0: Disable re-entrancy. FF_FS_TIMEOUT and FF_SYNC_t have no effect. / 1: Enable re-entrancy. Also user provided synchronization handlers, / ff_req_grant(), ff_rel_grant(), ff_del_syncobj() and ff_cre_syncobj() / function, must be added to the project. Samples are available in / option/syscall.c. / -/ The _FS_TIMEOUT defines timeout period in unit of time tick. -/ The _SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*, -/ SemaphoreHandle_t and etc.. A header file for O/S definitions needs to be +/ The FF_FS_TIMEOUT defines timeout period in unit of time tick. +/ The FF_SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*, +/ SemaphoreHandle_t and etc. A header file for O/S definitions needs to be / included somewhere in the scope of ff.h. */ -/* #include // O/S definitions */ /*--- End of configuration options ---*/ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/halconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/halconf.h index f84b7fcdc84b50..09d559300854e5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/halconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/halconf.h @@ -43,7 +43,7 @@ #pragma once #define _CHIBIOS_HAL_CONF_ -#define _CHIBIOS_HAL_CONF_VER_7_1_ +#define _CHIBIOS_HAL_CONF_VER_8_4_ #include "mcuconf.h" @@ -350,15 +350,18 @@ /*===========================================================================*/ /** - * @brief Delays insertions. - * @details If enabled this options inserts delays into the MMC waiting - * routines releasing some extra CPU time for the threads with - * lower priority, this may slow down the driver a bit however. - * This option is recommended also if the SPI driver does not - * use a DMA channel and heavily loads the CPU. + * @brief Timeout before assuming a failure while waiting for card idle. + * #note Time is in milliseconds. */ -#if !defined(MMC_NICE_WAITING) || defined(__DOXYGEN__) -#define MMC_NICE_WAITING TRUE +#if !defined(MMC_IDLE_TIMEOUT_MS) || defined(__DOXYGEN__) +#define MMC_IDLE_TIMEOUT_MS 1000 +#endif + +/** + * @brief Mutual exclusion on the SPI bus. + */ +#if !defined(MMC_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) +#define MMC_USE_MUTUAL_EXCLUSION TRUE #endif /*===========================================================================*/ @@ -434,6 +437,26 @@ #endif #endif +/*===========================================================================*/ +/* SIO driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Default bit rate. + * @details Configuration parameter, this is the baud rate selected for the + * default configuration. + */ +#if !defined(SIO_DEFAULT_BITRATE) || defined(__DOXYGEN__) +#define SIO_DEFAULT_BITRATE 38400 +#endif + +/** + * @brief Support for thread synchronization API. + */ +#if !defined(SIO_USE_SYNCHRONIZATION) || defined(__DOXYGEN__) +#define SIO_USE_SYNCHRONIZATION TRUE +#endif + /*===========================================================================*/ /* SERIAL_USB driver related setting. */ /*===========================================================================*/ @@ -478,6 +501,13 @@ #define SPI_USE_WAIT TRUE #endif +/** + * @brief Inserts an assertion on function errors before returning. + */ +#if !defined(SPI_USE_ASSERT_ON_ERROR) || defined(__DOXYGEN__) +#define SPI_USE_ASSERT_ON_ERROR TRUE +#endif + /** * @brief Enables circular transfers APIs. * @note Disabling this option saves both code and data space. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c index 7a415c99a3db08..8f7f8d8a98d8df 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c @@ -458,7 +458,7 @@ void system_halt_hook(void) #ifdef HAL_GPIO_PIN_FAULT // optionally print the message on a fault pin while (true) { - fault_printf("PANIC:%s\n", ch.dbg.panic_msg); + fault_printf("PANIC:%s\n", currcore->dbg.panic_msg); fault_printf("RA0:0x%08x\n", __builtin_return_address(0)); } #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h index 97ca23092c0a56..0f08d6f20c9684 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h @@ -63,9 +63,10 @@ /* * Memory attributes settings. */ -#define STM32_NOCACHE_MPU_REGION MPU_REGION_6 -#define STM32_NOCACHE_SRAM1_SRAM2 FALSE -#define STM32_NOCACHE_SRAM3 FALSE +#define STM32_NOCACHE_ENABLE FALSE +//#define STM32_NOCACHE_MPU_REGION MPU_REGION_6 +//#define STM32_NOCACHE_RBAR 0x24000000U +//#define STM32_NOCACHE_RASR MPU_RASR_SIZE_16K /* * PWR system settings. @@ -152,10 +153,9 @@ #define STM32_PLL2_DIVN_VALUE 45 #define STM32_PLL2_DIVP_VALUE 2 #define STM32_PLL2_DIVQ_VALUE 5 -#define STM32_PLL2_DIVR_VALUE 1 +#define STM32_PLL2_DIVR_VALUE 8 #define STM32_PLL3_DIVN_VALUE 15 -#define STM32_PLL3_DIVP_VALUE 3 #define STM32_PLL3_DIVQ_VALUE 5 #define STM32_PLL3_DIVR_VALUE 8 @@ -177,10 +177,9 @@ #define STM32_PLL2_DIVN_VALUE 45 #define STM32_PLL2_DIVP_VALUE 2 #define STM32_PLL2_DIVQ_VALUE 5 -#define STM32_PLL2_DIVR_VALUE 1 +#define STM32_PLL2_DIVR_VALUE 8 #define STM32_PLL3_DIVN_VALUE 72 -#define STM32_PLL3_DIVP_VALUE 3 #define STM32_PLL3_DIVQ_VALUE 6 #define STM32_PLL3_DIVR_VALUE 9 @@ -201,10 +200,9 @@ #define STM32_PLL2_DIVN_VALUE 30 #define STM32_PLL2_DIVP_VALUE 2 #define STM32_PLL2_DIVQ_VALUE 5 -#define STM32_PLL2_DIVR_VALUE 1 +#define STM32_PLL2_DIVR_VALUE 8 #define STM32_PLL3_DIVN_VALUE 72 -#define STM32_PLL3_DIVP_VALUE 3 #define STM32_PLL3_DIVQ_VALUE 6 #define STM32_PLL3_DIVR_VALUE 9 @@ -220,10 +218,9 @@ #define STM32_PLL2_DIVN_VALUE 72 #define STM32_PLL2_DIVP_VALUE 2 #define STM32_PLL2_DIVQ_VALUE 5 -#define STM32_PLL2_DIVR_VALUE 1 +#define STM32_PLL2_DIVR_VALUE 8 #define STM32_PLL3_DIVN_VALUE 48 -#define STM32_PLL3_DIVP_VALUE 3 #define STM32_PLL3_DIVQ_VALUE 5 #define STM32_PLL3_DIVR_VALUE 8 #endif // clock selection @@ -251,7 +248,7 @@ #define STM32_PLL2_FRACN_VALUE 0 #define STM32_PLL3_ENABLED TRUE -#define STM32_PLL3_P_ENABLED TRUE +#define STM32_PLL3_P_ENABLED FALSE #define STM32_PLL3_Q_ENABLED TRUE #define STM32_PLL3_R_ENABLED TRUE #define STM32_PLL3_FRACN_VALUE 0 @@ -287,7 +284,7 @@ #ifndef STM32_CKPERSEL #define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK #endif -#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL1_Q_CK +#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL2_R_CK #define STM32_QSPISEL STM32_QSPISEL_PLL2_R_CK #define STM32_FMCSEL STM32_QSPISEL_HCLK #define STM32_SWPSEL STM32_SWPSEL_PCLK1 @@ -368,6 +365,7 @@ * ADC driver system settings. */ #define STM32_ADC_DUAL_MODE FALSE +#define STM32_ADC_SAMPLES_SIZE 16 #define STM32_ADC_COMPACT_SAMPLES FALSE #define STM32_ADC_USE_ADC12 TRUE #ifndef STM32H750xx @@ -483,6 +481,7 @@ #define STM32_SDC_SDMMC_CLOCK_DELAY 10 #define STM32_SDC_SDMMC1_DMA_PRIORITY 3 #define STM32_SDC_SDMMC1_IRQ_PRIORITY 9 +#define STM32_SDC_SDMMC_PWRSAV FALSE /* * SERIAL driver system settings. @@ -505,6 +504,19 @@ #define STM32_UART7CLK STM32_PCLK1 #define STM32_UART8CLK STM32_PCLK1 +/* + * SIO driver system settings. + */ +#define STM32_SIO_USE_USART1 FALSE +#define STM32_SIO_USE_USART2 FALSE +#define STM32_SIO_USE_USART3 FALSE +#define STM32_SIO_USE_UART4 FALSE +#define STM32_SIO_USE_UART5 FALSE +#define STM32_SIO_USE_USART6 FALSE +#define STM32_SIO_USE_UART7 FALSE +#define STM32_SIO_USE_UART8 FALSE +#define STM32_SIO_USE_LPUART1 FALSE + /* * SPI driver system settings. */ @@ -548,6 +560,11 @@ #define STM32_ST_USE_TIMER 5 #endif +/* + * TRNG driver system settings. + */ +#define STM32_TRNG_USE_RNG1 FALSE + /* * UART driver system settings. */ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h index 73dea046289c41..2c76eb2151622e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h @@ -20,6 +20,7 @@ #ifndef MCUCONF_H #define MCUCONF_H +#define STM32L431_MCUCONF #define STM32L4xx_MCUCONF #define STM32L496_MCUCONF #define STM32L4A6_MCUCONF diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index a52997873e340d..13af450beeaee6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -963,13 +963,13 @@ def write_mcu_config(f): env_vars['EXT_FLASH_SIZE_MB'] = get_config('EXT_FLASH_SIZE_MB', default=0, type=int) if env_vars['EXT_FLASH_SIZE_MB'] and not args.bootloader: - f.write('#define CRT1_AREAS_NUMBER 3\n') + f.write('#define CRT0_AREAS_NUMBER 3\n') f.write('#define CRT1_RAMFUNC_ENABLE TRUE\n') # this will enable loading program sections to RAM f.write('#define __FASTRAMFUNC__ __attribute__ ((__section__(".fastramfunc")))\n') f.write('#define __RAMFUNC__ __attribute__ ((__section__(".ramfunc")))\n') f.write('#define PORT_IRQ_ATTRIBUTES __FASTRAMFUNC__\n') else: - f.write('#define CRT1_AREAS_NUMBER 1\n') + f.write('#define CRT0_AREAS_NUMBER 1\n') f.write('#define CRT1_RAMFUNC_ENABLE FALSE\n') storage_flash_page = get_storage_flash_page() @@ -1153,6 +1153,7 @@ def write_mcu_config(f): #endif #define CH_CFG_USE_EVENTS FALSE #define CH_CFG_USE_EVENTS_TIMEOUT FALSE +#define CH_CFG_OPTIMIZE_SPEED FALSE #define HAL_USE_EMPTY_STORAGE 1 #ifndef HAL_STORAGE_SIZE #define HAL_STORAGE_SIZE 16384 @@ -1451,6 +1452,11 @@ def write_QSPI_table(f): def write_QSPI_config(f): '''write SPI config defines''' global qspi_list + # only the bootloader must reset the QSPI clock otherwise it is not possible to + # bootstrap into external flash + if not args.bootloader: + f.write('#define STM32_QSPI_NO_RESET TRUE\n') + if len(qspidev) == 0: # nothing to do return diff --git a/libraries/AP_HAL_ChibiOS/sdcard.cpp b/libraries/AP_HAL_ChibiOS/sdcard.cpp index efc50ce481f09d..ddc51177b27f66 100644 --- a/libraries/AP_HAL_ChibiOS/sdcard.cpp +++ b/libraries/AP_HAL_ChibiOS/sdcard.cpp @@ -22,6 +22,7 @@ #include #include #include "bouncebuffer.h" +#include "stm32_util.h" extern const AP_HAL::HAL& hal; @@ -35,7 +36,9 @@ static bool sdcard_running; #if HAL_USE_SDC static SDCConfig sdcconfig = { +#if !defined(STM32H7) NULL, +#endif SDC_MODE_4BIT, 0 }; @@ -99,6 +102,11 @@ bool sdcard_init() return true; } #elif HAL_USE_MMC_SPI + if (MMCD1.buffer == nullptr) { + // allocate 16 byte non-cacheable buffer for microSD + MMCD1.buffer = (uint8_t*)malloc_axi_sram(MMC_BUFFER_SIZE); + } + if (sdcard_running) { sdcard_stop(); } @@ -113,7 +121,7 @@ bool sdcard_init() } device->set_slowdown(sd_slowdown); - mmcObjectInit(&MMCD1); + mmcObjectInit(&MMCD1, MMCD1.buffer); mmcconfig.spip = static_cast(device.get())->get_driver(); diff --git a/libraries/AP_HAL_ChibiOS/system.cpp b/libraries/AP_HAL_ChibiOS/system.cpp index da1490e2353a9f..d936edf49c55a2 100644 --- a/libraries/AP_HAL_ChibiOS/system.cpp +++ b/libraries/AP_HAL_ChibiOS/system.cpp @@ -107,9 +107,9 @@ void HardFault_Handler(void) { fault_printf("HARDFAULT(%d)\n", int(faultType)); } fault_printf("CSFR=0x%08x\n", cfsr); - fault_printf("CUR=0x%08x\n", ch.rlist.current); - if (ch.rlist.current) { - fault_printf("NAME=%s\n", ch.rlist.current->name); + fault_printf("CUR=0x%08x\n", currcore->rlist.current); + if (currcore->rlist.current) { + fault_printf("NAME=%s\n", currcore->rlist.current->name); } fault_printf("FA=0x%08x\n", faultAddress); fault_printf("PC=0x%08x\n", ctx.pc); From d9d252a1b7902fb4d6c3b18520359eef4e97a085 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 15 Jan 2023 15:21:10 +0000 Subject: [PATCH 071/287] AP_HAL_ChibiOS: update clock trees for H7 variants --- .../hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc | 265 +++++++++------ .../hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc | 266 +++++++++------ .../hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc | 320 ++++++++++++------ .../hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc | 267 +++++++++------ .../hwdef/common/stm32h7_mcuconf.h | 46 ++- 5 files changed, 698 insertions(+), 466 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc index e95f668d4622ff..119173883bd16b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc @@ -237,6 +237,12 @@ Dma.SPI4_TX.5.SyncEnable=DISABLE Dma.SPI4_TX.5.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT Dma.SPI4_TX.5.SyncRequestNumber=1 Dma.SPI4_TX.5.SyncSignalID=NONE +FDCAN1.CalculateBaudRateNominal=1000000 +FDCAN1.CalculateTimeQuantumNominal=200.0 +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateBaudRateNominal +FDCAN2.CalculateBaudRateNominal=1000000 +FDCAN2.CalculateTimeQuantumNominal=200.0 +FDCAN2.IPParameters=CalculateTimeQuantumNominal,CalculateBaudRateNominal File.Version=6 I2C1.IPParameters=Timing I2C1.Timing=0x00707CBB @@ -245,27 +251,29 @@ I2C2.Timing=0x00707CBB I2C4.IPParameters=Timing I2C4.Timing=0x00707CBB KeepUserPlacement=false +Mcu.CPN=STM32H743ZIT6 Mcu.Family=STM32H7 Mcu.IP0=ADC1 Mcu.IP1=BDMA -Mcu.IP10=RCC -Mcu.IP11=RTC -Mcu.IP12=SDMMC1 -Mcu.IP13=SPI1 -Mcu.IP14=SPI2 -Mcu.IP15=SPI4 -Mcu.IP16=SPI5 -Mcu.IP17=SPI6 -Mcu.IP18=SYS -Mcu.IP19=TIM1 +Mcu.IP10=QUADSPI +Mcu.IP11=RCC +Mcu.IP12=RTC +Mcu.IP13=SDMMC1 +Mcu.IP14=SPI1 +Mcu.IP15=SPI2 +Mcu.IP16=SPI4 +Mcu.IP17=SPI5 +Mcu.IP18=SPI6 +Mcu.IP19=SYS Mcu.IP2=CORTEX_M7 -Mcu.IP20=UART4 -Mcu.IP21=UART7 -Mcu.IP22=UART8 -Mcu.IP23=USART2 -Mcu.IP24=USART3 -Mcu.IP25=USART6 -Mcu.IP26=USB_OTG_FS +Mcu.IP20=TIM1 +Mcu.IP21=UART4 +Mcu.IP22=UART7 +Mcu.IP23=UART8 +Mcu.IP24=USART2 +Mcu.IP25=USART3 +Mcu.IP26=USART6 +Mcu.IP27=USB_OTG_FS Mcu.IP3=DMA Mcu.IP4=FDCAN1 Mcu.IP5=FDCAN2 @@ -273,95 +281,101 @@ Mcu.IP6=I2C1 Mcu.IP7=I2C2 Mcu.IP8=I2C4 Mcu.IP9=NVIC -Mcu.IPNb=27 +Mcu.IPNb=28 Mcu.Name=STM32H743ZITx Mcu.Package=LQFP144 Mcu.Pin0=PE2 Mcu.Pin1=PE5 -Mcu.Pin10=PH1-OSC_OUT (PH1) -Mcu.Pin11=PC1 -Mcu.Pin12=PC2_C -Mcu.Pin13=PA0 -Mcu.Pin14=PA1 -Mcu.Pin15=PA2 -Mcu.Pin16=PA3 -Mcu.Pin17=PA5 -Mcu.Pin18=PA6 -Mcu.Pin19=PA7 +Mcu.Pin10=PH0-OSC_IN (PH0) +Mcu.Pin11=PH1-OSC_OUT (PH1) +Mcu.Pin12=PC1 +Mcu.Pin13=PC2_C +Mcu.Pin14=PA0 +Mcu.Pin15=PA1 +Mcu.Pin16=PA2 +Mcu.Pin17=PA3 +Mcu.Pin18=PA5 +Mcu.Pin19=PA6 Mcu.Pin2=PE6 -Mcu.Pin20=PC4 -Mcu.Pin21=PF11 -Mcu.Pin22=PF14 -Mcu.Pin23=PF15 -Mcu.Pin24=PE8 -Mcu.Pin25=PE9 -Mcu.Pin26=PB10 -Mcu.Pin27=PB11 -Mcu.Pin28=PB12 -Mcu.Pin29=PB13 +Mcu.Pin20=PA7 +Mcu.Pin21=PC4 +Mcu.Pin22=PF11 +Mcu.Pin23=PF14 +Mcu.Pin24=PF15 +Mcu.Pin25=PE7 +Mcu.Pin26=PE8 +Mcu.Pin27=PE9 +Mcu.Pin28=PE12 +Mcu.Pin29=PB10 Mcu.Pin3=PF0 -Mcu.Pin30=PC6 -Mcu.Pin31=PC7 -Mcu.Pin32=PC8 -Mcu.Pin33=PC9 -Mcu.Pin34=PA9 -Mcu.Pin35=PA11 -Mcu.Pin36=PA12 -Mcu.Pin37=PC10 -Mcu.Pin38=PC11 -Mcu.Pin39=PC12 +Mcu.Pin30=PB11 +Mcu.Pin31=PB12 +Mcu.Pin32=PB13 +Mcu.Pin33=PD8 +Mcu.Pin34=PD11 +Mcu.Pin35=PD12 +Mcu.Pin36=PC6 +Mcu.Pin37=PC7 +Mcu.Pin38=PC8 +Mcu.Pin39=PC9 Mcu.Pin4=PF1 -Mcu.Pin40=PD0 -Mcu.Pin41=PD1 -Mcu.Pin42=PD2 -Mcu.Pin43=PD7 -Mcu.Pin44=PG9 -Mcu.Pin45=PG11 -Mcu.Pin46=PG12 -Mcu.Pin47=PB6 -Mcu.Pin48=PB7 -Mcu.Pin49=PE0 +Mcu.Pin40=PA9 +Mcu.Pin41=PA11 +Mcu.Pin42=PA12 +Mcu.Pin43=PC10 +Mcu.Pin44=PC11 +Mcu.Pin45=PC12 +Mcu.Pin46=PD0 +Mcu.Pin47=PD1 +Mcu.Pin48=PD2 +Mcu.Pin49=PD7 Mcu.Pin5=PF6 -Mcu.Pin50=PE1 -Mcu.Pin51=VP_RTC_VS_RTC_Activate -Mcu.Pin52=VP_SYS_VS_Systick +Mcu.Pin50=PG9 +Mcu.Pin51=PG11 +Mcu.Pin52=PG12 +Mcu.Pin53=PB6 +Mcu.Pin54=PB7 +Mcu.Pin55=PE0 +Mcu.Pin56=PE1 +Mcu.Pin57=VP_RTC_VS_RTC_Activate +Mcu.Pin58=VP_SYS_VS_Systick Mcu.Pin6=PF7 Mcu.Pin7=PF8 Mcu.Pin8=PF9 -Mcu.Pin9=PH0-OSC_IN (PH0) -Mcu.PinsNb=53 +Mcu.Pin9=PF10 +Mcu.PinsNb=59 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32H743ZITx -MxCube.Version=5.6.1 -MxDb.Version=DB.5.0.60 -NVIC.BDMA_Channel0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.BDMA_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.DMA1_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream4_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream5_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream6_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA2_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false +MxCube.Version=6.6.1 +MxDb.Version=DB.6.0.60 +NVIC.BDMA_Channel0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.BDMA_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.DMA1_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream5_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.ForceEnableDMAVector=true -NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false +NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4 -NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI2_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI4_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI6_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false +NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:false +NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false PA0.Mode=Asynchronous PA0.Signal=UART4_TX PA1.Mode=Asynchronous @@ -381,16 +395,20 @@ PA7.Mode=Full_Duplex_Master PA7.Signal=SPI6_MOSI PA9.Mode=Full_Duplex_Master PA9.Signal=SPI2_SCK -PB10.Mode=Asynchronous -PB10.Signal=USART3_TX +PB10.Mode=Single Bank 1 +PB10.Signal=QUADSPI_BK1_NCS PB11.Mode=Asynchronous PB11.Signal=USART3_RX -PB12.Mode=FDCANSlave +PB12.Mode=FDCAN_Activate PB12.Signal=FDCAN2_RX -PB13.Mode=FDCANSlave +PB13.Mode=FDCAN_Activate PB13.Signal=FDCAN2_TX +PB6.GPIOParameters=GPIO_Pu +PB6.GPIO_Pu=GPIO_PULLUP PB6.Mode=I2C PB6.Signal=I2C1_SCL +PB7.GPIOParameters=GPIO_Pu +PB7.GPIO_Pu=GPIO_PULLUP PB7.Mode=I2C PB7.Signal=I2C1_SDA PC1.Mode=Full_Duplex_Master @@ -412,39 +430,59 @@ PC8.Mode=SD_4_bits_Wide_bus PC8.Signal=SDMMC1_D0 PC9.Mode=SD_4_bits_Wide_bus PC9.Signal=SDMMC1_D1 -PD0.Mode=FDCANMaster +PD0.Mode=FDCAN_Activate PD0.Signal=FDCAN1_RX -PD1.Mode=FDCANMaster +PD1.Mode=FDCAN_Activate PD1.Signal=FDCAN1_TX +PD11.Mode=Single Bank 1 +PD11.Signal=QUADSPI_BK1_IO0 +PD12.Mode=Single Bank 1 +PD12.Signal=QUADSPI_BK1_IO1 PD2.Mode=SD_4_bits_Wide_bus PD2.Signal=SDMMC1_CMD PD7.Mode=Full_Duplex_Master PD7.Signal=SPI1_MOSI +PD8.Mode=Asynchronous +PD8.Signal=USART3_TX PE0.Mode=Asynchronous PE0.Signal=UART8_RX PE1.Mode=Asynchronous PE1.Signal=UART8_TX -PE2.Mode=Full_Duplex_Master -PE2.Signal=SPI4_SCK +PE12.Mode=Full_Duplex_Master +PE12.Signal=SPI4_SCK +PE2.Mode=Single Bank 1 +PE2.Signal=QUADSPI_BK1_IO2 PE5.Mode=Full_Duplex_Master PE5.Signal=SPI4_MISO PE6.Mode=Full_Duplex_Master PE6.Signal=SPI4_MOSI +PE7.Mode=Asynchronous +PE7.Signal=UART7_RX PE8.Mode=Asynchronous PE8.Signal=UART7_TX PE9.Signal=S_TIM1_CH1 +PF0.GPIOParameters=GPIO_Pu +PF0.GPIO_Pu=GPIO_PULLUP PF0.Mode=I2C PF0.Signal=I2C2_SDA +PF1.GPIOParameters=GPIO_Pu +PF1.GPIO_Pu=GPIO_PULLUP PF1.Mode=I2C PF1.Signal=I2C2_SCL +PF10.Mode=Single Bank 1 +PF10.Signal=QUADSPI_CLK PF11.Mode=IN2-Single-Ended PF11.Signal=ADC1_INP2 +PF14.GPIOParameters=GPIO_Pu +PF14.GPIO_Pu=GPIO_PULLUP PF14.Mode=I2C PF14.Signal=I2C4_SCL +PF15.GPIOParameters=GPIO_Pu +PF15.GPIO_Pu=GPIO_PULLUP PF15.Mode=I2C PF15.Signal=I2C4_SDA -PF6.Mode=Asynchronous -PF6.Signal=UART7_RX +PF6.Mode=Single Bank 1 +PF6.Signal=QUADSPI_BK1_IO3 PF7.Mode=Full_Duplex_Master PF7.Signal=SPI5_SCK PF8.Mode=Full_Duplex_Master @@ -471,7 +509,7 @@ ProjectManager.CustomerFirmwarePackage= ProjectManager.DefaultFWLocation=true ProjectManager.DeletePrevious=true ProjectManager.DeviceId=STM32H743ZITx -ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.7.0 +ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.10.0 ProjectManager.FreePins=false ProjectManager.HalAssertFull=false ProjectManager.HeapSize=0x2000 @@ -516,21 +554,22 @@ RCC.DIVM1=2 RCC.DIVM2=2 RCC.DIVM3=4 RCC.DIVN1=100 -RCC.DIVN2=45 +RCC.DIVN2=75 RCC.DIVN3=72 RCC.DIVP1Freq_Value=400000000 -RCC.DIVP2Freq_Value=180000000 +RCC.DIVP2=3 +RCC.DIVP2Freq_Value=200000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=96000000 RCC.DIVQ1=10 RCC.DIVQ1Freq_Value=80000000 -RCC.DIVQ2=5 -RCC.DIVQ2Freq_Value=72000000 +RCC.DIVQ2=6 +RCC.DIVQ2Freq_Value=100000000 RCC.DIVQ3=6 RCC.DIVQ3Freq_Value=48000000 RCC.DIVR1Freq_Value=400000000 -RCC.DIVR2=1 -RCC.DIVR2Freq_Value=360000000 +RCC.DIVR2=3 +RCC.DIVR2Freq_Value=200000000 RCC.DIVR3=9 RCC.DIVR3Freq_Value=32000000 RCC.FDCANFreq_Value=80000000 @@ -546,22 +585,25 @@ RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=32000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=32000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL1_VCI_Range-AdvancedSettings,PLL1_VCO_SEL-AdvancedSettings,PLL2_VCI_Range-AdvancedSettings,PLL2_VCO_SEL-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2I2SEnable-ClockTree,MCO2PinFreq_Value,PLL1_VCI_Range-AdvancedSettings,PLL1_VCO_SEL-AdvancedSettings,PLL2_VCI_Range-AdvancedSettings,PLL2_VCO_SEL-AdvancedSettings,PLL3FRACN,PLL3_VCI_Range-AdvancedSettings,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPICLockSelection,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFEnable-ClockTree,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6CLockSelection,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Spi45ClockSelection,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16CLockSelection,USART16Freq_Value,USART234578CLockSelection,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value RCC.LPTIM1Freq_Value=100000000 RCC.LPTIM2Freq_Value=100000000 RCC.LPTIM345Freq_Value=100000000 RCC.LPUART1Freq_Value=100000000 RCC.LTDCFreq_Value=32000000 RCC.MCO1PinFreq_Value=16000000 +RCC.MCO2I2SEnable-ClockTree=true RCC.MCO2PinFreq_Value=400000000 RCC.PLL1_VCI_Range-AdvancedSettings=RCC_PLL1VCIRANGE_0 RCC.PLL1_VCO_SEL-AdvancedSettings=RCC_PLL1VCOMEDIUM RCC.PLL2_VCI_Range-AdvancedSettings=RCC_PLL2VCIRANGE_0 RCC.PLL2_VCO_SEL-AdvancedSettings=RCC_PLL2VCOMEDIUM RCC.PLL3FRACN=0 +RCC.PLL3_VCI_Range-AdvancedSettings=RCC_PLL3VCIRANGE_0 RCC.PLLFRACN=0 RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 +RCC.QSPICLockSelection=RCC_QSPICLKSOURCE_PLL2 RCC.QSPIFreq_Value=200000000 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 @@ -570,22 +612,27 @@ RCC.SAI23Freq_Value=80000000 RCC.SAI4AFreq_Value=80000000 RCC.SAI4BFreq_Value=80000000 RCC.SDMMCFreq_Value=80000000 +RCC.SPDIFEnable-ClockTree=true RCC.SPDIFRXFreq_Value=80000000 RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 +RCC.SPI6CLockSelection=RCC_SPI6CLKSOURCE_PLL2 RCC.SPI6Freq_Value=100000000 RCC.SWPMI1Freq_Value=100000000 RCC.SYSCLKFreq_VALUE=400000000 RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK +RCC.Spi45ClockSelection=RCC_SPI45CLKSOURCE_PLL2 RCC.Tim1OutputFreq_Value=200000000 RCC.Tim2OutputFreq_Value=200000000 RCC.TraceFreq_Value=16000000 +RCC.USART16CLockSelection=RCC_USART16CLKSOURCE_PLL2 RCC.USART16Freq_Value=100000000 +RCC.USART234578CLockSelection=RCC_USART234578CLKSOURCE_PLL2 RCC.USART234578Freq_Value=100000000 RCC.USBCLockSelection=RCC_USBCLKSOURCE_PLL3 RCC.USBFreq_Value=48000000 RCC.VCO1OutputFreq_Value=800000000 -RCC.VCO2OutputFreq_Value=360000000 +RCC.VCO2OutputFreq_Value=600000000 RCC.VCO3OutputFreq_Value=288000000 RCC.VCOInput1Freq_Value=8000000 RCC.VCOInput2Freq_Value=8000000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc index 721b69d23ec4d3..92d86b18b32821 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc @@ -237,6 +237,12 @@ Dma.SPI4_TX.5.SyncEnable=DISABLE Dma.SPI4_TX.5.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT Dma.SPI4_TX.5.SyncRequestNumber=1 Dma.SPI4_TX.5.SyncSignalID=NONE +FDCAN1.CalculateBaudRateNominal=1000000 +FDCAN1.CalculateTimeQuantumNominal=200.0 +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateBaudRateNominal +FDCAN2.CalculateBaudRateNominal=1000000 +FDCAN2.CalculateTimeQuantumNominal=200.0 +FDCAN2.IPParameters=CalculateTimeQuantumNominal,CalculateBaudRateNominal File.Version=6 I2C1.IPParameters=Timing I2C1.Timing=0x00707CBB @@ -245,27 +251,29 @@ I2C2.Timing=0x00707CBB I2C4.IPParameters=Timing I2C4.Timing=0x00707CBB KeepUserPlacement=false +Mcu.CPN=STM32H743ZIT6 Mcu.Family=STM32H7 Mcu.IP0=ADC1 Mcu.IP1=BDMA -Mcu.IP10=RCC -Mcu.IP11=RTC -Mcu.IP12=SDMMC1 -Mcu.IP13=SPI1 -Mcu.IP14=SPI2 -Mcu.IP15=SPI4 -Mcu.IP16=SPI5 -Mcu.IP17=SPI6 -Mcu.IP18=SYS -Mcu.IP19=TIM1 +Mcu.IP10=QUADSPI +Mcu.IP11=RCC +Mcu.IP12=RTC +Mcu.IP13=SDMMC1 +Mcu.IP14=SPI1 +Mcu.IP15=SPI2 +Mcu.IP16=SPI4 +Mcu.IP17=SPI5 +Mcu.IP18=SPI6 +Mcu.IP19=SYS Mcu.IP2=CORTEX_M7 -Mcu.IP20=UART4 -Mcu.IP21=UART7 -Mcu.IP22=UART8 -Mcu.IP23=USART2 -Mcu.IP24=USART3 -Mcu.IP25=USART6 -Mcu.IP26=USB_OTG_FS +Mcu.IP20=TIM1 +Mcu.IP21=UART4 +Mcu.IP22=UART7 +Mcu.IP23=UART8 +Mcu.IP24=USART2 +Mcu.IP25=USART3 +Mcu.IP26=USART6 +Mcu.IP27=USB_OTG_FS Mcu.IP3=DMA Mcu.IP4=FDCAN1 Mcu.IP5=FDCAN2 @@ -273,95 +281,101 @@ Mcu.IP6=I2C1 Mcu.IP7=I2C2 Mcu.IP8=I2C4 Mcu.IP9=NVIC -Mcu.IPNb=27 +Mcu.IPNb=28 Mcu.Name=STM32H743ZITx Mcu.Package=LQFP144 Mcu.Pin0=PE2 Mcu.Pin1=PE5 -Mcu.Pin10=PH1-OSC_OUT (PH1) -Mcu.Pin11=PC1 -Mcu.Pin12=PC2_C -Mcu.Pin13=PA0 -Mcu.Pin14=PA1 -Mcu.Pin15=PA2 -Mcu.Pin16=PA3 -Mcu.Pin17=PA5 -Mcu.Pin18=PA6 -Mcu.Pin19=PA7 +Mcu.Pin10=PH0-OSC_IN (PH0) +Mcu.Pin11=PH1-OSC_OUT (PH1) +Mcu.Pin12=PC1 +Mcu.Pin13=PC2_C +Mcu.Pin14=PA0 +Mcu.Pin15=PA1 +Mcu.Pin16=PA2 +Mcu.Pin17=PA3 +Mcu.Pin18=PA5 +Mcu.Pin19=PA6 Mcu.Pin2=PE6 -Mcu.Pin20=PC4 -Mcu.Pin21=PF11 -Mcu.Pin22=PF14 -Mcu.Pin23=PF15 -Mcu.Pin24=PE8 -Mcu.Pin25=PE9 -Mcu.Pin26=PB10 -Mcu.Pin27=PB11 -Mcu.Pin28=PB12 -Mcu.Pin29=PB13 +Mcu.Pin20=PA7 +Mcu.Pin21=PC4 +Mcu.Pin22=PF11 +Mcu.Pin23=PF14 +Mcu.Pin24=PF15 +Mcu.Pin25=PE7 +Mcu.Pin26=PE8 +Mcu.Pin27=PE9 +Mcu.Pin28=PE12 +Mcu.Pin29=PB10 Mcu.Pin3=PF0 -Mcu.Pin30=PC6 -Mcu.Pin31=PC7 -Mcu.Pin32=PC8 -Mcu.Pin33=PC9 -Mcu.Pin34=PA9 -Mcu.Pin35=PA11 -Mcu.Pin36=PA12 -Mcu.Pin37=PC10 -Mcu.Pin38=PC11 -Mcu.Pin39=PC12 +Mcu.Pin30=PB11 +Mcu.Pin31=PB12 +Mcu.Pin32=PB13 +Mcu.Pin33=PD8 +Mcu.Pin34=PD11 +Mcu.Pin35=PD12 +Mcu.Pin36=PC6 +Mcu.Pin37=PC7 +Mcu.Pin38=PC8 +Mcu.Pin39=PC9 Mcu.Pin4=PF1 -Mcu.Pin40=PD0 -Mcu.Pin41=PD1 -Mcu.Pin42=PD2 -Mcu.Pin43=PD7 -Mcu.Pin44=PG9 -Mcu.Pin45=PG11 -Mcu.Pin46=PG12 -Mcu.Pin47=PB6 -Mcu.Pin48=PB7 -Mcu.Pin49=PE0 +Mcu.Pin40=PA9 +Mcu.Pin41=PA11 +Mcu.Pin42=PA12 +Mcu.Pin43=PC10 +Mcu.Pin44=PC11 +Mcu.Pin45=PC12 +Mcu.Pin46=PD0 +Mcu.Pin47=PD1 +Mcu.Pin48=PD2 +Mcu.Pin49=PD7 Mcu.Pin5=PF6 -Mcu.Pin50=PE1 -Mcu.Pin51=VP_RTC_VS_RTC_Activate -Mcu.Pin52=VP_SYS_VS_Systick +Mcu.Pin50=PG9 +Mcu.Pin51=PG11 +Mcu.Pin52=PG12 +Mcu.Pin53=PB6 +Mcu.Pin54=PB7 +Mcu.Pin55=PE0 +Mcu.Pin56=PE1 +Mcu.Pin57=VP_RTC_VS_RTC_Activate +Mcu.Pin58=VP_SYS_VS_Systick Mcu.Pin6=PF7 Mcu.Pin7=PF8 Mcu.Pin8=PF9 -Mcu.Pin9=PH0-OSC_IN (PH0) -Mcu.PinsNb=53 +Mcu.Pin9=PF10 +Mcu.PinsNb=59 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32H743ZITx -MxCube.Version=5.6.1 -MxDb.Version=DB.5.0.60 -NVIC.BDMA_Channel0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.BDMA_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.DMA1_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream4_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream5_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream6_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA2_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false +MxCube.Version=6.6.1 +MxDb.Version=DB.6.0.60 +NVIC.BDMA_Channel0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.BDMA_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.DMA1_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream5_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.ForceEnableDMAVector=true -NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false +NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4 -NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI2_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI4_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI6_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false +NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:false +NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false PA0.Mode=Asynchronous PA0.Signal=UART4_TX PA1.Mode=Asynchronous @@ -381,16 +395,20 @@ PA7.Mode=Full_Duplex_Master PA7.Signal=SPI6_MOSI PA9.Mode=Full_Duplex_Master PA9.Signal=SPI2_SCK -PB10.Mode=Asynchronous -PB10.Signal=USART3_TX +PB10.Mode=Single Bank 1 +PB10.Signal=QUADSPI_BK1_NCS PB11.Mode=Asynchronous PB11.Signal=USART3_RX -PB12.Mode=FDCANSlave +PB12.Mode=FDCAN_Activate PB12.Signal=FDCAN2_RX -PB13.Mode=FDCANSlave +PB13.Mode=FDCAN_Activate PB13.Signal=FDCAN2_TX +PB6.GPIOParameters=GPIO_Pu +PB6.GPIO_Pu=GPIO_PULLUP PB6.Mode=I2C PB6.Signal=I2C1_SCL +PB7.GPIOParameters=GPIO_Pu +PB7.GPIO_Pu=GPIO_PULLUP PB7.Mode=I2C PB7.Signal=I2C1_SDA PC1.Mode=Full_Duplex_Master @@ -412,39 +430,59 @@ PC8.Mode=SD_4_bits_Wide_bus PC8.Signal=SDMMC1_D0 PC9.Mode=SD_4_bits_Wide_bus PC9.Signal=SDMMC1_D1 -PD0.Mode=FDCANMaster +PD0.Mode=FDCAN_Activate PD0.Signal=FDCAN1_RX -PD1.Mode=FDCANMaster +PD1.Mode=FDCAN_Activate PD1.Signal=FDCAN1_TX +PD11.Mode=Single Bank 1 +PD11.Signal=QUADSPI_BK1_IO0 +PD12.Mode=Single Bank 1 +PD12.Signal=QUADSPI_BK1_IO1 PD2.Mode=SD_4_bits_Wide_bus PD2.Signal=SDMMC1_CMD PD7.Mode=Full_Duplex_Master PD7.Signal=SPI1_MOSI +PD8.Mode=Asynchronous +PD8.Signal=USART3_TX PE0.Mode=Asynchronous PE0.Signal=UART8_RX PE1.Mode=Asynchronous PE1.Signal=UART8_TX -PE2.Mode=Full_Duplex_Master -PE2.Signal=SPI4_SCK +PE12.Mode=Full_Duplex_Master +PE12.Signal=SPI4_SCK +PE2.Mode=Single Bank 1 +PE2.Signal=QUADSPI_BK1_IO2 PE5.Mode=Full_Duplex_Master PE5.Signal=SPI4_MISO PE6.Mode=Full_Duplex_Master PE6.Signal=SPI4_MOSI +PE7.Mode=Asynchronous +PE7.Signal=UART7_RX PE8.Mode=Asynchronous PE8.Signal=UART7_TX PE9.Signal=S_TIM1_CH1 +PF0.GPIOParameters=GPIO_Pu +PF0.GPIO_Pu=GPIO_PULLUP PF0.Mode=I2C PF0.Signal=I2C2_SDA +PF1.GPIOParameters=GPIO_Pu +PF1.GPIO_Pu=GPIO_PULLUP PF1.Mode=I2C PF1.Signal=I2C2_SCL +PF10.Mode=Single Bank 1 +PF10.Signal=QUADSPI_CLK PF11.Mode=IN2-Single-Ended PF11.Signal=ADC1_INP2 +PF14.GPIOParameters=GPIO_Pu +PF14.GPIO_Pu=GPIO_PULLUP PF14.Mode=I2C PF14.Signal=I2C4_SCL +PF15.GPIOParameters=GPIO_Pu +PF15.GPIO_Pu=GPIO_PULLUP PF15.Mode=I2C PF15.Signal=I2C4_SDA -PF6.Mode=Asynchronous -PF6.Signal=UART7_RX +PF6.Mode=Single Bank 1 +PF6.Signal=QUADSPI_BK1_IO3 PF7.Mode=Full_Duplex_Master PF7.Signal=SPI5_SCK PF8.Mode=Full_Duplex_Master @@ -471,7 +509,7 @@ ProjectManager.CustomerFirmwarePackage= ProjectManager.DefaultFWLocation=true ProjectManager.DeletePrevious=true ProjectManager.DeviceId=STM32H743ZITx -ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.7.0 +ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.10.0 ProjectManager.FreePins=false ProjectManager.HalAssertFull=false ProjectManager.HeapSize=0x2000 @@ -489,7 +527,7 @@ ProjectManager.StackSize=0x4000 ProjectManager.TargetToolchain=Makefile ProjectManager.ToolChainLocation= ProjectManager.UnderRoot=false -ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-MX_BDMA_Init-BDMA-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-SystemClock_Config-RCC-false-HAL-false,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,7-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,8-MX_SPI1_Init-SPI1-false-HAL-true,9-MX_I2C1_Init-I2C1-false-HAL-true,10-MX_I2C2_Init-I2C2-false-HAL-true,11-MX_I2C4_Init-I2C4-false-HAL-true,12-MX_USART2_UART_Init-USART2-false-HAL-true,13-MX_USART3_UART_Init-USART3-false-HAL-true,14-MX_USART6_UART_Init-USART6-false-HAL-true,15-MX_UART4_Init-UART4-false-HAL-true,16-MX_UART7_Init-UART7-false-HAL-true,17-MX_SPI2_Init-SPI2-false-HAL-true,18-MX_SPI4_Init-SPI4-false-HAL-true,19-MX_RTC_Init-RTC-false-HAL-true,20-MX_SPI5_Init-SPI5-false-HAL-true,21-MX_SPI6_Init-SPI6-false-HAL-true,22-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,23-MX_FDCAN1_Init-FDCAN1-false-HAL-true,24-MX_FDCAN2_Init-FDCAN2-false-HAL-true,25-MX_UART8_Init-UART8-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true +ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-MX_BDMA_Init-BDMA-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-SystemClock_Config-RCC-false-HAL-false,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,7-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,8-MX_SPI1_Init-SPI1-false-HAL-true,9-MX_I2C1_Init-I2C1-false-HAL-true,10-MX_I2C2_Init-I2C2-false-HAL-true,11-MX_I2C4_Init-I2C4-false-HAL-true,12-MX_USART2_UART_Init-USART2-false-HAL-true,13-MX_USART3_UART_Init-USART3-false-HAL-true,14-MX_USART6_UART_Init-USART6-false-HAL-true,15-MX_UART4_Init-UART4-false-HAL-true,16-MX_UART7_Init-UART7-false-HAL-true,17-MX_SPI2_Init-SPI2-false-HAL-true,18-MX_SPI4_Init-SPI4-false-HAL-true,19-MX_RTC_Init-RTC-false-HAL-true,20-MX_SPI5_Init-SPI5-false-HAL-true,21-MX_SPI6_Init-SPI6-false-HAL-true,22-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,23-MX_FDCAN1_Init-FDCAN1-false-HAL-true,24-MX_FDCAN2_Init-FDCAN2-false-HAL-true,25-MX_UART8_Init-UART8-false-HAL-true,26-MX_QUADSPI_Init-QUADSPI-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true RCC.ADCCLockSelection=RCC_ADCCLKSOURCE_PLL3 RCC.ADCFreq_Value=32000000 RCC.AHB12Freq_Value=200000000 @@ -516,21 +554,22 @@ RCC.DIVM1=3 RCC.DIVM2=2 RCC.DIVM3=6 RCC.DIVN1=100 -RCC.DIVN2=30 +RCC.DIVN2=50 RCC.DIVN3=72 RCC.DIVP1Freq_Value=400000000 -RCC.DIVP2Freq_Value=180000000 +RCC.DIVP2=3 +RCC.DIVP2Freq_Value=200000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=96000000 RCC.DIVQ1=10 RCC.DIVQ1Freq_Value=80000000 -RCC.DIVQ2=5 -RCC.DIVQ2Freq_Value=72000000 +RCC.DIVQ2=6 +RCC.DIVQ2Freq_Value=100000000 RCC.DIVQ3=6 RCC.DIVQ3Freq_Value=48000000 RCC.DIVR1Freq_Value=400000000 -RCC.DIVR2=1 -RCC.DIVR2Freq_Value=360000000 +RCC.DIVR2=3 +RCC.DIVR2Freq_Value=200000000 RCC.DIVR3=9 RCC.DIVR3Freq_Value=32000000 RCC.FDCANFreq_Value=80000000 @@ -546,7 +585,7 @@ RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=32000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=32000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL1_VCO_SEL-AdvancedSettings,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLL3_VCI_Range-AdvancedSettings,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPICLockSelection,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6CLockSelection,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Spi45ClockSelection,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16CLockSelection,USART16Freq_Value,USART234578CLockSelection,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value RCC.LPTIM1Freq_Value=100000000 RCC.LPTIM2Freq_Value=100000000 RCC.LPTIM345Freq_Value=100000000 @@ -554,11 +593,14 @@ RCC.LPUART1Freq_Value=100000000 RCC.LTDCFreq_Value=32000000 RCC.MCO1PinFreq_Value=16000000 RCC.MCO2PinFreq_Value=400000000 +RCC.PLL1_VCO_SEL-AdvancedSettings=RCC_PLL1VCOMEDIUM RCC.PLL2_VCI_Range-AdvancedSettings=RCC_PLL2VCIRANGE_0 RCC.PLL3FRACN=0 +RCC.PLL3_VCI_Range-AdvancedSettings=RCC_PLL3VCIRANGE_0 RCC.PLLFRACN=0 RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 +RCC.QSPICLockSelection=RCC_QSPICLKSOURCE_PLL2 RCC.QSPIFreq_Value=200000000 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 @@ -570,19 +612,23 @@ RCC.SDMMCFreq_Value=80000000 RCC.SPDIFRXFreq_Value=80000000 RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 +RCC.SPI6CLockSelection=RCC_SPI6CLKSOURCE_PLL2 RCC.SPI6Freq_Value=100000000 RCC.SWPMI1Freq_Value=100000000 RCC.SYSCLKFreq_VALUE=400000000 RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK +RCC.Spi45ClockSelection=RCC_SPI45CLKSOURCE_PLL2 RCC.Tim1OutputFreq_Value=200000000 RCC.Tim2OutputFreq_Value=200000000 RCC.TraceFreq_Value=16000000 +RCC.USART16CLockSelection=RCC_USART16CLKSOURCE_PLL2 RCC.USART16Freq_Value=100000000 +RCC.USART234578CLockSelection=RCC_USART234578CLKSOURCE_PLL2 RCC.USART234578Freq_Value=100000000 RCC.USBCLockSelection=RCC_USBCLKSOURCE_PLL3 RCC.USBFreq_Value=48000000 RCC.VCO1OutputFreq_Value=800000000 -RCC.VCO2OutputFreq_Value=360000000 +RCC.VCO2OutputFreq_Value=600000000 RCC.VCO3OutputFreq_Value=288000000 RCC.VCOInput1Freq_Value=8000000 RCC.VCOInput2Freq_Value=12000000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc index f324f458d9fc6b..66c4b455d763f5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc @@ -237,6 +237,12 @@ Dma.SPI4_TX.5.SyncEnable=DISABLE Dma.SPI4_TX.5.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT Dma.SPI4_TX.5.SyncRequestNumber=1 Dma.SPI4_TX.5.SyncSignalID=NONE +FDCAN1.CalculateBaudRateNominal=1000000 +FDCAN1.CalculateTimeQuantumNominal=200.0 +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateBaudRateNominal +FDCAN2.CalculateBaudRateNominal=1000000 +FDCAN2.CalculateTimeQuantumNominal=200.0 +FDCAN2.IPParameters=CalculateTimeQuantumNominal,CalculateBaudRateNominal File.Version=6 I2C1.IPParameters=Timing I2C1.Timing=0x007074AF @@ -245,27 +251,29 @@ I2C2.Timing=0x007074AF I2C4.IPParameters=Timing I2C4.Timing=0x007074AF KeepUserPlacement=false +Mcu.CPN=STM32H743ZIT6 Mcu.Family=STM32H7 Mcu.IP0=ADC1 Mcu.IP1=BDMA -Mcu.IP10=RCC -Mcu.IP11=RTC -Mcu.IP12=SDMMC1 -Mcu.IP13=SPI1 -Mcu.IP14=SPI2 -Mcu.IP15=SPI4 -Mcu.IP16=SPI5 -Mcu.IP17=SPI6 -Mcu.IP18=SYS -Mcu.IP19=TIM1 +Mcu.IP10=QUADSPI +Mcu.IP11=RCC +Mcu.IP12=RTC +Mcu.IP13=SDMMC1 +Mcu.IP14=SPI1 +Mcu.IP15=SPI2 +Mcu.IP16=SPI4 +Mcu.IP17=SPI5 +Mcu.IP18=SPI6 +Mcu.IP19=SYS Mcu.IP2=CORTEX_M7 -Mcu.IP20=UART4 -Mcu.IP21=UART7 -Mcu.IP22=UART8 -Mcu.IP23=USART2 -Mcu.IP24=USART3 -Mcu.IP25=USART6 -Mcu.IP26=USB_OTG_FS +Mcu.IP20=TIM1 +Mcu.IP21=UART4 +Mcu.IP22=UART7 +Mcu.IP23=UART8 +Mcu.IP24=USART2 +Mcu.IP25=USART3 +Mcu.IP26=USART6 +Mcu.IP27=USB_OTG_FS Mcu.IP3=DMA Mcu.IP4=FDCAN1 Mcu.IP5=FDCAN2 @@ -273,95 +281,101 @@ Mcu.IP6=I2C1 Mcu.IP7=I2C2 Mcu.IP8=I2C4 Mcu.IP9=NVIC -Mcu.IPNb=27 +Mcu.IPNb=28 Mcu.Name=STM32H743ZITx Mcu.Package=LQFP144 Mcu.Pin0=PE2 Mcu.Pin1=PE5 -Mcu.Pin10=PH1-OSC_OUT (PH1) -Mcu.Pin11=PC1 -Mcu.Pin12=PC2_C -Mcu.Pin13=PA0 -Mcu.Pin14=PA1 -Mcu.Pin15=PA2 -Mcu.Pin16=PA3 -Mcu.Pin17=PA5 -Mcu.Pin18=PA6 -Mcu.Pin19=PA7 +Mcu.Pin10=PH0-OSC_IN (PH0) +Mcu.Pin11=PH1-OSC_OUT (PH1) +Mcu.Pin12=PC1 +Mcu.Pin13=PC2_C +Mcu.Pin14=PA0 +Mcu.Pin15=PA1 +Mcu.Pin16=PA2 +Mcu.Pin17=PA3 +Mcu.Pin18=PA5 +Mcu.Pin19=PA6 Mcu.Pin2=PE6 -Mcu.Pin20=PC4 -Mcu.Pin21=PF11 -Mcu.Pin22=PF14 -Mcu.Pin23=PF15 -Mcu.Pin24=PE8 -Mcu.Pin25=PE9 -Mcu.Pin26=PB10 -Mcu.Pin27=PB11 -Mcu.Pin28=PB12 -Mcu.Pin29=PB13 +Mcu.Pin20=PA7 +Mcu.Pin21=PC4 +Mcu.Pin22=PF11 +Mcu.Pin23=PF14 +Mcu.Pin24=PF15 +Mcu.Pin25=PE7 +Mcu.Pin26=PE8 +Mcu.Pin27=PE9 +Mcu.Pin28=PE12 +Mcu.Pin29=PB10 Mcu.Pin3=PF0 -Mcu.Pin30=PC6 -Mcu.Pin31=PC7 -Mcu.Pin32=PC8 -Mcu.Pin33=PC9 -Mcu.Pin34=PA9 -Mcu.Pin35=PA11 -Mcu.Pin36=PA12 -Mcu.Pin37=PC10 -Mcu.Pin38=PC11 -Mcu.Pin39=PC12 +Mcu.Pin30=PB11 +Mcu.Pin31=PB12 +Mcu.Pin32=PB13 +Mcu.Pin33=PD8 +Mcu.Pin34=PD11 +Mcu.Pin35=PD12 +Mcu.Pin36=PC6 +Mcu.Pin37=PC7 +Mcu.Pin38=PC8 +Mcu.Pin39=PC9 Mcu.Pin4=PF1 -Mcu.Pin40=PD0 -Mcu.Pin41=PD1 -Mcu.Pin42=PD2 -Mcu.Pin43=PD7 -Mcu.Pin44=PG9 -Mcu.Pin45=PG11 -Mcu.Pin46=PG12 -Mcu.Pin47=PB6 -Mcu.Pin48=PB7 -Mcu.Pin49=PE0 +Mcu.Pin40=PA9 +Mcu.Pin41=PA11 +Mcu.Pin42=PA12 +Mcu.Pin43=PC10 +Mcu.Pin44=PC11 +Mcu.Pin45=PC12 +Mcu.Pin46=PD0 +Mcu.Pin47=PD1 +Mcu.Pin48=PD2 +Mcu.Pin49=PD7 Mcu.Pin5=PF6 -Mcu.Pin50=PE1 -Mcu.Pin51=VP_RTC_VS_RTC_Activate -Mcu.Pin52=VP_SYS_VS_Systick +Mcu.Pin50=PG9 +Mcu.Pin51=PG11 +Mcu.Pin52=PG12 +Mcu.Pin53=PB6 +Mcu.Pin54=PB7 +Mcu.Pin55=PE0 +Mcu.Pin56=PE1 +Mcu.Pin57=VP_RTC_VS_RTC_Activate +Mcu.Pin58=VP_SYS_VS_Systick Mcu.Pin6=PF7 Mcu.Pin7=PF8 Mcu.Pin8=PF9 -Mcu.Pin9=PH0-OSC_IN (PH0) -Mcu.PinsNb=53 +Mcu.Pin9=PF10 +Mcu.PinsNb=59 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32H743ZITx -MxCube.Version=5.6.1 -MxDb.Version=DB.5.0.60 -NVIC.BDMA_Channel0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.BDMA_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.DMA1_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream4_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream5_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream6_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA2_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false +MxCube.Version=6.6.1 +MxDb.Version=DB.6.0.60 +NVIC.BDMA_Channel0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.BDMA_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.DMA1_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream5_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.ForceEnableDMAVector=true -NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false +NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4 -NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI2_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI4_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI6_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false +NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:false +NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false PA0.Mode=Asynchronous PA0.Signal=UART4_TX PA1.Mode=Asynchronous @@ -381,16 +395,20 @@ PA7.Mode=Full_Duplex_Master PA7.Signal=SPI6_MOSI PA9.Mode=Full_Duplex_Master PA9.Signal=SPI2_SCK -PB10.Mode=Asynchronous -PB10.Signal=USART3_TX +PB10.Mode=Single Bank 1 +PB10.Signal=QUADSPI_BK1_NCS PB11.Mode=Asynchronous PB11.Signal=USART3_RX -PB12.Mode=FDCANSlave +PB12.Mode=FDCAN_Activate PB12.Signal=FDCAN2_RX -PB13.Mode=FDCANSlave +PB13.Mode=FDCAN_Activate PB13.Signal=FDCAN2_TX +PB6.GPIOParameters=GPIO_Pu +PB6.GPIO_Pu=GPIO_PULLUP PB6.Mode=I2C PB6.Signal=I2C1_SCL +PB7.GPIOParameters=GPIO_Pu +PB7.GPIO_Pu=GPIO_PULLUP PB7.Mode=I2C PB7.Signal=I2C1_SDA PC1.Mode=Full_Duplex_Master @@ -412,39 +430,65 @@ PC8.Mode=SD_4_bits_Wide_bus PC8.Signal=SDMMC1_D0 PC9.Mode=SD_4_bits_Wide_bus PC9.Signal=SDMMC1_D1 -PD0.Mode=FDCANMaster +PD0.Mode=FDCAN_Activate PD0.Signal=FDCAN1_RX -PD1.Mode=FDCANMaster +PD1.Mode=FDCAN_Activate PD1.Signal=FDCAN1_TX +PD11.Mode=Single Bank 1 +PD11.Signal=QUADSPI_BK1_IO0 +PD12.Mode=Single Bank 1 +PD12.Signal=QUADSPI_BK1_IO1 PD2.Mode=SD_4_bits_Wide_bus PD2.Signal=SDMMC1_CMD PD7.Mode=Full_Duplex_Master PD7.Signal=SPI1_MOSI +PD8.Mode=Asynchronous +PD8.Signal=USART3_TX PE0.Mode=Asynchronous PE0.Signal=UART8_RX PE1.Mode=Asynchronous PE1.Signal=UART8_TX -PE2.Mode=Full_Duplex_Master -PE2.Signal=SPI4_SCK +PE12.GPIOParameters=PinAttribute +PE12.Mode=Full_Duplex_Master +PE12.PinAttribute=Free +PE12.Signal=SPI4_SCK +PE2.Mode=Single Bank 1 +PE2.Signal=QUADSPI_BK1_IO2 PE5.Mode=Full_Duplex_Master PE5.Signal=SPI4_MISO PE6.Mode=Full_Duplex_Master PE6.Signal=SPI4_MOSI +PE7.Mode=Asynchronous +PE7.Signal=UART7_RX +PE8.GPIOParameters=PinAttribute PE8.Mode=Asynchronous +PE8.PinAttribute=Free PE8.Signal=UART7_TX +PE9.GPIOParameters=PinAttribute +PE9.PinAttribute=Free PE9.Signal=S_TIM1_CH1 +PF0.GPIOParameters=GPIO_Pu +PF0.GPIO_Pu=GPIO_PULLUP PF0.Mode=I2C PF0.Signal=I2C2_SDA +PF1.GPIOParameters=GPIO_Pu +PF1.GPIO_Pu=GPIO_PULLUP PF1.Mode=I2C PF1.Signal=I2C2_SCL +PF10.Mode=Single Bank 1 +PF10.Signal=QUADSPI_CLK PF11.Mode=IN2-Single-Ended PF11.Signal=ADC1_INP2 +PF14.GPIOParameters=GPIO_Pu +PF14.GPIO_Pu=GPIO_PULLUP PF14.Mode=I2C PF14.Signal=I2C4_SCL +PF15.GPIOParameters=GPIO_Pu +PF15.GPIO_Pu=GPIO_PULLUP PF15.Mode=I2C PF15.Signal=I2C4_SDA -PF6.Mode=Asynchronous -PF6.Signal=UART7_RX +PF6.Mode=Single Bank 1 +PF6.Signal=QUADSPI_BK1_IO3 PF7.Mode=Full_Duplex_Master PF7.Signal=SPI5_SCK PF8.Mode=Full_Duplex_Master @@ -471,7 +515,7 @@ ProjectManager.CustomerFirmwarePackage= ProjectManager.DefaultFWLocation=true ProjectManager.DeletePrevious=true ProjectManager.DeviceId=STM32H743ZITx -ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.7.0 +ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.10.0 ProjectManager.FreePins=false ProjectManager.HalAssertFull=false ProjectManager.HeapSize=0x2000 @@ -489,7 +533,7 @@ ProjectManager.StackSize=0x4000 ProjectManager.TargetToolchain=Makefile ProjectManager.ToolChainLocation= ProjectManager.UnderRoot=false -ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-MX_BDMA_Init-BDMA-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-SystemClock_Config-RCC-false-HAL-false,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,7-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,8-MX_SPI1_Init-SPI1-false-HAL-true,9-MX_I2C1_Init-I2C1-false-HAL-true,10-MX_I2C2_Init-I2C2-false-HAL-true,11-MX_I2C4_Init-I2C4-false-HAL-true,12-MX_USART2_UART_Init-USART2-false-HAL-true,13-MX_USART3_UART_Init-USART3-false-HAL-true,14-MX_USART6_UART_Init-USART6-false-HAL-true,15-MX_UART4_Init-UART4-false-HAL-true,16-MX_UART7_Init-UART7-false-HAL-true,17-MX_SPI2_Init-SPI2-false-HAL-true,18-MX_SPI4_Init-SPI4-false-HAL-true,19-MX_RTC_Init-RTC-false-HAL-true,20-MX_SPI5_Init-SPI5-false-HAL-true,21-MX_SPI6_Init-SPI6-false-HAL-true,22-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,23-MX_FDCAN1_Init-FDCAN1-false-HAL-true,24-MX_FDCAN2_Init-FDCAN2-false-HAL-true,25-MX_UART8_Init-UART8-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true +ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-MX_BDMA_Init-BDMA-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-SystemClock_Config-RCC-false-HAL-false,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,7-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,8-MX_SPI1_Init-SPI1-false-HAL-true,9-MX_I2C1_Init-I2C1-false-HAL-true,10-MX_I2C2_Init-I2C2-false-HAL-true,11-MX_I2C4_Init-I2C4-false-HAL-true,12-MX_USART2_UART_Init-USART2-false-HAL-true,13-MX_USART3_UART_Init-USART3-false-HAL-true,14-MX_USART6_UART_Init-USART6-false-HAL-true,15-MX_UART4_Init-UART4-false-HAL-true,16-MX_UART7_Init-UART7-false-HAL-true,17-MX_SPI2_Init-SPI2-false-HAL-true,18-MX_SPI4_Init-SPI4-false-HAL-true,19-MX_RTC_Init-RTC-false-HAL-true,20-MX_SPI5_Init-SPI5-false-HAL-true,21-MX_SPI6_Init-SPI6-false-HAL-true,22-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,23-MX_FDCAN1_Init-FDCAN1-false-HAL-true,24-MX_FDCAN2_Init-FDCAN2-false-HAL-true,25-MX_UART8_Init-UART8-false-HAL-true,26-MX_QUADSPI_Init-QUADSPI-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true RCC.ADCCLockSelection=RCC_ADCCLKSOURCE_PLL3 RCC.ADCFreq_Value=30000000 RCC.AHB12Freq_Value=200000000 @@ -499,41 +543,62 @@ RCC.APB2Freq_Value=100000000 RCC.APB3Freq_Value=100000000 RCC.APB4Freq_Value=100000000 RCC.AXIClockFreq_Value=200000000 +RCC.CECCLockSelection=RCC_CECCLKSOURCE_LSI RCC.CECFreq_Value=32000 RCC.CKPERFreq_Value=16000000 +RCC.CKPERSourceSelection=RCC_CLKPSOURCE_HSI RCC.CPU2Freq_Value=100000000 RCC.CPU2SystikFreq_Value=100000000 +RCC.CSI_VALUE=4000000 RCC.CortexFreq_Value=400000000 +RCC.Cortex_Div=SYSTICK_CLKSOURCE_HCLK +RCC.Cortex_DivARG=SystemCoreClock/1000 RCC.CpuClockFreq_Value=400000000 +RCC.D1CPRE=RCC_SYSCLK_DIV1 RCC.D1CPREFreq_Value=400000000 RCC.D1PPRE=RCC_APB3_DIV2 RCC.D2PPRE1=RCC_APB1_DIV2 RCC.D2PPRE2=RCC_APB2_DIV2 RCC.D3PPRE=RCC_APB4_DIV2 RCC.DFSDMACLkFreq_Value=80000000 +RCC.DFSDMCLockSelection=RCC_DFSDM1CLKSOURCE_D2PCLK1 RCC.DFSDMFreq_Value=100000000 RCC.DIVM1=2 RCC.DIVM2=5 RCC.DIVM3=5 RCC.DIVN1=64 -RCC.DIVN2=72 +RCC.DIVN2=120 RCC.DIVN3=48 +RCC.DIVP1=2 RCC.DIVP1Freq_Value=400000000 -RCC.DIVP2Freq_Value=180000000 +RCC.DIVP2=3 +RCC.DIVP2Freq_Value=200000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=80000000 RCC.DIVQ1=10 RCC.DIVQ1Freq_Value=80000000 -RCC.DIVQ2=5 -RCC.DIVQ2Freq_Value=72000000 +RCC.DIVQ2=6 +RCC.DIVQ2Freq_Value=100000000 RCC.DIVQ3=5 RCC.DIVQ3Freq_Value=48000000 +RCC.DIVR1=2 RCC.DIVR1Freq_Value=400000000 -RCC.DIVR2=1 -RCC.DIVR2Freq_Value=360000000 +RCC.DIVR2=3 +RCC.DIVR2Freq_Value=200000000 RCC.DIVR3=8 RCC.DIVR3Freq_Value=30000000 +RCC.DSICLockSelection=RCC_DSICLKSOURCE_PHY +RCC.DSIFreq_Value=96000000 +RCC.DSIPHYCLKFreq_Value=96000000 +RCC.DSIPHY_Div=8 +RCC.DSITXEscFreq_Value=20000000 +RCC.DSITX_Div=4 +RCC.DSI_PHY_VALUE=12288000 +RCC.EXTERNAL_CLOCK_VALUE=12288000 +RCC.EnbaleCSS=false +RCC.FDCANCLockSelection=RCC_FDCANCLKSOURCE_PLL RCC.FDCANFreq_Value=80000000 +RCC.FMCCLockSelection=RCC_FMCCLKSOURCE_D1HCLK RCC.FMCFreq_Value=200000000 RCC.FamilyName=M RCC.HCLK3ClockFreq_Value=200000000 @@ -542,51 +607,86 @@ RCC.HPRE=RCC_HCLK_DIV2 RCC.HRTIMFreq_Value=200000000 RCC.HSE_VALUE=25000000 RCC.HSIDiv=RCC_PLLSAIDIVR_4 +RCC.HSI_VALUE=64000000 RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=30000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=30000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECCLockSelection,CECFreq_Value,CKPERFreq_Value,CKPERSourceSelection,CPU2Freq_Value,CPU2SystikFreq_Value,CSI_VALUE,CortexFreq_Value,Cortex_Div,Cortex_DivARG,CpuClockFreq_Value,D1CPRE,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMCLockSelection,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1,DIVP1Freq_Value,DIVP2,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,DSICLockSelection,DSIFreq_Value,DSIPHYCLKFreq_Value,DSIPHY_Div,DSITXEscFreq_Value,DSITX_Div,DSI_PHY_VALUE,EXTERNAL_CLOCK_VALUE,EnbaleCSS,FDCANCLockSelection,FDCANFreq_Value,FMCCLockSelection,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,HSI_VALUE,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1CLockSelection,LPTIM1Freq_Value,LPTIM2CLockSelection,LPTIM2Freq_Value,LPTIM345CLockSelection,LPTIM345Freq_Value,LPUART1CLockSelection,LPUART1Freq_Value,LSEState,LSE_VALUE,LSI_VALUE,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLDSIDev,PLLDSIFreq_Value,PLLDSIIDF,PLLDSIMult,PLLDSINDIV,PLLDSIODF,PLLDSIVCOFreq_Value,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPICLockSelection,QSPIFreq_Value,RC48_VALUE,RCC_MCO1Source,RCC_MCO2Source,RCC_MCODiv1,RCC_MCODiv2,RCC_RTC_Clock_Source_FROM_HSE,RNGCLockSelection,RNGFreq_Value,RTCFreq_Value,SAI1CLockSelection,SAI1Freq_Value,SAI23CLockSelection,SAI23Freq_Value,SAI4ACLockSelection,SAI4AFreq_Value,SAI4BCLockSelection,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFCLockSelection,SPDIFRXFreq_Value,SPI123CLockSelection,SPI123Freq_Value,SPI45Freq_Value,SPI6CLockSelection,SPI6Freq_Value,SWPCLockSelection,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Spi45ClockSelection,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16CLockSelection,USART16Freq_Value,USART234578CLockSelection,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value,WatchDogFreq_Value +RCC.LPTIM1CLockSelection=RCC_LPTIM1CLKSOURCE_D2PCLK1 RCC.LPTIM1Freq_Value=100000000 +RCC.LPTIM2CLockSelection=RCC_LPTIM2CLKSOURCE_D3PCLK1 RCC.LPTIM2Freq_Value=100000000 +RCC.LPTIM345CLockSelection=RCC_LPTIM345CLKSOURCE_D3PCLK1 RCC.LPTIM345Freq_Value=100000000 +RCC.LPUART1CLockSelection=RCC_LPUART1CLKSOURCE_D3PCLK1 RCC.LPUART1Freq_Value=100000000 +RCC.LSEState=RCC_LSE_OFF +RCC.LSE_VALUE=32768 +RCC.LSI_VALUE=32000 RCC.LTDCFreq_Value=30000000 RCC.MCO1PinFreq_Value=16000000 RCC.MCO2PinFreq_Value=400000000 RCC.PLL2_VCI_Range-AdvancedSettings=RCC_PLL2VCIRANGE_0 RCC.PLL3FRACN=0 +RCC.PLLDSIDev=2 +RCC.PLLDSIFreq_Value=500000000 +RCC.PLLDSIIDF=DSI_PLL_IN_DIV1 +RCC.PLLDSIMult=2 +RCC.PLLDSINDIV=20 +RCC.PLLDSIODF=DSI_PLL_OUT_DIV1 +RCC.PLLDSIVCOFreq_Value=500000000 RCC.PLLFRACN=0 RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 +RCC.QSPICLockSelection=RCC_QSPICLKSOURCE_PLL2 RCC.QSPIFreq_Value=200000000 +RCC.RC48_VALUE=48000000 +RCC.RCC_MCO1Source=RCC_MCO1SOURCE_HSI +RCC.RCC_MCO2Source=RCC_MCO2SOURCE_SYSCLK +RCC.RCC_MCODiv1=RCC_MCODIV_1 +RCC.RCC_MCODiv2=RCC_MCODIV_1 +RCC.RCC_RTC_Clock_Source_FROM_HSE=RCC_RTCCLKSOURCE_HSE_DIV2 +RCC.RNGCLockSelection=RCC_RNGCLKSOURCE_HSI48 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 +RCC.SAI1CLockSelection=RCC_SAI1CLKSOURCE_PLL RCC.SAI1Freq_Value=80000000 +RCC.SAI23CLockSelection=RCC_SAI23CLKSOURCE_PLL RCC.SAI23Freq_Value=80000000 +RCC.SAI4ACLockSelection=RCC_SAI4ACLKSOURCE_PLL RCC.SAI4AFreq_Value=80000000 +RCC.SAI4BCLockSelection=RCC_SAI4BCLKSOURCE_PLL RCC.SAI4BFreq_Value=80000000 RCC.SDMMCFreq_Value=80000000 +RCC.SPDIFCLockSelection=RCC_SPDIFRXCLKSOURCE_PLL RCC.SPDIFRXFreq_Value=80000000 +RCC.SPI123CLockSelection=RCC_SPI123CLKSOURCE_PLL RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 +RCC.SPI6CLockSelection=RCC_SPI6CLKSOURCE_PLL2 RCC.SPI6Freq_Value=100000000 +RCC.SWPCLockSelection=RCC_SWPMI1CLKSOURCE_D2PCLK1 RCC.SWPMI1Freq_Value=100000000 RCC.SYSCLKFreq_VALUE=400000000 RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK +RCC.Spi45ClockSelection=RCC_SPI45CLKSOURCE_PLL2 RCC.Tim1OutputFreq_Value=200000000 RCC.Tim2OutputFreq_Value=200000000 RCC.TraceFreq_Value=16000000 +RCC.USART16CLockSelection=RCC_USART16CLKSOURCE_PLL2 RCC.USART16Freq_Value=100000000 +RCC.USART234578CLockSelection=RCC_USART234578CLKSOURCE_PLL2 RCC.USART234578Freq_Value=100000000 RCC.USBCLockSelection=RCC_USBCLKSOURCE_PLL3 RCC.USBFreq_Value=48000000 RCC.VCO1OutputFreq_Value=800000000 -RCC.VCO2OutputFreq_Value=360000000 +RCC.VCO2OutputFreq_Value=600000000 RCC.VCO3OutputFreq_Value=240000000 RCC.VCOInput1Freq_Value=12500000 RCC.VCOInput2Freq_Value=5000000 RCC.VCOInput3Freq_Value=5000000 +RCC.WatchDogFreq_Value=32000 SH.ADCx_INP3.0=ADC1_INP3,IN3-Single-Ended SH.ADCx_INP3.ConfNb=1 SH.ADCx_INP4.0=ADC1_INP4,IN4-Single-Ended diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc index 862b90d42d7665..2c84b4045a6238 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc @@ -237,6 +237,12 @@ Dma.SPI4_TX.5.SyncEnable=DISABLE Dma.SPI4_TX.5.SyncPolarity=HAL_DMAMUX_SYNC_NO_EVENT Dma.SPI4_TX.5.SyncRequestNumber=1 Dma.SPI4_TX.5.SyncSignalID=NONE +FDCAN1.CalculateBaudRateNominal=1000000 +FDCAN1.CalculateTimeQuantumNominal=200.0 +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateBaudRateNominal +FDCAN2.CalculateBaudRateNominal=1000000 +FDCAN2.CalculateTimeQuantumNominal=200.0 +FDCAN2.IPParameters=CalculateTimeQuantumNominal,CalculateBaudRateNominal File.Version=6 I2C1.IPParameters=Timing I2C1.Timing=0x00707CBB @@ -245,27 +251,29 @@ I2C2.Timing=0x00707CBB I2C4.IPParameters=Timing I2C4.Timing=0x00707CBB KeepUserPlacement=false +Mcu.CPN=STM32H743ZIT6 Mcu.Family=STM32H7 Mcu.IP0=ADC1 Mcu.IP1=BDMA -Mcu.IP10=RCC -Mcu.IP11=RTC -Mcu.IP12=SDMMC1 -Mcu.IP13=SPI1 -Mcu.IP14=SPI2 -Mcu.IP15=SPI4 -Mcu.IP16=SPI5 -Mcu.IP17=SPI6 -Mcu.IP18=SYS -Mcu.IP19=TIM1 +Mcu.IP10=QUADSPI +Mcu.IP11=RCC +Mcu.IP12=RTC +Mcu.IP13=SDMMC1 +Mcu.IP14=SPI1 +Mcu.IP15=SPI2 +Mcu.IP16=SPI4 +Mcu.IP17=SPI5 +Mcu.IP18=SPI6 +Mcu.IP19=SYS Mcu.IP2=CORTEX_M7 -Mcu.IP20=UART4 -Mcu.IP21=UART7 -Mcu.IP22=UART8 -Mcu.IP23=USART2 -Mcu.IP24=USART3 -Mcu.IP25=USART6 -Mcu.IP26=USB_OTG_FS +Mcu.IP20=TIM1 +Mcu.IP21=UART4 +Mcu.IP22=UART7 +Mcu.IP23=UART8 +Mcu.IP24=USART2 +Mcu.IP25=USART3 +Mcu.IP26=USART6 +Mcu.IP27=USB_OTG_FS Mcu.IP3=DMA Mcu.IP4=FDCAN1 Mcu.IP5=FDCAN2 @@ -273,95 +281,101 @@ Mcu.IP6=I2C1 Mcu.IP7=I2C2 Mcu.IP8=I2C4 Mcu.IP9=NVIC -Mcu.IPNb=27 +Mcu.IPNb=28 Mcu.Name=STM32H743ZITx Mcu.Package=LQFP144 Mcu.Pin0=PE2 Mcu.Pin1=PE5 -Mcu.Pin10=PH1-OSC_OUT (PH1) -Mcu.Pin11=PC1 -Mcu.Pin12=PC2_C -Mcu.Pin13=PA0 -Mcu.Pin14=PA1 -Mcu.Pin15=PA2 -Mcu.Pin16=PA3 -Mcu.Pin17=PA5 -Mcu.Pin18=PA6 -Mcu.Pin19=PA7 +Mcu.Pin10=PH0-OSC_IN (PH0) +Mcu.Pin11=PH1-OSC_OUT (PH1) +Mcu.Pin12=PC1 +Mcu.Pin13=PC2_C +Mcu.Pin14=PA0 +Mcu.Pin15=PA1 +Mcu.Pin16=PA2 +Mcu.Pin17=PA3 +Mcu.Pin18=PA5 +Mcu.Pin19=PA6 Mcu.Pin2=PE6 -Mcu.Pin20=PC4 -Mcu.Pin21=PF11 -Mcu.Pin22=PF14 -Mcu.Pin23=PF15 -Mcu.Pin24=PE8 -Mcu.Pin25=PE9 -Mcu.Pin26=PB10 -Mcu.Pin27=PB11 -Mcu.Pin28=PB12 -Mcu.Pin29=PB13 +Mcu.Pin20=PA7 +Mcu.Pin21=PC4 +Mcu.Pin22=PF11 +Mcu.Pin23=PF14 +Mcu.Pin24=PF15 +Mcu.Pin25=PE7 +Mcu.Pin26=PE8 +Mcu.Pin27=PE9 +Mcu.Pin28=PE12 +Mcu.Pin29=PB10 Mcu.Pin3=PF0 -Mcu.Pin30=PC6 -Mcu.Pin31=PC7 -Mcu.Pin32=PC8 -Mcu.Pin33=PC9 -Mcu.Pin34=PA9 -Mcu.Pin35=PA11 -Mcu.Pin36=PA12 -Mcu.Pin37=PC10 -Mcu.Pin38=PC11 -Mcu.Pin39=PC12 +Mcu.Pin30=PB11 +Mcu.Pin31=PB12 +Mcu.Pin32=PB13 +Mcu.Pin33=PD8 +Mcu.Pin34=PD11 +Mcu.Pin35=PD12 +Mcu.Pin36=PC6 +Mcu.Pin37=PC7 +Mcu.Pin38=PC8 +Mcu.Pin39=PC9 Mcu.Pin4=PF1 -Mcu.Pin40=PD0 -Mcu.Pin41=PD1 -Mcu.Pin42=PD2 -Mcu.Pin43=PD7 -Mcu.Pin44=PG9 -Mcu.Pin45=PG11 -Mcu.Pin46=PG12 -Mcu.Pin47=PB6 -Mcu.Pin48=PB7 -Mcu.Pin49=PE0 +Mcu.Pin40=PA9 +Mcu.Pin41=PA11 +Mcu.Pin42=PA12 +Mcu.Pin43=PC10 +Mcu.Pin44=PC11 +Mcu.Pin45=PC12 +Mcu.Pin46=PD0 +Mcu.Pin47=PD1 +Mcu.Pin48=PD2 +Mcu.Pin49=PD7 Mcu.Pin5=PF6 -Mcu.Pin50=PE1 -Mcu.Pin51=VP_RTC_VS_RTC_Activate -Mcu.Pin52=VP_SYS_VS_Systick +Mcu.Pin50=PG9 +Mcu.Pin51=PG11 +Mcu.Pin52=PG12 +Mcu.Pin53=PB6 +Mcu.Pin54=PB7 +Mcu.Pin55=PE0 +Mcu.Pin56=PE1 +Mcu.Pin57=VP_RTC_VS_RTC_Activate +Mcu.Pin58=VP_SYS_VS_Systick Mcu.Pin6=PF7 Mcu.Pin7=PF8 Mcu.Pin8=PF9 -Mcu.Pin9=PH0-OSC_IN (PH0) -Mcu.PinsNb=53 +Mcu.Pin9=PF10 +Mcu.PinsNb=59 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32H743ZITx -MxCube.Version=5.6.1 -MxDb.Version=DB.5.0.60 -NVIC.BDMA_Channel0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.BDMA_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.DMA1_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream4_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream5_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream6_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA1_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DMA2_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false +MxCube.Version=6.6.1 +MxDb.Version=DB.6.0.60 +NVIC.BDMA_Channel0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.BDMA_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.DMA1_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream3_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream5_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Stream7_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Stream0_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Stream1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.ForceEnableDMAVector=true -NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false +NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4 -NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI2_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI4_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SPI6_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false -NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true -NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false +NVIC.SPI1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI2_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SPI6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false +NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:false +NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false PA0.Mode=Asynchronous PA0.Signal=UART4_TX PA1.Mode=Asynchronous @@ -381,16 +395,20 @@ PA7.Mode=Full_Duplex_Master PA7.Signal=SPI6_MOSI PA9.Mode=Full_Duplex_Master PA9.Signal=SPI2_SCK -PB10.Mode=Asynchronous -PB10.Signal=USART3_TX +PB10.Mode=Single Bank 1 +PB10.Signal=QUADSPI_BK1_NCS PB11.Mode=Asynchronous PB11.Signal=USART3_RX -PB12.Mode=FDCANSlave +PB12.Mode=FDCAN_Activate PB12.Signal=FDCAN2_RX -PB13.Mode=FDCANSlave +PB13.Mode=FDCAN_Activate PB13.Signal=FDCAN2_TX +PB6.GPIOParameters=GPIO_Pu +PB6.GPIO_Pu=GPIO_PULLUP PB6.Mode=I2C PB6.Signal=I2C1_SCL +PB7.GPIOParameters=GPIO_Pu +PB7.GPIO_Pu=GPIO_PULLUP PB7.Mode=I2C PB7.Signal=I2C1_SDA PC1.Mode=Full_Duplex_Master @@ -412,39 +430,59 @@ PC8.Mode=SD_4_bits_Wide_bus PC8.Signal=SDMMC1_D0 PC9.Mode=SD_4_bits_Wide_bus PC9.Signal=SDMMC1_D1 -PD0.Mode=FDCANMaster +PD0.Mode=FDCAN_Activate PD0.Signal=FDCAN1_RX -PD1.Mode=FDCANMaster +PD1.Mode=FDCAN_Activate PD1.Signal=FDCAN1_TX +PD11.Mode=Single Bank 1 +PD11.Signal=QUADSPI_BK1_IO0 +PD12.Mode=Single Bank 1 +PD12.Signal=QUADSPI_BK1_IO1 PD2.Mode=SD_4_bits_Wide_bus PD2.Signal=SDMMC1_CMD PD7.Mode=Full_Duplex_Master PD7.Signal=SPI1_MOSI +PD8.Mode=Asynchronous +PD8.Signal=USART3_TX PE0.Mode=Asynchronous PE0.Signal=UART8_RX PE1.Mode=Asynchronous PE1.Signal=UART8_TX -PE2.Mode=Full_Duplex_Master -PE2.Signal=SPI4_SCK +PE12.Mode=Full_Duplex_Master +PE12.Signal=SPI4_SCK +PE2.Mode=Single Bank 1 +PE2.Signal=QUADSPI_BK1_IO2 PE5.Mode=Full_Duplex_Master PE5.Signal=SPI4_MISO PE6.Mode=Full_Duplex_Master PE6.Signal=SPI4_MOSI +PE7.Mode=Asynchronous +PE7.Signal=UART7_RX PE8.Mode=Asynchronous PE8.Signal=UART7_TX PE9.Signal=S_TIM1_CH1 +PF0.GPIOParameters=GPIO_Pu +PF0.GPIO_Pu=GPIO_PULLUP PF0.Mode=I2C PF0.Signal=I2C2_SDA +PF1.GPIOParameters=GPIO_Pu +PF1.GPIO_Pu=GPIO_PULLUP PF1.Mode=I2C PF1.Signal=I2C2_SCL +PF10.Mode=Single Bank 1 +PF10.Signal=QUADSPI_CLK PF11.Mode=IN2-Single-Ended PF11.Signal=ADC1_INP2 +PF14.GPIOParameters=GPIO_Pu +PF14.GPIO_Pu=GPIO_PULLUP PF14.Mode=I2C PF14.Signal=I2C4_SCL +PF15.GPIOParameters=GPIO_Pu +PF15.GPIO_Pu=GPIO_PULLUP PF15.Mode=I2C PF15.Signal=I2C4_SDA -PF6.Mode=Asynchronous -PF6.Signal=UART7_RX +PF6.Mode=Single Bank 1 +PF6.Signal=QUADSPI_BK1_IO3 PF7.Mode=Full_Duplex_Master PF7.Signal=SPI5_SCK PF8.Mode=Full_Duplex_Master @@ -471,7 +509,7 @@ ProjectManager.CustomerFirmwarePackage= ProjectManager.DefaultFWLocation=true ProjectManager.DeletePrevious=true ProjectManager.DeviceId=STM32H743ZITx -ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.7.0 +ProjectManager.FirmwarePackage=STM32Cube FW_H7 V1.10.0 ProjectManager.FreePins=false ProjectManager.HalAssertFull=false ProjectManager.HeapSize=0x2000 @@ -489,7 +527,7 @@ ProjectManager.StackSize=0x4000 ProjectManager.TargetToolchain=Makefile ProjectManager.ToolChainLocation= ProjectManager.UnderRoot=false -ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-MX_BDMA_Init-BDMA-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-SystemClock_Config-RCC-false-HAL-false,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,7-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,8-MX_SPI1_Init-SPI1-false-HAL-true,9-MX_I2C1_Init-I2C1-false-HAL-true,10-MX_I2C2_Init-I2C2-false-HAL-true,11-MX_I2C4_Init-I2C4-false-HAL-true,12-MX_USART2_UART_Init-USART2-false-HAL-true,13-MX_USART3_UART_Init-USART3-false-HAL-true,14-MX_USART6_UART_Init-USART6-false-HAL-true,15-MX_UART4_Init-UART4-false-HAL-true,16-MX_UART7_Init-UART7-false-HAL-true,17-MX_SPI2_Init-SPI2-false-HAL-true,18-MX_SPI4_Init-SPI4-false-HAL-true,19-MX_RTC_Init-RTC-false-HAL-true,20-MX_SPI5_Init-SPI5-false-HAL-true,21-MX_SPI6_Init-SPI6-false-HAL-true,22-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,23-MX_FDCAN1_Init-FDCAN1-false-HAL-true,24-MX_FDCAN2_Init-FDCAN2-false-HAL-true,25-MX_UART8_Init-UART8-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true +ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-MX_BDMA_Init-BDMA-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-SystemClock_Config-RCC-false-HAL-false,5-MX_ADC1_Init-ADC1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,7-MX_USB_OTG_FS_PCD_Init-USB_OTG_FS-false-HAL-true,8-MX_SPI1_Init-SPI1-false-HAL-true,9-MX_I2C1_Init-I2C1-false-HAL-true,10-MX_I2C2_Init-I2C2-false-HAL-true,11-MX_I2C4_Init-I2C4-false-HAL-true,12-MX_USART2_UART_Init-USART2-false-HAL-true,13-MX_USART3_UART_Init-USART3-false-HAL-true,14-MX_USART6_UART_Init-USART6-false-HAL-true,15-MX_UART4_Init-UART4-false-HAL-true,16-MX_UART7_Init-UART7-false-HAL-true,17-MX_SPI2_Init-SPI2-false-HAL-true,18-MX_SPI4_Init-SPI4-false-HAL-true,19-MX_RTC_Init-RTC-false-HAL-true,20-MX_SPI5_Init-SPI5-false-HAL-true,21-MX_SPI6_Init-SPI6-false-HAL-true,22-MX_SDMMC1_SD_Init-SDMMC1-false-HAL-true,23-MX_FDCAN1_Init-FDCAN1-false-HAL-true,24-MX_FDCAN2_Init-FDCAN2-false-HAL-true,25-MX_UART8_Init-UART8-false-HAL-true,26-MX_QUADSPI_Init-QUADSPI-false-HAL-true,0-MX_CORTEX_M7_Init-CORTEX_M7-false-HAL-true RCC.ADCCLockSelection=RCC_ADCCLKSOURCE_PLL3 RCC.ADCFreq_Value=32000000 RCC.AHB12Freq_Value=200000000 @@ -516,23 +554,25 @@ RCC.DIVM1=1 RCC.DIVM2=1 RCC.DIVM3=2 RCC.DIVN1=100 -RCC.DIVN2=45 +RCC.DIVN2=75 RCC.DIVN3=72 RCC.DIVP1Freq_Value=400000000 -RCC.DIVP2Freq_Value=180000000 +RCC.DIVP2=3 +RCC.DIVP2Freq_Value=200000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=96000000 RCC.DIVQ1=10 RCC.DIVQ1Freq_Value=80000000 -RCC.DIVQ2=5 -RCC.DIVQ2Freq_Value=72000000 +RCC.DIVQ2=6 +RCC.DIVQ2Freq_Value=100000000 RCC.DIVQ3=6 RCC.DIVQ3Freq_Value=48000000 RCC.DIVR1Freq_Value=400000000 -RCC.DIVR2=1 -RCC.DIVR2Freq_Value=360000000 +RCC.DIVR2=3 +RCC.DIVR2Freq_Value=200000000 RCC.DIVR3=9 RCC.DIVR3Freq_Value=32000000 +RCC.EnbaleCSS=false RCC.FDCANFreq_Value=80000000 RCC.FMCFreq_Value=200000000 RCC.FamilyName=M @@ -546,7 +586,7 @@ RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=32000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=32000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,EnbaleCSS,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL1_VCI_Range-AdvancedSettings,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPICLockSelection,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Enable-ClockTree,SPI123Freq_Value,SPI45Freq_Value,SPI6CLockSelection,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Spi45ClockSelection,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16CLockSelection,USART16Freq_Value,USART234578CLockSelection,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value RCC.LPTIM1Freq_Value=100000000 RCC.LPTIM2Freq_Value=100000000 RCC.LPTIM345Freq_Value=100000000 @@ -554,11 +594,13 @@ RCC.LPUART1Freq_Value=100000000 RCC.LTDCFreq_Value=32000000 RCC.MCO1PinFreq_Value=16000000 RCC.MCO2PinFreq_Value=400000000 +RCC.PLL1_VCI_Range-AdvancedSettings=RCC_PLL1VCIRANGE_0 RCC.PLL2_VCI_Range-AdvancedSettings=RCC_PLL2VCIRANGE_0 RCC.PLL3FRACN=0 RCC.PLLFRACN=0 RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 +RCC.QSPICLockSelection=RCC_QSPICLKSOURCE_PLL2 RCC.QSPIFreq_Value=200000000 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 @@ -568,21 +610,26 @@ RCC.SAI4AFreq_Value=80000000 RCC.SAI4BFreq_Value=80000000 RCC.SDMMCFreq_Value=80000000 RCC.SPDIFRXFreq_Value=80000000 +RCC.SPI123Enable-ClockTree=true RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 +RCC.SPI6CLockSelection=RCC_SPI6CLKSOURCE_PLL2 RCC.SPI6Freq_Value=100000000 RCC.SWPMI1Freq_Value=100000000 RCC.SYSCLKFreq_VALUE=400000000 RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK +RCC.Spi45ClockSelection=RCC_SPI45CLKSOURCE_PLL2 RCC.Tim1OutputFreq_Value=200000000 RCC.Tim2OutputFreq_Value=200000000 RCC.TraceFreq_Value=16000000 +RCC.USART16CLockSelection=RCC_USART16CLKSOURCE_PLL2 RCC.USART16Freq_Value=100000000 +RCC.USART234578CLockSelection=RCC_USART234578CLKSOURCE_PLL2 RCC.USART234578Freq_Value=100000000 RCC.USBCLockSelection=RCC_USBCLKSOURCE_PLL3 RCC.USBFreq_Value=48000000 RCC.VCO1OutputFreq_Value=800000000 -RCC.VCO2OutputFreq_Value=360000000 +RCC.VCO2OutputFreq_Value=600000000 RCC.VCO3OutputFreq_Value=288000000 RCC.VCOInput1Freq_Value=8000000 RCC.VCOInput2Freq_Value=8000000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h index 0f08d6f20c9684..109d044b2d537e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h @@ -164,20 +164,21 @@ #ifdef HAL_CUSTOM_MCU_CLOCKRATE #if HAL_CUSTOM_MCU_CLOCKRATE == 480000000 #define STM32_PLL1_DIVN_VALUE 120 +#define STM32_PLL1_DIVQ_VALUE 12 #else #error "Unable to configure custom clockrate" #endif #else #define STM32_PLL1_DIVN_VALUE 100 +#define STM32_PLL1_DIVQ_VALUE 10 #endif #define STM32_PLL1_DIVP_VALUE 2 -#define STM32_PLL1_DIVQ_VALUE 10 #define STM32_PLL1_DIVR_VALUE 2 -#define STM32_PLL2_DIVN_VALUE 45 -#define STM32_PLL2_DIVP_VALUE 2 -#define STM32_PLL2_DIVQ_VALUE 5 -#define STM32_PLL2_DIVR_VALUE 8 +#define STM32_PLL2_DIVN_VALUE 75 +#define STM32_PLL2_DIVP_VALUE 3 +#define STM32_PLL2_DIVQ_VALUE 6 +#define STM32_PLL2_DIVR_VALUE 3 #define STM32_PLL3_DIVN_VALUE 72 #define STM32_PLL3_DIVQ_VALUE 6 @@ -197,10 +198,10 @@ #define STM32_PLL1_DIVQ_VALUE 10 #define STM32_PLL1_DIVR_VALUE 2 -#define STM32_PLL2_DIVN_VALUE 30 -#define STM32_PLL2_DIVP_VALUE 2 -#define STM32_PLL2_DIVQ_VALUE 5 -#define STM32_PLL2_DIVR_VALUE 8 +#define STM32_PLL2_DIVN_VALUE 50 +#define STM32_PLL2_DIVP_VALUE 3 +#define STM32_PLL2_DIVQ_VALUE 6 +#define STM32_PLL2_DIVR_VALUE 3 #define STM32_PLL3_DIVN_VALUE 72 #define STM32_PLL3_DIVQ_VALUE 6 @@ -215,10 +216,10 @@ #define STM32_PLL1_DIVQ_VALUE 10 #define STM32_PLL1_DIVR_VALUE 2 -#define STM32_PLL2_DIVN_VALUE 72 -#define STM32_PLL2_DIVP_VALUE 2 -#define STM32_PLL2_DIVQ_VALUE 5 -#define STM32_PLL2_DIVR_VALUE 8 +#define STM32_PLL2_DIVN_VALUE 120 +#define STM32_PLL2_DIVP_VALUE 3 +#define STM32_PLL2_DIVQ_VALUE 6 +#define STM32_PLL2_DIVR_VALUE 3 #define STM32_PLL3_DIVN_VALUE 48 #define STM32_PLL3_DIVQ_VALUE 5 @@ -284,14 +285,14 @@ #ifndef STM32_CKPERSEL #define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK #endif -#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL2_R_CK +#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL1_Q_CK #define STM32_QSPISEL STM32_QSPISEL_PLL2_R_CK #define STM32_FMCSEL STM32_QSPISEL_HCLK #define STM32_SWPSEL STM32_SWPSEL_PCLK1 #define STM32_FDCANSEL STM32_FDCANSEL_PLL1_Q_CK #define STM32_DFSDM1SEL STM32_DFSDM1SEL_PCLK2 #define STM32_SPDIFSEL STM32_SPDIFSEL_PLL1_Q_CK -#define STM32_SPI45SEL STM32_SPI45SEL_PCLK2 +#define STM32_SPI45SEL STM32_SPI45SEL_PLL2_Q_CK #define STM32_SPI123SEL STM32_SPI123SEL_PLL1_Q_CK #define STM32_SAI23SEL STM32_SAI23SEL_PLL1_Q_CK #define STM32_SAI1SEL STM32_SAI1SEL_PLL1_Q_CK @@ -300,9 +301,9 @@ #define STM32_USBSEL STM32_USBSEL_PLL3_Q_CK #define STM32_I2C123SEL STM32_I2C123SEL_PLL3_R_CK #define STM32_RNGSEL STM32_RNGSEL_HSI48_CK -#define STM32_USART16SEL STM32_USART16SEL_PCLK2 -#define STM32_USART234578SEL STM32_USART234578SEL_PCLK1 -#define STM32_SPI6SEL STM32_SPI6SEL_PCLK4 +#define STM32_USART16SEL STM32_USART16SEL_PLL2_Q_CK +#define STM32_USART234578SEL STM32_USART234578SEL_PLL2_Q_CK +#define STM32_SPI6SEL STM32_SPI6SEL_PLL2_Q_CK #define STM32_SAI4BSEL STM32_SAI4BSEL_PLL1_Q_CK #define STM32_SAI4ASEL STM32_SAI4ASEL_PLL1_Q_CK #define STM32_ADCSEL STM32_ADCSEL_PLL3_R_CK @@ -495,15 +496,6 @@ #define STM32_SERIAL_UART7_PRIORITY 12 #define STM32_SERIAL_UART8_PRIORITY 12 -#define STM32_UART1CLK STM32_PCLK1 -#define STM32_UART2CLK STM32_PCLK1 -#define STM32_UART3CLK STM32_PCLK1 -#define STM32_UART4CLK STM32_PCLK1 -#define STM32_UART5CLK STM32_PCLK1 -#define STM32_UART6CLK STM32_PCLK1 -#define STM32_UART7CLK STM32_PCLK1 -#define STM32_UART8CLK STM32_PCLK1 - /* * SIO driver system settings. */ From 39b226c46bf88b93652b436af5b8fd783433c958 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 30 Jan 2023 16:18:13 +0000 Subject: [PATCH 072/287] AP_HAL_ChibiOS: support EXPECTED_CLOCKS and assert on meaningful ones for H7 --- libraries/AP_HAL_ChibiOS/QSPIDevice.cpp | 3 --- .../hwdef/scripts/STM32H743xx.py | 8 ++++++++ .../hwdef/scripts/STM32H750xx.py | 7 +++++++ .../hwdef/scripts/chibios_hwdef.py | 8 ++++++++ libraries/AP_HAL_ChibiOS/system.cpp | 20 +++++++++++++++++++ 5 files changed, 43 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp b/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp index 5ae2d69092198e..b0afeccfd924e9 100644 --- a/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp @@ -45,9 +45,6 @@ static const struct QSPIDriverInfo { QSPIDesc QSPIDeviceManager::device_table[] = { HAL_QSPI_DEVICE_LIST }; // Check clock sanity during runtime -#define XSTR(x) STR(x) -#define STR(x) #x - #if (STM32_QSPICLK < HAL_QSPI1_CLK) #error "Flash speed must not be greater than QSPI Clock" #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py index 82c860195e0559..62d734a7e11804 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py @@ -58,6 +58,14 @@ 'EXPECTED_CLOCK' : 400000000, + 'EXPECTED_CLOCKS' : [ + ('STM32_SYS_CK', 400000000), + ('STM32_QSPICLK', 200000000), + ('STM32_SDMMC1CLK', 80000000), + ('STM32_SPI45CLK', 100000000), + ('STM32_FDCANCLK', 80000000), + ], + # this MCU has M7 instructions and hardware double precision 'CORTEX' : 'cortex-m7', 'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard', diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py index 1d7d9ac4334a0c..c81e630310b0b5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py @@ -63,6 +63,13 @@ 'EXPECTED_CLOCK' : 400000000, + 'EXPECTED_CLOCKS' : [ + ('STM32_SYS_CK', 400000000), + ('STM32_QSPICLK', 200000000), + ('STM32_SDMMC1CLK', 80000000), + ('STM32_SPI45CLK', 100000000), + ], + # this MCU has M7 instructions and hardware double precision 'CORTEX' : 'cortex-m7', 'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard', diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 13af450beeaee6..d1410d50ae580e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -1082,6 +1082,14 @@ def write_mcu_config(f): elif get_mcu_config('EXPECTED_CLOCK', required=True): f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % get_mcu_config('EXPECTED_CLOCK')) + if get_mcu_config('EXPECTED_CLOCKS', required=False): + clockrate = get_config('MCU_CLOCKRATE_MHZ', required=False) + for mcu_clock, mcu_clock_speed in get_mcu_config('EXPECTED_CLOCKS'): + if (mcu_clock == 'STM32_HCLK' or mcu_clock == 'STM32_SYS_CK') and clockrate: + f.write('#define HAL_EXPECTED_%s %u\n' % (mcu_clock, int(clockrate) * 1000000)) + else: + f.write('#define HAL_EXPECTED_%s %u\n' % (mcu_clock, mcu_clock_speed)) + env_vars['CORTEX'] = cortex if not args.bootloader: diff --git a/libraries/AP_HAL_ChibiOS/system.cpp b/libraries/AP_HAL_ChibiOS/system.cpp index d936edf49c55a2..d9e177c5963090 100644 --- a/libraries/AP_HAL_ChibiOS/system.cpp +++ b/libraries/AP_HAL_ChibiOS/system.cpp @@ -53,6 +53,26 @@ static_assert(HAL_EXPECTED_SYSCLOCK == STM32_HCLK, "unexpected STM32_HCLK value" #define AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED 1 #endif +#define QUOTE(str) #str +#define EXPAND_AND_QUOTE(str) QUOTE(str) +#define ASSERT_CLOCK(clk) static_assert(HAL_EXPECTED_ ##clk == (clk), "unexpected " #clk " value: '" EXPAND_AND_QUOTE(clk) "'") + +#if defined(HAL_EXPECTED_STM32_SYS_CK) && defined(STM32_SYS_CK) +ASSERT_CLOCK(STM32_SYS_CK); +#endif +#if defined(HAL_EXPECTED_STM32_HCLK) && defined(STM32_HCLK) +ASSERT_CLOCK(STM32_HCLK); +#endif +#if defined(HAL_EXPECTED_STM32_SDMMC1CLK) && defined(STM32_SDMMC1CLK) +ASSERT_CLOCK(STM32_SDMMC1CLK); +#endif +#if defined(HAL_EXPECTED_STM32_SPI45CLK) && defined(STM32_SPI45CLK) +ASSERT_CLOCK(STM32_SPI45CLK); +#endif +#if defined(HAL_EXPECTED_STM32_FDCANCLK) && defined(STM32_FDCANCLK) +ASSERT_CLOCK(STM32_FDCANCLK); +#endif + extern const AP_HAL::HAL& hal; extern "C" { From 4b4d2c52c850a3ebf7a1baeb70e01e20a7408821 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 15 Jan 2023 15:22:03 +0000 Subject: [PATCH 073/287] AP_HAL_ChibiOS: correct QSPI flash and GPIO speeds on SPRacingH7 and DevEBoxH7v2 --- .../hwdef/DevEBoxH7v2/hwdef-bl.dat | 14 +++++++------- .../AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat | 12 ++++++------ .../AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat | 16 +++++++++------- .../AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat | 12 ++++++------ 4 files changed, 28 insertions(+), 26 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef-bl.dat index 87c992d08e273d..7284b25fbc5293 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef-bl.dat @@ -29,15 +29,15 @@ PE8 UART7_TX UART7 NODMA define BOOTLOADER_DEBUG SD7 # QuadSPI Flash -PD11 QUADSPI_BK1_IO0 QUADSPI1 -PD12 QUADSPI_BK1_IO1 QUADSPI1 -PE2 QUADSPI_BK1_IO2 QUADSPI1 -PD13 QUADSPI_BK1_IO3 QUADSPI1 -PB6 QUADSPI_BK1_NCS QUADSPI1 -PB2 QUADSPI_CLK QUADSPI1 +PD11 QUADSPI_BK1_IO0 QUADSPI1 SPEED_HIGH +PD12 QUADSPI_BK1_IO1 QUADSPI1 SPEED_HIGH +PE2 QUADSPI_BK1_IO2 QUADSPI1 SPEED_HIGH +PD13 QUADSPI_BK1_IO3 QUADSPI1 SPEED_HIGH +PB6 QUADSPI_BK1_NCS QUADSPI1 SPEED_HIGH +PB2 QUADSPI_CLK QUADSPI1 SPEED_HIGH # IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay -QSPIDEV w25q QUADSPI1 MODE3 120*MHZ 23 2 +QSPIDEV w25q QUADSPI1 MODE3 100*MHZ 23 1 # USART1 PA10 USART1_RX USART1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat index 2a8bc1d34a807c..ebd3003de9afbd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat @@ -102,12 +102,12 @@ PC12 SDMMC1_CK SDMMC1 PD2 SDMMC1_CMD SDMMC1 # QuadSPI Flash -PD11 QUADSPI_BK1_IO0 QUADSPI1 -PD12 QUADSPI_BK1_IO1 QUADSPI1 -PE2 QUADSPI_BK1_IO2 QUADSPI1 -PD13 QUADSPI_BK1_IO3 QUADSPI1 -PB6 QUADSPI_BK1_NCS QUADSPI1 -PB2 QUADSPI_CLK QUADSPI1 +PD11 QUADSPI_BK1_IO0 QUADSPI1 SPEED_HIGH +PD12 QUADSPI_BK1_IO1 QUADSPI1 SPEED_HIGH +PE2 QUADSPI_BK1_IO2 QUADSPI1 SPEED_HIGH +PD13 QUADSPI_BK1_IO3 QUADSPI1 SPEED_HIGH +PB6 QUADSPI_BK1_NCS QUADSPI1 SPEED_HIGH +PB2 QUADSPI_CLK QUADSPI1 SPEED_HIGH # Motors PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) # M1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat index d1e7543e1a84ba..51200e048de844 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat @@ -10,6 +10,8 @@ APJ_BOARD_ID 1060 # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 +MCU_CLOCKRATE_MHZ 480 + # limited flash that can't be used FLASH_SIZE_KB 128 FLASH_RESERVE_START_KB 0 @@ -39,15 +41,15 @@ PE3 LED_BOOTLOADER OUTPUT LOW # Red LED define HAL_LED_ON 0 # QuadSPI Flash -PD11 QUADSPI_BK1_IO0 QUADSPI1 -PD12 QUADSPI_BK1_IO1 QUADSPI1 -PE2 QUADSPI_BK1_IO2 QUADSPI1 -PD13 QUADSPI_BK1_IO3 QUADSPI1 -PB10 QUADSPI_BK1_NCS QUADSPI1 -PB2 QUADSPI_CLK QUADSPI1 +PD11 QUADSPI_BK1_IO0 QUADSPI1 SPEED_HIGH +PD12 QUADSPI_BK1_IO1 QUADSPI1 SPEED_HIGH +PE2 QUADSPI_BK1_IO2 QUADSPI1 SPEED_HIGH +PD13 QUADSPI_BK1_IO3 QUADSPI1 SPEED_HIGH +PB10 QUADSPI_BK1_NCS QUADSPI1 SPEED_HIGH +PB2 QUADSPI_CLK QUADSPI1 SPEED_HIGH # IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay -QSPIDEV w25q-dtr QUADSPI1 MODE3 120*MHZ 24 2 +QSPIDEV w25q-dtr QUADSPI1 MODE3 100*MHZ 24 1 define HAL_USE_EMPTY_STORAGE 1 define HAL_STORAGE_SIZE 16384 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat index 13538e105fa552..43b6901a0706b3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat @@ -127,12 +127,12 @@ PC12 SDMMC1_CK SDMMC1 PD2 SDMMC1_CMD SDMMC1 # QuadSPI Flash -PD11 QUADSPI_BK1_IO0 QUADSPI1 -PD12 QUADSPI_BK1_IO1 QUADSPI1 -PE2 QUADSPI_BK1_IO2 QUADSPI1 -PD13 QUADSPI_BK1_IO3 QUADSPI1 -PB10 QUADSPI_BK1_NCS QUADSPI1 -PB2 QUADSPI_CLK QUADSPI1 +PD11 QUADSPI_BK1_IO0 QUADSPI1 SPEED_HIGH +PD12 QUADSPI_BK1_IO1 QUADSPI1 SPEED_HIGH +PE2 QUADSPI_BK1_IO2 QUADSPI1 SPEED_HIGH +PD13 QUADSPI_BK1_IO3 QUADSPI1 SPEED_HIGH +PB10 QUADSPI_BK1_NCS QUADSPI1 SPEED_HIGH +PB2 QUADSPI_CLK QUADSPI1 SPEED_HIGH # Motors PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) BIDIR # M1 From 73da2162d26d269ffad5153b83b9aa5737910c46 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Tue, 31 Jan 2023 22:40:00 +0000 Subject: [PATCH 074/287] AP_HAL_ChibiOS: QSPI prescaler is indexed from 1 --- libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h index 109d044b2d537e..82b4efa8ef20f5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h @@ -612,7 +612,7 @@ #if STM32_WSPI_USE_QUADSPI1 #define STM32_WSPI_QUADSPI1_MDMA_CHANNEL STM32_MDMA_CHANNEL_ID_ANY #define STM32_WSPI_QUADSPI1_MDMA_PRIORITY 1 -#define STM32_WSPI_QUADSPI1_PRESCALER_VALUE ((STM32_QSPICLK / HAL_QSPI1_CLK) - 1) +#define STM32_WSPI_QUADSPI1_PRESCALER_VALUE (STM32_QSPICLK / HAL_QSPI1_CLK) #endif /* From 5af45db4f2d70ca7fdf90ac5722ebc7146ff63a6 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 2 Feb 2023 08:58:31 +0000 Subject: [PATCH 075/287] bootloaders: update SPRacingH7 bootloader --- Tools/bootloaders/SPRacingH7_bl.bin | Bin 26464 -> 27056 bytes Tools/bootloaders/SPRacingH7_bl.hex | 3345 ++++++++++++++------------- 2 files changed, 1691 insertions(+), 1654 deletions(-) diff --git a/Tools/bootloaders/SPRacingH7_bl.bin b/Tools/bootloaders/SPRacingH7_bl.bin index 07d603851818fdbbb560c4d732e61f48167e83a2..842e1e3c4d6dc7f14ff4dc45f294ed6701f18ec4 100644 GIT binary patch delta 12353 zcmb6<4OkRMvfVSYyR(3>2r4Y7yR7IUsEc4kjbT}E_*o4oCQ+kt08IuHFPLA=&+RJa zVq)$EZNCKJE^18fG>JcGxQJ%OJH0!TyIer!1vI{pm}EurGYDpfpWS)YyO_Us@7_JM zrfa&Zs;jEItGjEq^B?%|dF(=3WV)e2e4`QZ=>X3Smn)$3LH&S3{|Kq=*XyMHc{tx-Cf2YHnG;Ia{e@k!j{x9Xf9{>M^>Hi%6pYwI- z5U+;`ZB9l!g1^$Hq9&BWHzVuO;|#|dvI^Y2{Fa&U)WdUTA-SMgte@P^$$wWg@)44* zjd6`Fj4RsaxV1S);lc;J#=?Z61ZSP&w&sQK?f_7{$Q1Vz8czNkxS4_2`J)!R(S-tjJKrkzu<7bYOnLU1SFh~)eH zyL(LR633Dp-lJ>e%(!MmH%3U_KrZXXxYqjF!z&bSFsspKsqT&5GNyo)!W&rm*#Tr3 zRaD&f#JZRQR(=fLXzR%N7AdB|BH=j}u>!CPz$(NM3sTo-G*w7XHZdk7TLaTA6=Ldo zHdWVJA*BZE#sxsq!xdtdr^JFxvv|Z;frgR=xlFt>u8Orrw109H$-IW)sR-3WpVvK% z6D2JZtMY-+L>YXIcNXCNSpL9|tVrJLE_E(0N)+NHoQ~w3ZZ3m3l-6>o1cuyxeVe=3 zc}Ze>47uzLcTAnbEpKtdP|3-D#-#ers0B`BKCh5J@LTXilC8flCS?CJ0-a>0e5L@) z&yps6f(zv_OAw6olrFjWsB_n0Q<7@tYew&TMY<&E2$CQ6A1aDjzqbjS4;DmMv0_M0 z$cy*&Bg_7v7k>|4yc6E27y0^_hS!~Zol$%ZIN4OT1zBRMb{Cb3$in}2cX6#yFMQCY z$-toQkZUNpq0X5gp;RP4TTLzKAB?PttVgNWFHwTeh9c|DbH=A$ZO5-JQY8Ky6AmqGT%H_$hkf;Vzwb>md3)FqxVIFv+D-ObaLiJ1^r&myrkeec-~de z>n)ZO^#y{yhtnhZ#30btK!@^XvNAlu_2tm99u%c%(bThYI2)b{@g!OG-S7**n^*9@ zm$vTtzV$b)RFMmQPC(X|TCk~DhGi{p9t^3sa$rk;0W7)~1~tO5hRB@-0^fuAJw0}2 zp<`hVl4}N$^{ZBmpxpt6#xS7sZkG_UH)Al;J5~5ZdCHBUgMhzX;cZ79x(*wNyK4~J z?DDBi+%3IcG%>-s8w8B2igVs0?h2}x-M8q_P4!)U^AD{uM}c{0a3d(`>dQMsm3uO% za(3U`L$lXBxh867Y3{F;nKfG-F5|g~0+=O(HZN+Xf$ITSM?YJH!I;HC8xIgcLr6K| zi~HQhw+hY*#|N(uAo)*&s&Ba;n@9A_L`eQ%AgVrhUQP$H7~WVYWWi)LWJJG-fNBH>(GFSCF9*M7$U%m}lz9f@sF{yPLp<`j-mAdT>WfbBew=V@UF6i)Y>h81ejSa zh*dhm4tvh^hl4-3?(jkCsvQ4xSU0y19PUA3>UY08sH<-kO7ryOVW+UY!@VJ@RsBvSti~)}H#^^9LjAab{Q@qu@DTd(VR06GL>?WcNJ{ z633@Tx1a7YF_v*Mi$=eBPvN3@ae3C}MMBtiB%24r>QwVm7?#_~*vJIUZ@tlPmXNuT zV-hk4sDKX-BH8PYs^27pZL7`O4~_)ak_RK>T?GoVe$)DoVcSxFWLk32v_A|{(@yt? zOiMUulv&QzH|F5fqOfi)yImq+oMG6wh=ZRfuhqOdZ^W=^`}%L1rXHZC>A|pXgNCIK z8`hh7;QiibnZ!byP<-tTP^x3V9kh7uL2dVQ+9_XB?FPUpfJ*%WR#tZ3 zKC(AzhRZduQTWo!S)$+IZn&fAggVy$t@k*rLMW;_KSOgqd++5 zMV3{=am3P3WlKTXyMnUI4@B1@`I-LuA5j^CRCffaUIQy#;LC2?6;l`=oO+K(!=jxkuAg_q) z4j&#HQ?RSMf-;N;Ccx+|&)YjMyYHR@ON8(qE*!~h{}|O*JlGcuo~q9gB-MZd8RTn& z*>zFjoAQK5zJO&kWWAjeMnHJkGGwSvh@aPkm}`js~4xSgUd?-ONUVYVY=| zKGR@g0V7`;8h_YxReq7i#q7TK-}+(ooO$a9|2?LJM(6lj)D1o0UphWVC%>io`~x}H zx7Zl@ogwN_)4*9F8M)AO9fmwc&T5A9L_Q^?3|Wnwpj(jA zV3kaHo~v1QM$T-eI3rJ1k+rua3k0txvtm;9&CMA2Q1eqq*T!7I&ZmHxaT?bHRMBdx zHMJ$HarFGr3+Pn8Whh0UrN(ql;j(gNhW!(ijC^b$vd{|c%SrvHo<1V`~&YX+PydRq2D&0^&nFG5+3 zBZO#y6O2N1gBxmf%9Mr_L0m(Z=;W95#5! znbGB`)fG-Dw_>Ywy5esVyDGdgcNI7Y%e@ANqTH>tHYQ<%EuC`E{;~Y|Njf5jVR|TyV~aIHB?oiT9b&l|s36kQ)NsVUJH%@(6vWRmwJR)vZ(rg7LP9{TA14?4no$6wf zPPw`?Nz4-tS;sIB>5EQvh37M(RkVVu>_Ga2$~Yc6*&V0Bxd)63LXH>KV`Ti^>QPvQo)zC_7{ZdU}n(B^>2 z_lv-1UNqqfoDZlLF`zo$ruyPlTxYqT1D?1I8tBIcJP!tt8RE9fw+*bIV@(-Cwlb;( zY@&qJrpgeZ?`fbj3=fvpiOt#~qll7>>oi5DyO@#1eJ?y@+(cIn^=AplLZ3pGqp|+* zx4rs}Qj!EdT;l(>S5wV7>+Zj}rf&Ejc_}^)JIJB%_{H_vBAjcq~6RzZJQ_UusHCU(1=q}^^Ly%zI5t3YnW;AgN2qDiXnW4PnN z(E54H#-wM!!RTexw*&f%Yohg^`v2htew+4XmT=Awy11D;l#Mn#rv(NK?jj$D8%4Rl?fI@<9V^Q3)y1&=I3c!>v3#ZOBvf|&n+#3DKQ}~H>S`2U~Jjnr3+;x zWj9*3N~G+%mvkm4!qEDYH|qZ`v2Y(^%g&HzCXSzuP<5qIa>xv06phk$-OvU4#=#p6 zESoBcM7yikg=}SqZ5{tpTlK@&*qgTI6V0U5oNWVKPb@-~;y(0HSRvX0$FhFClfLN- zxt=UUYyR4=E7Cd7bd9mlX%CKvu>1hPr;`x>09iL_ud4*SL~E%B;HsGam$e#Urqowy z)@7C(TViD%$2G&5dfjKbg616Ag!k%-WgAOzI~Id=ZcHzS*0HLuR1J;EXPU6KkOjb5 zMq7m87U0#xRvH#7oA|8OIoi=#ZL~_$lNDyt8rq%%K_#&3E`$TjEf;w+Wld2h$!<0S zd`i37pp9)S*N$wnk@u_#*g(FprsCryI%N!l5V5A1@LE!sk`TYrKU?@zvgHMQ%lucQ zIeFdQIAO97@RgFMQ!F@#>`56LKi!Xa&K5eQbf8KLQgwML%|!B1iZl9o1@0A|Vp+8f z!p>6FXd@Yu=i*YbZt_@cBQH)i;|$U;xfpPqItzb8=A_QRSID~5U~8%wA0-W`FS>9_ zZ1aP13?y5s@>Sm&59g$lBUe1t#bjU$`v?spQgEKyESx|MRDB!$44ft{kGSCt#te3! z)0Ol@l+eVP`8?J4x|$-;kym|h!C6Rq(KHsuyo~NKs_*6IEDs~)O3}GkWEzW|)Jc~1oC(kcEa;I!?X5Z!c&H;@HWrr{0b z=_#c+m9$QYA9a0@J6z?d0V~!{g>>u`#D_^XqE1O;Ol~q|YU-%R16n3rGOkPCxu*I{*3mAULg;oXf2ki(CGej>{MT&!VvbB=!tJO zAw+FyfRZb~=FsB0X`#F6ffQuYFD0{Yv0{l-+%joYRlmMRhu`Z#kx9Y?>47FYm{Ub| z-SRljBx7by!4HsmGcA$0e~z%rVU%#oQHS*$d2D8h>*HfF!iR8%+9a`$vXu$aPHCHC z@Z2(p^bXM=E}^mfr)}*&ZsQwyArub7o<m!ul0UaEEMfXfNJX3%;b z&XRZcJjCvoXQjBZ z8nK0kXk)2bEn<0`s`_jJO`#SNrVg0=mMS`-=?PtiOUhYTX(4$J{eg4Ftw!>6Kcub# zjFU|=Rt18dqjZq$Y5KM|+HHcTrrMUY31rYv1XG#TY(CS=bFmG>g#Q$$9z0INqJ~LI~-Vfj|O{bWVw4!MWSDVNkda1;5rRqD>_Dwq9u}@W z%f)9v?8AXRFAJxn-$<`IBHEWr&x_&We9KdwCL~B-foH=~vYNxp zRY7TC6UBHePY7T+BH-c@UWb|eXd)*}6?(m4Q@IXo3I+DfC#zt4P#R;MBZRQY#d4Ug zqYN_ec#{aCV5^9)j1{n0AjXyLi-U`gAIo3(a}%_}UWfMlQ;F92Nx}>Wzdioz-mqyQ zsS0clOHV2uYOvC%1;emQ{+mClC`Kq%46a=cZR=zK91g2Nv8%p6HMdrtkn)Ua@z&-v z5X*F=z{0CnlZ14Eg(EGc`DM`MwIC3#eile!z75|$oVhe^!0;IwwDnG5< z4hp^M_`D+;vI_>g-U#Qr=Fqs)bK)n;yKcV6pi8^GT`|Chw*pebiS{=nHUU0dwa4bc zDNo-9;p;5aLI@N8>{3t-kV5tt!=>*|KRxTUb+PGIp*BA>5$~@=sqHOT&hoFR+}+LT zHwi`aMx0|zSZ?&Aq!2IPx-hsO%W#~sHjgwWWwf_as1wf}Z z4>QW|`{lr2j=;vB$*vD?iW90l(}fhMErtALZ!0#z2RAgOOMy&71k_68%58;F{$t5g zr?%>na=?jxUm}^4oq}~_b#}(+Q_v@sejZA6wP$<;z}b7r!R$Mksrf`}e~1=O*vCN_ zEjTf1K1_xo)%Og10#to9D&4^<%FZaU=@yuePpA_tSHvq)E}Yx1h?dH`;noB9PM|^} z997|?mu|oce7}PbJbNg#)zrZ50m0XV7EzV$*BF+nJw|BPGA#&}sq*3^dA#lu<$~)l zT&~qgdGEr^rJp1=tFqUW6iQe9PBk={W|%T%Z>peyEcQ5QU1Db|mr>{FZ&iJRgPNZ8 zxt5}%H{9csoYv+#f$ibgtmYcw)gGR)HrEP!dw6zs^ETn4uoKi9qn=fe_ zt_Lo7aE-g~J$OkPe-WBS%Np%K>mr5Ae%>)(VQhV^&Ar7hLPr7c2TXj}Tq!LuQ6AOz z=Rs4F861!0MUd2bqs1od@aZFP` zF*@?hFF|_Qb|P*js#`y;ua!oLUqj8+CRCRq7-4$;intt;@I&PHj!C8mly)yC{HJ&P z3{z6FJYKWgE9N7U4d8Pakh=DSbdvZtHo^Gnj&uY{xKoi)^N(mSt!`rBgO!GnHrleJkhTAv6K>c+< z1J=IUPhQKlTAJuldnW^T1=QRQN^}BLHI57t?gfudcb_bUZ{&7>ue^sV5l=sK-vqjGv62zab<4zDDWSn}4d=L}xO`e)EWegZPcxl5 zrp*c-?pF5zHVLpV)pEd+0sB<705$=zkJU~s)0PC-N9rEH%z&L!%e9QFZ9JeKs1~Rk z2iRG)Q^T|+0(M&616TrJC)IMm;sI+?Er7)V_O{x|F>Rv(JEZObY!qN`sO5mg0QS0S z0c<2-yJ4fJaU3WfFwGL+ zGPbf_J9J?rOnc^-p)m}yFah5u1A6BfrN+j?bBB!&*0l{legf*W!8%CIff8^UvDe&( z`1yqt=j^`$ysD9150fc%d26n-MX9mZI+nENI3vxgO`w>`A)|6o%ygc7R5V5R^3ZhW z6>&NVcTOsKMa`(Z1OaHIiALKD*kXn*qKQ`FcOs1=_e*CK0~}!?bO9tv)hEU}_m+ji z*nB6N@dE%Y5j`vz)oW-(RB%7TxZ?mbsC^gc&!1Rh&>-@kQ)EOLLk41JCa_i_; z+bOC$52eybwbcm74B_uydK$NpsQJZAtV+cBCCmf&kt6f}f}bQC78FBv;k^aZn5dIS z2Nq1maCJ*AhFvok_(d8Fi?OylC+57uKNlzCsMAm;w*04J$hxG9YeU@|+4D-osgIRd z8w^P2Md_t^wsWs`M>2FDHj1Yet|qk4K)_Jx)*C0gqs9V%W)`0KJ9~y>OpB&_GmA4J z*eSTzG9!PVUG~Hb0IS{!}S~oBDd>b%Wu4%P@Rx%}s%GHp>7{J%r=PVGh*^M8= z*I|^}+ESbUq4ywsvUyiAplXM;nH4@#;`Ht#N4wooSK4c&-SEkKslvT@MnUe~-Fm(@ z?^q8Pb)!8lFFdbCEEUgs=`H|NeOFScG%^^ZX4UC#4VWtrwq0Y(G0L}Mc@sNa6jNo z5MLOW1~?nUoq?+i+r|a)d4c_aYl3)oU=85fAU-RQ3b@W}a)Ho{z_*xfJ$>?OFU z#Wc)>x+}ddD1GOV~SS;Rngw zJ11c$Sq-?2?7GuQIqrNIFD5JRaz?(|gq=&)Kon|55y(#7x+~2EH#JBtvqkiGIA}Q3 z!wtx!a~3)bjmssIk+;W7n~cvp*z>PCaQia2LIm%TKnpj1QBws5l69HbB%JBu zEpAIhQS$15?~;NoVMU!H+Ri>I2@gql`w{7bF2(}Eq>Gyo@bxO%;5JFGnEN339RL`+ z6n>#nbbd`-Zc90}lwK|1W0km7suuqyofhF^RhhGrE#F$1TOKZv+n4ZTXE^QG)vEJK zrvc}lh9|@hGm~p8fY@QSk%yN&lenQj3Icmgl0(K2%xjX)D?5hq9Z6(piD~rP&@=rN z(RjqO^jBHVLBH>^N~SNJp13v;@O=cwH{KrbJ$@Wq4-pW>F$JI;B8vqRjL@UP3~VBA z3h{vdSxB||eSv_XK?@<)02j+aFHLyDZJ2%!=tSS5&U_u>ivWmwsTF@q_Akx3B{UL# zU*7j4L5EliT7PU}z^acS{&QvnU>pW)cq`hz?6&w%>~`6O+V5+B&?KvNQ=f`VeV^D( zvWwicY-@bx@SJ?ViRulv-=sU8)Gv3E{$=B57CSGB%cO1GP}_o{+Y4!~rB3XClwo{X zai2YBXIYW+VmW&wI-{;~JJ3K%zt8=UQM8l7yAxcqASqI!8)}0OMrFpzk#ZI@*ow{Z za0zqgEQKdp*dZ>vZ${C@@)<=yL3yVe#WdjB#tzF`6#Q5KlBX0+EvzetUz1hDSKu2@ z;ENUb`uXUc70Xto6d3_7mebD(`+zP*Y{ zq8KqoV&y27OC4w(Q4~{|E3<4&SxhA>XR&cm2bz_rzVmQ+b=%=m2_>?Jk_YcWx(B(@ z!r%xOz$l+WG6VTm#Gxe!sTggk;YY#=_Hia0=SOPz%Q4~27j}3Z5ClrvXe|z~v z9@6rDSrTSI} z>qAjy$al|RNZVx|`c;QUo*|z$I6qZiiHCmUpl8Ef{t#6@-1xO-nwo>dcE8rFgOkb? zC~5ZN6DajiUV<_V%8#HN1Lb)rtx$g0uQxwY2*}_1!_3Q}gwHJI=}?~Tk1!|0ZG~oB zJdl;79sU{;M^VaT=Zf=pg%oWw)i35S$G9AxPx9YZMK zI|kQ)p=NB&0$m?rfY$-` z0~`RL9>(a0zYpRN{{;Y*-2@OHkN7qy8=(9YfXZ$K@Qgvz`40g3SHf?KT>t_bfVPqR zv23sFZTLcII*!nBD8IEMM8CU!TXmBbp>1Zw_gLWPfuMRTz=i}c3*OrR?*Lesg!n?J zYk;y5!r7-#cNt*g1jOe+{Y^>plEDmsbbwg^D*(!p5xG)6Me0aH{GS0ZeB}5V%6@<^ z09pY&03)ED%ISgfGC(|h5YYfc1Nh;+3!n`k8Qv+~O&3cX5YP}eAWA7$4&>eGNHE_q28{-*_8s7q>#eZ3Hr5VmA^ohs~%WQ%2rQekH2x8 zY+XGw;o2eEpQ_R){MGD4BIrv0j+4u)PcT_^r0(8vX=yN0*-%-+AvALsM=wz_{$>G@ S1fh4~=1A~;ab)P;RsRjz;kp3; delta 11881 zcmb_?3s@9Kws2MV4AVT+K@f)lrDq0YU@(AaM2!IkXdZ*&Gor>gJhJwf7aFtCJa#ac zUyYj$TJA<6*=s^}uP;?}o*~KR@5y z_EWs|LBxFn5WWI&vjH3cKc#_Z=fA4_vF_LZy3>#C|AL{vZR10C2J8R7@^IcE{PkU( z{wK!&zv`b_I6SWNCo2AT26*h>5VU+`fd7TR^WPb8gyx%qJK7ql`+qD`|JSvo1H7(5 z+#E2-74gTeGm&i6%)*+R+?E;e9}NF%fM@Ke`HDIoP$>O z(jr+Ev!$TljigdJyd?ae>R{aC=w3t}3K;RfJAGO zG~f06+^iHsiZpTBO%;gCY+jtdLb+O-s&=u`FZ2dz)lc8j^B`>v@y5rS@j{ma&EHVrVlfX$FuDZmD#y?LUt2M#aF@MeY5qcv;jCB$W@nRUEOtu@xH{3&X41?Ezka*|RX;-}-0& z8qEHb9GE@VP+!b8N7#{RcMN)mWD$J4ny42qbQ9Haa*Ay!z-ROK4i|8Dr>n0#t>8=z858P zZ4(5rfs7_O57yu1ebY@X3rY1})x@65w9gXg^KA#dPo08p6q5Hs#}&Ql9e+h-SXkKa zRvDHS-iH6O!kg|=DK@xJ2<}w{BdOi1GKALwf9aRr*4~scH##w|ZYY&dC>l`p#pZr} zR1G@+j>LtHTbkr60}lCxe|8`5MPuIRP&cqrC>v^dt&@(<`BVZj|E2@;U&>c%C_ms5 z%Z;l*j$(uXgo?!DsBWz!IqGOKUa;hC$ST|H*^!rYhT>2=$zdgs}&LL`0by~mB(XgmqT(M z{qu!P;Y_zSBm4l8I$@!*`kaT6^pa28fO^@zQTO|VkX3on{rJn%%b7d z!jN7Zg1uaCv-f5%NUZ(%DAnYw)w}Y}K*U?+3vbZn73OE%UJOj_!%Vde)Iu7)h-IXY zd}rKMrhs631mFPL-2|}$JSw0&XWy|yca+z3h~c00yKjki3V6W$fg`;rM7jOOAx%T4 zurM!}JY@^6zbw{Uvu?k7=)|oWXO@Q?T2qYT-^>r$G5U*uY2G^!@FL~*i-$%x;He?? zjEraf!~GE~#Pz|zLaYalahC84&h}oOF-a_nI6%MEQ7@< z^&-4j^I!Et&?Xx<5Vy zjyyD`;RPXN`>wowpmZetWk}l)QXkP1!djiZh^e)%?ZNELvsCrdWn})o^Do1OHR&$h z@SvM%e%-VUP~DvF59lWHkX~X{&OYs-dx}GPg4i7*0qq12Ye#+POL=eIoB5-Lb+fO3 zL^pC1)r~V4RP%#hH4hD|=DVgp-`vc^7NrTL*Y|_87Y1tlw)^m*pq{NklfI?)TsTPQ z_Fqj%3iZ$OY!mgmFXhZVCBh}}9b10b#SvdW)vq#wukWKf)1Cp9@V%QC6i@0P{gJ#>*VbFeG?rn+&|nNGF>|@V%5M#;aj)L6uw_|t0tW4 z>@DKdj&ttrFBBFC;jn?s1&TtU$&E}^hVZ@N5J*h@l$YJl>l1MOtiEMU;k%Gj+h2bd zmDW!+$4_YQ#>r=gL#elS$z*Ql?kD} zs!$}c{fg&VZ=XNrDxSyvltTxRlukB=8=N1?Tx*{2$TvvZFle5u5=KF^S~sX|h>6bs z(X4Krr7`SFaDAzh?rBjV*$LoU;*Bk2q%(tYM_kvWS7>C->U;m-9alVg@Q(U^E(aFl z=s~K63I52I)psEIpyEmL=G@ql#z^}HsXiwTd?X~maG&+hxmqJ!y-EZ6t5<_|>WOXa z6A=}Iu*ti%u+Etl#1BHGJ5J7wU72?rus*PYJ^u%z>XwkXC_ZEkBYo#ft1*iiTWYP` zMMnC{XAxC-IOFYGD9d8MajqH;5GSDDIsis`u8mYj=<>bqBBZwIMYSzvOM|}F%3Rdu zG17^55no+E32BGS7R?-$U>133Ip#CBQp|NNGnQGJ9~c7*W_I*YRg%Rc5Zlu^I zN)|#4j8v`gLZ<7}3UVpRXn#^c=9`@;o)=`7L6|9ss~PD(6uM^DJ2OON>FwAHHGfvV zcO#V9GD-*+RDxazZ?1vb=atFLNrHWKKnF+KKnDn>=m)Ad3S`~*3JY6l6Wc4ciMf@Z zh_#iWj`m7Qmf2FfS|yB|6SHBloPn@ZuAJ`~NC&iYkfR*pEiMPI5GMuUi%qT*TS%YJ8_IBP>n^G-R1ueXlr zh!i;l}+2C5?K2w2iL5UUi0#T)}@7dTB~>@P_;^W#a|02 z_?GBq#q*qkdCpb4TEBs@EtIFg#J}?0a?=S+?pAWXkj*s{)WUdy-5xivkwu8{VL-M}`?lc&P4^L=h;vw~$+`2Oxj@n6HVs2C9-I^M2$;uKupxLO5$ zbQ{z#P8#&7^dSR;;72{%VHV60t&4UD%#~9bVNR5g&S^z}(DOXd(GxqR3$kHDP_f>Q zjQTa|;`VN4Y-wN6TKx;uEvP;R!I9DEL=9?bIP$~I;EkeD1Rbs>S$YdzL>__v`^l^N z#LXUKyF^|3pN38=6Rd6do2?(o<%|#)5RnnLJ=C0wW!&)Ff) zw9)t?XbrupcwQY+3%XWXe|4ynDDmTT=iG30U;!eqjRECU7tj%pmy>%EGMTa=A||9c z!BZSGL@#$N!@90qF-EjBtBp+ct^(6~wFP%FCR26bQh^MrUJleB26jxZQCA#{lrqqx zQFSqe0e^YwM5gO1%mo&$1Z0xD3R{d!r@MnpTG!_=GMa}LXj|CzU;~!%om$&2Yb1%8 z6pYW2gh?6mC`DI1C>X9h;}C;u9Wh32%O!hfH{!?kmE;9=?!d9-7s{EwZ0oXeSonBt z?%2NUCt}M#6+bU8E5{u#iS_06;*Oxf^FKgHA$umpVu83OZPc)E+hNPwNkL*95ffwc zM_8+1+RL&2{J%5pad18iOxtx$3voGvoJq9gY#UJZMj~V??L%uriqK9ZmGlSO=u>c! zsy7qSnh*Ll#Twh`?(rsS)u?R{CMqT%J~|O`BAH=sboPPLXf2&O-1G`Qd`vA&7yBFr z&D4tMj!22ay0#j_-!+A8ITDW>HKh{IQal^mX`nEnCh)ur{&R%=0qu5qxJU)Cx??Px|aTzfWFW12ltVREq?5T z8@Bb$q%Vn|wt1-0VaaPOHw%s8@|Z@u>@j15Vq% zc*jqdPVxT&oVGOu=%!HoKZ)U)f6u~HgE!cwy1mm%B`876&NJPpva~PzNk+Qn zRUN5zO@+Dao{TtG3gSXUo}9ZUg)!9A=2gs`#NigB}GUktebO@VO9Sj`yBM)0_^=^x8mm5n9Nz&9f&1AU= z_M3^M6mUkahx(i3si_M?s$fkX1h7|g%~m}csaG_U^? zzs$SFh9D&e1=i9p)!nPEc;?G@ONp^S{4ZpLfL^y!J? zp6L(n)!>hN(P*O(FFx9u4HJ5XJURVo*zbF$PsSpN&NPh^eBei@U|`R`1zmB5SwWwf3^%b`JDN!vXUg zGO3e;E_`{7kwVpKcI;@YBf?JII=5W$d_EkCIhWNzM4UnF9o=Y3gngO)9}ukkV>s^& za^a_gsBO^>ZkSr7ALF9gEVi)}jUuL?G$ zlw-lPj(SXH_MitYHvU0XaJh+b)PZm8vhHj{Jch7InQB|O5|hX~^x`7B(TS2ocTk@j^jvzE(s3<{=L<#G?7GH5FudBvxzHkrlULeKbtAM9R9h?JS;zvpUHhm@ zni8vMa+Hby8U~(t z&~CA>wvV&di!1D7W9t1beY3pU^_D(H{LXKCnJqCTm5yE3Q5_q_5w}Lh_n}8f9?&}> z27FykXJQnP!74{)5$iJhdv>;y`V^Lqy6VM^V!~=ljHN#gRXTEF>cy9=-&{PPo1o`c z2T$JBhI>O8O0CU<)Rl{B4-Snvx)PKK2aKSH9aw4@GOgY(zNdf5I_^S5UY8tJW2)%# z$C#{T_DaVO_G4BIm%8VMHiO}r9j6KcYy6eF+|g_e?uf{X(ZfM4C&ZG{c1jnLhNZ_` z@VpV$mu$U1%kUs12JVA|i5AN0mii-VffFJHybnq5%XsgQXCLXlf5!L#Pqq-wJ|piQ z;PjhGW@OF6tH@JXmiYk+Z80`r$WUqf@h-+Ns#x)a_K$*IDZ{-2?|cHZnnIuFwsOOL zhxaJC$9)8R@jO5#>CKvM)8-+bN>>Lp^#H#Es0K6Qz>tPK0|Or(h0Sv+yFRp4Csezp z2uV=;SI8IMgls>&mqL@fWw`8zLG4xYWOmV*hT{qM+|#Ks=D=ZM$g_)llAVNW$*t^+ zsOMn*l=~}CqHDczVE~(|$o)AFFpmr5H#uu*5n`R_zFj!b94 zlAl-NP3`t}F&EC*?RM6&Tr+rH@vH?ZWQW5$yk;7N#Mpi%5FLL5@fG4Dj~0xGsTK0C zGwkJ{6`e+jWh_E+9o#`kV@@A};MqJ+X@ zw`$_zZJ7|@*5~N-YJz{rkvzb8}3q;<@F+a6*8vWf|GVV9_F5~dPZIR74mXG;FA@KZEX+&fZ_5|l zD&aGC+%(>pAjPToxc3Nf@CVof%eqA%^?8%R&&e9E%8sWdI~L1faf)Xf>CB5uf422> z&uJB&U3&ez>ibUF73dJ?tTHGb8${5;T*dPqjiivD=_ZE!m`F-h-J+fQ!V$%j5AT1l zq#q#j^3A5{kj%lm890!mHXWq6c$(&F8S5vE^Aq-whWw=Ha4)=3Sc^=Q+Uvk3ksbcMWGV2w2cbCk`L(apD4VQf0_ z)Xf?@=c4r_aye|`WZLp+SW6yR9u4@5%PnTb$-0lT7H31Yg8fL&JJ0L%c`XG#TNae#FyCMTd1 z0sU0DqGq~c0sE8k24FFOy{}XN77dt7F#)Cn?6`78#dJjhc1(E#uyKGLQYrw80BoOP z0*pHFTVSr#nE_oPnzbvG|NHS zodu-amZe!Um}&dko=N`GmbhT2lHs@v!H$mfE5N~}FQG|h;rDj9ekhNKr)4d?nbTcxI;&OpgZ7%JN1CmzZs|SGy)c8tJ3XXxnJR9G*-pnZAfWCtu)=QcXoWl;>n* z2;lUsJ4z>RjjbI_)-O3^Te2fjHVavFbYI#jIs*<$xrNHChV2a zS4-wG=7-6>b3TNd_0XJBTtMc`O=bS%I`)gX$r#*ZU+D*NQV#UD(_>3ePfo-+ncL6~ z;MK%-eI{!&FOlu@#yexqzS%RH0sfrc-Y%k{*V780%pVw z-v^BhdDgcV@W7Ct`W%1sy6&o~_1V}lh$Nsx3j9=%nQ8sABuP%?jsmR70G+74x)&U<;O0IU$i8n1C{ z$Ux{#<8_ubZB+GaV=u$yD57~OtmCc%`mcC4c=7Zi<0;)zQEqUzm=LT*Fuj}zZkCD)B4Lo^7x{&cq_?SJPlWnrxzzc z`r>uKA&;}T0RCehcs6)7dTm}}qa2nziJv0{Wj5yeak8f@Wg@nft*(ZHJ_>`)!^T2ZnJr!hSF~(@ zd?$Y^i!#%T<4!9+w~T&I12;0-bmvBP?Z+D#IkMC^A=Q?BL#aL|U(w>+cK8Q(F)+Ew zh2S!VWb(t(7gb(4*hcD>@ljO}S?E?1hd7pg6Vx-{^AySC!(~%q%Y8o2CxcW=kUTsA z($UXmbW9;gipYiKX8b3DAIymgc$v?myK^3eX^`~~-XEPcFI&n&7gk+(f|rzRzE6Rd ze_8W*DU1B|!ELK#zqaAJ*h)E<+pv+!XSbb``*^FwFzryDlVc45Jl4P%;VFHo?UH?& zxLq~aRR(&(#(Mjb;!E@uML8tjto7ya(U4;YwCY7`U(H&*y@Y(cBF32yx9NGB!7fUt zcZ`)X8E+>xM8j31CTFRA*{Yo4OBFfA&_;Vr(c5PL{dRVk%L2V!FH)W}i)R+qS0LlE z%IL}&MVBgfS1zl{EY<^Ds(_x-UZAurAFbI=A_&<-Vh-UiyB zxC#O<1=>~v?lRIw@w?m5oi>|9AN-B!eq*aa^ZiR&2+Mj3zJ!5%Awmj9Tk5#6a7wIX zf^iC?LIo-{Hx#O1*ob(fy#iDi5pLxq&gZ##615c;k$YFh!^0PWhYJ70p8^lR@;@{O z9!~fl8UhdBu6!uS=Mhgr_hS2_PM;^$Umx(qLC>UNyNf?b-(XPh9Q1rTT&F)t)B5y? z_4-i2I>RAF8)V>GI0yl+4+I%BJlun!q}S_TLm3R^b|^!jd>P8|P;Q0N4CRXh!G>pw z0NFSYVt5eB=La-~DNt@02s0$`fgthZ3D}Wgz-Nb$G)5lu?Dh?L)|0rUe50Z{G2s{i;4*C8$mfbtC<58qq@o&e=7S^_Tv z;G+O0007_Q|B>+s$Jc=n1E|S_szxVdbvPb$`4E&pWFs_ahq8Kv7NIU4annrj-LM{U z;{aR$uNx5;4dn!YUmFnjGL*NV?4JlC0d4^J0Q$TLkw0GJFA4FKP?alKHV1104%0dn`j0Qmsv0J8y-0LB4efcXHFZbW^L zl{+4%&yK1`AEsqB++j~81wMeFH1Eyu(}VMzf7txc>{P@x0c4|WbR`$@5&(Fh|HlrO zx1gP(TKWg~Z(59uMmH^t8HDc#ZOsN=0NVj_fkszFmi?@lsj4Es|Jk1>6s3c_Q-K12 zj%Ef^qCh!il9yM-khfRGv-|h&Czn@EC%0FP39H+U>_A9=`^jYS9j5R#a$TI5asgH= h3o7TS5c+x;N57$D+(?0-39YX}9GUOXkrGGMe*+&D*aQFo diff --git a/Tools/bootloaders/SPRacingH7_bl.hex b/Tools/bootloaders/SPRacingH7_bl.hex index e7a1420986b59f..620282252b3fb4 100644 --- a/Tools/bootloaders/SPRacingH7_bl.hex +++ b/Tools/bootloaders/SPRacingH7_bl.hex @@ -1,1656 +1,1693 @@ :020000040800F2 -:1000000000060020B5050008F91900087519000858 -:10001000CD19000875190008A1190008B7050008D6 -:10002000B7050008B7050008B705000855460008E1 -:10003000B7050008B7050008B7050008B7050008B0 -:10004000B7050008B7050008B7050008B7050008A0 -:10005000B7050008B7050008B95C0008E55C0008B2 -:10006000115D00083D5D0008695D0008B7050008E6 -:10007000B7050008B7050008B7050008B705000870 -:10008000B7050008B7050008B7050008B705000860 -:10009000B7050008B7050008B7050008955D00081A -:1000A000B7050008B7050008B7050008B705000840 -:1000B000B7050008B7050008B7050008B705000830 -:1000C000B7050008B7050008B7050008B705000820 -:1000D000B7050008815E0008B7050008B7050008ED -:1000E000F95D0008B7050008B7050008B705000866 -:1000F000B7050008B7050008B7050008B7050008F0 -:10010000B7050008B7050008955E0008B7050008A8 -:10011000B7050008B7050008B7050008B7050008CF -:10012000B7050008B7050008B7050008B7050008BF -:10013000B7050008B7050008B7050008B7050008AF -:10014000B7050008B7050008B7050008B70500089F -:10015000B7050008B7050008B7050008B70500088F -:10016000B7050008B7050008B7050008B70500087F -:10017000B705000875530008B7050008B705000863 -:10018000B7050008B7050008B7050008B70500085F -:10019000B7050008B7050008B7050008B70500084F -:1001A000B7050008B7050008B7050008B70500083F -:1001B0006D5E0008B7050008B7050008B705000820 -:1001C000B7050008B7050008B7050008B70500081F -:1001D000B705000861530008B7050008B705000817 -:1001E000B7050008B7050008B7050008B7050008FF -:1001F000B7050008B7050008B7050008B7050008EF -:10020000B7050008B7050008B7050008B7050008DE -:10021000B7050008B7050008B7050008B7050008CE -:10022000B7050008B7050008E5470008B70500084E -:10023000B7050008B7050008B7050008B7050008AE -:10024000B7050008B7050008B7050008B70500089E -:10025000B7050008B7050008B7050008B70500088E -:10026000B7050008B7050008B7050008B70500087E -:10027000B7050008B7050008B7050008B70500086E -:10028000B7050008B7050008B7050008B70500085E -:10029000B7050008B7050008B7050008B70500084E -:1002A0009D0700084D1900085D24000800000000AB -:1002B00053B94AB9002908BF00281CBF4FF0FF31CD -:1002C0004FF0FF3000F074B9ADF1080C6DE904CEC9 -:1002D00000F006F8DDF804E0DDE9022304B0704721 -:1002E0002DE9F047089D04468E46002B4DD18A42E9 -:1002F000944669D9B2FA82F252B101FA02F3C2F11C -:10030000200120FA01F10CFA02FC41EA030E9440AC -:100310004FEA1C48210CBEFBF8F61FFA8CF708FBCD -:1003200016E341EA034306FB07F199420AD91CEBA5 -:10033000030306F1FF3080F01F81994240F21C81D7 -:10034000023E63445B1AA4B2B3FBF8F008FB10331F -:1003500044EA034400FB07F7A7420AD91CEB040454 -:1003600000F1FF3380F00A81A74240F20781644424 -:10037000023840EA0640E41B00261DB1D4400023A9 -:10038000C5E900433146BDE8F0878B4209D9002D0D -:1003900000F0EF800026C5E9000130463146BDE897 -:1003A000F087B3FA83F6002E4AD18B4202D3824201 -:1003B00000F2F980841A61EB030301209E46002DB0 -:1003C000E0D0C5E9004EDDE702B9FFDEB2FA82F205 -:1003D000002A40F09280A1EB0C014FEA1C471FFA63 -:1003E0008CFE0126200CB1FBF7F307FB131140EA4A -:1003F00001410EFB03F0884208D91CEB010103F117 -:10040000FF3802D2884200F2CB804346091AA4B2D8 -:10041000B1FBF7F007FB101144EA01440EFB00FEAC -:10042000A64508D91CEB040400F1FF3102D2A64511 -:1004300000F2BB800846A4EB0E0440EA03409CE7B0 -:10044000C6F12007B34022FA07FC4CEA030C20FA5D -:1004500007F401FA06F31C43F9404FEA1C4900FA7D -:1004600006F3B1FBF9F8200C1FFA8CFE09FB1811FA -:1004700040EA014108FB0EF0884202FA06F20BD96D -:100480001CEB010108F1FF3A80F08880884240F2BD -:100490008580A8F102086144091AA4B2B1FBF9F001 -:1004A00009FB101144EA014100FB0EFE8E4508D9FC -:1004B0001CEB010100F1FF346CD28E456AD9023881 -:1004C000614440EA0840A0FB0294A1EB0E01A14266 -:1004D000C846A64656D353D05DB1B3EB080261EBD4 -:1004E0000E0101FA07F722FA06F3F1401F43C5E9AE -:1004F000007100263146BDE8F087C2F12003D840E4 -:100500000CFA02FC21FA03F3914001434FEA1C4725 -:100510001FFA8CFEB3FBF7F007FB10360B0C43EA17 -:10052000064300FB0EF69E4204FA02F408D91CEBC7 -:10053000030300F1FF382FD29E422DD902386344C5 -:100540009B1B89B2B3FBF7F607FB163341EA034165 -:1005500006FB0EF38B4208D91CEB010106F1FF38B4 -:1005600016D28B4214D9023E6144C91A46EA0046AB -:1005700038E72E46284605E70646E3E61846F8E63D -:100580004B45A9D2B9EB020864EB0C0E0138A3E786 -:100590004646EAE7204694E74046D1E7D0467BE767 -:1005A000023B614432E7304609E76444023842E7DF -:1005B000704700BF02E000F000F8FEE772B63A486C -:1005C00080F30888394880F3098839484EF6085185 -:1005D000CEF20001086040F20000CCF200004EF6BE -:1005E0003471CEF200010860BFF34F8FBFF36F8FFD -:1005F00040F20000C0F2F0004EF68851CEF2000149 -:100600000860BFF34F8FBFF36F8F4FF00000E1EE34 -:10061000100A4EF63C71CEF200010860062080F30D -:100620001488BFF36F8F04F0D3F804F075F805F069 -:1006300011F94FF055301F491B4A91423CBF41F818 -:10064000040BFAE71C49194A91423CBF41F8040BDC -:10065000FAE71A491A4A1B4B9A423EBF51F8040B5B -:1006600042F8040BF8E700201749184A91423CBFB2 -:1006700041F8040BFAE704F08DF805F055F9144C35 -:10068000144DAC4203DA54F8041B8847F9E700F034 -:100690004FF8114C114DAC4203DA54F8041B884753 -:1006A000F9E704F075B800000006002000220020E1 -:1006B000000000080000002000060020A0660008DE -:1006C00000220020C0220020C0220020D0490020AB -:1006D000A0020008AC020008AC020008AC0200084E -:1006E0002DE9F04F2DED108AC1F80CD0D0F80CD0C8 -:1006F000BDEC108ABDE8F08F002383F311882846F3 -:10070000A047002003F0ECF9FEE703F01BF900DF3F -:10071000FEE70000054B10B504460360806810B189 -:1007200003685B689847204610BD00BF84620008DC -:1007300038B503F0B5FE054603F082FF0446F0B974 -:10074000144B9D421DD001339D4241F2883512BFAA -:10075000044600250124002003F0ACFE0CB100F09B -:100760007FF80D4C00F000FF00F09CFD204601F0EA -:10077000B1FC40B94FF47A7003F0B8F9F6E7002500 -:10078000E9E70546E7E7284600F02AF900F068F8AF -:10079000F9E700BF010007B0C02200200448054B64 -:1007A000054A036000230549836005F0CDBB00BF07 -:1007B000C022002084620008D02400201507000811 -:1007C00008B500F03BFDA0F120035842584108BD98 -:1007D00007B5042101900DEB010000F04DFD03B0C1 -:1007E0005DF804FB07B541F21203022101A8ADF840 -:1007F000043000F041FD03B05DF804FB202310B588 -:1008000083F311881248C3680BB103F007FA002381 -:10081000104A4FF47A710E4803F0C4F9002383F3B1 -:1008200011880D4C236813B12368013B2360636872 -:1008300013B16368013B6360084B1B7833B963688D -:1008400023B9022000F0FAFD3223636010BD00BF1F -:1008500050230020FD0700086C24002064230020A2 -:10086000F7B5574801A901F0ADFD002800F0A580BB -:10087000544B554A1C461968013100F09B800433E3 -:100880009342F8D16268514B9A4240F29380504BA8 -:10089000DB6803F1104303F580139A4280F08A80ED -:1008A000002000F019FD02204A4B187000F0BEFD38 -:1008B000494B0021D3F8E820C3F8E810D3F8102101 -:1008C000C3F81011D3F81021D3F8EC20C3F8EC10C2 -:1008D000D3F81421C3F81411D3F81421D3F8F0205D -:1008E000C3F8F010D3F81821C3F81811D3F8182161 -:1008F000D3F8802042F00062C3F88020D3F8802033 -:1009000022F00062C3F88020D3F88020D3F8802042 -:1009100042F00072C3F88020D3F8802022F00072E9 -:10092000C3F88020D3F8803072B64FF0E023C3F8CC -:10093000084DD4E90004BFF34F8FBFF36F8F274AF0 -:10094000C2F88410BFF34F8F536923F4803353618F -:10095000BFF34F8FD2F8803043F6E076C3F3C9057A -:10096000C3F34E335B0103EA060C29464CEA817758 -:100970000139C2F87472F9D2203B13F1200FF2D181 -:10098000BFF34F8FBFF36F8FBFF34F8FBFF36F8FE7 -:10099000536923F4003353610023C2F85032BFF38C -:1009A0004F8FBFF36F8F202383F31188854680F329 -:1009B00008882047024801F065F803B0F0BD00BF89 -:1009C000C02200200000109020001090FFFF0F9028 -:1009D00000220020642300200044025800ED00E0C3 -:1009E0002DE9F04FA84B9FB02022FF21089016A8B8 -:1009F0009E68DB68079300F061FDA44A1378A3B9F1 -:100A00000121A3481170C360202383F31188C368B8 -:100A10000BB103F003F900239E4A4FF47A719C480E -:100A200003F0C0F8002383F31188089B9A4A03B1AE -:100A3000136000239949089D98469B46984F0B7078 -:100A40005360CDE90533012000F0F0FC25B1924B55 -:100A50001B68002B00F07D83002000F0EFFB0E9060 -:100A60000E9B002BF2DB012000F0D6FC0E9B213BFD -:100A7000162BE8D801A252F823F000BFD90A0008CB -:100A8000010B00089B0B0008470A0008470A0008F2 -:100A9000470A0008910E0008951000082B0F000867 -:100AA00013100008391000085F100008470A0008FA -:100AB00071100008470A0008DD100008790B0008D3 -:100AC000470A0008591100083D0C0008770D00087E -:100AD000470A0008890F00080220FFF771FE00286E -:100AE00040F06383089B0221069A11A8002A08BFE0 -:100AF0001D4641F21233ADF8443000F0BDFBA2E7D1 -:100B00004FF47A7000F09AFB041EEBDB0220FFF733 -:100B100057FE0028E6D0013C052C00F24883DFE8B0 -:100B200004F0030A0D1013390523042111A81193B1 -:100B300000F0A2FB17E004215348F9E704215948CB -:100B4000F6E704215848F3E74FF01C09484609F13D -:100B5000040900F0C3FB0421119011A800F08CFBE4 -:100B6000B9F12C0FF2D10120059B4FF0000B00FAD8 -:100B700004F41C43E3B2059300F0ECFCB8F1000F61 -:100B800005D0059B03F00B030B2B08BF0025FFF7D7 -:100B900029FE58E704214548CAE7B8F1000FA1D063 -:100BA000059B03F00B030B2B9CD10220FFF708FEE3 -:100BB0000446002896D00120DFF8E08000F08CFB8E -:100BC0004FF00009022088F8000000F02FFC5FFAC7 -:100BD00089FA504600F090FB054690B1504609F165 -:100BE000010900F099FB0028F1D10546069441F275 -:100BF0001213022111A8A046ADF8443000F03CFBCE -:100C000021E701232E46DFF88090022088F800308B -:100C100000F002FCD9F80830B34207D9304600F0A2 -:100C20005DFB013040F0C6820436F3E700261A4B24 -:100C3000069488F80060A0465E609DE7B8F1000F5A -:100C40003FF450AF059B03F00B030B2B7FF44AAF2F -:100C500064210FA800F006FB814600287FF442AF14 -:100C60000220FFF7ADFD044600283FF43BAF3A6A8F -:100C70007B6A0F9953438DF837908B421AD20C48F8 -:100C800000F0E6FB2EE700BF0022002068240020D1 -:100C900050230020FD0700086C240020642300205E -:100CA000C022002004220020082200200C22002064 -:100CB0008C6000084FF4801AAE48C846BAFBF2FABE -:100CC00000F0C6FBFFF78EFD01210DF1370000F0AB -:100CD000D3FA0F9B434542D9002310AA5146384608 -:100CE000CDE9103311AB00F0D1FE00283FF47FAF07 -:100CF00000F08AFE109B00EB030901210DF1370083 -:100D000000F0BAFA00F080FE484520D9384601F0DC -:100D1000F3F880B964210F9B97480AF1010A01FB9F -:100D200008F1B1FBF3F18DF83710C9B200F090FB78 -:100D30003B6A9844CDE700F067FE119B1844484594 -:100D40003FF655AF00F060FE109B00EB0309109BCF -:100D50004FF47A70A3FB000302F0C8FECDE76423D2 -:100D600001210DF13700A0468DF8373000F084FAEC -:100D70000023079300E7B8F1000F3FF4B3AE059BE3 -:100D800003F00B030B2B7FF4ADAE02207B4B1870EE -:100D900000F04CFB322000F051FAB0F1000AFFF6EF -:100DA000A1AE079BD14653440993754B099ADB6862 -:100DB0009A423FF697AEBAF5807F3FF793AE714AFD -:100DC0000024A2450A920EDD4FF47A7000F036FA44 -:100DD0000E900E9B002BFFF685AE0E9B01340A9AF7 -:100DE00002F8013BEDE7C820FFF7EAFC04460028C3 -:100DF0003FF478AE079B1F2B11D8C3F1200223F0DC -:100E0000030016AB5F495245184428BF52460A9268 -:100E100000F022FB0A9AFF215A4800F04FFB002302 -:100E20009846CDE91033079B03F580130B93B9F176 -:100E3000000F02D1A046099B9BE711AB514A0B99C9 -:100E40003846029310AB4244414401930FAB0093E8 -:100E50004B4601F023FA00283FF4C9AE00F0D6FD5E -:100E60000F9B82460A919844A9EB030900F0CEFD3E -:100E7000109B0A9A13EB0A0342F10002834272EBC1 -:100E80000103F3D2384601F037F80028EED1CEE75F -:100E9000B8F1000F3FF426AE059B03F00B030B2BBC -:100EA0007FF420AE0220354B187000F0BFFA3220DC -:100EB00000F0C4F9B0F1000AFFF614AE1AF0030412 -:100EC0007FF410AE2E4A0AEB0603926893423FF677 -:100ED00009AEBAF5807F3FF705AEDFF8A890A245CE -:100EE0000DDD4FF47A7000F0A9F90E900E9B002BE7 -:100EF000FFF6F8AD0E9B013409F8013BEFE7C8207F -:100F0000FFF75EFC044600283FF4ECADCAF387020D -:100F10001C4930464FEAAA0900F0D8FA804600285A -:100F20003FF465AE06EB890626E60220FFF748FC93 -:100F300000283FF4D7AD00F00BFA00283FF4D2AD03 -:100F40004FF00009DFF838A04C46DAF808304B457E -:100F50000CD9484609F1040900F0C0F904221190A7 -:100F600011A9204601F0A0FA0446EEE72046FFF75B -:100F70002FFC01E6B1600008C9600008642300206E -:100F80000022002068230020642110A800F06AF9E4 -:100F9000044600287FF4A6AD0220FFF711FC0028CC -:100FA0003FF4A0AD109BA14603F0030A1099A1EBFA -:100FB0000A01A1421BD91F2C11D8169B01330ED058 -:100FC00024F003031EAA134453F8203C119348460F -:100FD000042211A9043401F067FA8146E6E70423EC -:100FE00011AA04F58011384601F0A4F9EFE7BAF12F -:100FF000000F0CD0534611AA01F58011384601F0BC -:1010000099F94846524611A901F04EFA81464846E0 -:10101000ADE70023642111A8119300F023F9002803 -:101020007FF460AD0220FFF7CBFB00283FF45AAD00 -:10103000119800F083F99AE70023642111A8119315 -:1010400000F010F900287FF44DAD0220FFF7B8FB47 -:1010500000283FF447AD119800F072F987E70220AD -:10106000FFF7AEFB00283FF43DAD00F081F97EE7CD -:101070000220FFF7A5FB00283FF434AD11A914208E -:1010800000F07CF90990FFF7A3FB099911A800F083 -:10109000F3F871E5322000F0D1F8041EFFF622AD1E -:1010A000A3077FF41FAD444A04EB0B0392689342FD -:1010B0003FF618AD0220FFF783FB00283FF412AD86 -:1010C00024F003045C44A3453FF456AD58460BF1AD -:1010D000040B00F003F9FFF77BFBF4E74FF47A70A1 -:1010E000FFF76EFB00283FF4FDAC00F031F980B152 -:1010F000169B013328D011AB16AA4FF48011384645 -:10110000029310AB01930FAB0093202301F0C6F8BC -:1011100008B944466BE500F079FC284E04460D46BC -:1011200000F074FC109B1B1945F10002834272EB26 -:101130000103F5D2304600F0DFFE0028F0D1202276 -:10114000FF2116A800F0BAF9FFF74CFB1C4802F08B -:10115000CDFC1FB0BDE8F08FB8F1000F3FF4C2AC7A -:10116000059B03F00B030B2B7FF4BCAC0023642125 -:1011700011A8119300F076F8044600287FF4B2AC71 -:101180000220FFF71DFB814600283FF4ABACFFF7C0 -:1011900029FB41F2883002F0A9FC119800F01EFAF8 -:1011A000C846254600F0D6F94DE48046E4E44FF009 -:1011B000000B97E406941AE500220020C0220020CC -:1011C000A0860100F7B50C46184E4FF47A7105461B -:1011D00002FB01F396F90020501C0BD1144829465C -:1011E00001930268176A2246B8478442019B03D1E3 -:1011F000002310E0002AF1D096F90020511C01D004 -:10120000012A0DD10B4829460268166A2246B047CA -:10121000844205D10123084A0120137003B0F0BDB8 -:101220004FF4FA7002F062FC0020F7E71022002071 -:10123000382B0020FC240020B8240020002307B510 -:10124000024601210DF107008DF80730FFF7BAFFC4 -:1012500020B19DF8070003B05DF804FB4FF0FF30AC -:10126000F9E700000A46042108B5FFF7ABFF80F05C -:101270000100C0B2404208BD074B0A4630B419789D -:10128000064B53F82140014623682046DD69044B94 -:10129000AC4630BC604700BFB8240020F4600008B2 -:1012A000A086010070B50A4E00240A4D02F0ECFE43 -:1012B000308028683388834208D902F0E1FE2B6829 -:1012C00004440133B4F5003F2B60F2D370BD00BF7E -:1012D000BA2400207424002002F07CBF00F10060DA -:1012E00000F500300068704700F10060920000F5E2 -:1012F000003002F0FBBE0000054B1A68054B1B884E -:101300009B1A834202D9104402F0BABE00207047F3 -:1013100074240020BA24002038B5074D04462868FC -:10132000204402F0B3FE28B928682044BDE83840C4 -:1013300002F0B2BE38BD00BF742400200020704708 -:1013400000F1FF5000F58F10D0F800087047000042 -:10135000064991F8243033B100230822086A81F845 -:101360002430FFF7C1BF0120704700BF7824002060 -:10137000014B1868704700BF0010005C244BF0B5AB -:101380001A680446234BC2F30B06120C1F885868D8 -:10139000BE4293F9085028D09F89BE4206D1012051 -:1013A0000C2505FB0033586893F9085041F20103FE -:1013B0009A421CD041F203039A421AD042F201032E -:1013C0009A4218D042F203039A4208BF5625621E81 -:1013D0000B46441E0A4493420FD214F9016F581C65 -:1013E0006EB1034600F8016CF5E70020D8E75A25F6 -:1013F000EDE75925EBE75825E9E7184605E02C24E9 -:1014000082421C7001D9981C5D70401AF0BD00BF6B -:101410000010005C14220020022803D1024B4FF47C -:1014200000229A61704700BF00100258022802D1C2 -:10143000014B08229A61704700100258022804D11B -:10144000024A536983F00803536170470010025841 -:101450000FB404B070470000002310B5934203D0CE -:10146000CC5CC4540133F9E710BD0000013810B55D -:1014700010F9013F3BB191F900409C4203D11AB1F0 -:101480000131013AF4E71AB191F90020981A10BD20 -:101490001046FCE70138013910F9013F11F9012F1D -:1014A0000BB19342F8D0981A7047000003460246E9 -:1014B000D01A12F9011B0029FAD1704702440346E1 -:1014C000934202D003F8011BFAE770472DE9F84375 -:1014D0001F4D14460746884695F8242052BBDFF876 -:1014E00070909CB395F824302BB92022FF214846F8 -:1014F0002F62FFF7E3FF95F824004146C0F1080290 -:1015000005EB8000A24228BF2246D6B29200FFF728 -:10151000A3FF95F82430A41B17441E449044E4B262 -:10152000F6B2082E85F82460DBD1FFF711FF002802 -:10153000D7D108E02B6A03EB82038342CFD0FFF7B9 -:1015400007FF0028CBD10020BDE8F8830120FBE78E -:1015500078240020024B1A78024B1A70704700BFA3 -:10156000B82400201022002038B5164C164D204615 -:1015700001F018FC2946204601F040FC2D68134874 -:10158000D5F89020D2F8043843F00203C2F80438AA -:1015900002F0ACFA0E49284601F03EFDD5F8902045 -:1015A0000C48D2F804380C49A04223F00203C2F8D8 -:1015B00004384FF4E1330B6003D0BDE8384001F04C -:1015C0004FBB38BD382B0020F863000840420F00A5 -:1015D00000640008FC240020A024002038B50B4B38 -:1015E00004461A780A4B53F822500A4B9D420CD0FD -:1015F000094B002118221846FFF760FF04600146DE -:101600002846BDE8384001F02BBB38BDB824002087 -:10161000F4600008382B0020A024002038B5084BC7 -:1016200004461546017543600A21243002F076FF16 -:1016300004F128002A460A2102F070FF204638BD36 -:10164000CC620008F8B51E461B6805460C461746D6 -:101650001BB9236863B9012408E0BDF8182031469E -:10166000806A02F073FF0028F3D100242046F8BD01 -:1016700021463A46686A02F09FFF04460028EAD1F4 -:101680003368002BF1D0A86A02F0CAFFEEE7000031 -:1016900038B50D46114604461A4611B1806A02F06B -:1016A0007DFF2DB12946606ABDE8384002F0B0BF29 -:1016B00038BD0000704700007047000000207047F0 -:1016C000002070470020704713B56C4600F10C03F2 -:1016D00084E8060094E8030083E8050002B010BD2A -:1016E0000023C0E90333704782B002AB03E9060070 -:1016F00002B070477047000000207047704700003C -:1017000000207047002070470120704782B0002001 -:1017100002A901E90C0002B07047000000207047E8 -:10172000002070470B6803634B68C3628B68436398 -:10173000CB6883630B69C3637047000038B5836A65 -:101740000446154D1B7955F8330001F061FFD4E9CB -:1017500009231B7955F8331002F130034968994287 -:1017600018D000231363626A5363D4E90912537CCF -:10177000581E137C92681B0443EA002313438B63B7 -:10178000D4E909131B79303155F83300BDE83840EE -:1017900001F0D2BE38BD00BF58610008F8B51A4F3D -:1017A00005460E4611463868FFF774FE40BB746864 -:1017B0003B792CB194F82C209A420FD02468F8E79A -:1017C000402004F0CBFB0122B5210446FFF726FFA1 -:1017D000736823603B79746084F82C30402004F0F7 -:1017E000BDFB002328600371C0E90333037A43F093 -:1017F00007030372054BC0E9094703602846F8BD9B -:1018000000232B60FAE700BFBC24002068610008B9 -:10181000044B10B504460360C06908B104F09CFB9A -:10182000204610BD1061000810B50446FFF7F0FF18 -:10183000204604F08FFB204610BD000008B519B10A -:10184000FFF77CFF012008BD836A1A79024B53F829 -:10185000320001F0E1FEF5E7586100082DE9FF4193 -:10186000DDF828800546174603911FFA88F6029393 -:10187000FFF764FF02ABBAB203A9686A0096FFF7EC -:10188000E1FE044638B900212846FFF7D7FF20467D -:1018900004B0BDE8F081AFB9AB6A05F12C011A794B -:1018A000134B53F83200B8F1000F19D101F052FE7A -:1018B00080F00104E4B23346686ADDE90221FFF7F3 -:1018C000E7FEE0E7029B83B9AB6A3A46084805F1B8 -:1018D0002C011C79039B50F8340001F051FEE7E71E -:1018E000029B424601F062FEE2E70024E3E700BF0C -:1018F0005861000813B504460191FFF71FFF019AD4 -:10190000A36A04F12C011879054B53F8300001F05B -:1019100063FE00212046FFF791FF012002B010BDB9 -:101920005861000810B50446FFF708FFA36A1A794A -:10193000054B53F8320001F05DFE00212046FFF711 -:101940007DFF012010BD00BF58610008064B01213A -:10195000064A1A6000221A71054AC3E902124FF4BE -:1019600006721A82704700BFBC240020FC60000889 -:10197000000E270700B59BB0EFF309816822684687 -:10198000FFF76AFDEFF30583044B9A6BDA6A9A6AF4 -:101990009A6A9A6A9A6A9A6A9B6AFEE700ED00E080 -:1019A00000B59BB0EFF3098168226846FFF754FD4C -:1019B000EFF30583044B9A6B9A6A9A6A9A6A9A6A59 -:1019C0009A6A9B6AFEE700BF00ED00E000B59BB09D -:1019D000EFF3098168226846FFF73EFDEFF30583C8 -:1019E000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7EA -:1019F00000ED00E0FEE70000FEE700000FB408B5D0 -:101A0000029802F003F8FEE702F0EABC02F0C2BC62 -:101A100080697047C0697047006A7047406A7047C4 -:101A2000806A7047F0B5ADF2044D0E4605460021C0 -:101A30004FF47F7201A80091FFF740FD2C6A7443B8 -:101A400001362B6A7343A34216D92B686A46214696 -:101A500028465F684FF48063B84770B16A464FF418 -:101A6000806312F8011BFF290AD1013B9BB2002BB6 -:101A7000F7D104F58064E4E701200DF2044DF0BDD8 -:101A80000020FAE780680368DB69184730B5456ACB -:101A900085B004468D420FD30568CDE90023026A64 -:101AA00003ABAD6A5143A84720B1206A039BC31A18 -:101AB0005842584105B030BD0020FBE7F0B5C5697C -:101AC00087B004468D4212D30C9F86690568714326 -:101AD000CDE9013705AB00936D69036AA84720B1D2 -:101AE000A069059BC31A5842584107B0F0BD0020B9 -:101AF000FBE70000F0B5662389B0002405464FF4EB -:101B000080768068079403A9CDE90336CDE90544C2 -:101B100003685B699847A8682246214603680094D9 -:101B20001F692346B847A8689923079403A9CDE9FC -:101B30000336CDE9054403685B699847A8682246E7 -:101B40002146036800941D692346A84709B0F0BDEB -:101B5000254B2DE9F04F1B789FB0002504468DF8EA -:101B600028304FF09F0E80684FF00123ADF82950C8 -:101B700005A90995CDE905E3CDE9075503685B693A -:101B80009847A06803222946036800922A461E69E6 -:101B90000AABB04728B394F88C20144B9DF828105A -:101BA00003EBC2031A7991421BD19DF829205B797E -:101BB0009A4216D1A0684FF05A0C0D4B082605A981 -:101BC0000996CDE905C3CDE9075503685B699847D8 -:101BD000A0682A462946036800961F690AABB847E1 -:101BE00040B9002048E100BF74600008646200084A -:101BF000002500010422B1490AA804F0DFF90546D6 -:101C00000028EED1BDF82C306FF48277A3813B44DD -:101C1000012BE6D8079605A9CDE90A00A06803685C -:101C20005B699847A0682A462946036800961E69A2 -:101C30000AABB0470028D4D0DDE90A361A0202F414 -:101C4000706242EA1662FF2ACBD11B0E26F07F4655 -:101C500050222946142B26610AA828BF1423A373F7 -:101C6000FFF72CFCA068079605A903685B699847F5 -:101C7000A068A37B294602689B0000930AAB166903 -:101C80002A46B0470028ACD00B990029A9DBC90827 -:101C90006FF07E43149D4FF0010E994228BF194604 -:101CA000C5F303130EFA03F221FA03F30391616102 -:101CB000A261E361002B94D02646A44600274FF092 -:101CC00002081EAAC7F3460302EB830353F834ACA1 -:101CD00007F001031B01DA1D0EFA03F908FA02F2FC -:101CE000A2EB090202EA0A02DA401AD003F108095B -:101CF0000F330EFA02F2216A08FA03F30EFA09FB17 -:101D0000CCF830208A42A3EB0B0B0BEA0A0A2AFA22 -:101D100009F98CF82C90A36A88BF2262934288BF8D -:101D2000A26201370CF1100C042FCAD1236A4FF0C4 -:101D3000020C039A4FF0010E139F9A4224BFB2FB8C -:101D4000F3F1616207F00F0138BF01234FF0090280 -:101D500001F1010138BF63624900336B33B3531C97 -:101D60000EFA02F8A2F105090CFA03F30EFA09FAC9 -:101D7000A3EB080302F1FF380CFA08F83B40A8EB8C -:101D80000A08D34008EA070828FA09F877D0012B97 -:101D900077D0022B77D0032B08BF4FF47A735FFA0A -:101DA00088F808FB033373634B43B3630732103681 -:101DB000252AD2D115F0C04FC5F3417365D0012B50 -:101DC00065D0022B0CBF4FF47A634FF47A43C5F30E -:101DD000046202FB0333E3664B432367199B9E07B0 -:101DE00058D0062384F8743015F4005F05F00F0313 -:101DF000C5F3042514BF40220822013305FB022548 -:101E00005B00A5675D430A9B9F02E5677FF5E9AE2E -:101E10000C9B1A0A84F88020C3F3421203F01F03BC -:101E200084F8882084F88130189BC3F3025213F49D -:101E3000401F84F883207FF4D4AEDE0602D5042A46 -:101E40007FF4CFAE03F40072002A14BF01220022F7 -:101E500084F8872004D0DD0324D5002384F889305A -:101E6000179B1A0722D5002384F88630702384F844 -:101E70008530012384F88D301FB0BDE8F08F012339 -:101E80008DE710238BE7802389E710239FE74FF42A -:101E900080739CE7590701D55023A3E713F0780F0F -:101EA000A2D09EE69903DBD50123D7E75B07E0D5F7 -:101EB000012384F886300523D9E700BFC4610008F8 -:101EC00030B58BB000240546806803924FF00122A4 -:101ED000059105A9CDE90624CDE9084402685269B7 -:101EE0009047A8680121039B02680091214615696B -:101EF0002246A8470BB030BD13B504460DF10702CA -:101F000090F88510FFF7DCFF94F886309DF8070005 -:101F10001BB100F0010002B010BDC043C0F3C010FF -:101F2000F9E7000030B54FF001238BB000240546DF -:101F300080688DF80F20059105A9CDE90634CDE91B -:101F4000084403685B699847A86801220DF10F01F6 -:101F5000036800941D692346A8470BB030BD0000FC -:101F6000F7B517460DF1070206461D46FFF7A8FF15 -:101F700068B19DF8074039469DF82020304624EA94 -:101F800005042A4022438DF80720FFF7CBFF03B05A -:101F9000F0BD000030B54FF4807389B000240546D1 -:101FA0008068039103A9CDE90434CDE906440368B0 -:101FB0005B699847A86822462146036800941D691A -:101FC0002346A84709B030BD10B504462368204613 -:101FD000DB6A98470028F9D110BD000010B590F8D1 -:101FE000743004465BB1FFF7EFFF012394F87410DF -:101FF000204684F88E30BDE81040FFF7CBBF0120AB -:1020000010BD000010B590F87430044653B1FFF7CE -:10201000DBFF01232046042184F88E30BDE8104008 -:10202000FFF7B8BF012010BD70B590F883308AB0BB -:102030000446042B48D10DF10E020521FFF740FFA5 -:1020400000282FD00DF10F0235212046FFF738FF71 -:1020500040B320461E4EFFF7C1FF2046FFF7B4FFF6 -:1020600005AD0FCE0FC5336805A99DF80E202B6076 -:102070009DF80F30A06843F002038DF810208DF812 -:102080000F308DF8113003685B699847A068002312 -:1020900004A90268009315690222A84728B92046BE -:1020A000FFF7B0FF00200AB070BD2046FFF7AAFF7F -:1020B0000DF10F0235212046FFF702FF0028F1D075 -:1020C0009DF80F309B07EDD501202071EBE700BF95 -:1020D000786000082DE9F341002304468068A3607E -:1020E00010B103685B6898470025244E244F56F8CA -:1020F000352001A839465FFA85F8FFF74FFB019BB1 -:10210000A0680022A360019210B103685B68984741 -:10211000019810B103685B689847A368DBB141F28E -:10212000883084F88C8001F0E1FC2046FFF7E2FC67 -:102130001E2001F0DBFC2046FFF70AFD054680B9B2 -:1021400094F88C300F4856F83310FFF781F9284681 -:1021500002B0BDE8F0810135032DC8D10A48FFF770 -:102160004DFC2046FFF760FF94F88C30054656F88A -:10217000331008B90548E8E70548E6E76462000857 -:10218000D4240020CC61000842620008F6610008F7 -:10219000206200082DE9F041044688B00F4616463B -:1021A000FFF71CFF2046FFF70FFF0025C722A0689E -:1021B0004FF48073079503A9CDE90323CDE90555B5 -:1021C00003685B699847A0682A462946036800951A -:1021D000D3F810802B46C047054630B92046FFF79C -:1021E00011FF284608B0BDE8F081E36E3B60236F25 -:1021F0003360F3E72DE9F041002588B01F4604461F -:102200000E460E9B00F1400CA8463D60016B81B16B -:10221000A9420ED391420CD8B6FBF1FE01FB1E6120 -:1022200039B9416B90F82C800F9D1960816B296042 -:10223000154610306045E9D16DB3AB196269934220 -:1022400029D82046FFF7CAFE2046FFF7BDFE4FF40F -:102250001453A06803A9CDF80C80CDE904360026FC -:10226000CDE9066603685B699847A0683246314647 -:1022700003680096D3F810803346C04706462046D0 -:102280002EB9FFF7BFFE304608B0BDE8F081FFF77A -:10229000B9FE3D60F7E70026F5E700002DE9F041C3 -:1022A0008669054688B00F46B3429046B1FBF6FCFE -:1022B00006FB1C1C28BF3346A6EB0C0C00269C45D5 -:1022C000644628BF1C46FFF789FE2846FFF77CFEC0 -:1022D0000222A86803A9164B0597CDE90323CDE98F -:1022E000066603685B699847A8682246414603680A -:1022F00000961F693346B847064628462EB9FFF7B1 -:1023000081FE304608B0BDE8F081FFF77BFE0E9BF2 -:102310001C60AB6FAA696343B3FBF2F30F9A1360BF -:10232000EA6F109B5443AA69B4FBF2F41C60E8E71F -:10233000002500012DE9F04FCE18436989B004460D -:102340009E420F46904634D83D464FF00009DFF8D4 -:1023500070A0FFF739FEAE422FD9A6EB050B94F81B -:10236000803094F8882003A9BBF5806F039394F81C -:10237000813028BF4FF4806B012AA06808BF03F1A9 -:10238000FF33CDF810A0CDE90559079303685B69C9 -:102390009847A068A8EB07030268CDF800B02B446B -:1023A000D2F810B000221146D84718B105F5806563 -:1023B000D1E7002009B0BDE8F08F0120FAE700BFA7 -:1023C00000ED0003F0B5044689B00E46FFF7FCFDB2 -:1023D00094F887502DB194F889302BB1012B1AD085 -:1023E0000025284609B0F0BD94F880200392A5226C -:1023F0000692184ACDE9042394F88130A06803A915 -:10240000079303685B699847A068314603689B6936 -:1024100098470546E5E720460027FFF7DFFD204601 -:10242000FFF7D2FD08238122852120460097FFF780 -:1024300097FD054618B92046FFF7E4FDD1E794F86B -:10244000803006970393044BCDE9043794F881302C -:10245000013BD3E700ED000300ED0013014B024AFE -:102460001A607047D4240020B86100080368002176 -:102470001B68184703790BB1002202711846704798 -:1024800003685B681847000003791BB901230371D7 -:1024900018467047002070477047000010B504468A -:1024A00003F058FD204610BD30B50A44084D914256 -:1024B0000DD011F8013B5840082340F30004013BC4 -:1024C0002C4013F0FF0384EA5000F6D1EFE730BD53 -:1024D0002083B8ED38B5836904460D465B695A011F -:1024E00018D543681B682BB10522027098472378E2 -:1024F000052B01D102232370202383F311880021AF -:1025000004F1080001F00CFB002383F31188E0695B -:1025100002F02CFAEB0704D50248BDE8384001F080 -:1025200075BA38BDE462000810B5044C204600F0CE -:10253000FBFF034A0023C4E9062310BDDC2400206E -:102540000050005210B503780446012B17D1104BF0 -:10255000984214D102460F49102002F0D3F90E4BD5 -:10256000E061D3F8D42042F48042C3F8D420D3F8F9 -:10257000FC2042F48042C3F8FC20D3F8FC306268AF -:10258000A36992685A60054A1A601B22DA6010BD7E -:10259000DC240020D5240008004402581500020164 -:1025A00083691B2210B5DA60D1E9002012F44C4493 -:1025B00006D192011C61D86102F440425A6110BDFB -:1025C0000024104312F4406F1C61CC68DC61586138 -:1025D00001D08A689A619A689206FCD4EFE70000FD -:1025E00030B584691B25C069E5600068836104F12A -:1025F0002003C36102234261013A03614623C360A1 -:1026000016238362CB682261E361D1E9002313437F -:1026100012F4406F636101D08B68A361C36843F01B -:102620000103C36030BD000030B5D0E9064000684A -:1026300004F120058561C36108234261013A036109 -:1026400046230D69C36016238362CB682261E36170 -:10265000D1E90023134312F4406F43EA854343F06A -:102660008063636101D08B68A361C36843F0010399 -:10267000C36030BD8069036823F0040310B50360B4 -:1026800000230361C3618361D1E9004309692343E6 -:1026900043EA814343F04063436112B14FF010437A -:1026A000136010BD83691A6842F002021A601A684A -:1026B0009207FCD41A6842F004021A6070470000C6 -:1026C00083691B2210B5DA6004465B695B011AD48A -:1026D00043681B682BB10522027098472378052BAD -:1026E00001D102232370202383F31188002104F1F8 -:1026F000080001F015FA002383F31188E069BDE8B2 -:10270000104002F033B910BD026843681143016004 -:1027100003B1184770470000024A136843F0C00332 -:10272000136070470010014013B50E4C204600F0B6 -:102730008BFA04F1140000234FF400720A4900944C -:1027400000F04CF9094B4FF40072094904F13800CC -:10275000009400F0C5F9074A074BC4E9172302B0FB -:1027600010BD00BFFC2400206825002019270008A8 -:10277000682700200010014000E1F505037C30B51A -:10278000244C002918BF0C46012B11D1224B984232 -:102790000ED1224BD3F8F02042F01002C3F8F02003 -:1027A000D3F8182142F01002C3F81821D3F81831D9 -:1027B0002268036EC16D03EB52038466B3FBF2F330 -:1027C0006268150442BF23F0070503F0070343EADC -:1027D0004503CB60A36843F040034B60E36843F0DC -:1027E00001038B6042F4967343F001030B604FF0DA -:1027F000FF330B62510505D512F0102205D0B2F15E -:10280000805F04D080F8643030BD7F23FAE73F2337 -:10281000F8E700BFF4620008FC24002000440258DE -:102820002DE9F047C66D05463768F4692107346223 -:1028300019D014F0080118BF8021E20748BF41F009 -:102840002001A3074FF0200348BF41F0400160077B -:1028500048BF41F4807183F31188281DFFF754FFAE -:10286000002383F31188E2050AD5202383F311881E -:102870004FF40071281DFFF747FF002383F31188F1 -:102880004FF020094FF0000A14F0200838D13B0621 -:1028900016D54FF0200905F1380A200610D589F326 -:1028A0001188504600F050F9002836DA0821281D1A -:1028B000FFF72AFF27F080033360002383F311889A -:1028C000790614D5620612D5202383F31188D5E941 -:1028D00013239A4208D12B6C33B127F04007102103 -:1028E000281DFFF711FF3760002383F31188E306EB -:1028F00018D5AA6E1369ABB15069BDE8F047184707 -:1029000089F31188736A284695F86410194000F01D -:10291000B5F98AF31188F469B6E7B06288F31188D3 -:10292000F469BAE7BDE8F087F8B515468268044651 -:102930000B46AA4200D28568A1692669761AB5427B -:102940000BD218462A46FEF787FDA3692B44A361E4 -:102950002846A3685B1BA360F8BD0CD9AF1B1846C3 -:102960003246FEF779FD3A46E1683044FEF774FDE1 -:10297000E3683B44EBE718462A46FEF76DFDE36843 -:10298000E5E7000083689342F7B50446154600D298 -:102990008568D4E90460361AB5420BD22A46FEF7A0 -:1029A0005BFD63692B4463612846A3685B1BA360DE -:1029B00003B0F0BD0DD93246AF1B0191FEF74CFDBF -:1029C00001993A46E0683144FEF746FDE3683B442E -:1029D000E9E72A46FEF740FDE368E4E710B50A445C -:1029E0000024C361029B8460C16002610362C0E98C -:1029F0000000C0E9051110BD08B5D0E905329342C9 -:102A000001D1826882B98268013282605A1C4261B7 -:102A100019700021D0E904329A4224BFC36843618F -:102A200001F098F8002008BD4FF0FF30FBE70000F0 -:102A300070B5202304460E4683F31188A568A5B11E -:102A4000A368A269013BA360531CA36115782269A6 -:102A5000934224BFE368A361E3690BB12046984722 -:102A6000002383F31188284607E03146204601F011 -:102A700061F80028E2DA85F3118870BD2DE9F74F7F -:102A800004460E4617469846D0F81C904FF0200A90 -:102A90008AF311884FF0000B154665B12A4631467E -:102AA0002046FFF741FF034660B94146204601F04A -:102AB00041F80028F1D0002383F31188781B03B07C -:102AC000BDE8F08FB9F1000F03D001902046C84750 -:102AD000019B8BF31188ED1A1E448AF31188DCE701 -:102AE000C160C361009B82600362C0E905111144AB -:102AF000C0E9000001617047F8B504460D4616466E -:102B0000202383F31188A768A7B1A368013BA360C2 -:102B100063695A1C62611D70D4E904329A4224BF71 -:102B2000E3686361E3690BB120469847002080F3B6 -:102B3000118807E03146204600F0FCFF0028E2DA69 -:102B400087F31188F8BD0000D0E9052310B59A423B -:102B500001D182687AB982680021013282605A1CF0 -:102B600082611C7803699A4224BFC368836100F0C4 -:102B7000F1FF204610BD4FF0FF30FBE72DE9F74F86 -:102B800004460E4617469846D0F81C904FF0200A8F -:102B90008AF311884FF0000B154665B12A4631467D -:102BA0002046FFF7EFFE034660B94146204600F09D -:102BB000C1FF0028F1D0002383F31188781B03B0F4 -:102BC000BDE8F08FB9F1000F03D001902046C8474F -:102BD000019B8BF31188ED1A1E448AF31188DCE700 -:102BE000026843681143016003B118477047000051 -:102BF0001430FFF743BF00004FF0FF331430FFF7EE -:102C00003DBF00003830FFF7B9BF00004FF0FF3381 -:102C10003830FFF7B3BF00001430FFF709BF0000E2 -:102C20004FF0FF311430FFF703BF00003830FFF7DB -:102C300063BF00004FF0FF323830FFF75DBF000088 -:102C400000207047FFF770BD044B03600023436012 -:102C5000C0E9023301230374704700BF0C6300080E -:102C600010B52023044683F31188FFF787FD022364 -:102C70002374002383F3118810BD000038B5C369A5 -:102C800004460D461BB904210844FFF7A9FF294655 -:102C900004F11400FFF7B0FE002806DA201D4FF4FF -:102CA0008061BDE83840FFF79BBF38BD02684368CC -:102CB0001143016003B118477047000013B5406B22 -:102CC00000F58054D4F8A4381A681178042914D176 -:102CD000017C022911D11979012312898B401342F9 -:102CE0000BD101A94C3002F08DFCD4F8A448024667 -:102CF000019B2179206800F0DFF902B010BD0000CF -:102D0000143002F00FBC00004FF0FF33143002F01B -:102D100009BC00004C3002F0E1BC00004FF0FF3372 -:102D20004C3002F0DBBC0000143002F0DDBB0000D0 -:102D30004FF0FF31143002F0D7BB00004C3002F0EE -:102D4000ADBC00004FF0FF324C3002F0A7BC0000D9 -:102D50000020704710B500F58054D4F8A4381A68E4 -:102D60001178042917D1017C022914D15979012342 -:102D700052898B4013420ED1143002F06FFB024691 -:102D800048B1D4F8A4484FF4407361792068BDE895 -:102D9000104000F07FB910BD406BFFF7DBBF0000B3 -:102DA000704700007FB5124B0125042604460360DE -:102DB0000023057400F1840243602946C0E9023310 -:102DC0000C4B0290143001934FF44073009602F0C4 -:102DD00021FB094B04F69442294604F14C0002946D -:102DE000CDE900634FF4407302F0E8FB04B070BD1E -:102DF00034630008992D0008BD2C00080A682023C0 -:102E000083F311880B790B3342F823004B7913338A -:102E100042F823008B7913B10B3342F8230000F5FD -:102E20008053C3F8A41802230374002383F311888A -:102E30007047000038B5037F044613B190F8543052 -:102E4000ABB90125201D0221FFF730FF04F114006A -:102E50006FF00101257700F089FE04F14C0084F841 -:102E600054506FF00101BDE8384000F07FBE38BD1E -:102E700010B5012104460430FFF718FF0023237723 -:102E800084F8543010BD000038B5044600251430D5 -:102E900002F0D8FA04F14C00257702F0A7FB201DC0 -:102EA00084F854500121FFF701FF2046BDE8384067 -:102EB000FFF750BF90F8803003F06003202B06D15D -:102EC00090F881200023212A03D81F2A06D8002049 -:102ED0007047222AFBD1C0E91D3303E0034A426751 -:102EE00007228267C3670120704700BF2C220020A1 -:102EF00037B500F58055D5F8A4381A68117804293B -:102F00001AD1017C022917D11979012312898B402A -:102F1000134211D100F14C04204602F027FC58B1B5 -:102F200001A9204602F06EFBD5F8A4480246019B99 -:102F30002179206800F0C0F803B030BD01F10B0327 -:102F4000F0B550F8236085B004460D46FEB120234D -:102F500083F3118804EB8507301D0821FFF7A6FED7 -:102F6000FB6806F14C005B691B681BB1019002F025 -:102F700057FB019803A902F045FB024648B1039BA9 -:102F80002946204600F098F8002383F3118805B005 -:102F9000F0BDFB685A691268002AF5D01B8A013B14 -:102FA0001340F1D104F18002EAE70000133138B593 -:102FB00050F82140ECB1202383F3118804F58053AD -:102FC000D3F8A4281368527903EB8203DB689B696A -:102FD0005D6845B104216018FFF768FE294604F1D9 -:102FE000140002F045FA2046FFF7B4FE002383F3F5 -:102FF000118838BD7047000001F038BD0123402220 -:10300000002110B5044600F8303BFEF757FA0023C4 -:10301000C4E9013310BD000010B52023044683F33A -:1030200011882422416000210C30FEF747FA204627 -:1030300001F03EFD02232370002383F3118810BDAD -:1030400070B500EB8103054650690E461446DA6000 -:1030500018B110220021FEF731FAA06918B1102230 -:103060000021FEF72BFA31462846BDE8704001F0FA -:1030700031BE000083682022002103F0011310B547 -:10308000044683601030FEF719FA2046BDE8104070 -:1030900001F0ACBEF0B4012500EB810447898D40FE -:1030A000E4683D43A469458123600023A260636016 -:1030B000F0BC01F0C9BE0000F0B4012500EB8104B2 -:1030C00007898D40E4683D436469058123600023DE -:1030D000A2606360F0BC01F03FBF000070B5022346 -:1030E00000250446242203702946C0F888500C307D -:1030F00040F8045CFEF7E2F9204684F8705001F0D5 -:103100007DFD63681B6823B129462046BDE87040F9 -:10311000184770BD037880F88C300523037043682E -:103120001B6810B504460BB1042198470023A36027 -:1031300010BD000090F88C20436802701B680BB132 -:10314000052118477047000070B590F870300446AC -:1031500013B1002380F8703004F18002204601F0A2 -:1031600069FE63689B68B3B994F8803013F060051A -:1031700035D00021204602F013F90021204602F04C -:1031800003F963681B6813B106212046984706239C -:1031900084F8703070BD204698470028E4D0B4F819 -:1031A0008630A26F9A4288BFA36794F98030A56FDA -:1031B000002B4FF0200380F20381002D00F0F280FD -:1031C000092284F8702083F3118800212046D4E975 -:1031D0001D23FFF771FF002383F31188DAE794F8CA -:1031E000812003F07F0343EA022340F2023293423C -:1031F00000F0C58021D8B3F5807F48D00DD8012BD1 -:103200003FD0022B00F09380002BB2D104F1880252 -:1032100062670222A267E367C1E7B3F5817F00F02E -:103220009B80B3F5407FA4D194F88230012BA0D1CC -:10323000B4F8883043F0020332E0B3F5006F4DD0AC -:1032400017D8B3F5A06F31D0A3F5C063012B90D888 -:103250006368204694F882205E6894F88310B4F87E -:103260008430B047002884D0436863670368A3674D -:103270001AE0B3F5106F36D040F6024293427FF465 -:1032800078AF5C4B63670223A3670023C3E794F81E -:103290008230012B7FF46DAFB4F8883023F0020345 -:1032A000A4F88830C4E91D55E56778E7B4F88030A4 -:1032B000B3F5A06F0ED194F88230204684F88A309E -:1032C00001F0FAFC63681B6813B10121204698479E -:1032D000032323700023C4E91D339CE704F18B030F -:1032E00063670123C3E72378042B10D1202383F3E2 -:1032F00011882046FFF7BEFE85F31188032163681D -:1033000084F88B5021701B680BB12046984794F8C5 -:103310008230002BDED084F88B3004232370636866 -:103320001B68002BD6D0022120469847D2E794F89C -:10333000843020461D0603F00F010AD501F06CFD14 -:10334000012804D002287FF414AF2B4B9AE72B4BB3 -:1033500098E701F053FDF3E794F88230002B7FF4F7 -:1033600008AF94F8843013F00F01B3D01A0620464A -:1033700002D502F02DF8ADE702F01EF8AAE794F8A6 -:103380008230002B7FF4F5AE94F8843013F00F01F7 -:10339000A0D01B06204602D502F002F89AE701F001 -:1033A000F3FF97E7142284F8702083F311882B46EB -:1033B0002A4629462046FFF76DFE85F31188E9E687 -:1033C0005DB1152284F8702083F311880021204616 -:1033D000D4E91D23FFF75EFEFDE60B2284F8702082 -:1033E00083F311882B462A4629462046FFF764FEC0 -:1033F000E3E700BF646300085C63000860630008E3 -:1034000038B590F870300446002B3ED0063BDAB257 -:103410000F2A34D80F2B32D8DFE803F037313108C8 -:10342000223231313131313131313737856FB0F8B6 -:1034300086309D4214D2C3681B8AB5FBF3F203FBAE -:1034400012556DB9202383F311882B462A4629464D -:10345000FFF732FE85F311880A2384F870300EE0FE -:10346000142384F87030202383F31188002320462E -:103470001A461946FFF70EFE002383F3118838BD64 -:10348000C36F03B198470023E7E70021204601F00E -:1034900087FF0021204601F077FF63681B6813B1A6 -:1034A0000621204698470623D7E7000010B590F87C -:1034B00070300446142B29D017D8062B05D001D81C -:1034C0001BB110BD093B022BFBD80021204601F0A7 -:1034D00067FF0021204601F057FF63681B6813B1A6 -:1034E000062120469847062319E0152BE9D10B2326 -:1034F00080F87030202383F3118800231A46194680 -:10350000FFF7DAFD002383F31188DAE7C3689B69CC -:103510005B68002BD5D1C36F03B19847002384F8B3 -:103520007030CEE7FFF700B8012100230170C0E939 -:1035300001330C3000F008BA10B52023044683F3A1 -:1035400011884160FEF7FEFF02232370002383F3FE -:10355000118810BD10B52023044683F3118803237E -:1035600004F8083BFFF71CF84FF0FF31204600F04D -:10357000C9FA002383F31188C01A18BF012010BDB7 -:1035800038B50446202585F31188032504F8085B27 -:10359000FFF726F84FF0FF31204600F0B3FA002382 -:1035A00083F31188C01A18BF012038BD38B504460E -:1035B000202585F31188042504F8085BFFF734F80B -:1035C0004FF0FF31204600F09DFA002383F311886D -:1035D000C01A18BF012038BD10B52023044683F35C -:1035E0001188FFF747F806232370002383F311881F -:1035F00010BD000010B52023044683F31188FFF7A7 -:1036000051F802232370002383F3118810BD0000BA -:103610000C3000F0B5B900000C3000F0BBB9000070 -:1036200004480121044B03600023C0E901330C303E -:1036300000F08AB96829002021580008CB1D083AFB -:1036400023F00703591A521A012110B4D20800249A -:10365000C0E9004384600C301C605A605DF8044B84 -:1036600000F072B92DE9F84F364ECD1D0F460028F7 -:1036700018BF0646082A4FEAD50538BF082206F1CA -:103680000C08341D9146404600F07AF909F1070113 -:10369000C9F1000E224624686CB9404600F07AF960 -:1036A0003368CBB308224946E8009847044698B3EC -:1036B00040E9026730E004EB010CD4F804A00CEA06 -:1036C0000E0C0AF10100ACF1080304EBC0009842B3 -:1036D000E0D9A0EB0C0CB5EBEC0F4FEAEC0BD9D812 -:1036E0009C421CD204F10802AB45A3EB02024FEA54 -:1036F000E202626009D9691CED43206803EBC10254 -:103700005D44556043F8310022601C465F604046CE -:1037100044F8086B00F03EF92046BDE8F88FAA4552 -:10372000216802D111602346EFE7013504EBC503A0 -:1037300044F8351003F10801401AC01058601360B6 -:10374000F1E700BF68290020F8B550F8043C0446B2 -:1037500050F8085CA0F1080607332F1D0C35DB0874 -:1037600040F8043C284600F00BF93B46BB421A687F -:1037700001D09E4228D90AB1964225D244F8082C9D -:1037800054F8042C1E60013254F8081C06EBC200E9 -:10379000814206D14868024444F8042C0A6844F87F -:1037A000082C5868411C03EBC1018E4207D154F824 -:1037B000042C013202445A6054F8082C1A6028463E -:1037C000BDE8F84000F0E6B81346CFE7024B002210 -:1037D000C3E900339A607047802900200023826883 -:1037E0000374054B1B6899689142FBD25A680360C9 -:1037F00042601060586070478029002008B520237F -:1038000083F31188027C0023052A06D8DFE802F042 -:103810000B050503120E426913604FF0FF3343613D -:10382000FFF7DCFF002383F3118808BD426993682A -:1038300001339360D0E9003213605A60EDE7000075 -:10384000002382680374054B1B6899689142FBD87A -:103850005A680360426010605860704780290020F9 -:10386000054B196908741868026853601A6018617A -:1038700001230374FCF734BF802900204B1C30B5B2 -:10388000044687B00A4D10D02B6901A8094A00F000 -:1038900089F92046FFF7E4FF049B13B101A800F06B -:1038A000BDF92B69586907B030BDFFF7D9FFF8E7BC -:1038B00080290020FD37000838B50C4D04464161D1 -:1038C0002B6981689A68914203D8BDE83840FFF7B8 -:1038D00085BF1846FFF7B4FF01232C61014623740E -:1038E0002046BDE83840FCF7FBBE00BF8029002021 -:1038F000044B1A681B6990689B68984294BF00202B -:10390000012070478029002010B5084C23682069E9 -:103910001A6854602260012223611A74FFF790FF35 -:1039200001462069BDE81040FCF7DABE802900207E -:1039300008B5FFF7DDFF18B1BDE80840FFF7E4BFA9 -:1039400008BD0000FFF7E0BFC0E9000081607047DC -:103950008368013B002B10B583600DDA074C426889 -:103960002369586118605A60136043600520FFF7AF -:1039700077FF2369586910BD0020FCE780290020EB -:1039800008B5202383F31188FFF7E2FF002383F3B8 -:10399000118808BD08B5202383F31188836801339B -:1039A000002B836007DC036800211A680260506006 -:1039B0001846FFF781FF002383F3118808BD00003C -:1039C000FEE7000010B50E4CFFF700FF00F0DCF83A -:1039D00001F008FFFFF724FE80220A49204600F08C -:1039E00047F8012344F8180C037400F043FE002349 -:1039F00083F3118862B60448BDE8104000F058B85F -:103A0000A8290020686300087863000808B572B62A -:103A1000034B586200F0B0FC00F07EFDFEE700BFF3 -:103A20008029002000F034B9EFF3118020B9EFF3C2 -:103A30000583202282F311887047000010B530B949 -:103A4000EFF30584C4F3080414B180F3118810BDAA -:103A5000FFF76EFF84F31188F9E70000034A51680D -:103A600053685B1A9842FBD8704700BF001000E013 -:103A700082600222028270478368A3F17C0243F8CD -:103A80000C2C026943F83C2C426943F8382C074A55 -:103A900043F81C2CC268A3F1180043F8102C022232 -:103AA00003F8082C002203F8072C7047F9060008D9 -:103AB00010B5202383F31188FFF7DEFF00210446B1 -:103AC000FFF7FAFE002383F31188204610BD0000A3 -:103AD000024B1B6958610F20FFF7C2BE80290020EE -:103AE000202383F31188FFF7F3BF000008B50146D8 -:103AF000202383F311880820FFF7C0FE002383F3FF -:103B0000118808BD054B1B6921B103605861032072 -:103B1000FFF7B4BE4FF0FF30704700BF8029002090 -:103B200003682BB10022026018465961FFF756BEA8 -:103B30007047000049B1064B42681B6918605A6023 -:103B4000136043600420FFF799BE4FF0FF307047C9 -:103B5000802900200368984206D01A6802605060ED -:103B600018465961FFF73ABE7047000038B5044661 -:103B70000D462068844200D138BD036823605C6034 -:103B80004561FFF72BFEF4E7054B4FF0FF3103F1E2 -:103B90001402C3E905220022C3E90712704700BFDF -:103BA0008029002070B51C4E05460C46C0E9032351 -:103BB00001F012FE334653F8142F9A420DD13062B1 -:103BC0000A2C2CBF00190A302A60C5E90124C6E975 -:103BD0000555BDE8704001F0E9BD316A431AE318AC -:103BE00038BF1C469368A34202D9081901F0EEFDC4 -:103BF00073699A6894420CD85A68AC602B606A600A -:103C000015609A685D60121B9A604FF0FF33F36194 -:103C100070BDA41A1B68ECE78029002038B51B4C46 -:103C2000636998420DD08168D0E9003213605A6010 -:103C30000022C2609A680A449A604FF0FF33E36141 -:103C400038BD03682246002142F8143F93425A606F -:103C5000C16003D1BDE8384001F0B2BD9A68816807 -:103C6000256A0A449A6001F0B7FD6369411B9A68AE -:103C70008A42E5D9AB181D1A206A092D98BF01F1B7 -:103C80000A02BDE83840104401F0A0BD80290020A0 -:103C90002DE9F041184C002704F11406656901F084 -:103CA0009BFD236AAA68C11A8A4215D81344D5F825 -:103CB0000C802362D5E9003213605A606369EF60BB -:103CC000B34201D101F07CFD87F311882869C04718 -:103CD000202383F31188E1E76169B14209D01344DD -:103CE0001B1ABDE8F0410A2B2CBFC0180A3001F0A6 -:103CF0006DBDBDE8F08100BF802900200020704725 -:103D0000FEE70000704700004FF0FF3070470000F2 -:103D100002290CD0032904D00129074818BF00202C -:103D20007047032A05D8054800EBC20070470448D5 -:103D300070470020704700BF5C6400083C220020F0 -:103D40001064000870B59AB005460846144601A9EB -:103D500000F0C2F801A8FDF7A9FB431C0022C6B27F -:103D60005B001046C5E9003423700323023404F8D5 -:103D7000013C01ABD1B202348E4201D81AB070BD01 -:103D800013F8011B013204F8010C04F8021CF1E7DE -:103D900008B5202383F311880348FFF7A9F800230F -:103DA00083F3118808BD00BF382B002090F88030C5 -:103DB00003F01F02012A07D190F881200B2A03D1BA -:103DC0000023C0E91D3315E003F06003202B08D168 -:103DD000B0F884302BB990F88120212A03D81F2A0B -:103DE00004D8FFF767B8222AEBD0FAE7034A426704 -:103DF00007228267C3670120704700BF332200207B -:103E000007B5052917D8DFE801F01916031919209D -:103E1000202383F31188104A01210190FFF710F944 -:103E2000019802210D4AFFF70BF90D48FFF72CF816 -:103E3000002383F3118803B05DF804FB202383F390 -:103E400011880748FEF7F6FFF2E7202383F3118875 -:103E50000348FFF70DF8EBE7B0630008D4630008F0 -:103E6000382B002038B50C4D0C4C2A460C4904F177 -:103E70000800FFF767FF05F1CA0204F110000949C5 -:103E8000FFF760FF05F5CA7204F118000649BDE8A6 -:103E90003840FFF757BF00BF104400203C220020ED -:103EA000906300089A630008A563000870B5044693 -:103EB00008460D46FDF7FAFAC6B2204601340378EB -:103EC0000BB9184670BD32462946FDF7CFFA0028D7 -:103ED000F3D10120F6E700002DE9F84F05460C4626 -:103EE000FDF7E4FA2C49C6B22846FFF7DFFF08B118 -:103EF0000336F6B229492846FFF7D8FF08B1103635 -:103F0000F6B2632E0DD8DFF89080DFF89090244F42 -:103F1000DFF894A0DFF894B02E7846B92670BDE89B -:103F2000F88F29462046BDE8F84F02F09BB8252EB1 -:103F30002ED1072241462846FDF798FA70B9DBF8E2 -:103F4000003007350A3444F80A3CDBF8043044F802 -:103F5000063CBBF8083024F8023CDDE7082249465D -:103F60002846FDF783FA98B9A21C0E4B1978023245 -:103F70000909C95D02F8041C13F8011B01F00F01C7 -:103F80005345C95D02F8031CF0D118340835C3E766 -:103F9000013504F8016BBFE77C640008A5630008E5 -:103FA0008F64000800E8F11F0CE8F11F846400082A -:103FB000BFF34F8F044B1A695107FCD1D3F810217E -:103FC0005207F8D1704700BF0020005208B50D4BD2 -:103FD0001B78ABB9FFF7ECFF0B4BDA68D10704D5C0 -:103FE0000A4A5A6002F188325A60D3F80C21D2078B -:103FF00006D5064AC3F8042102F18832C3F8042129 -:1040000008BD00BF6E460020002000522301674516 -:104010004FF00063054A1968013104D1043393421B -:10402000F9D1012070470020704700BF000002084E -:1040300008B5114B1B78F3B9104B1A69510703D51A -:10404000DA6842F04002DA60D3F81021520705D551 -:10405000D3F80C2142F04002C3F80C21FFF7A8FF6F -:10406000064BDA6842F00102DA60D3F80C2142F024 -:104070000102C3F80C2108BD6E460020002000524A -:104080004FF40030704700000120704708B9FFF777 -:10409000BFBF00207047000008B518BB1248FFF7EB -:1040A00087FFFFF793FF4FF0FF334361C0F81431F0 -:1040B0000361FFF77DFF2423C360C36843F08003DF -:1040C000C36003695B07FCD4FFF772FF4FF0006029 -:1040D0004FF4003100F0FCF9FFF7AAFFBDE80840FB -:1040E000FFF796BF002008BD002000522DE9F84FD1 -:1040F00005460C46104645EA0203DB065DD122F078 -:1041000003022B462A44934209D120F01F00DFF816 -:10411000BCB0DFF8BCA0FFF759FF271844E01968CE -:1041200001314AD10433EEE705F1784324492548AB -:10413000B3F5801F244B38BF184603F1F80339BF8D -:104140008846D9469846D146FFF732FF4FF0FF33F5 -:10415000A5EB040C04F11C010360D8F8003043F017 -:104160000203C8F80030231FD9F8006016F00506D6 -:10417000FAD153F8042F99424CF80320F4D1BFF33D -:104180004F8FFFF715FF4FF0FF33202221460360CA -:104190002846D8F8003023F00203C8F8003001F0B8 -:1041A0000DFF40B920352034BC42BDD10120FFF7BE -:1041B0003FFFBDE8F88F3046F9E70020F9E700BF80 -:1041C0000C200052142100521420005210200052E2 -:1041D0001021005210B5084C237828B11BB9FFF705 -:1041E000F5FE0123237010BD002BFCD02070BDE82C -:1041F0001040FFF71DBF00BF6E4600202DE9F74FAE -:104200000E460546002864D011F0050763D139B980 -:10421000082229463046FFF725FA0446002848D1EF -:1042200008224FF00109DFF8C08006F00403DFF830 -:10423000BCA006EA090BBBF1000F27D0D8F8141078 -:10424000C80723D409F1010908F10C08B9F1060FD8 -:10425000F1D18FB9224E2946F0190092FFF702FAE8 -:10426000044630BB1837009A782FF4D12946FFF75F -:10427000F9F90446E8B9009A29461A48FFF7F2F915 -:10428000044608BB204603B0BDE8F08FABB1D8F8B8 -:10429000141011F0040FD5D01820294600FB09A0F6 -:1042A000CDE90023FFF7DEF90446DDE9002300280D -:1042B000C8D02A460021204608E0B107ECD5D8F83E -:1042C000141011F0020FE6E72A460021FDF7F6F878 -:1042D000D8E70446D6E71F35202225F01F05A0E7C2 -:1042E000A046002070460020A064000888460020F8 -:1042F0000021FFF783BF00000121FFF77FBF00000F -:10430000F8B5144D01241827134E40F2FF32002156 -:104310000120FDF7D3F807FB046001342A6955F842 -:104320000C1FFFF78BF9062CF5D137254FF4C0543D -:104330002046FFF7E1FF014628B122460748BDE8C5 -:10434000F840FFF77BB9C4EBC404013D4FEAD40445 -:10435000EED1F8BDA0640008884600207046002019 -:104360000421FFF74BBF00004843FFF7C1BF000027 -:1043700008B1FFF7E9B9704738B5054D002403349B -:10438000696855F80C0B00F0B5F8122CF7D138BD60 -:10439000A064000870B5104E82B0FFF745FB0546DB -:1043A00001F01AFA326803469042336037BF0B4A75 -:1043B0000A495168146836BF0131D1E900415160A2 -:1043C0000419284641F100010191FFF737FB20460F -:1043D000019902B070BD00BF18470020204700209F -:1043E00070B5124E82B0FFF71FFB054601F0F4F9DD -:1043F000326803469042336037BF0D4A0C4951681A -:10440000146836BF0131D1E90041516004192846D2 -:1044100041F100010191FFF711FB4FF47A72002383 -:1044200020460199FBF744FF02B070BD18470020F9 -:10443000204700200244074BD2B210B5904200D171 -:1044400010BD441C00B253F8200041F8040BE0B248 -:10445000F4E700BF504000580E4B30B51C6F2404E9 -:1044600005D41C6F1C671C6F44F400441C670A4C85 -:1044700002442368D2B243F480732360074B904216 -:1044800000D130BD441C51F8045B00B243F8205009 -:10449000E0B2F4E700440258004802585040005887 -:1044A00007B5012201A90020FFF7C4FF019803B05E -:1044B0005DF804FB13B50446FFF7F2FFA04205D0F8 -:1044C000012201A900200194FFF7C6FF02B010BD30 -:1044D0000144BFF34F8F064B884204D3BFF34F8F85 -:1044E000BFF36F8F7047C3F85C022030F4E700BF62 -:1044F00000ED00E00144BFF34F8F064B884204D328 -:10450000BFF34F8FBFF36F8F7047C3F87002203037 -:10451000F4E700BF00ED00E07047000070B505460D -:1045200016460C4601201021FFF71EFF2860467337 -:104530003CB1204636B1FFF713FF2B68186000B17D -:104540009C6070BDFFF7D8FEF7E7000070B50E461F -:104550001546044600B30B6843608368934210D24B -:1045600013B10068FFF704FF637B28462BB1FFF708 -:10457000F7FE206020B9A06070BDFFF7BDFEF8E730 -:10458000A560206805F11F01306021F01F01FFF7D1 -:104590009FFF01202073EFE70120EDE710B50446EF -:1045A00040B10068884205D1606808B1FCF754FF4B -:1045B0000023237310BD000070B50E461546044657 -:1045C00020B38368934210D213B10068FFF7D0FE86 -:1045D000637B28462BB1FFF7C3FE206020B9A060A3 -:1045E00070BDFFF789FEF8E7A560316819B12A466A -:1045F0002068FCF731FF206805F11F01306021F0D1 -:104600001F01FFF777FF01202073E9E70120E7E7AB -:1046100020B103688B4204BF00230373704700007E -:1046200008B1002303737047034B1A681AB9034A91 -:10463000D2F8D0241A607047284700200040025862 -:1046400008B5FFF7F1FF024B1868C0F3806008BDA2 -:1046500028470020EFF30983054968334A6B22F0AD -:1046600001024A6383F30988002383F311887047AA -:1046700000EF00E0202080F3118862B60D4B0E4A57 -:10468000D96821F4E0610904090C0A430B49DA6096 -:10469000D3F8FC2042F08072C3F8FC20084AC2F82C -:1046A000B01F116841F0010111601022DA7783F820 -:1046B0002200704700ED00E00003FA0555CEACC5BE -:1046C000001000E0202310B583F311880E4B5B68C7 -:1046D00013F4006314D0F1EE103AEFF309844FF0B5 -:1046E0008073683CE361094BDB6B236684F30988C4 -:1046F000FFF7FEF810B1064BA36110BD054BFBE7B9 -:1047000083F31188F9E700BF00ED00E000EF00E05F -:104710000B0700080E07000870B5BFF34F8FBFF3FB -:104720006F8F1A4A0021C2F85012BFF34F8FBFF3A8 -:104730006F8F536943F400335361BFF34F8FBFF35F -:104740006F8FC2F88410BFF34F8FD2F8803043F6DA -:10475000E074C3F3C900C3F34E335B0103EA0406FC -:10476000014646EA81750139C2F86052F9D2203B10 -:1047700013F1200FF2D1BFF34F8F536943F480330D -:104780005361BFF34F8FBFF36F8F70BD00ED00E03B -:10479000FEE700000A4B0B480B4A90420BD30B4B31 -:1047A000C11EDA1C121A22F003028B4238BF00220B -:1047B0000021FCF783BE53F8041B40F8041BECE710 -:1047C00060670008D0490020D0490020D04900206F -:1047D0007047000003681968596043680BB180682E -:1047E000184770474FF0A44310B51C68E00702D586 -:1047F0002848FFF7EFFFA10702D52748FFF7EAFF98 -:10480000620702D52548FFF7E5FF230702D52448B4 -:10481000FFF7E0FFE00602D52248FFF7DBFFA10625 -:1048200002D52148FFF7D6FF620602D51F48FFF7E1 -:10483000D1FF230602D51E48FFF7CCFFE00502D5C5 -:104840001C48FFF7C7FFA10502D51B48FFF7C2FFB1 -:10485000620502D51948FFF7BDFF230502D51848A8 -:10486000FFF7B8FFE00402D51648FFF7B3FFA10435 -:1048700002D51548FFF7AEFF620402D51348FFF7D3 -:10488000A9FF230402D51248FFF7A4FFBDE810409A -:10489000FFF718BF304700203C4700204847002062 -:1048A00054470020604700206C47002078470020D4 -:1048B00084470020904700209C470020A847002004 -:1048C000B4470020C0470020CC470020D847002034 -:1048D000E447002030B5094B0021094C1020072582 -:1048E000196054F8042B0138C3E90121D16003F1A8 -:1048F0000C0311615560F4D130BD00BF2C4700207E -:10490000E86400080F28F0B50AD9102806D10F2353 -:104910000020144C01272568984203D900201DE08F -:104920000346F6E707FA00F6354218D10C23354363 -:1049300043432560181D2344C3E902120A4B204457 -:10494000D3F8D42042F00102C3F8D420D3F8FC20DD -:1049500042F00102C3F8FC20D3F8FC30F0BD013076 -:10496000DAE700BF2C470020004402580368D968EA -:10497000DA68C90722F03F02DA6002D51A689207A6 -:10498000FCD507225A60704770B5D0E92443002255 -:104990004FF0FF359E6804EB42135101D3F8000934 -:1049A000002805DAD3F8000940F08040C3F8000978 -:1049B000D3F8000B002805DAD3F8000B40F0804054 -:1049C000C3F8000B013263189642C3F80859C3F8C4 -:1049D000085BE0D24FF00113C4F81C3870BD000032 -:1049E00000EB8103D3F80CC02DE9F043DCF8142070 -:1049F0004E1CD0F89050D2F800E005EB063605EBDF -:104A00004118506870450AD30122D5F8343802FAAB -:104A100001F123EA0101C5F83418BDE8F083AEEBDB -:104A20000003BCF81040A34228BF2346D8F8184919 -:104A3000A4B2B3EB840FF0D89468A4F1040959F838 -:104A4000047F3760A4EB09071F44042FF7D81C44E8 -:104A5000034494605360D4E7890141F0200101616F -:104A600003699B06FCD41220FEF7F8BF10B50A4C70 -:104A70002046FEF7C3FA094BC4F89030084BC4F83F -:104A80009430084C2046FEF7B9FA074BC4F8903032 -:104A9000064BC4F8943010BDF047002000000840D9 -:104AA0004C6500088C480020000004405865000850 -:104AB00070B503780546012B5DD1494BD0F8904085 -:104AC000984259D1474B0E216520D3F8D82042F0A7 -:104AD0000062C3F8D820D3F8002142F00062C3F886 -:104AE0000021D3F80021D3F8802042F00062C3F8FF -:104AF0008020D3F8802022F00062C3F88020D3F811 -:104B0000803000F071FC384BE360384BC4F800385B -:104B10000023D5F89060C4F8003EC02323604FF412 -:104B20000413A3633369002BFCDA01230C203361E7 -:104B3000FEF794FF3369DB07FCD41220FEF78EFFEB -:104B40003369002BFCDA00262846A660FFF71CFF1D -:104B50006B68C4F81068DB68C4F81468C4F81C6893 -:104B6000002B3AD1224BA3614FF0FF336361A3685E -:104B700043F00103A36070BD1E4B9842C8D1194B8E -:104B80000E214D20D3F8D82042F00072C3F8D8206F -:104B9000D3F8002142F00072C3F80021D3F80021BD -:104BA000D3F8802042F00072C3F88020D3F8802030 -:104BB00022F00072C3F88020D3F88020D3F8D820E8 -:104BC00022F08062C3F8D820D3F8002122F080625E -:104BD000C3F80021D3F8003193E7074BC3E700BFC8 -:104BE000F047002000440258401400400300200217 -:104BF000003C30C08C480020083C30C0F8B5D0F8EC -:104C00009040054600214FF000662046FFF724FF44 -:104C1000D5F8941000234FF001128F684FF0FF3049 -:104C2000C4F83438C4F81C2804EB431201339F4203 -:104C3000C2F80069C2F8006BC2F80809C2F8080B94 -:104C4000F2D20B68D5F89020C5F898306362102333 -:104C50001361166916F01006FBD11220FEF7FEFE56 -:104C6000D4F8003823F4FE63C4F80038A36943F491 -:104C7000402343F01003A3610923C4F81038C4F89B -:104C800014380B4BEB604FF0C043C4F8103B094B9A -:104C9000C4F8003BC4F81069C4F80039D5F898305E -:104CA00003F1100243F48013C5F89820A362F8BD05 -:104CB0002865000840800010D0F8902090F88A10F5 -:104CC000D2F8003823F4FE6343EA0113C2F8003837 -:104CD000704700002DE9F84300EB8103D0F89050B5 -:104CE0000C468046DA680FFA81F94801166806F02A -:104CF0000306731E022B05EB41134FF0000194BF16 -:104D0000B604384EC3F8101B4FF0010104F1100334 -:104D100098BF06F1805601FA03F3916998BF06F532 -:104D2000004600293AD0578A04F158013743490117 -:104D30006F50D5F81C180B430021C5F81C382B18F0 -:104D40000127C3F81019A7405369611E9BB3138A4A -:104D5000928B9B08012A88BF5343D8F89820981853 -:104D600042EA034301F140022146C8F89800284670 -:104D700005EB82025360FFF76FFE08EB8900C36802 -:104D80001B8A43EA845348341E4364012E51D5F8EC -:104D90001C381F43C5F81C78BDE8F88305EB49179C -:104DA000D7F8001B21F40041C7F8001BD5F81C18E8 -:104DB00021EA0303C0E704F13F030B4A28462146DA -:104DC00005EB83035A60FFF747FE05EB4910D0F867 -:104DD000003923F40043C0F80039D5F81C3823EA21 -:104DE0000707D7E70080001000040002D0F89420E5 -:104DF0001268C0F89820FFF7C7BD00005831D0F8FE -:104E0000903049015B5813F4004004D013F4001FA4 -:104E10000CBF0220012070474831D0F89030490182 -:104E20005B5813F4004004D013F4001F0CBF0220A1 -:104E30000120704700EB8101CB68196A0B68136091 -:104E40004B6853607047000000EB810330B5DD68AC -:104E5000AA691368D36019B9402B84BF402313603B -:104E60006B8A1468D0F890201C4402EB4110013C7E -:104E700009B2B4FBF3F46343033323F0030343EABF -:104E8000C44343F0C043C0F8103B2B6803F0030356 -:104E9000012B0ED1D2F8083802EB411013F4807FB9 -:104EA000D0F8003B14BF43F0805343F00053C0F8E8 -:104EB000003B02EB4112D2F8003B43F00443C2F83E -:104EC000003B30BD2DE9F041D0F8906005460C461E -:104ED00006EB4113D3F8087B3A07C3F8087B08D5E3 -:104EE000D6F814381B0704D500EB8103DB685B6838 -:104EF0009847FA071FD5D6F81438DB071BD505EB02 -:104F00008403D968CCB98B69488A5A68B2FBF0F639 -:104F100000FB16228AB91868DA6890420DD2121A7C -:104F2000C3E90024202383F3118821462846FFF794 -:104F30008BFF84F31188BDE8F081012303FA04F2AA -:104F40006B8923EA02036B81CB68002BF3D02146E7 -:104F50002846BDE8F041184700EB81034A0170B5CF -:104F6000DD68D0F890306C692668E66056BB1A445C -:104F70004FF40020C2F810092A6802F00302012A47 -:104F80000AB20ED1D3F8080803EB421410F4807F64 -:104F9000D4F8000914BF40F0805040F00050C4F82D -:104FA000000903EB4212D2F8000940F00440C2F8B5 -:104FB00000090122D3F8340802FA01F10143C3F8D1 -:104FC000341870BD19B9402E84BF4020206020687D -:104FD0001A442E8A8419013CB4FBF6F440EAC4401A -:104FE00040F00050C6E700002DE9F041D0F8906095 -:104FF00004460D4606EB4113D3F80879C3F8087947 -:10500000FB071CD5D6F81038DA0718D500EB81035A -:10501000D3F80CC0DCF81430D3F800E0DA68964519 -:105020001BD2A2EB0E024FF000081A60C3F80480F6 -:10503000202383F31188FFF78FFF88F311883B0645 -:1050400018D50123D6F83428AB40134212D0294694 -:105050002046BDE8F041FFF7C3BC012303FA01F28B -:10506000038923EA02030381DCF80830002BE6D031 -:105070009847E4E7BDE8F0812DE9F84FD0F890506B -:1050800004466E69AB691E4016F480586E6103D009 -:10509000BDE8F84FFEF722B8002E12DAD5F8003E30 -:1050A0009F0705D0D5F8003E23F00303C5F8003E66 -:1050B000D5F80438204623F00103C5F80438FEF77C -:1050C00039F8300505D52046FFF75EFC2046FEF78F -:1050D00021F8B1040CD5D5F8083813F0060FEB68A9 -:1050E00023F470530CBF43F4105343F4A053EB600C -:1050F000320704D56368DB680BB120469847F3029A -:1051000000F1BA80B70226D5D4F8909000274FF06E -:10511000010A09EB4712D2F8003B03F44023B3F530 -:10512000802F11D1D2F8003B002B0DDA62890AFAE8 -:1051300007F322EA0303638104EB8703DB68DB6880 -:1051400013B13946204698470137D4F89430FFB25E -:105150009B689F42DDD9F00619D5D4F89000026A09 -:10516000C2F30A1702F00F0302F4F012B2F5802F17 -:1051700000F0CC80B2F5402F09D104EB830300226C -:1051800000F58050DB681B6A974240F0B280300324 -:10519000D5F8185835D5E90303D500212046FFF787 -:1051A00091FEAA0303D501212046FFF78BFE6B0376 -:1051B00003D502212046FFF785FE2F0303D50321E7 -:1051C0002046FFF77FFEE80203D504212046FFF7C3 -:1051D00079FEA90203D505212046FFF773FE6A0276 -:1051E00003D506212046FFF76DFE2B0203D50721CC -:1051F0002046FFF767FEEF0103D508212046FFF7A1 -:1052000061FE700340F1A980E90703D50021204623 -:10521000FFF7EAFEAA0703D501212046FFF7E4FEC7 -:105220006B0703D502212046FFF7DEFE2F0703D5CB -:1052300003212046FFF7D8FEEE0603D504212046C1 -:10524000FFF7D2FEA80603D505212046FFF7CCFEC6 -:10525000690603D506212046FFF7C6FE2A0603D5B8 -:1052600007212046FFF7C0FEEB0576D52046082132 -:10527000BDE8F84FFFF7B8BED4F8909000274FF084 -:10528000010AD4F894305FFA87FB9B689B453FF690 -:1052900039AF09EB4B13D3F8002902F44022B2F5E1 -:1052A000802F24D1D3F80029002A20DAD3F800294E -:1052B00042F09042C3F80029D3F80029002AFBDB12 -:1052C0005946D4F89000FFF7C7FB22890AFA0BF37E -:1052D00022EA0303238104EB8B03DB689B6813B191 -:1052E00059462046984759462046FFF779FB013733 -:1052F000C7E7910701D1D0F80080072A02F1010227 -:105300009CBF03F8018B4FEA18283DE704EB8303A9 -:1053100000F58050DA68D2F818C0DCF80820DCE923 -:10532000001CA1EB0C0C00218F4208D1DB689B69AB -:105330009A683A449A605A683A445A6027E711F0EA -:10534000030F01D1D0F800808C4501F1010184BF29 -:1053500002F8018B4FEA1828E6E7BDE8F88F000055 -:1053600008B50348FFF788FEBDE80840FFF7AAB973 -:10537000F047002008B50348FFF77EFEBDE808406F -:10538000FFF7A0B98C480020D0F8903003EB411112 -:10539000D1F8003B43F40013C1F8003B7047000014 -:1053A000D0F8903003EB4111D1F8003943F40013E9 -:1053B000C1F8003970470000D0F8903003EB41117C -:1053C000D1F8003B23F40013C1F8003B7047000004 -:1053D000D0F8903003EB4111D1F8003923F40013D9 -:1053E000C1F8003970470000090100F16043012253 -:1053F00003F56143C9B283F8001300F01F039A401C -:1054000043099B0003F1604303F56143C3F8802126 -:105410001A60704730B50433039C0172002104FB0D -:105420000325C160C0E90653049B0363059BC0E9E3 -:105430000000C0E90422C0E90842C0E90A11436340 -:1054400030BD00000022416AC260C0E90411C0E919 -:105450000A226FF00101FEF789BB0000D0E9043297 -:10546000934201D1C2680AB9181D704700207047E5 -:10547000036919600021C2680132C260C269134425 -:1054800082699342036124BF436A0361FEF762BBF2 -:1054900038B504460D46E3683BB162690020131D30 -:1054A0001268A3621344E36207E0237A33B9294602 -:1054B0002046FEF73FFB0028EDDA38BD6FF0010013 -:1054C000FBE70000C368C269013BC3604369134442 -:1054D00082699342436124BF436A4361002383622C -:1054E000036B03B11847704770B52023044683F35C -:1054F0001188866A3EB9FFF7CBFF054618B186F3DF -:105500001188284670BDA36AE26A13F8015B9342D2 -:10551000A36202D32046FFF7D5FF002383F311884F -:10552000EFE700002DE9F84F04460E46174698466F -:105530004FF0200989F311880025AA46D4F828B035 -:10554000BBF1000F09D141462046FFF7A1FF20B172 -:105550008BF311882846BDE8F88FD4E90A12A7EB2F -:10556000050B521A934528BF9346BBF1400F1BD938 -:10557000334601F1400251F8040B914243F8040B09 -:10558000F9D1A36A403640354033A362D4E90A23F7 -:105590009A4202D32046FFF795FF8AF31188BD4255 -:1055A000D8D289F31188C9E730465A46FBF754FF31 -:1055B000A36A5E445D445B44A362E7E710B5029CC6 -:1055C0000433017204FB0321C460C0E90613002305 -:1055D000C0E90A33039B0363049BC0E90000C0E9F0 -:1055E0000422C0E90842436310BD0000026A6FF064 -:1055F0000101C260426AC0E904220022C0E90A2215 -:10560000FEF7B4BAD0E904239A4201D1C26822B9A4 -:10561000184650F8043B0B607047002070470000AC -:10562000C3680021C2690133C360436913448269BE -:105630009342436124BF436A4361FEF78BBA000083 -:1056400038B504460D46E3683BB1236900201A1DB6 -:10565000A262E2691344E36207E0237A33B9294680 -:105660002046FEF767FA0028EDDA38BD6FF001003A -:10567000FBE7000003691960C268013AC260C269B1 -:10568000134482699342036124BF436A0361002388 -:105690008362036B03B118477047000070B5202385 -:1056A0000D460446114683F31188866A2EB9FFF72A -:1056B000C7FF10B186F3118870BDA36A1D70A36A7D -:1056C000E26A01339342A36204D3E16920460439BC -:1056D000FFF7D0FF002080F31188EDE72DE9F84FA8 -:1056E00004460D46904699464FF0200A8AF31188E9 -:1056F0000026B346A76A4FB949462046FFF7A0FFE8 -:1057000020B187F311883046BDE8F88FD4E90A0745 -:105710003A1AA8EB0607974228BF1746402F1BD915 -:1057200005F1400355F8042B9D4240F8042BF9D1B4 -:10573000A36A40364033A362D4E90A239A4204D3D1 -:10574000E16920460439FFF795FF8BF31188464540 -:10575000D9D28AF31188CDE729463A46FBF77CFE79 -:10576000A36A3D443E443B44A362E5E7D0E90423F9 -:105770009A4217D1C3689BB1836A8BB1043B9B1AD1 -:105780000ED01360C368013BC360C3691A448369C8 -:105790009A42026124BF436A0361002383620123AA -:1057A000184670470023FBE700F0EAB8034B0022DD -:1057B00058631A610222DA60704700BF000C004093 -:1057C000014B0022DA607047000C0040014B586327 -:1057D000704700BF000C0040014B586A704700BF83 -:1057E000000C0040024B034A1A60034A5A6070479B -:1057F00040490020D049002000000220074B4942C8 -:1058000010B55C68201A08401968821A914203D8C2 -:10581000944201D35A6010BD0020FCE740490020AB -:1058200008B5202383F31188FFF7E8FF002383F3F3 -:10583000118808BD4B6843608B688360CB68C36088 -:105840000B6943614B6903628B6943620B680360B8 -:105850007047000008B52F4B40F2FF70D3F8E010FE -:105860000143C3F8E010D3F8082102432A48C3F8E3 -:1058700008212A4AD3F808311146FFF7DBFF00F56B -:10588000806002F11C01FFF7D5FF00F5806002F196 -:105890003801FFF7CFFF00F5806002F15401FFF7F8 -:1058A000C9FF00F5806002F17001FFF7C3FF00F54A -:1058B000806002F18C01FFF7BDFF00F5806002F10E -:1058C000A801FFF7B7FF00F5806002F1C401FFF700 -:1058D000B1FF00F5806002F1E001FFF7ABFF00F5DA -:1058E000806002F1FC01FFF7A5FF02F58C7100F565 -:1058F0008060FFF79FFF00F0FBF8094B0522C3F81B -:1059000098204FF06052C3F89C20064AC3F8A020AC -:1059100008BD00BF0044025800000258646500083A -:1059200000ED00E01F00080308B500F0EBFAFEF7F9 -:1059300049F8104BD3F8DC2042F04002C3F8DC20D9 -:10594000D3F8042122F04002C3F80421D3F8043133 -:10595000094B1A6842F008021A601A6842F0040201 -:105960001A60FEF761FEFEF7CBFCBDE80840FEF7CB -:1059700079BA00BF0044025800180248704700007E -:10598000114BD3F8E82042F00802C3F8E820D3F81E -:10599000102142F00802C3F810210C4AD3F810314C -:1059A000D36B43F00803D363C722094B9A624FF0CD -:1059B000FF32DA6200229A615A63DA605A60012289 -:1059C0005A611A60704700BF004402580010005C22 -:1059D000000C0040094A08B51169D3680B40D9B2E0 -:1059E0009B076FEA0101116107D5202383F311881A -:1059F000FEF718F8002383F3118808BD000C00405F -:105A000008B54FF0FF31394BD3F88020C3F8801030 -:105A1000D3F880200022C3F88020D3F88000D3F888 -:105A20008400C3F88410D3F88400C3F88420D3F82A -:105A30008400D86F40F0FF4040F4FF0040F43F5036 -:105A400040F03F00D867D86F20F0FF4020F4FF00FF -:105A500020F43F5020F03F00D867D86FD3F888007B -:105A60006FEA40506FEA5050C3F88800D3F88800BE -:105A7000C0F30A00C3F88800D3F88800D3F8900078 -:105A8000C3F89010D3F89000C3F89020D3F890009A -:105A9000D3F89400C3F89410D3F89400C3F894207A -:105AA000D3F89400D3F89800C3F89810D3F898006E -:105AB000C3F89820D3F89800D3F88C00C3F88C1062 -:105AC000D3F88C00C3F88C20D3F88C00D3F89C005A -:105AD000C3F89C10D3F89C10C3F89C20D3F89C30DA -:105AE000FEF7F8FEBDE8084000F0DCB900440258BB -:105AF000614B0122C3F80821604BD3F8F42042F037 -:105B00000202C3F8F420D3F81C2142F00202C3F8C9 -:105B10001C210222D3F81C31594BDA605A689104D7 -:105B2000FCD5584A1A6001229A60574ADA6000226E -:105B30001A614FF440429A61514B9A699204FCD524 -:105B40001A6842F480721A604C4B1A6F12F4407F4C -:105B500004D04FF480321A6700221A671A6842F0A4 -:105B600001021A60454B1A685007FCD500221A61E1 -:105B70001A6912F03802FBD1012119604FF08041FF -:105B800059605A67414ADA62414A1A611A6842F416 -:105B900080321A60394B1A689103FCD51A6842F4B6 -:105BA00080521A601A689204FCD53A4A3A499A62BD -:105BB00000225A6319633949DA6399635A64384A8F -:105BC0001A64384ADA621A6842F0A8521A602B4BFB -:105BD0001A6802F02852B2F1285FF9D148229A617E -:105BE0004FF48862DA6140221A622F4ADA644FF079 -:105BF00080521A652D4A5A652D4A9A6532232D4ADC -:105C00001360136803F00F03022BFAD11B4B1A69C0 -:105C100042F003021A611A6902F03802182AFAD116 -:105C2000D3F8DC2042F00052C3F8DC20D3F8042182 -:105C300042F00052C3F80421D3F80421D3F8DC2049 -:105C400042F08042C3F8DC20D3F8042142F08042C5 -:105C5000C3F80421D3F80421D3F8DC2042F0004239 -:105C6000C3F8DC20D3F8042142F00042C3F8042139 -:105C7000D3F80431704700BF00800051004402583F -:105C80000048025800C000F0020000010000FF01BF -:105C90000088900812102000630209012C02040001 -:105CA00047040508FD0BFF01200000200010E00064 -:105CB00000010100002000524FF0B04208B5D2F8B8 -:105CC000883003F00103C2F8883023B1044A136816 -:105CD0000BB150689847BDE80840FEF7F3BC00BF21 -:105CE000484900204FF0B04208B5D2F8883003F0A0 -:105CF0000203C2F8883023B1044A93680BB1D0681C -:105D00009847BDE80840FEF7DDBC00BF48490020C9 -:105D10004FF0B04208B5D2F8883003F00403C2F85F -:105D2000883023B1044A13690BB150699847BDE824 -:105D30000840FEF7C7BC00BF484900204FF0B04202 -:105D400008B5D2F8883003F00803C2F8883023B1D0 -:105D5000044A93690BB1D0699847BDE80840FEF743 -:105D6000B1BC00BF484900204FF0B04208B5D2F89E -:105D7000883003F01003C2F8883023B1044A136A54 -:105D80000BB1506A9847BDE80840FEF79BBC00BFC6 -:105D9000484900204FF0B04310B5D3F8884004F4D0 -:105DA0007872C3F88820A30604D5124A936A0BB10F -:105DB000D06A9847600604D50E4A136B0BB1506B3E -:105DC0009847210604D50B4A936B0BB1D06B9847CB -:105DD000E20504D5074A136C0BB1506C9847A30534 -:105DE00004D5044A936C0BB1D06C9847BDE81040C1 -:105DF000FEF768BC484900204FF0B04310B5D3F817 -:105E0000884004F47C42C3F88820620504D5164A11 -:105E1000136D0BB1506D9847230504D5124A936D4D -:105E20000BB1D06D9847E00404D50F4A136E0BB147 -:105E3000506E9847A10404D50B4A936E0BB1D06EF7 -:105E40009847620404D5084A136F0BB1506F984706 -:105E5000230404D5044A936F0BB1D06F9847BDE873 -:105E60001040FEF72FBC00BF4849002008B503488A -:105E7000FCF726FCBDE80840FEF724BCDC2400202B -:105E800008B50348FCF7CCFCBDE80840FEF71ABC97 -:105E9000FC24002008B5FFF79DFDBDE80840FEF793 -:105EA00011BC0000062108B50846FFF79DFA06213F -:105EB0000720FFF799FA06210820FFF795FA062137 -:105EC0000920FFF791FA06210A20FFF78DFA062133 -:105ED0001720FFF789FA06212820FFF785FA092104 -:105EE0007A20FFF781FA0A215C20FFF77DFA07216B -:105EF0003220FFF779FA0C212520BDE80840FFF792 -:105F000073BA000008B5FFF77BFD00F00FF8FCF74F -:105F100099FEFDF771F8FCF743FFFDF703FBFFF770 -:105F20002DFDBDE80840FFF73FBC00000023054AF7 -:105F300019460133102BC2E9001102F10802F8D111 -:105F4000704700BF484900200B460146184600F044 -:105F500027B80000FEF70CBAFFF7FCBF012838BFD6 -:105F6000012010B504462046FEF7C2F930B900F012 -:105F700007F808B900F00CF88047F4E710BD0000FE -:105F8000024B1868BFF35B8F704700BFC849002001 -:105F900008B5062000F04AF80120FDF7B1FE000028 -:105FA00010B5054C13462CB10A4601460220AFF34A -:105FB000008010BD2046FCE70000000010B501394C -:105FC0000244904201D1002005E0037811F8014F0E -:105FD000A34201D0181B10BD0130F2E71F2938B5CC -:105FE00004460D4604D9162303604FF0FF3038BD38 -:105FF000426C12B152F821304BB9204600F030F813 -:106000002A4601462046BDE8384000F017B8012B6B -:106010000AD0591C03D1162303600120E7E70024AE -:1060200042F82540284698470020E0E7024B014609 -:106030001868FFF7D3BF00BF5C22002038B5074DBA -:1060400000230446084611462B60FDF75DFE431C05 -:1060500002D12B6803B1236038BD00BFCC490020BA -:10606000FDF74CBE034611F8012B03F8012B002A63 -:10607000F9D170470000000001000000000100019C -:106080000000000000000000000000005265717573 -:10609000657374656420746F206572617365206D2B -:1060A0006F7265207468616E2077652063616E0A87 -:1060B00000457261736520436F6D6D616E6420529F -:1060C000656365697665640A0050435420444F4E09 -:1060D000453A2025640A000053544D333248373F77 -:1060E0003F3F0053544D3332483734332F37353325 -:1060F00000000000382B0020FC240020773235718E -:106100002D64747200000000000000000000000018 -:106110000000000000000000B5160008F519000896 -:10612000F5190008B9160008BD160008C1160008C8 -:10613000F5190008F5190008F5190008C51600083A -:10614000C9160008E1160008E9160008F51600084F -:10615000F9160008FD160008DC24002001000000EC -:1061600000000000000000001118000829180008B5 -:10617000B5160008091700085D1800082517000863 -:10618000F518000825190008211700080D17000848 -:106190001D170008C5160008C9160008E1160008FA -:1061A000E9160008F5160008F9160008FD160008A3 -:1061B00000000000000000009D1700080117000803 -:1061C0000517000853464450000000004A45444566 -:1061D000433A204661696C656420746F206465747D -:1061E00065637420666C61736820646576696365B5 -:1061F0003A2025730A004A454445433A20466169DE -:106200006C656420746F20636F6E66696720666CCE -:10621000617368206465766963653A2025730A00B6 -:106220004A454445433A2044657465637465642077 -:10623000466C617368204465766963653A2025730E -:106240000A0045787420466C617368204E6F742094 -:10625000466F756E642100006D74323571007732BF -:10626000357100005862000820BA00005E62000824 -:10627000EF400000FC600008EF700000000000002C -:1062800000000000D520000835230008111A00087E -:10629000151A0008BD1A00089D220008191A0008E6 -:1062A0001D1A0008952100088D1A0008F521000824 -:1062B000F91E0008251A0008211A0008C523000845 -:1062C000851A00080000000000000000812400087A -:1062D000892400086D24000875240008992400080A -:1062E0009D2400084D444D41206661696C757265BE -:1062F0000000000000960000000000000000000008 -:10630000000000000000000000000000000000008D -:106310000D2C0008F92B0008352C0008212C000852 -:106320002D2C0008192C0008052C0008F12B000862 -:10633000412C0008000000001D2D0008092D000858 -:10634000452D0008312D00083D2D0008292D00089D -:10635000152D0008012D0008512D00080000000037 -:1063600001000000000000006D61696E0000000087 -:1063700069646C650000000070630008C02900209B -:10638000382B002001000000C13900080000000087 -:106390004172647550696C6F740025424F415244DC -:1063A000252D424C002553455249414C2500000003 -:1063B00002000000000000003D2F0008AD2F000883 -:1063C00040004000E0430020F043002002000000B5 -:1063D000000000000300000000000000F52F00088E -:1063E0000000000010000000004400200000000039 -:1063F0000100000000000000F04700200101020041 -:10640000013E0008113D0008AD3D0008913D000827 -:10641000430000001864000809024300020100C0A4 -:1064200032090400000102020100052400100105E8 -:10643000240100010424020205240600010705824C -:10644000030800FF09040100020A0000000705011B -:106450000240000007058102400000001200000019 -:106460006464000812011001020000400912415743 -:1064700000020102030100000403090425424F4108 -:10648000524425005350526163696E6748370030AB -:10649000313233343536373839414243444546008A -:1064A0000000002000000200020000000000003098 -:1064B00000000400000000000000002400000800AC -:1064C000040000000004000000FC000002000000C6 -:1064D00000000430008000000000000000000038D0 -:1064E0000000010001000000400000528000005246 -:1064F000C0000052000100524001005280010052D1 -:10650000C0010052000200524002005280020052BC -:10651000C0020052000300524003005280030052A8 -:10652000C00300520004005200000000493100087E -:1065300001340008AD340008400040002849002024 -:106540002849002001000000384900208000000098 -:1065500040010000080000000001000000040000ED -:10656000080000000000806A00000000AAAAAAAA91 -:1065700000000064FFFF00000000000000A00A000F -:10658000240020A100000000AAAAAAAA000000512D -:10659000FFFF0000000900000009004400000000A7 -:1065A00000000000AAAAAAAA00000000FFFF000045 -:1065B00000000000000000000000800A0000000051 -:1065C000AAAAAAAA00000000FFFF00000000000025 -:1065D000009099006000400000000000AAAAAAAA4A -:1065E00000004000F7FF000000090000000000006C -:1065F0000000000000000000AAAAAAAA00000000F3 -:10660000FFFF00000000000000000000000000008C -:1066100000000000AAAAAAAA00000000FFFF0000D4 -:10662000000000000000000000000000000000006A -:10663000AAAAAAAA00000000FFFF000000000000B4 -:10664000000000000000000000000000AAAAAAAAA2 -:1066500000000000FFFF000000000000000000003C -:106660000000000000000000AAAAAAAA0000000082 -:10667000FFFF00000000000000000000000000001C -:1066800000000000AAAAAAAA00000000FFFF000064 -:106690000000000000000000489CFF7F0100000097 -:1066A0002404000000000000000000000000E900D9 -:1066B000FF00000000000000D86000083F0000005C -:1066C00050040000E36000083F0000000096000056 -:1066D0000000080096000000000800000400000010 -:1066E00078640008000000000000000000000000C6 -:1066F00000000000000000000000000060220020F8 -:106700000000000000000000000000000000000089 -:106710000000000000000000000000000000000079 -:106720000000000000000000000000000000000069 -:106730000000000000000000000000000000000059 -:106740000000000000000000000000000000000049 -:106750000000000000000000000000000000000039 +:1000000000060020F5050008B51A0008311A00089E +:10001000891A0008311A00085D1A0008F70500085F +:10002000F7050008F7050008F7050008155B00084C +:10003000F7050008F7050008F7050008F7050008B0 +:10004000F7050008F7050008F7050008F7050008A0 +:10005000F7050008F70500080D5F0008395F000884 +:10006000655F0008915F0008BD5F0008F7050008A4 +:10007000F7050008F7050008F7050008F705000870 +:10008000F7050008F7050008F7050008F705000860 +:10009000F7050008F7050008F7050008E95F000804 +:1000A000F7050008F7050008F7050008F705000840 +:1000B000F7050008F7050008F7050008F705000830 +:1000C000F7050008F7050008F7050008F705000820 +:1000D000F7050008D5600008F7050008F7050008D7 +:1000E0004D600008F7050008F7050008F70500084F +:1000F000F7050008F7050008F7050008F7050008F0 +:10010000F7050008F7050008E9600008F705000892 +:10011000F7050008F7050008F7050008F7050008CF +:10012000F7050008F7050008F7050008F7050008BF +:10013000F7050008F7050008F7050008F7050008AF +:10014000F7050008F7050008F7050008F70500089F +:10015000F7050008F7050008F7050008F70500088F +:10016000F7050008F7050008F7050008F70500087F +:10017000F70500085D540008F7050008F7050008BA +:10018000F7050008F7050008F7050008F70500085F +:10019000F7050008F7050008F7050008F70500084F +:1001A000F7050008F7050008F7050008F70500083F +:1001B000C1600008F7050008F7050008F70500080A +:1001C000F7050008F7050008F7050008F70500081F +:1001D000F705000849540008F7050008F70500086E +:1001E000F7050008F7050008F7050008F7050008FF +:1001F000F7050008F7050008F7050008F7050008EF +:10020000F7050008F7050008F7050008F7050008DE +:10021000F7050008F7050008F7050008F7050008CE +:10022000F7050008F7050008D5480008F70500089D +:10023000F7050008F7050008F7050008F7050008AE +:10024000F7050008F7050008F7050008F70500089E +:10025000F7050008F7050008F7050008F70500088E +:10026000F7050008F7050008F7050008F70500087E +:10027000F7050008F7050008F7050008F70500086E +:10028000F7050008F7050008F7050008F70500085E +:10029000F7050008F7050008F7050008F70500084E +:1002A000F7050008F7050008F7050008F70500083E +:1002B000F7050008F7050008F7050008F70500082E +:1002C000F7050008F7050008F7050008F70500081E +:1002D000F7050008F7050008F7050008F70500080E +:1002E000D9070008091A00082125000800000000AD +:1002F00053B94AB9002908BF00281CBF4FF0FF318D +:100300004FF0FF3000F074B9ADF1080C6DE904CE88 +:1003100000F006F8DDF804E0DDE9022304B07047E0 +:100320002DE9F047089D04468E46002B4DD18A42A8 +:10033000944669D9B2FA82F252B101FA02F3C2F1DB +:10034000200120FA01F10CFA02FC41EA030E94406C +:100350004FEA1C48210CBEFBF8F61FFA8CF708FB8D +:1003600016E341EA034306FB07F199420AD91CEB65 +:10037000030306F1FF3080F01F81994240F21C8197 +:10038000023E63445B1AA4B2B3FBF8F008FB1033DF +:1003900044EA034400FB07F7A7420AD91CEB040414 +:1003A00000F1FF3380F00A81A74240F207816444E4 +:1003B000023840EA0640E41B00261DB1D440002369 +:1003C000C5E900433146BDE8F0878B4209D9002DCD +:1003D00000F0EF800026C5E9000130463146BDE857 +:1003E000F087B3FA83F6002E4AD18B4202D38242C1 +:1003F00000F2F980841A61EB030301209E46002D70 +:10040000E0D0C5E9004EDDE702B9FFDEB2FA82F2C4 +:10041000002A40F09280A1EB0C014FEA1C471FFA22 +:100420008CFE0126200CB1FBF7F307FB131140EA09 +:1004300001410EFB03F0884208D91CEB010103F1D6 +:10044000FF3802D2884200F2CB804346091AA4B298 +:10045000B1FBF7F007FB101144EA01440EFB00FE6C +:10046000A64508D91CEB040400F1FF3102D2A645D1 +:1004700000F2BB800846A4EB0E0440EA03409CE770 +:10048000C6F12007B34022FA07FC4CEA030C20FA1D +:1004900007F401FA06F31C43F9404FEA1C4900FA3D +:1004A00006F3B1FBF9F8200C1FFA8CFE09FB1811BA +:1004B00040EA014108FB0EF0884202FA06F20BD92D +:1004C0001CEB010108F1FF3A80F08880884240F27D +:1004D0008580A8F102086144091AA4B2B1FBF9F0C1 +:1004E00009FB101144EA014100FB0EFE8E4508D9BC +:1004F0001CEB010100F1FF346CD28E456AD9023841 +:10050000614440EA0840A0FB0294A1EB0E01A14225 +:10051000C846A64656D353D05DB1B3EB080261EB93 +:100520000E0101FA07F722FA06F3F1401F43C5E96D +:10053000007100263146BDE8F087C2F12003D840A3 +:100540000CFA02FC21FA03F3914001434FEA1C47E5 +:100550001FFA8CFEB3FBF7F007FB10360B0C43EAD7 +:10056000064300FB0EF69E4204FA02F408D91CEB87 +:10057000030300F1FF382FD29E422DD90238634485 +:100580009B1B89B2B3FBF7F607FB163341EA034125 +:1005900006FB0EF38B4208D91CEB010106F1FF3874 +:1005A00016D28B4214D9023E6144C91A46EA00466B +:1005B00038E72E46284605E70646E3E61846F8E6FD +:1005C0004B45A9D2B9EB020864EB0C0E0138A3E746 +:1005D0004646EAE7204694E74046D1E7D0467BE727 +:1005E000023B614432E7304609E76444023842E79F +:1005F000704700BF02E000F000F8FEE772B638482E +:1006000080F30888374880F30988374837490860FD +:1006100040F20000CCF200004EF63471CEF2000140 +:100620000860BFF34F8FBFF36F8F40F20000C0F23E +:10063000F0004EF68851CEF200010860BFF34F8FF4 +:10064000BFF36F8F4FF00000E1EE100A4EF63C71E1 +:10065000CEF200010860062080F31488BFF36F8F8C +:1006600004F02AF904F0CCF805F0B2F94FF0553057 +:100670001F491B4A91423CBF41F8040BFAE71D4950 +:10068000184A91423CBF41F8040BFAE71A491B4A49 +:100690001B4B9A423EBF51F8040B42F8040BF8E79B +:1006A00000201849184A91423CBF41F8040BFAE770 +:1006B00004F0E4F805F002FA144C154DAC4203DAEC +:1006C00054F8041B8847F9E700F050F8114C124D1C +:1006D000AC4203DA54F8041B8847F9E704F0CCB8BD +:1006E00000060020002200200000000808ED00E0C5 +:1006F0000000002000060020F06800080022002012 +:10070000C0220020C0220020904A0020E002000801 +:10071000EC020008EC020008EC0200082DE9F04FA2 +:100720002DED108AC1F80CD0D0F80CD0BDEC108A99 +:10073000BDE8F08F002383F311882846A0470020EE +:1007400003F026FAFEE703F03FF900DFFEE70000C2 +:10075000054B10B504460360806810B103685B6800 +:100760009847204610BD00BFE064000838B503F08C +:100770006DFF054604F03AF80446F0B9144B9D426B +:100780001DD001339D4241F2883512BF0446002539 +:100790000124002003F064FF0CB100F09FF80D4C21 +:1007A00000F02EFF00F0C8FD204601F0F1FC40B93A +:1007B00044F6206003F0F2F9F6E70025E9E7054684 +:1007C000E7E7284600F046F900F088F8F9E700BFAF +:1007D000010007B0C02200200448054B054A036011 +:1007E00000230549836005F0D9BC00BFC02200206A +:1007F000E0640008D42400205107000808B500F088 +:1008000067FDA0F120035842584108BD07B50421F7 +:1008100001900DEB010000F079FD03B05DF804FBE1 +:1008200007B541F21203022101A8ADF8043000F02F +:100830006DFD03B05DF804FB38B5302383F31188F8 +:10084000174803680BB103F087FA0023154A4FF4E9 +:100850007A71134803F076FA002383F31188124C5F +:10086000236813B12368013B2360636813B1636895 +:10087000013B63600D4D2B7833B963687BB902206F +:1008800000F028FE322363602B78032B07D16368C6 +:100890002BB9022000F01EFE4FF47A73636038BD5E +:1008A000502300203908000870240020682300200D +:1008B000084B187003280CD8DFE800F00805020880 +:1008C000022000F0FFBD022000F0F2BD024B00222A +:1008D0005A6070476823002070240020F7B55648FE +:1008E00001A901F0CDFD002800F0A380534B544A2C +:1008F0001C461968013100F0998004339342F8D105 +:100900006268504B9A4240F291804F4BDB6803F192 +:10091000104303F580139A4280F08880002000F095 +:1009200025FD0220FFF7C4FF484B0021D3F8E82043 +:10093000C3F8E810D3F81021C3F81011D3F8102130 +:10094000D3F8EC20C3F8EC10D3F81421C3F8141139 +:10095000D3F81421D3F8F020C3F8F010D3F81821FD +:10096000C3F81811D3F81821D3F8802042F00062A0 +:10097000C3F88020D3F8802022F00062C3F88020E2 +:10098000D3F88020D3F8802042F00072C3F8802092 +:10099000D3F8802022F00072C3F88020D3F8803092 +:1009A00072B64FF0E023C3F8084DD4E90004BFF35A +:1009B0004F8FBFF36F8F264AC2F88410BFF34F8F5B +:1009C000536923F480335361BFF34F8FD2F88030E3 +:1009D00043F6E076C3F3C905C3F34E335B0103EA84 +:1009E000060C29464CEA81770139C2F87472F9D2B3 +:1009F000203B13F1200FF2D1BFF34F8FBFF36F8F66 +:100A0000BFF34F8FBFF36F8F536923F400335361EC +:100A10000023C2F85032BFF34F8FBFF36F8F3023E4 +:100A200083F31188854680F308882047024801F047 +:100A300087F803B0F0BD00BFC02200200000109076 +:100A400020001090FFFF0F90002200200044025869 +:100A500000ED00E02DE9F04FB34B9FB02022FF21C5 +:100A6000089016A89E68DB68079300F073FDAF4AF4 +:100A70001378A3B90121AE4811700360302383F3CA +:100A8000118803680BB103F067F90023A94A4FF4FA +:100A90007A71A74803F056F9002383F31188089B65 +:100AA00013B1A54B089A1A60A44A1378032B03D0FC +:100AB00000231370A04A53600023089DA04F98465E +:100AC0009B46CDE90533012000F0FCFC25B19A4B93 +:100AD0001B68002B00F08783002000F0F9FB0E90CC +:100AE0000E9B002BF2DB012000F0E2FC0E9B213B71 +:100AF0001F2BE8D801A252F823F000BF7D0B00089D +:100B0000A50B00083F0C0008C70A0008C70A000828 +:100B1000C70A00082B0F000829110008C10F0008A0 +:100B2000A7100008CD100008F3100008C70A00083D +:100B300005110008C70A0008711100081D0C000803 +:100B4000C70A0008ED110008DD0C0008150E0008AA +:100B5000C70A00081D100008C70A0008C70A0008D5 +:100B6000C70A0008C70A0008C70A0008C70A000821 +:100B7000C70A0008C70A00083F0C00080220FFF758 +:100B80003DFE002840F05B83089B0221069A11A8D5 +:100B9000002A08BF1D4641F21233ADF8443000F080 +:100BA000B5FB90E74FF47A7000F092FB041EEBDB8C +:100BB0000220FFF723FE0028E6D0013C052C00F2BE +:100BC0004083DFE804F0030A0D10133905230421E4 +:100BD00011A8119300F09AFB17E004215248F9E79D +:100BE00004215848F6E704215748F3E74FF01C0961 +:100BF000484609F1040900F0BBFB0421119011A83B +:100C000000F084FBB9F12C0FF2D10120059B4FF0CD +:100C1000000B00FA04F41C43E3B2059300F0E6FC79 +:100C2000B8F1000F05D0059B03F00B030B2B08BF99 +:100C30000025FFF7F5FD46E704214448CAE7B8F16F +:100C4000000FA1D0059B03F00B030B2B9CD10220BE +:100C5000FFF7D4FD0446002896D001204FF000088D +:100C600000F084FB0220FFF723FE5FFA88F9484674 +:100C700000F08CFB0546B8B10E99484608F1010812 +:100C8000A1F140025142514100F090FB0028ECD10B +:100C90000546069441F21213022111A8A046ADF8B0 +:100CA000443000F033FB0EE72E46DFF87C80012055 +:100CB000FFF7FEFDD8F80830B34207D9304600F000 +:100CC00057FB013040F0C0820436F3E700261B4B8F +:100CD000A04606941E70184B5E609FE7B8F1000FA7 +:100CE0003FF452AF059B03F00B030B2B7FF44CAF8B +:100CF00064210FA800F000FB814600287FF444AF78 +:100D00000220FFF77BFD044600283FF43DAF3A6A1E +:100D10007B6A0F9953438DF837908B421AD20C4857 +:100D200000F0E2FB30E700BF002200206C2400202E +:100D30005023002039080008702400206823002078 +:100D4000C022002004220020082200200C220020C3 +:100D5000E06200084FF4801AAC48C846BAFBF2FAC9 +:100D600000F0C2FBFFF75CFD01210DF1370000F040 +:100D7000CDFA0F9B434541D9002310AA514638466E +:100D8000CDE9103311AB00F0DFFE002882D000F077 +:100D900099FE109B00EB030901210DF1370000F0D3 +:100DA000B5FA00F08FFE484520D9384601F002F927 +:100DB00080B964210F9B96480AF1010A01FB08F1F2 +:100DC000B1FBF3F18DF83710C9B200F08DFB3B6A2F +:100DD0009844CEE700F076FE119B184448453FF654 +:100DE00059AF00F06FFE109B00EB0309109B4FF40E +:100DF0007A70A3FB000302F0D1FECDE7642301214A +:100E00000DF13700A0468DF8373000F07FFA00234F +:100E1000079303E7B8F1000F3FF4B6AE059B03F06C +:100E20000B030B2B7FF4B0AE0220FFF741FD322005 +:100E300000F04EFAB0F1000AFFF6A6AE079BD146CD +:100E400053440993734B099ADB689A423FF69CAE70 +:100E5000BAF5807F3FF798AE6F4A0024A2450A9208 +:100E60000EDD4FF47A7000F033FA0E900E9B002BDB +:100E7000FFF68AAE0E9B01340A9A02F8013BEDE7B9 +:100E8000C820FFF7BBFC044600283FF47DAE079B5B +:100E90001F2B11D8C3F1200223F0030016AB5E49CB +:100EA0005245184428BF52460A9200F021FB0A9A84 +:100EB000FF21594800F04EFB00239846CDE910333E +:100EC000079B03F580130B93B9F1000F02D1A046E5 +:100ED000099B9DE711AB504A0B993846029310AB22 +:100EE0004244414401930FAB00934B4601F034FA66 +:100EF00000283FF4CFAE00F0E7FD0F9B82460A9139 +:100F00009844A9EB030900F0DFFD109B0A9A13EB4C +:100F10000A0342F10002834272EB0103F3D2384626 +:100F200001F048F80028EED1CEE7B8F1000F3FF409 +:100F30002BAE059B03F00B030B2B7FF425AE022099 +:100F4000FFF7B6FC322000F0C3F9B0F1000AFFF65B +:100F50001BAE1AF003047FF417AE2E4A0AEB060309 +:100F6000926893423FF610AEBAF5807F3FF70CAE21 +:100F7000DFF8A490A2450DDD4FF47A7000F0A8F9D7 +:100F80000E900E9B002BFFF6FFAD0E9B013409F86F +:100F9000013BEFE7C820FFF731FC044600283FF48F +:100FA000F3ADCAF387021C4930464FEAAA0900F0A4 +:100FB000D9FA804600283FF46DAE06EB89062DE68F +:100FC0000220FFF71BFC00283FF4DEAD00F00CFA16 +:100FD00000283FF4D9AD4FF00009DFF838A04C46A7 +:100FE000DAF808304B450CD9484609F1040900F0FD +:100FF000BFF90422119011A9204601F0B7FA044666 +:10100000EEE72046FFF702FC08E600BF0563000894 +:101010001D630008002200206C230020642110A81A +:1010200000F06AF9044600287FF4AEAD0220FFF715 +:10103000E5FB00283FF4A8AD109BA14603F0030A8E +:101040001099A1EB0A01A1421BD91F2C11D8169BA4 +:1010500001330ED024F003031EAA134453F8203C9E +:1010600011934846042211A9043401F07FFA814605 +:10107000E6E7042311AA04F58011384601F0B8F917 +:10108000EFE7BAF1000F0CD0534611AA01F5801119 +:10109000384601F0ADF94846524611A901F066FA0A +:1010A00081464846AEE70023642111A8119300F061 +:1010B00023F900287FF468AD0220FFF79FFB00288A +:1010C0003FF462AD119800F085F99BE7002364219D +:1010D00011A8119300F010F900287FF455AD0220FB +:1010E000FFF78CFB00283FF44FAD119800F074F926 +:1010F00088E70220FFF782FB00283FF445AD00F0AF +:1011000083F97FE70220FFF779FB00283FF43CAD2D +:1011100011A9142000F07EF90990FFF777FB0999D7 +:1011200011A800F0F3F879E5322000F0D1F8041EA0 +:10113000FFF62AADA3077FF427AD444A04EB0B0367 +:10114000926893423FF620AD0220FFF757FB00283C +:101150003FF41AAD24F003045C44A3453FF45EADB4 +:1011600058460BF1040B00F003F9FFF74FFBF4E7CF +:101170004FF47A70FFF742FB00283FF405AD00F012 +:1011800033F980B1169B013328D011AB16AA4FF466 +:1011900080113846029310AB01930FAB00932023CC +:1011A00001F0DAF808B9444674E500F08DFC284EE9 +:1011B00004460D4600F088FC109B1B1945F1000207 +:1011C000834272EB0103F5D2304600F0F3FE0028B3 +:1011D000F0D12022FF2116A800F0BCF9FFF720FB78 +:1011E0001C4802F0DBFC1FB0BDE8F08FB8F1000F27 +:1011F0003FF4CAAC059B03F00B030B2B7FF4C4AC8C +:101200000023642111A8119300F076F80446002809 +:101210007FF4BAAC0220FFF7F1FA814600283FF4D0 +:10122000B3ACFFF7FDFA41F2883002F0B7FC119839 +:1012300000F020FAC846254600F0D8F943E480467D +:10124000ECE44FF0000B9FE4069423E5002200201D +:10125000C0220020A0860100F7B50C46184E4FF4BE +:101260007A71054602FB01F396F90020501C0BD160 +:101270001448294601930268176A2246B8478442F7 +:10128000019B03D1002310E0002AF1D096F9002041 +:10129000511C01D0012A0DD10B4829460268166A5B +:1012A0002246B047844205D10123084A0120137029 +:1012B00003B0F0BD4FF4FA7002F070FC0020F7E7C5 +:1012C00010220020F82B002000250020BC24002044 +:1012D000002307B5024601210DF107008DF8073004 +:1012E000FFF7BAFF20B19DF8070003B05DF804FBDB +:1012F0004FF0FF30F9E700000A46042108B5FFF778 +:10130000ABFF80F00100C0B2404208BD074B0A4667 +:1013100030B41978064B53F8214001462368204623 +:10132000DD69044BAC4630BC604700BFBC240020E4 +:1013300048630008A086010070B50A4E00240A4DDB +:1013400002F06AFF308028683388834208D902F0AF +:101350005FFF2B6804440133B4F5003F2B60F2D3E8 +:1013600070BD00BFBE2400207824002003F008B820 +:1013700000F1006000F500300068704700F1006087 +:10138000920000F5003002F07FBF0000054B1A68A4 +:10139000054B1B889B1A834202D9104402F038BFC8 +:1013A0000020704778240020BE24002038B5044671 +:1013B000074D29B128682044BDE8384002F034BF09 +:1013C0002868204402F02AFF0028F3D038BD00BF6F +:1013D000782400200020704700F1FF5000F58F10A6 +:1013E000D0F8000870470000064991F8243033B166 +:1013F00000230822086A81F82430FFF7BFBF0120CC +:10140000704700BF7C240020014B1868704700BF64 +:101410000010005C244BF0B51A680446234BC2F35D +:101420000B06120C1F885868BE4293F9085028D04A +:101430009F89BE4206D101200C2505FB0033586868 +:1014400093F9085041F201039A421CD041F2030380 +:101450009A421AD042F201039A4218D042F2030390 +:101460009A4208BF5625621E0B46441E0A44934208 +:101470000FD214F9016F581C6EB1034600F8016CCD +:10148000F5E70020D8E75A25EDE75925EBE7582581 +:10149000E9E7184605E02C2482421C7001D9981C0B +:1014A0005D70401AF0BD00BF0010005C14220020E7 +:1014B000022803D1024B4FF400229A61704700BF0B +:1014C00000100258022802D1014B08229A6170478D +:1014D00000100258022804D1024A536983F008031D +:1014E00053617047001002580FB404B070470000F9 +:1014F000002310B5934203D0CC5CC4540133F9E708 +:1015000010BD0000013810B510F9013F3BB191F951 +:1015100000409C4203D11AB10131013AF4E71AB1FB +:1015200091F90020981A10BD1046FCE701380139E6 +:1015300010F9013F11F9012F0BB19342F8D0981A1D +:101540007047000003460246D01A12F9011B002919 +:10155000FAD1704702440346934202D003F8011BBC +:10156000FAE770472DE9F8431F4D144607468846B1 +:1015700095F8242052BBDFF870909CB395F8243086 +:101580002BB92022FF2148462F62FFF7E3FF95F891 +:1015900024004146C0F1080205EB8000A24228BFAA +:1015A0002246D6B29200FFF7A3FF95F82430A41B81 +:1015B00017441E449044E4B2F6B2082E85F8246025 +:1015C000DBD1FFF711FF0028D7D108E02B6A03EB2E +:1015D00082038342CFD0FFF707FF0028CBD1002042 +:1015E000BDE8F8830120FBE77C240020024B1A7839 +:1015F000024B1A70704700BFBC240020102200204C +:1016000038B5164C164D204601F036FC29462046CA +:1016100001F05EFC2D681348D5F89020D2F804380C +:1016200043F00203C2F8043802F0B8FA0E49284623 +:1016300001F05CFDD5F890200C48D2F804380C4934 +:10164000A04223F00203C2F804384FF4E1330B60E8 +:1016500003D0BDE8384001F06DBB38BDF82B002049 +:101660003C66000840420F00446600080025002048 +:10167000A424002038B50B4B04461A780A4B53F8C3 +:1016800022500A4B9D420CD0094B002118221846CB +:10169000FFF760FF046001462846BDE8384001F0CE +:1016A00049BB38BDBC24002048630008F82B00204B +:1016B000A424002038B5084B044615460175436044 +:1016C0000A21243003F000F804F128002A460A21F8 +:1016D00002F0FAFF204638BD28650008F8B51E461E +:1016E0001B6805460C4617461BB9236863B90124DD +:1016F00008E0BDF818203146806A02F0FDFF00289E +:10170000F3D100242046F8BD21463A46686A03F02A +:1017100029F804460028EAD13368002BF1D0A86AE2 +:1017200003F054F8EEE7000038B50D4611460446C4 +:101730001A4611B1806A03F007F82DB12946606A94 +:10174000BDE8384003F03AB838BD000070470000EB +:1017500070470000002070470020704713B56C46AA +:1017600000F1140384E8060094E8030083E8050010 +:1017700002B010BD0020704713B56C4600F10C0399 +:1017800084E8060094E8030083E8050002B010BD79 +:101790000023C0E90333704782B002AB03E90600BF +:1017A00002B070477047000000207047704700008B +:1017B00000207047002070470120704782B0002051 +:1017C00002A901E90C0002B0704700000020704738 +:1017D000002070470B6883634B6843638B68C36367 +:1017E000CB6803640B6943647047000038B5036B32 +:1017F0000446154D1B7955F8330001F073FFD4E909 +:101800000B231B7955F8331002F1300349689942D4 +:1018100018D000231363E26A5363D4E90B12537C9C +:10182000581E137C92681B0443EA002313438B6306 +:10183000D4E90B131B79303155F83300BDE838403B +:1018400001F0E4BE38BD00BFB0630008F8B51D4F1D +:1018500005460E4611463868FFF768FE78BB746887 +:101860003B7924B394F82C209A420BD02468F8E7F3 +:101870000122B521FFF71EFF736823603B79746076 +:1018800084F82C30482004F093FC68B100220271E7 +:10189000C0E90322C0E90522027A42F0070202727F +:1018A000094AC0E90B47026028602846F8BD40207D +:1018B00004F07EFC04460028DAD12C60F5E7002312 +:1018C0002B60F2E7C0240020C0630008044B10B571 +:1018D00004460360406A08B104F068FC204610BD6D +:1018E0006463000810B50446FFF7F0FF204604F0DB +:1018F0005BFC204610BD000008B519B1FFF776FF6C +:10190000012008BD036B1A79024B53F8320001F035 +:10191000EDFEF5E7B06300082DE9FF41DDF8288012 +:101920000546174603911FFA88F60293FFF75EFFFC +:1019300002ABBAB203A9E86A0096FFF7CFFE0446ED +:1019400038B900212846FFF7D7FF204604B0BDE88C +:10195000F081AFB92B6B05F134011A79134B53F8B1 +:101960003200B8F1000F19D101F05EFE80F00104E1 +:10197000E4B23346E86ADDE90221FFF7D5FEE0E78D +:10198000029B83B92B6B3A46084805F134011C7958 +:10199000039B50F8340001F05DFEE7E7029B4246EE +:1019A00001F06EFEE2E70024E3E700BFB063000849 +:1019B00013B504460191FFF719FF019A236B04F157 +:1019C00034011879054B53F8300001F06FFE002107 +:1019D0002046FFF791FF012002B010BDB063000860 +:1019E00010B50446FFF702FF236B1A79054B53F835 +:1019F000320001F069FE00212046FFF77DFF012043 +:101A000010BD00BFB0630008064B0121064A1A60F2 +:101A100000221A71054AC3E902124FF48C721A822D +:101A2000704700BFC02400205063000800E1F505A6 +:101A300000B59BB0EFF3098168226846FFF758FDB7 +:101A4000EFF30583044B9A6BDA6A9A6A9A6A9A6A88 +:101A50009A6A9A6A9B6AFEE700ED00E000B59BB0C7 +:101A6000EFF3098168226846FFF742FDEFF3058333 +:101A7000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6AF9 +:101A8000FEE700BF00ED00E000B59BB0EFF3098179 +:101A900068226846FFF72CFDEFF30583034B5A6B72 +:101AA0009A6A9A6A9A6A9A6A9B6AFEE700ED00E06F +:101AB000FEE70000FEE700000FB408B5029801F051 +:101AC000F9FFFEE702F062BD02F03ABD806970479F +:101AD000C0697047006A7047406A7047806A704703 +:101AE000F0B5ADF2044D0E46054600214FF47F726D +:101AF00001A80091FFF72EFD2C6A744301362B6A72 +:101B00007343A34216D92B686A46214628465F686C +:101B10004FF48063B84770B16A464FF4806312F89F +:101B2000011BFF290AD1013B9BB2002BF7D104F521 +:101B30008064E4E701200DF2044DF0BD0020FAE7D7 +:101B400080680368DB69184730B5456A85B004468C +:101B50008D420FD30568CDE90023026A03ABAD6A5D +:101B60005143A84720B1206A039BC31A58425841E9 +:101B700005B030BD0020FBE7F0B5C56987B004466D +:101B80008D4212D30C9F866905687143CDE90137F8 +:101B900005AB00936D69036AA84720B1A069059B56 +:101BA000C31A5842584107B0F0BD0020FBE70000BF +:101BB000F0B5662389B0002405464FF4807680682E +:101BC000079403A9CDE90336CDE9054403685B69B1 +:101BD0009847A86822462146036800941F69234657 +:101BE000B847A8689923079403A9CDE90336CDE93E +:101BF000054403685B699847A86822462146036844 +:101C000000941D692346A84709B0F0BD254B2DE976 +:101C1000F04F1B789FB0002504468DF828304FF018 +:101C20009F0E80684FF00123ADF8295005A9099552 +:101C3000CDE905E3CDE9075503685B699847A068DE +:101C400003222946036800922A461E690AABB04760 +:101C500028B394F88C20144B9DF8281003EBC20392 +:101C60001A7991421BD19DF829205B799A4216D1AD +:101C7000A0684FF05A0C0D4B082605A90996CDE92E +:101C800005C3CDE9075503685B699847A0682A46F4 +:101C90002946036800961F690AABB84740B900207F +:101CA00048E100BFC8620008C064000800250001C8 +:101CB0000422B1490AA804F0ABFA05460028EED187 +:101CC000BDF82C306FF48277A3813B44012BE6D81A +:101CD000079605A9CDE90A00A06803685B699847E3 +:101CE000A0682A462946036800961E690AABB047D9 +:101CF0000028D4D0DDE90A361A0202F4706242EA02 +:101D00001662FF2ACBD11B0E26F07F4650222946B1 +:101D1000142B26610AA828BF1423A373FFF71AFC0B +:101D2000A068079605A903685B699847A068A37B2C +:101D3000294602689B0000930AAB16692A46B04701 +:101D40000028ACD00B990029A9DBC9086FF07E43AD +:101D5000149D4FF0010E994228BF1946C5F3031395 +:101D60000EFA03F221FA03F303916161A261E361C8 +:101D7000002B94D02646A44600274FF002081EAA46 +:101D8000C7F3460302EB830353F834AC07F00103B7 +:101D90001B01DA1D0EFA03F908FA02F2A2EB09029E +:101DA00002EA0A02DA401AD003F108090F330EFAE8 +:101DB00002F2216A08FA03F30EFA09FBCCF830208C +:101DC0008A42A3EB0B0B0BEA0A0A2AFA09F98CF8F0 +:101DD0002C90A36A88BF2262934288BFA262013717 +:101DE0000CF1100C042FCAD1236A4FF0020C039A95 +:101DF0004FF0010E139F9A4224BFB2FBF3F16162D0 +:101E000007F00F0138BF01234FF0090201F1010172 +:101E100038BF63624900336B33B3531C0EFA02F8C8 +:101E2000A2F105090CFA03F30EFA09FAA3EB080371 +:101E300002F1FF380CFA08F83B40A8EB0A08D3403F +:101E400008EA070828FA09F877D0012B77D0022B87 +:101E500077D0032B08BF4FF47A735FFA88F808FB3A +:101E6000033373634B43B36307321036252AD2D151 +:101E700015F0C04FC5F3417365D0012B65D0022B1F +:101E80000CBF4FF47A634FF47A43C5F3046202FB4C +:101E90000333E3664B432367199B9E0758D0062301 +:101EA00084F8743015F4005F05F00F03C5F30425C2 +:101EB00014BF40220822013305FB02255B00A56701 +:101EC0005D430A9B9F02E5677FF5E9AE0C9B1A0A0A +:101ED00084F88020C3F3421203F01F0384F88820A3 +:101EE00084F88130189BC3F3025213F4401F84F826 +:101EF00083207FF4D4AEDE0602D5042A7FF4CFAE71 +:101F000003F40072002A14BF0122002284F8872003 +:101F100004D0DD0324D5002384F88930179B1A07E9 +:101F200022D5002384F88630702384F8853001237D +:101F300084F88D301FB0BDE8F08F01238DE71023AA +:101F40008BE7802389E710239FE74FF480739CE79A +:101F5000590701D55023A3E713F0780FA2D09EE6CE +:101F60009903DBD50123D7E75B07E0D5012384F88C +:101F700086300523D9E700BF2064000830B58BB058 +:101F800000240546806803924FF00122059105A9BF +:101F9000CDE90624CDE90844026852699047A86853 +:101FA0000121039B02680091214615692246A8473A +:101FB0000BB030BD13B504460DF1070290F8851043 +:101FC000FFF7DCFF94F886309DF807001BB100F0A6 +:101FD000010002B010BDC043C0F3C010F9E700001B +:101FE00030B54FF001238BB00024054680688DF892 +:101FF0000F20059105A9CDE90634CDE90844036811 +:102000005B699847A86801220DF10F0103680094ED +:102010001D692346A8470BB030BD0000F7B5174631 +:102020000DF1070206461D46FFF7A8FF68B19DF8AF +:10203000074039469DF82020304624EA05042A400E +:1020400022438DF80720FFF7CBFF03B0F0BD00005F +:1020500030B54FF4807389B0002405468068039141 +:1020600003A9CDE90434CDE9064403685B699847C8 +:10207000A86822462146036800941D692346A847A4 +:1020800009B030BD10B5044623682046DB6A984786 +:102090000028F9D110BD000010B590F87430044646 +:1020A0005BB1FFF7EFFF012394F87410204684F82A +:1020B0008E30BDE81040FFF7CBBF012010BD0000FF +:1020C00010B590F87430044653B1FFF7DBFF0123DD +:1020D0002046042184F88E30BDE81040FFF7B8BFD9 +:1020E000012010BD70B590F883308AB00446042BEF +:1020F00048D10DF10E020521FFF740FF00282FD037 +:102100000DF10F0235212046FFF738FF40B320467E +:102110001E4EFFF7C1FF2046FFF7B4FF05AD0FCEFF +:102120000FC5336805A99DF80E202B609DF80F3070 +:10213000A06843F002038DF810208DF80F308DF861 +:10214000113003685B699847A068002304A90268FE +:10215000009315690222A84728B92046FFF7B0FF6F +:1021600000200AB070BD2046FFF7AAFF0DF10F0254 +:1021700035212046FFF702FF0028F1D09DF80F30EF +:102180009B07EDD501202071EBE700BFCC62000872 +:102190002DE9F341002304468068A36010B1036871 +:1021A0005B6898470025244E244F56F8352001A837 +:1021B00039465FFA85F8FFF749FB019BA0680022CA +:1021C000A360019210B103685B689847019810B151 +:1021D00003685B689847A368DBB141F2883084F8F4 +:1021E0008C8001F0DBFC2046FFF7E2FC1E2001F0B2 +:1021F000D5FC2046FFF70AFD054680B994F88C30DF +:102200000F4856F83310FFF76FF9284602B0BDE8C3 +:10221000F0810135032DC8D10A48FFF74DFC204657 +:10222000FFF760FF94F88C30054656F8331008B974 +:102230000548E8E70548E6E7C0640008D824002020 +:10224000286400089E640008526400087C6400084A +:102250002DE9F041044688B00F461646FFF71CFFF3 +:102260002046FFF70FFF0025C722A0684FF48073B8 +:10227000079503A9CDE90323CDE9055503685B69FB +:102280009847A0682A46294603680095D3F810802D +:102290002B46C047054630B92046FFF711FF2846B8 +:1022A00008B0BDE8F081E36E3B60236F3360F3E775 +:1022B0002DE9F041002588B01F4604460E460E9BCE +:1022C00000F1400CA8463D60016B81B1A9420ED3DC +:1022D00091420CD8B6FBF1FE01FB1E6139B9416B8E +:1022E00090F82C800F9D1960816B29601546103085 +:1022F0006045E9D16DB3AB196269934229D8204694 +:10230000FFF7CAFE2046FFF7BDFE4FF41453A06846 +:1023100003A9CDF80C80CDE904360026CDE9066688 +:1023200003685B699847A0683246314603680096A7 +:10233000D3F810803346C047064620462EB9FFF733 +:10234000BFFE304608B0BDE8F081FFF7B9FE3D6042 +:10235000F7E70026F5E700002DE9F041866905461C +:1023600088B00F46B3429046B1FBF6FC06FB1C1C3E +:1023700028BF3346A6EB0C0C00269C45644628BFBC +:102380001C46FFF789FE2846FFF77CFE0222A8685C +:1023900003A9164B0597CDE90323CDE9066603682B +:1023A0005B699847A86822464146036800961F6902 +:1023B0003346B847064628462EB9FFF781FE304619 +:1023C00008B0BDE8F081FFF77BFE0E9B1C60AB6F91 +:1023D000AA696343B3FBF2F30F9A1360EA6F109B91 +:1023E0005443AA69B4FBF2F41C60E8E7002500013D +:1023F0002DE9F04FCE18436989B004469E420F463E +:10240000904634D83D464FF00009DFF870A0FFF742 +:1024100039FEAE422FD9A6EB050B94F8803094F824 +:10242000882003A9BBF5806F039394F8813028BFFF +:102430004FF4806B012AA06808BF03F1FF33CDF889 +:1024400010A0CDE90559079303685B699847A06818 +:10245000A8EB07030268CDF800B02B44D2F810B007 +:1024600000221146D84718B105F58065D1E7002054 +:1024700009B0BDE8F08F0120FAE700BF00ED0003CE +:10248000F0B5044689B00E46FFF7FCFD94F887507E +:102490002DB194F889302BB1012B1DD00025284691 +:1024A00009B0F0BD94F880200392F02206921A4AF7 +:1024B000CDE9042394F88130A06803A90793036849 +:1024C0005B699847A068314603689B699847054651 +:1024D000642001F063FBE2E720460027FFF7DCFD04 +:1024E0002046FFF7CFFD0823812285212046009753 +:1024F000FFF794FD054618B92046FFF7E1FDCEE74A +:1025000094F8803006970393044BCDE9043794F890 +:102510008130013BD0E700BF00ED000300ED001368 +:10252000014B024A1A607047D82400201464000846 +:10253000036800211B68184703790BB10022027160 +:102540001846704703685B681847000003791BB999 +:102550000123037118467047002070477047000040 +:1025600010B5044603F020FE204610BD30B50A44E5 +:10257000084D91420DD011F8013B5840082340F31B +:102580000004013B2C4013F0FF0384EA5000F6D115 +:10259000EFE730BD2083B8ED8A0710B504461DD59E +:1025A0000378042B1AD143681B682BB105220270F3 +:1025B00098472378052B01D102232370302383F31E +:1025C0001188002104F1080001F002FB002383F3CD +:1025D0001188E069BDE8104002F040BACB0704D58D +:1025E0000248BDE8104001F065BA10BD4065000822 +:1025F00010B5044C204601F001F8034A0023C4E959 +:10260000062310BDE02400200050005210B50378CE +:102610000446012B17D1104B984214D102460F49A2 +:10262000102002F0E7F90E4BE061D3F8D42042F419 +:102630008042C3F8D420D3F8FC2042F48042C3F88F +:10264000FC20D3F8FC306268A36992685A60054A9E +:102650001A601B22DA6010BDE024002099250008D2 +:10266000004402581500020182691B2310B5D36093 +:10267000D1E9003013F44C4406D19B011461D061C0 +:1026800003F44043536110BD0024184313F4406F1A +:102690001461CC68D4615061F5D08B689361F2E726 +:1026A00030B584691B25C069E5600068836104F169 +:1026B0002003C36102234261013A03614223C360E4 +:1026C00016238362CB682261E361D1E900231343BF +:1026D00012F4406F636101D08B68A361C36843F05B +:1026E0000103C36030BD000030B5D0E9064000688A +:1026F00004F120058561C36108234261013A036149 +:1027000046230D69C36016238362CB682261E361AF +:10271000D1E90023134312F4406F43EA854343F0A9 +:102720008063636101D08B68A361C36843F00103D8 +:10273000C36030BD8069036823F0040310B5CC6822 +:10274000036000230361C4618361D1E90043096927 +:10275000234343EA814343F04063436112B14FF0A6 +:102760001043136010BD000083691A6842F0020232 +:102770001A601A689207FCD41A6842F004021A60C0 +:10278000704700008269936810B5D3609B070446C8 +:102790001DD50378032B1AD143681B682BB1052282 +:1027A000027098472378052B01D102232370302330 +:1027B00083F31188002104F1080001F009FA0023D5 +:1027C00083F31188E069BDE8104002F047B910BDFD +:1027D000026843681143016003B118477047000065 +:1027E000024A136843F0C0031360704700100140B1 +:1027F00013B50E4C204600F091FA04F114000023AA +:102800004FF400720A49009400F04EF9094B4FF45E +:102810000072094904F13800009400F0C7F9074A32 +:10282000074BC4E9172302B010BD00BF00250020EC +:102830006C250020E12700086C27002000100140D3 +:1028400000E1F505037C30B5244C002918BF0C4687 +:10285000012B11D1224B98420ED1224BD3F8F020FC +:1028600042F01002C3F8F020D3F8182142F0100211 +:10287000C3F81821D3F818312268036EC16D03EB39 +:1028800052038466B3FBF2F36268150442BF23F07F +:10289000070503F0070343EA4503CB60A36843F051 +:1028A00040034B60E36843F001038B6042F496738E +:1028B00043F001030B604FF0FF330B62510505D568 +:1028C00012F0102205D0B2F1805F04D080F864309D +:1028D00030BD7F23FAE73F23F8E700BF50650008CB +:1028E00000250020004402582DE9F047C66D05463A +:1028F0003768F469210734621AD014F0080118BF50 +:102900004FF48071E20748BF41F02001A3074FF068 +:10291000300348BF41F04001600748BF41F08001EB +:1029200083F31188281DFFF753FF002383F31188D9 +:10293000E2050AD5302383F311884FF48061281D06 +:10294000FFF746FF002383F311884FF030094FF063 +:10295000000A14F0200838D13B0616D54FF0300994 +:1029600005F1380A200610D589F31188504600F089 +:1029700051F9002836DA0821281DFFF729FF27F032 +:1029800080033360002383F31188790614D562062F +:1029900012D5302383F31188D5E913239A4208D145 +:1029A0002B6C33B127F040071021281DFFF710FFD3 +:1029B0003760002383F31188E30618D5AA6E1369E4 +:1029C000ABB15069BDE8F047184789F31188736AC5 +:1029D000284695F86410194000F0BAF98AF3118876 +:1029E000F469B6E7B06288F31188F469BAE7BDE824 +:1029F000F0870000F8B51546826804460B46AA42E7 +:102A000000D28568A1692669761AB5420BD21846AC +:102A10002A46FEF76DFDA3692B44A3612846A368EF +:102A20005B1BA360F8BD0CD9AF1B18463246FEF7FE +:102A30005FFD3A46E1683044FEF75AFDE3683B44E7 +:102A4000EBE718462A46FEF753FDE368E5E700008A +:102A500083689342F7B50446154600D28568D4E9E9 +:102A60000460361AB5420BD22A46FEF741FD63696F +:102A70002B4463612846A3685B1BA36003B0F0BDD1 +:102A80000DD93246AF1B0191FEF732FD01993A464E +:102A9000E0683144FEF72CFDE3683B44E9E72A4651 +:102AA000FEF726FDE368E4E710B50A440024C3619D +:102AB000029B8460C16002610362C0E90000C0E95A +:102AC000051110BD08B5D0E90532934201D18268E5 +:102AD00082B98268013282605A1C426119700021F9 +:102AE000D0E904329A4224BFC368436101F08AF8F6 +:102AF000002008BD4FF0FF30FBE7000070B5302329 +:102B000004460E4683F31188A568A5B1A368A2699F +:102B1000013BA360531CA36115782269934224BF33 +:102B2000E368A361E3690BB120469847002383F370 +:102B30001188284607E03146204601F053F8002866 +:102B4000E2DA85F3118870BD2DE9F74F04460E4691 +:102B500017469846D0F81C904FF0300A8AF3118837 +:102B60004FF0000B154665B12A4631462046FFF767 +:102B700041FF034660B94146204601F033F8002882 +:102B8000F1D0002383F31188781B03B0BDE8F08FE8 +:102B9000B9F1000F03D001902046C847019B8BF389 +:102BA0001188ED1A1E448AF31188DCE7C160C36105 +:102BB000009B82600362C0E905111144C0E9000076 +:102BC00001617047F8B504460D461646302383F37D +:102BD0001188A768A7B1A368013BA36063695A1C69 +:102BE00062611D70D4E904329A4224BFE3686361D4 +:102BF000E3690BB120469847002080F3118807E075 +:102C00003146204600F0EEFF0028E2DA87F3118813 +:102C1000F8BD0000D0E9052310B59A4201D18268C1 +:102C20007AB982680021013282605A1C82611C7864 +:102C300003699A4224BFC368836100F0E3FF204622 +:102C400010BD4FF0FF30FBE72DE9F74F04460E466D +:102C500017469846D0F81C904FF0300A8AF3118836 +:102C60004FF0000B154665B12A4631462046FFF766 +:102C7000EFFE034660B94146204600F0B3FF00284E +:102C8000F1D0002383F31188781B03B0BDE8F08FE7 +:102C9000B9F1000F03D001902046C847019B8BF388 +:102CA0001188ED1A1E448AF31188DCE70268436834 +:102CB0001143016003B11847704700001430FFF75B +:102CC00043BF00004FF0FF331430FFF73DBF00005B +:102CD0003830FFF7B9BF00004FF0FF333830FFF74F +:102CE000B3BF00001430FFF709BF00004FF0FF3101 +:102CF0001430FFF703BF00003830FFF763BF000058 +:102D00004FF0FF323830FFF75DBF0000012914BFDC +:102D10006FF0130000207047FFF76ABD044B03609B +:102D200000234360C0E9023301230374704700BFEE +:102D30006865000810B53023044683F31188FFF757 +:102D400081FD02230020237480F3118810BD000050 +:102D500038B5C36904460D461BB904210844FFF782 +:102D6000A5FF294604F11400FFF7ACFE002806DA9F +:102D7000201D4FF40061BDE83840FFF797BF38BD14 +:102D8000026843681143016003B1184770470000AF +:102D900013B5406B00F58054D4F8A4381A68117844 +:102DA000042914D1017C022911D119790123128936 +:102DB0008B4013420BD101A94C3002F097FCD4F8A0 +:102DC000A4480246019B2179206800F0DFF902B097 +:102DD00010BD0000143002F019BC00004FF0FF33AA +:102DE000143002F013BC00004C3002F0EBBC0000C9 +:102DF0004FF0FF334C3002F0E5BC0000143002F01D +:102E0000E7BB00004FF0FF31143002F0E1BB0000DF +:102E10004C3002F0B7BC00004FF0FF324C3002F0F3 +:102E2000B1BC00000020704710B500F58054D4F804 +:102E3000A4381A681178042917D1017C022914D109 +:102E40005979012352898B4013420ED1143002F07C +:102E500079FB024648B1D4F8A4484FF44073617935 +:102E60002068BDE8104000F07FB910BD406BFFF74F +:102E7000DBBF0000704700007FB5124B0125042620 +:102E8000044603600023057400F184024360294670 +:102E9000C0E902330C4B0290143001934FF440739D +:102EA000009602F02BFB094B04F69442294604F1EC +:102EB0004C000294CDE900634FF4407302F0F2FB42 +:102EC00004B070BD906500086D2E0008912D0008BB +:102ED0000A68302383F311880B790B3342F82300FF +:102EE0004B79133342F823008B7913B10B3342F83B +:102EF000230000F58053C3F8A418022303740020B4 +:102F000080F311887047000038B5037F044613B181 +:102F100090F85430ABB90125201D0221FFF730FF96 +:102F200004F114006FF00101257700F077FE04F141 +:102F30004C0084F854506FF00101BDE8384000F0B7 +:102F40006DBE38BD10B5012104460430FFF718FFEF +:102F50000023237784F8543010BD000038B50446B0 +:102F60000025143002F0E2FA04F14C00257702F05B +:102F7000B1FB201D84F854500121FFF701FF2046CA +:102F8000BDE83840FFF750BF90F8803003F0600391 +:102F9000202B06D190F881200023212A03D81F2A54 +:102FA00006D800207047222AFBD1C0E91D3303E078 +:102FB000034A426707228267C3670120704700BF48 +:102FC0002C22002037B500F58055D5F8A4381A68B2 +:102FD000117804291AD1017C022917D1197901230A +:102FE00012898B40134211D100F14C04204602F0AB +:102FF00031FC58B101A9204602F078FBD5F8A4486D +:103000000246019B2179206800F0C0F803B030BD72 +:1030100001F10B03F0B550F8236085B004460D466E +:10302000FEB1302383F3118804EB8507301D08219E +:10303000FFF7A6FEFB6806F14C005B691B681BB13D +:10304000019002F061FB019803A902F04FFB0246D8 +:1030500048B1039B2946204600F098F8002383F3EB +:10306000118805B0F0BDFB685A691268002AF5D0D6 +:103070001B8A013B1340F1D104F18002EAE7000012 +:10308000133138B550F82140ECB1302383F3118867 +:1030900004F58053D3F8A4281368527903EB820314 +:1030A000DB689B695D6845B104216018FFF768FE25 +:1030B000294604F1140002F04FFA2046FFF7B4FE4F +:1030C000002383F3118838BD7047000001F01CBD58 +:1030D00001234022002110B5044600F8303BFEF7E2 +:1030E00039FA0023C4E9013310BD000010B53023C4 +:1030F000044683F311882422416000210C30FEF73E +:1031000029FA204601F022FD02230020237080F3DB +:10311000118810BD70B500EB8103054650690E465D +:103120001446DA6018B110220021FEF713FAA069E4 +:1031300018B110220021FEF70DFA31462846BDE8ED +:10314000704001F009BE000083682022002103F0D6 +:10315000011310B5044683601030FEF7FBF92046DA +:10316000BDE8104001F084BEF0B4012500EB8104FD +:1031700047898D40E4683D43A4694581236000236D +:10318000A2606360F0BC01F0A1BE0000F0B40125B4 +:1031900000EB810407898D40E4683D436469058143 +:1031A00023600023A2606360F0BC01F017BF000041 +:1031B00070B5022300250446242203702946C0F876 +:1031C00088500C3040F8045CFEF7C4F9204684F8BF +:1031D000705001F055FD63681B6823B129462046F5 +:1031E000BDE87040184770BD037880F88C30052327 +:1031F000037043681B6810B504460BB1042198475F +:103200000023A36010BD000090F88C20436802707A +:103210001B680BB1052118477047000070B590F886 +:103220007030044613B1002380F8703004F180023E +:10323000204601F041FE63689B68B3B994F8803082 +:1032400013F0600535D00021204602F01DF9002161 +:10325000204602F00DF963681B6813B10621204671 +:103260009847062384F8703070BD204698470028A0 +:10327000E4D0B4F88630A26F9A4288BFA36794F96D +:103280008030A56F002B4FF0300380F20381002DBA +:1032900000F0F280092284F8702083F31188002165 +:1032A0002046D4E91D23FFF771FF002383F3118823 +:1032B000DAE794F8812003F07F0343EA022340F227 +:1032C0000232934200F0C58021D8B3F5807F48D008 +:1032D0000DD8012B3FD0022B00F09380002BB2D1F0 +:1032E00004F1880262670222A267E367C1E7B3F5CF +:1032F000817F00F09B80B3F5407FA4D194F88230A9 +:10330000012BA0D1B4F8883043F0020332E0B3F5CA +:10331000006F4DD017D8B3F5A06F31D0A3F5C063BF +:10332000012B90D86368204694F882205E6894F858 +:103330008310B4F88430B047002884D043686367B2 +:103340000368A3671AE0B3F5106F36D040F6024267 +:1033500093427FF478AF5C4B63670223A36700233B +:10336000C3E794F88230012B7FF46DAFB4F8883056 +:1033700023F00203A4F88830C4E91D55E56778E717 +:10338000B4F88030B3F5A06F0ED194F882302046A7 +:1033900084F88A3001F0D2FC63681B6813B1012104 +:1033A00020469847032323700023C4E91D339CE77C +:1033B00004F18B0363670123C3E72378042B10D147 +:1033C000302383F311882046FFF7BEFE85F3118872 +:1033D0000321636884F88B5021701B680BB1204671 +:1033E000984794F88230002BDED084F88B30042389 +:1033F000237063681B68002BD6D0022120469847B3 +:10340000D2E794F8843020461D0603F00F010AD558 +:1034100001F044FD012804D002287FF414AF2B4BA7 +:103420009AE72B4B98E701F02BFDF3E794F88230F5 +:10343000002B7FF408AF94F8843013F00F01B3D061 +:103440001A06204602D502F037F8ADE702F028F858 +:10345000AAE794F88230002B7FF4F5AE94F884301C +:1034600013F00F01A0D01B06204602D502F00CF885 +:103470009AE701F0FDFF97E7142284F8702083F3A8 +:1034800011882B462A4629462046FFF76DFE85F314 +:103490001188E9E65DB1152284F8702083F3118864 +:1034A00000212046D4E91D23FFF75EFEFDE60B2236 +:1034B00084F8702083F311882B462A46294620463B +:1034C000FFF764FEE3E700BFC0650008B8650008C9 +:1034D000BC65000838B590F870300446002B3ED02B +:1034E000063BDAB20F2A34D80F2B32D8DFE803F0CC +:1034F00037313108223231313131313131313737E1 +:10350000856FB0F886309D4214D2C3681B8AB5FB24 +:10351000F3F203FB12556DB9302383F311882B4668 +:103520002A462946FFF732FE85F311880A2384F8DC +:1035300070300EE0142384F87030302383F3118848 +:10354000002320461A461946FFF70EFE002383F398 +:10355000118838BDC36F03B198470023E7E7002106 +:10356000204601F091FF0021204601F081FF6368B1 +:103570001B6813B10621204698470623D7E70000B1 +:1035800010B590F870300446142B29D017D8062BAC +:1035900005D001D81BB110BD093B022BFBD800217F +:1035A000204601F071FF0021204601F061FF6368B1 +:1035B0001B6813B1062120469847062319E0152BF6 +:1035C000E9D10B2380F87030302383F31188002376 +:1035D0001A461946FFF7DAFD002383F31188DAE76C +:1035E000C3689B695B68002BD5D1C36F03B1984753 +:1035F000002384F87030CEE7FEF7FABF01210023E4 +:103600000170C0E901330C3000F0FEB910B5302371 +:10361000044683F311884160FEF7F8FF022300207F +:10362000237080F3118810BD10B53023044683F356 +:103630001188032304F8083BFFF716F84FF0FF3119 +:10364000204600F0B7FA002383F31188C01A18BF90 +:10365000012010BD38B50446302585F311880325B7 +:1036600004F8085BFFF71CF84FF0FF31204600F02C +:10367000A1FA002383F31188C01A18BF012038BDB6 +:1036800038B50446302585F31188042504F8085B15 +:10369000FFF72AF84FF0FF31204600F08BFA0023A5 +:1036A00083F31188C01A18BF012038BD10B530232C +:1036B000044683F31188FFF73DF8062323700023A7 +:1036C00083F3118810BD000010B53023044683F346 +:1036D0001188FFF749F802232370002383F3118830 +:1036E00010BD00000C3000F0ABB900000C3000F051 +:1036F000B1B9000004480121044B03600023C0E974 +:1037000001330C3000F080B96C2900200959000801 +:10371000CB1D083A23F00703591A521A012110B49D +:10372000D2080024C0E9004384600C301C605A6059 +:103730005DF8044B00F068B92DE9F84F364ECD1D09 +:103740000F46002818BF0646082A4FEAD50538BF9D +:10375000082206F10C08341D9146404600F070F92D +:1037600009F10701C9F1000E224624686CB94046F0 +:1037700000F070F93368CBB308224946E800984757 +:10378000044698B340E9026730E004EB010CD4F83A +:1037900004A00CEA0E0C0AF10100ACF1080304EBE2 +:1037A000C0009842E0D9A0EB0C0CB5EBEC0F4FEA4F +:1037B000EC0BD9D89C421CD204F10802AB45A3EB18 +:1037C00002024FEAE202626009D9691CED432068F7 +:1037D00003EBC1025D44556043F8310022601C4692 +:1037E0005F60404644F8086B00F034F92046BDE8BD +:1037F000F88FAA45216802D111602346EFE7013511 +:1038000004EBC50344F8351003F10801401AC01059 +:1038100058601360F1E700BF6C290020F8B550F83C +:10382000043C044650F8085CA0F1080607332F1D3D +:103830000C35DB0840F8043C284600F001F93B4613 +:103840009F421A6801D0B34228D20AB1964225D2CB +:1038500044F8082C54F8042C1E60013254F8081C5B +:1038600006EBC200814206D14868024444F8042CA9 +:103870000A6844F8082C5868411C03EBC1018E42C9 +:1038800007D154F8042C013202445A6054F8082C31 +:103890001A602846BDE8F84000F0DCB81346CFE7D0 +:1038A00000238268037503691B6899689142FBD203 +:1038B0005A68036042601060586070470023826855 +:1038C000037503691B6899689142FBD85A680360C5 +:1038D000426010605860704708B50846302383F393 +:1038E00011880A7D0023052A06D8DFE802F00B05BF +:1038F0000503120E826913604FF0FF338361FFF7F7 +:10390000CFFF002383F3118808BD826993680133D8 +:103910009360D0E9003213605A60EDE7FFF7C0BF53 +:10392000054BD96808751868026853601A6001224F +:10393000D8600275FCF7F2BE882900200C4B30B528 +:10394000DD684B1C87B004460FD02B46094A6846F9 +:1039500000F0F8F92046FFF7E3FF009B13B168463B +:1039600000F0FAF9A86907B030BDFFF7D9FFF9E711 +:1039700088290020D938000838B50C4D04468161EB +:10398000EB6881689A68914203D8BDE83840FFF738 +:1039900087BF1846FFF792FF01230146EC602046DF +:1039A0002375BDE83840FCF7B9BE00BF8829002068 +:1039B000044B1A68DB6890689B68984294BF0020AB +:1039C0000120704788290020084B10B51C68D86872 +:1039D000226853601A600122DC602275FFF76EFFD7 +:1039E00001462046BDE81040FCF798BE882900201B +:1039F000044B1A68DB6892689B689A4201D9FFF70A +:103A0000E3BF704788290020C0E90000816070474B +:103A10008368013B002B10B583600CDA074BDC6830 +:103A20004368A061206063601C6044600520FFF76C +:103A300077FFA06910BD0020FCE700BF88290020A7 +:103A400008B5302383F31188FFF7E2FF002383F3E7 +:103A5000118808BD08B5302383F3118883680133CA +:103A6000002B836007DC036800211A680260506045 +:103A70001846FFF781FF002383F3118808BD00007B +:103A800038B50123084C00252370656001F01EFF46 +:103A9000FFF730FE0549064801F042FF022323707C +:103AA00085F3118838BD00BFF02B0020C8650008E1 +:103AB0008829002008B572B6044B186500F032FD65 +:103AC00000F000FE024B03221A70FEE78829002056 +:103AD000F02B002000F076B9EFF3118020B9EFF35E +:103AE0000583302282F311887047000010B530B989 +:103AF000EFF30584C4F3080414B180F3118810BDFA +:103B0000FFF776FF84F31188F9E70000034A516854 +:103B100053685B1A9842FBD8704700BF001000E062 +:103B20008B600223086108468B8270478368A3F18B +:103B3000840243F8142C026943F8442C426943F888 +:103B4000402C094A43F8242CC268A3F1200043F812 +:103B5000182C022203F80C2C002203F80B2C034A29 +:103B600043F8102C704700BF350700088829002053 +:103B700008B5FFF7DBFFBDE80840FFF7CFBE000048 +:103B8000024BDB6898610F20FFF7CABE882900202E +:103B9000302383F31188FFF7F3BF000008B5014617 +:103BA000302383F311880820FFF7C8FE002383F336 +:103BB000118808BD054BDB6821B1036098610320C3 +:103BC000FFF7BCBE4FF0FF30704700BF88290020D0 +:103BD00003682BB10022026018469961FFF79EBE70 +:103BE00070470000064BDB6839B1426818605A60C4 +:103BF000136043600420FFF7A1BE4FF0FF30704711 +:103C0000882900200368984206D01A680260506034 +:103C100018469961FFF782BE7047000038B5044628 +:103C20000D462068844200D138BD036823605C6083 +:103C30008561FFF773FEF4E7036810B59C68A24244 +:103C40000CD85C688A600B604C6021605960996890 +:103C50008A1A9A604FF0FF33836010BD121B1B68F5 +:103C6000ECE700000A2938BF0A2170B504460D466A +:103C70000A26601901F024FE01F00CFE041BA54287 +:103C800003D8751C04462E46F3E70A2E04D90120FA +:103C9000BDE8704001F084BE70BD0000F8B5144B63 +:103CA0000D460A2A4FF00A07D96103F1100182601C +:103CB00038BF0A22416019691446016048601861E2 +:103CC000A81801F0EDFD01F0E5FD431B0646A342F7 +:103CD00006D37C1C28192746354601F0F1FDF2E792 +:103CE0000A2F04D90120BDE8F84001F059BEF8BD03 +:103CF00088290020F8B506460D4601F0CBFD0F4A95 +:103D0000134653F8107F9F4206D12A46014630469B +:103D1000BDE8F840FFF7C2BFD169BB68441A2C194F +:103D200028BF2C46A34202D92946FFF79BFF224613 +:103D300031460348BDE8F840FFF77EBF88290020E0 +:103D400098290020C0E90323002310B45DF8044B38 +:103D50004361FFF7CFBF000010B5194C23699842AB +:103D60000DD08168D0E9003213605A609A680A4425 +:103D70009A60002303604FF0FF33A36110BD026817 +:103D8000234643F8102F53600022026022699A42B2 +:103D900003D1BDE8104001F08DBD936881680B44EC +:103DA000936001F077FD2269E1699268441AA242AA +:103DB000E4D91144BDE81040091AFFF753BF00BF12 +:103DC000882900202DE9F047DFF8BC8008F11007B2 +:103DD0002C4ED8F8105001F05DFDD8F81C40AA68B0 +:103DE000031B9A423ED814444FF00009D5E9003233 +:103DF000C8F81C4013605A60C5F80090D8F810301D +:103E0000B34201D101F056FD89F31188D5E90331A0 +:103E100028469847302383F311886B69002BD8D04C +:103E200001F038FD6A69A0EB040982464A450DD2CB +:103E3000022001F0B5FD0022D8F81030B34208D1BD +:103E400051462846BDE8F047FFF728BF121A224422 +:103E5000F2E712EB09092946384638BF4A46FFF710 +:103E6000EBFEB5E7D8F81030B34208D01444C8F8D8 +:103E70001C00211AA960BDE8F047FFF7F3BEBDE8BA +:103E8000F08700BF98290020882900200020704773 +:103E9000FEE70000704700004FF0FF307047000061 +:103EA00002290CD0032904D00129074818BF00209B +:103EB0007047032A05D8054800EBC2007047044844 +:103EC00070470020704700BFA06600083C22002019 +:103ED0005466000870B59AB005460846144601A914 +:103EE00000F0C2F801A8FDF72DFB431C0022C6B26A +:103EF0005B001046C5E9003423700323023404F844 +:103F0000013C01ABD1B202348E4201D81AB070BD6F +:103F100013F8011B013204F8010C04F8021CF1E74C +:103F200008B5302383F311880348FFF74BF80023CB +:103F300083F3118808BD00BFF82B002090F8803073 +:103F400003F01F02012A07D190F881200B2A03D128 +:103F50000023C0E91D3315E003F06003202B08D1D6 +:103F6000B0F884302BB990F88120212A03D81F2A79 +:103F700004D8FFF709B8222AEBD0FAE7034A4267D0 +:103F800007228267C3670120704700BF33220020E9 +:103F900007B5052917D8DFE801F01916031919200C +:103FA000302383F31188104A01210190FFF7B2F802 +:103FB000019802210D4AFFF7ADF80D48FEF7CEFF3C +:103FC000002383F3118803B05DF804FB302383F3EF +:103FD00011880748FEF798FFF2E7302383F3118832 +:103FE0000348FEF7AFFFEBE7F4650008186600082A +:103FF000F82B002038B50C4D0C4C2A460C4904F126 +:104000000800FFF767FF05F1CA0204F11000094933 +:10401000FFF760FF05F5CA7204F118000649BDE814 +:104020003840FFF757BF00BFD04400203C2200209B +:10403000D4650008DE650008E965000870B504462F +:1040400008460D46FDF77EFAC6B2204601340378D5 +:104050000BB9184670BD32462946FDF753FA0028C1 +:10406000F3D10120F6E700002DE9F84F05460C4694 +:10407000FDF768FA2C49C6B22846FFF7DFFF08B102 +:104080000336F6B229492846FFF7D8FF08B11036A3 +:10409000F6B2632E0DD8DFF89080DFF89090244FB1 +:1040A000DFF894A0DFF894B02E7846B92670BDE80A +:1040B000F88F29462046BDE8F84F02F0FDB8252EBE +:1040C0002ED1072241462846FDF71CFA70B9DBF8CD +:1040D000003007350A3444F80A3CDBF8043044F871 +:1040E000063CBBF8083024F8023CDDE708224946CC +:1040F0002846FDF707FA98B9A21C0E4B1978023230 +:104100000909C95D02F8041C13F8011B01F00F0135 +:104110005345C95D02F8031CF0D118340835C3E7D4 +:10412000013504F8016BBFE7C0660008E9650008C7 +:10413000D366000800E8F11F0CE8F11FC86600080C +:10414000BFF34F8F044B1A695107FCD1D3F81021EC +:104150005207F8D1704700BF0020005208B50D4B40 +:104160001B78ABB9FFF7ECFF0B4BDA68D10704D52E +:104170000A4A5A6002F188325A60D3F80C21D207F9 +:1041800006D5064AC3F8042102F18832C3F8042197 +:1041900008BD00BF2E4700200020005223016745C4 +:1041A0004FF00063054A1968013104D1043393428A +:1041B000F9D1012070470020704700BF00000208BD +:1041C00008B5114B1B78F3B9104B1A69510703D589 +:1041D000DA6842F04002DA60D3F81021520705D5C0 +:1041E000D3F80C2142F04002C3F80C21FFF7A8FFDE +:1041F000064BDA6842F00102DA60D3F80C2142F093 +:104200000102C3F80C2108BD2E47002000200052F7 +:104210004FF40030704700000120704708B9FFF7E5 +:10422000BFBF00207047000038B548BB154CFFF7F2 +:1042300053FCFFF785FF0546FFF790FF4FF0FF3374 +:104240006361C4F814312361FFF77AFF2423E3602C +:10425000E36843F08003E36023695B07FCD4FFF766 +:104260006FFF4FF000604FF4003100F007FA28466E +:10427000FFF7A6FFFFF73AFCBDE83840FFF790BF15 +:10428000002038BD002000522DE9F84F40EA02031B +:1042900005460C461746D80602D00020BDE8F88F28 +:1042A00027F01F07DFF8D4B0FFF758FF2744BC42C0 +:1042B00003D10120FFF784FFF0E7202229462046A2 +:1042C00001F0A6FF10B920352034F0E72B4605F1A8 +:1042D00020021E68711CE0D104339A42F9D1FFF725 +:1042E000FBFB05F17843234AB3F5801F224B28BF1F +:1042F0009A4603F1040338BF9046A2F1080228BF92 +:104300009846A3F108033ABF9146DA469946FFF76B +:1043100017FFC8F80060A5EB040CD9F8002004F1E1 +:104320001C0142F00202C9F80020221FDAF80060E6 +:1043300016F00506FAD152F8043F8A424CF80230D2 +:10434000F4D1BFF34F8FFFF7FBFE4FF0FF32C8F8F9 +:104350000020D9F8002022F00202C9F80020FFF75F +:10436000C5FB20222146284601F052FF0028AAD092 +:1043700030469FE7142000521021005210200052B6 +:1043800010B5084C237828B11BB9FFF7E7FE0123CD +:10439000237010BD002BFCD02070BDE81040FFF74B +:1043A0000FBF00BF2E4700202DE9F74F0E460546F0 +:1043B000002864D011F0050763D139B908222946D5 +:1043C0003046FFF7B9F90446002848D108224FF0DB +:1043D0000109DFF8C08006F00403DFF8BCA006EA9C +:1043E000090BBBF1000F27D0D8F81410C80723D44D +:1043F00009F1010908F10C08B9F1060FF1D18FB9E3 +:10440000224E2946F0190092FFF796F9044630BB78 +:104410001837009A782FF4D12946FFF78DF9044612 +:10442000E8B9009A29461A48FFF786F9044608BBFE +:10443000204603B0BDE8F08FABB1D8F8141011F0EE +:10444000040FD5D01820294600FB09A0CDE9002390 +:10445000FFF772F90446DDE900230028C8D02A4698 +:104460000021204608E0B107ECD5D8F8141011F06F +:10447000020FE6E72A460021FDF76CF8D8E704466C +:10448000D6E71F35202225F01F05A0E76047002052 +:1044900030470020E4660008484700200021FFF76D +:1044A00083BF00000121FFF77FBF0000F8B5144D66 +:1044B00001241827134E40F2FF3200210120FDF79E +:1044C00049F807FB046001342A6955F80C1FFFF70F +:1044D0001FF9062CF5D137254FF4C0542046FFF7BD +:1044E000E1FF014628B122460748BDE8F840FFF742 +:1044F0000FB9C4EBC404013D4FEAD404EED1F8BDBA +:10450000E466000848470020304700200421FFF7F8 +:104510004BBF00004843FFF7C1BF000008B1FFF7E1 +:104520007DB9704738B5054D00240334696855F8E6 +:104530000C0B00F0B5F8122CF7D138BDE46600087A +:1045400070B5104E82B0FFF7C7FA054601F0A2F928 +:10455000326803469042336037BF0B4A0A495168BC +:10456000146836BF0131D1E9004151600419284671 +:1045700041F100010191FFF7B9FA2046019902B01B +:1045800070BD00BFD8470020E047002070B5124E34 +:1045900082B0FFF7A1FA054601F07CF932680346C4 +:1045A0009042336037BF0D4A0C495168146836BFDA +:1045B0000131D1E9004151600419284641F100015F +:1045C0000191FFF793FA4FF47A7200232046019984 +:1045D000FBF78EFE02B070BDD8470020E0470020F8 +:1045E0000244074BD2B210B5904200D110BD441C1A +:1045F00000B253F8200041F8040BE0B2F4E700BF2A +:10460000504000580E4B30B51C6F240405D41C6F6D +:104610001C671C6F44F400441C670A4C0244236866 +:10462000D2B243F480732360074B904200D130BD77 +:10463000441C51F8045B00B243F82050E0B2F4E7A8 +:1046400000440258004802585040005807B5012263 +:1046500001A90020FFF7C4FF019803B05DF804FB37 +:1046600013B50446FFF7F2FFA04205D0012201A9CD +:1046700000200194FFF7C6FF02B010BD0144BFF354 +:104680004F8F064B884204D3BFF34F8FBFF36F8F1A +:104690007047C3F85C022030F4E700BF00ED00E093 +:1046A0000144BFF34F8F064B884204D3BFF34F8FB3 +:1046B000BFF36F8F7047C3F870022030F4E700BF7C +:1046C00000ED00E07047000070B5054616460C4648 +:1046D00001201021FFF71EFF286046733CB12046E1 +:1046E00036B1FFF713FF2B68186000B19C6070BDF6 +:1046F000FFF7D8FEF7E7000070B50E4615460446F2 +:1047000000B30B6843608368934210D213B1006812 +:10471000FFF704FF637B28462BB1FFF7F7FE20600D +:1047200020B9A06070BDFFF7BDFEF8E7A560206866 +:1047300005F11F01306021F01F01FFF79FFF0120ED +:104740002073EFE70120EDE710B5044640B10068A3 +:10475000884205D1606808B1FCF7CAFE00232373C4 +:1047600010BD000070B50E461546044620B38368A0 +:104770009A4210D913B10068FFF7D0FE637B284638 +:104780002BB1FFF7C3FE206020B9A06070BDFFF71A +:1047900089FEF8E7A560316819B12A462068FCF760 +:1047A000A7FE206805F11F01306021F01F01FFF70F +:1047B00077FF01202073E9E70120E7E720B10368D4 +:1047C0008B4204BF002303737047000008B100232D +:1047D00003737047034B1A681AB9034AD2F8D024FE +:1047E0001A607047E84700200040025808B5FFF7FC +:1047F000F1FF024B1868C0F3806008BDE847002055 +:1048000070B5BFF34F8FBFF36F8F1A4A0021C2F804 +:104810005012BFF34F8FBFF36F8F536943F40033D0 +:104820005361BFF34F8FBFF36F8FC2F88410BFF394 +:104830004F8FD2F8803043F6E074C3F3C900C3F35E +:104840004E335B0103EA0406014646EA81750139ED +:10485000C2F86052F9D2203B13F1200FF2D1BFF31E +:104860004F8F536943F480335361BFF34F8FBFF3CE +:104870006F8F70BD00ED00E0FEE700000A4B0B48B3 +:104880000B4A90420BD30B4BC11EDA1C121A22F0BA +:1048900003028B4238BF00220021FCF75BBE53F8B5 +:1048A000041B40F8041BECE7B0690008904A0020A4 +:1048B000904A0020904A00207047000003681A6860 +:1048C00099685A6043681BB142EA01418068184701 +:1048D000704700004FF0A44310B51C68E00702D5F4 +:1048E0002848FFF7EBFFA10702D52748FFF7E6FFAF +:1048F000620702D52548FFF7E1FF230702D52448C8 +:10490000FFF7DCFFE00602D52248FFF7D7FFA1063C +:1049100002D52148FFF7D2FF620602D51F48FFF7F4 +:10492000CDFF230602D51E48FFF7C8FFE00502D5DC +:104930001C48FFF7C3FFA10502D51B48FFF7BEFFC8 +:10494000620502D51948FFF7B9FF230502D51848BB +:10495000FFF7B4FFE00402D51648FFF7AFFFA1044C +:1049600002D51548FFF7AAFF620402D51348FFF7E6 +:10497000A5FF230402D51248FFF7A0FFBDE81040B1 +:1049800001F000B9F0470020FC4700200848002053 +:1049900014480020204800202C48002038480020DF +:1049A00044480020504800205C480020684800200F +:1049B00074480020804800208C480020984800203F +:1049C000A448002030B5094B0021094C10200725D0 +:1049D000196054F8042B0138C3E90121D16003F1B7 +:1049E0000C0311615560F4D130BD00BFEC470020CD +:1049F0002C6700080F28F0B50AD9102806D10F231C +:104A00000020144C01272568984203D900201DE09E +:104A10000346F6E707FA00F6354218D10C23354372 +:104A200043432560181D2344C3E902120A4B204466 +:104A3000D3F8D42042F00102C3F8D420D3F8FC20EC +:104A400042F00102C3F8FC20D3F8FC30F0BD013085 +:104A5000DAE700BFEC470020004402580368D96839 +:104A6000DA68C90722F03F02DA6002D51A689207B5 +:104A7000FCD507225A607047074BD3F8D81021EABB +:104A80000001C3F8D810D3F8002122EA0002C3F8CD +:104A90000021D3F8003170470044025870B5D0E9C6 +:104AA000244300224FF0FF359E6804EB421351016E +:104AB000D3F80009002805DAD3F8000940F0804057 +:104AC000C3F80009D3F8000B002805DAD3F8000B6F +:104AD00040F08040C3F8000B013263189642C3F8DF +:104AE0000859C3F8085BE0D24FF00113C4F81C3832 +:104AF00070BD0000890141F02001016103699B063E +:104B0000FCD41220FFF702B810B50A4C2046FEF77D +:104B1000DFFA094BC4F89030084BC4F89430084CC5 +:104B20002046FEF7D5FA074BC4F89030064BC4F880 +:104B3000943010BDB0480020000008409067000885 +:104B40004C490020000004409C67000870B50378C1 +:104B50000546012B5CD1434BD0F89040984258D188 +:104B6000414B0E216520D3F8D82042F00062C3F8F3 +:104B7000D820D3F8002142F00062C3F80021D3F816 +:104B80000021D3F8802042F00062C3F88020D3F8DF +:104B9000802022F00062C3F88020D3F8803000F03B +:104BA00097FC324BE360324BC4F800380023D5F851 +:104BB0009060C4F8003EC02323604FF40413A36345 +:104BC0003369002BFCDA01230C203361FEF79EFFD2 +:104BD0003369DB07FCD41220FEF798FF3369002B02 +:104BE000FCDA00262846A660FFF758FF6B68C4F879 +:104BF0001068DB68C4F81468C4F81C6883BB1D4BDC +:104C0000A3614FF0FF336361A36843F00103A36026 +:104C100070BD194B9842C9D1134B4FF08060D3F847 +:104C2000D82042F00072C3F8D820D3F8002142F017 +:104C30000072C3F80021D3F80021D3F8802042F09D +:104C40000072C3F88020D3F8802022F00072C3F8ED +:104C50008020D3F88030FFF70FFF0E214D209EE714 +:104C6000064BCDE7B04800200044025840140040F5 +:104C700003002002003C30C04C490020083C30C0FA +:104C8000F8B5D0F89040054600214FF00066204668 +:104C9000FFF730FFD5F8941000234FF001128F6812 +:104CA0004FF0FF30C4F83438C4F81C2804EB43122A +:104CB00001339F42C2F80069C2F8006BC2F80809CC +:104CC000C2F8080BF2D20B68D5F89020C5F89830DE +:104CD000636210231361166916F01006FBD11220CF +:104CE000FEF714FFD4F8003823F4FE63C4F800384C +:104CF000A36943F4402343F01003A3610923C4F8DC +:104D00001038C4F814380B4BEB604FF0C043C4F8B4 +:104D1000103B094BC4F8003BC4F81069C4F80039D3 +:104D2000D5F8983003F1100243F48013C5F89820A9 +:104D3000A362F8BD6C67000840800010D0F8902096 +:104D400090F88A10D2F8003823F4FE6343EA011386 +:104D5000C2F80038704700002DE9F84300EB8103EA +:104D6000D0F890500C468046DA680FFA81F9480175 +:104D7000166806F00306731E022B05EB41134FF075 +:104D8000000194BFB604384EC3F8101B4FF0010168 +:104D900004F1100398BF06F1805601FA03F39169FC +:104DA00098BF06F5004600293AD0578A04F1580109 +:104DB000374349016F50D5F81C180B430021C5F843 +:104DC0001C382B180127C3F81019A7405369611E1E +:104DD0009BB3138A928B9B08012A88BF5343D8F850 +:104DE0009820981842EA034301F140022146C8F88E +:104DF0009800284605EB82025360FFF77BFE08EB24 +:104E00008900C3681B8A43EA845348341E43640103 +:104E10002E51D5F81C381F43C5F81C78BDE8F8831F +:104E200005EB4917D7F8001B21F40041C7F8001B18 +:104E3000D5F81C1821EA0303C0E704F13F030B4A2D +:104E40002846214605EB83035A60FFF753FE05EB26 +:104E50004910D0F8003923F40043C0F80039D5F8E0 +:104E60001C3823EA0707D7E700800010000400027F +:104E7000D0F894201268C0F89820FFF70FBE000009 +:104E80005831D0F8903049015B5813F4004004D0F9 +:104E900013F4001F0CBF0220012070474831D0F8E6 +:104EA000903049015B5813F4004004D013F4001F04 +:104EB0000CBF02200120704700EB8101CB68196A0A +:104EC0000B6813604B6853607047000000EB810370 +:104ED00030B5DD68AA691368D36019B9402B84BF67 +:104EE000402313606B8A1468D0F890201C4402EBB6 +:104EF0004110013C09B2B4FBF3F46343033323F0E4 +:104F0000030343EAC44343F0C043C0F8103B2B689B +:104F100003F00303012B0ED1D2F8083802EB411045 +:104F200013F4807FD0F8003B14BF43F0805343F06C +:104F30000053C0F8003B02EB4112D2F8003B43F0B3 +:104F40000443C2F8003B30BD2DE9F041D0F8906039 +:104F500005460C4606EB4113D3F8087B3A07C3F825 +:104F6000087B08D5D6F814381B0704D500EB81035D +:104F7000DB685B689847FA071FD5D6F81438DB075B +:104F80001BD505EB8403D968CCB98B69488A5A686C +:104F9000B2FBF0F600FB16228AB91868DA68904274 +:104FA0000DD2121AC3E90024302383F3118821465D +:104FB0002846FFF78BFF84F31188BDE8F0810123B9 +:104FC00003FA04F26B8923EA02036B81CB68002B9E +:104FD000F3D021462846BDE8F041184700EB810395 +:104FE0004A0170B5DD68D0F890306C692668E660DB +:104FF00056BB1A444FF40020C2F810092A6802F088 +:105000000302012A0AB20ED1D3F8080803EB4214B6 +:1050100010F4807FD4F8000914BF40F0805040F0B5 +:105020000050C4F8000903EB4212D2F8000940F026 +:105030000440C2F800090122D3F8340802FA01F151 +:105040000143C3F8341870BD19B9402E84BF402005 +:10505000206020681A442E8A8419013CB4FBF6F4BF +:1050600040EAC44040F00050C6E700002DE9F84394 +:10507000D0F8906005460C464F0106EB4113D3F87B +:10508000088918F0010FC3F808891CD0D6F8103829 +:10509000DB0718D500EB8103D3F80CC0DCF8143023 +:1050A000D3F800E0DA68964530D2A2EB0E024FF05A +:1050B00000091A60C3F80490302383F31188FFF7C6 +:1050C0008DFF89F3118818F0800F1DD0D6F8343881 +:1050D0000126A640334217D005EB84030134D5F8EE +:1050E0009050D3F80CC0E4B22F44DCF8142005EB48 +:1050F0000434D2F800E05168714514D3D5F834383F +:1051000023EA0606C5F83468BDE8F883012303FAEC +:1051100001F2038923EA02030381DCF80830002B43 +:10512000D1D09847CFE7AEEB0103BCF81000834223 +:1051300028BF0346D7F8180980B2B3EB800FE3D835 +:105140009068A0F1040959F8048FC4F80080A0EB1E +:1051500009089844B8F1040FF5D818440B4490603E +:105160005360C8E72DE9F84FD0F8905004466E69B7 +:10517000AB691E4016F480586E6103D0BDE8F84F4D +:10518000FEF716B8002E12DAD5F8003E9F0705D0BC +:10519000D5F8003E23F00303C5F8003ED5F80438E7 +:1051A000204623F00103C5F80438FEF72DF830053A +:1051B00005D52046FFF772FC2046FEF715F8B1042E +:1051C0000CD5D5F8083813F0060FEB6823F47053AC +:1051D0000CBF43F4105343F4A053EB60320704D5E3 +:1051E0006368DB680BB120469847F30200F1BA8090 +:1051F000B70226D5D4F8909000274FF0010A09EBAA +:105200004712D2F8003B03F44023B3F5802F11D1AD +:10521000D2F8003B002B0DDA62890AFA07F322EA82 +:105220000303638104EB8703DB68DB6813B1394652 +:10523000204698470137D4F89430FFB29B689F42CC +:10524000DDD9F00619D5D4F89000026AC2F30A1726 +:1052500002F00F0302F4F012B2F5802F00F0CA80C2 +:10526000B2F5402F09D104EB8303002200F58050F2 +:10527000DB681B6A974240F0B0803003D5F81858BD +:1052800035D5E90303D500212046FFF75DFEAA03CB +:1052900003D501212046FFF757FE6B0303D50221FA +:1052A0002046FFF751FE2F0303D503212046FFF7C9 +:1052B0004BFEE80203D504212046FFF745FEA90274 +:1052C00003D505212046FFF73FFE6A0203D50621DC +:1052D0002046FFF739FE2B0203D507212046FFF7B2 +:1052E00033FEEF0103D508212046FFF72DFE7003A2 +:1052F00040F1A780E90703D500212046FFF7B6FE5D +:10530000AA0703D501212046FFF7B0FE6B0703D59E +:1053100002212046FFF7AAFE2F0703D503212046CE +:10532000FFF7A4FEEE0603D504212046FFF79EFEFC +:10533000A80603D505212046FFF798FE690603D588 +:1053400006212046FFF792FE2A0603D507212046B4 +:10535000FFF78CFEEB0574D520460821BDE8F84F19 +:10536000FFF784BED4F890904FF0000B4FF0010A85 +:10537000D4F894305FFA8BF79B689F423FF638AFC2 +:1053800009EB4713D3F8002902F44022B2F5802F2D +:1053900020D1D3F80029002A1CDAD3F8002942F0E2 +:1053A0009042C3F80029D3F80029002AFBDB3946D4 +:1053B000D4F89000FFF79EFB22890AFA07F322EA4D +:1053C0000303238104EB8703DB689B6813B1394631 +:1053D000204698470BF1010BCAE7910701D1D0F89D +:1053E0000080072A02F101029CBF03F8018B4FEAFB +:1053F00018283FE704EB830300F58050DA68D2F801 +:1054000018C0DCF80820DCE9001CA1EB0C0C002122 +:105410008F4208D1DB689B699A683A449A605A685F +:105420003A445A6029E711F0030F01D1D0F8008007 +:105430008C4501F1010184BF02F8018B4FEA182865 +:10544000E6E7BDE8F88F000008B50348FFF78AFEDD +:10545000BDE8084000F096BBB048002008B50348FE +:10546000FFF780FEBDE8084000F08CBB4C490020EF +:10547000D0F8903003EB4111D1F8003B43F4001316 +:10548000C1F8003B70470000D0F8903003EB4111A9 +:10549000D1F8003943F40013C1F800397047000017 +:1054A000D0F8903003EB4111D1F8003B23F4001306 +:1054B000C1F8003B70470000D0F8903003EB411179 +:1054C000D1F8003923F40013C1F800397047000007 +:1054D000090100F16043012203F56143C9B283F879 +:1054E000001300F01F039A4043099B0003F160433F +:1054F00003F56143C3F880211A60704730B5043367 +:10550000039C0172002104FB0325C160C0E906531E +:10551000049B0363059BC0E90000C0E90422C0E9C5 +:105520000842C0E90A11436330BD00000022416A0D +:10553000C260C0E90411C0E90A226FF00101FEF760 +:105540006DBB0000D0E90432934201D1C2680AB9B0 +:10555000181D704700207047036919600021C26858 +:105560000132C260C269134482699342036124BF5D +:10557000436A0361FEF746BB38B504460D46E3684F +:105580003BB162690020131D1268A3621344E362F9 +:1055900007E0237A33B929462046FEF723FB00288B +:1055A000EDDA38BD6FF00100FBE70000C368C269A7 +:1055B000013BC3604369134482699342436124BF42 +:1055C000436A436100238362036B03B1184770474A +:1055D00070B53023044683F31188866A3EB9FFF71D +:1055E000CBFF054618B186F31188284670BDA36A23 +:1055F000E26A13F8015B9342A36202D32046FFF7ED +:10560000D5FF002383F31188EFE700002DE9F84F61 +:1056100004460E46174698464FF0300989F3118824 +:105620000025AA46D4F828B0BBF1000F09D14146A5 +:105630002046FFF7A1FF20B18BF311882846BDE873 +:10564000F88FD4E90A12A7EB050B521A934528BF2D +:105650009346BBF1400F1BD9334601F1400251F88C +:10566000040B914243F8040BF9D1A36A403640354C +:105670004033A362D4E90A239A4202D32046FFF7BB +:1056800095FF8AF31188BD42D8D289F31188C9E702 +:1056900030465A46FBF72CFFA36A5E445D445B44E8 +:1056A000A362E7E710B5029C0433017203FB0421F7 +:1056B000C460C0E906130023C0E90A33039B0363F7 +:1056C000049BC0E90000C0E90422C0E9084243632A +:1056D00010BD0000026A6FF00101C260426AC0E9B9 +:1056E00004220022C0E90A22FEF798BAD0E9042376 +:1056F0009A4201D1C26822B9184650F8043B0B60A7 +:105700007047002070470000C3680021C269013360 +:10571000C3604369134482699342436124BF436A6F +:105720004361FEF76FBA000038B504460D46E368E2 +:105730003BB1236900201A1DA262E2691344E362AF +:1057400007E0237A33B929462046FEF74BFA0028B2 +:10575000EDDA38BD6FF00100FBE700000369196066 +:10576000C268013AC260C26913448269934203610C +:1057700024BF436A036100238362036B03B11847AC +:105780007047000070B530230D460446114683F380 +:105790001188866A2EB9FFF7C7FF10B186F311880A +:1057A00070BDA36A1D70A36AE26A01339342A362CB +:1057B00004D3E16920460439FFF7D0FF002080F3CD +:1057C0001188EDE72DE9F84F04460D4690469946BD +:1057D0004FF0300A8AF311880026B346A76A4FB902 +:1057E00049462046FFF7A0FF20B187F311883046D5 +:1057F000BDE8F88FD4E90A073A1AA8EB06079742E2 +:1058000028BF1746402F1BD905F1400355F8042B3C +:105810009D4240F8042BF9D1A36A40364033A3627D +:10582000D4E90A239A4204D3E16920460439FFF7F8 +:1058300095FF8BF311884645D9D28AF31188CDE7BD +:1058400029463A46FBF754FEA36A3D443E443B4496 +:10585000A362E5E7D0E904239A4217D1C3689BB15C +:10586000836A8BB1043B9B1A0ED01360C368013B63 +:10587000C360C3691A4483699A42026124BF436AC0 +:105880000361002383620123184670470023FBE76E +:1058900000F0A2B9014B586A704700BF000C0040ED +:1058A000034B002258631A610222DA60704700BF7E +:1058B000000C0040014B0022DA607047000C0040F1 +:1058C000014B5863704700BF000C0040024B034A75 +:1058D0001A60034A5A607047004A0020904A00202C +:1058E00000000220074B494210B55C68201A0840AE +:1058F0001968821A8A4203D3A24201D85A6010BDA5 +:105900000020FCE7004A002008B5302383F311880B +:10591000FFF7E8FF002383F3118808BDFEE70000CE +:1059200070B51B4B0025044686B058600E46856254 +:10593000016300F0FFF804F11003A560E562C4E91B +:1059400004334FF0FF33C4E90044C4E90635FFF7E0 +:10595000A1FF2B46024604F134012046C4E9082386 +:1059600080230C4A2565FEF7DBF801230A4AE06034 +:1059700000920375684672680192B268CDE902230D +:10598000064BCDE90435FEF7F3F806B070BD00BF55 +:10599000F02B0020A8670008AD6700081D5900081B +:1059A000024AD36A1843D062704700BF882900209A +:1059B0004B6843608B688360CB68C3600B6943614D +:1059C0004B6903628B6943620B6803607047000098 +:1059D00008B5354B40F2FF70D3F8E0100143C3F82F +:1059E000E010D3F8082102433048C3F80821304AB8 +:1059F000D3F808311146FFF7DBFF00F5806002F1B4 +:105A00001C01FFF7D5FF00F5806002F13801FFF7B8 +:105A1000CFFF00F5806002F15401FFF7C9FF00F5E8 +:105A2000806002F17001FFF7C3FF00F5806002F1B2 +:105A30008C01FFF7BDFF00F5806002F1A801FFF7C0 +:105A4000B7FF00F5806002F1C401FFF7B1FF00F578 +:105A5000806002F1E001FFF7ABFF00F5806002F12A +:105A6000FC01FFF7A5FF02F58C7100F58060FFF7E0 +:105A70009FFF00F079F90F4BD3F8902242F001021A +:105A8000C3F89022D3F8942242F00102C3F8942282 +:105A90000522C3F898204FF06052C3F89C20064AB4 +:105AA000C3F8A02008BD00BF0044025800000258FF +:105AB000B467000800ED00E01F00080308B500F01F +:105AC0004BFBFDF7DDFF104BD3F8DC2042F040022A +:105AD000C3F8DC20D3F8042122F04002C3F80421EB +:105AE000D3F80431094B1A6842F008021A601A68A8 +:105AF00042F004021A60FEF76DFEFEF7D7FCBDE827 +:105B00000840FEF777BA00BF004402580018024868 +:105B100070470000EFF30983054968334A6B22F0B0 +:105B200001024A6383F30988002383F311887047D5 +:105B300000EF00E0302080F3118862B60D4B0E4A72 +:105B4000D96821F4E0610904090C0A430B49DA60C1 +:105B5000D3F8FC2042F08072C3F8FC20084AC2F857 +:105B6000B01F116841F0010111602022DA7783F83B +:105B70002200704700ED00E00003FA0555CEACC5E9 +:105B8000001000E0302310B583F311880E4B5B68E2 +:105B900013F4006314D0F1EE103AEFF309844FF0E0 +:105BA0008073683CE361094BDB6B236684F30988EF +:105BB000FDF7FEFE10B1064BA36110BD054BFBE7E0 +:105BC00083F31188F9E700BF00ED00E000EF00E08B +:105BD000470700084A070008114BD3F8E82042F0B5 +:105BE0000802C3F8E820D3F8102142F00802C3F8F5 +:105BF00010210C4AD3F81031D36B43F00803D36360 +:105C0000EF22094B9A624FF0FF32DA6200229A616A +:105C10005A63DA605A6001225A611A60704700BF05 +:105C2000004402580010005C000C0040094A08B50E +:105C30001169D3680B40D9B29B076FEA010111616A +:105C400007D5302383F31188FDF744FF002383F346 +:105C5000118808BD000C0040064BD3F8DC2002433D +:105C6000C3F8DC20D3F804211043C3F80401D3F8AF +:105C7000043170470044025808B54FF0FF31394BEA +:105C8000D3F88020C3F88010D3F880200022C3F816 +:105C90008020D3F88000D3F88400C3F88410D3F8B0 +:105CA0008400C3F88420D3F88400D86F40F0FF400C +:105CB00040F4FF0040F4DF4040F07F00D867D86F29 +:105CC00020F0FF4020F4FF0020F4DF4020F07F00B0 +:105CD000D867D86FD3F888006FEA40506FEA505009 +:105CE000C3F88800D3F88800C0F30A00C3F888001E +:105CF000D3F88800D3F89000C3F89010D3F8900040 +:105D0000C3F89020D3F89000D3F89400C3F894100F +:105D1000D3F89400C3F89420D3F89400D3F89800F3 +:105D2000C3F89810D3F89800C3F89820D3F89800D7 +:105D3000D3F88C00C3F88C10D3F88C00C3F88C20F7 +:105D4000D3F88C00D3F89C00C3F89C10D3F89C10B7 +:105D5000C3F89C20D3F89C30FEF734FEBDE8084021 +:105D600000F0CAB90044025808B50122564BC3F8E6 +:105D70000821564BD3F8F42042F00202C3F8F42075 +:105D8000D3F81C2142F00202C3F81C210222D3F8EE +:105D90001C314F4BDA605A689104FCD54D4A4E498C +:105DA0001A6001229A60D960002119614FF44041C4 +:105DB00099614A4BDA6203F511339A699204FCD572 +:105DC0001A6842F480721A60404B1A6F12F4407FD6 +:105DD00004D04FF480321A6700221A671A6842F022 +:105DE00001021A60394B1A685007FCD500221A616B +:105DF0001A6912F03802FBD1012119604FF080417D +:105E000059604FF00051D9605A67354ADA62354A15 +:105E10001A611A6842F480321A602C4B1A68910396 +:105E2000FCD51A6842F480521A601A689204FCD5B4 +:105E30002D4A2E499A6200225A63196301F57A01AC +:105E4000DA6301F2D31199635A64294A1A64294A20 +:105E5000DA621A6842F0A8521A601C4B1A6802F003 +:105E60002852B2F1285FF9D148229A614FF4886232 +:105E7000DA6140221A62204ADA64204A1A65204A0E +:105E80005A65204A9A6534231F4A1360136803F049 +:105E90000F03042BFAD10D4A136943F00303136176 +:105EA000136903F03803182BFAD14FF00050FFF7B5 +:105EB000D3FE4FF08040FFF7CFFE4FF00040BDE82B +:105EC0000840FFF7C9BE00BF0080005100440258DF +:105ED0000048025800C000F0020000010004005811 +:105EE0000000FF01008890081210200077020B01CB +:105EF000470E0508DD0BBF01200000200000011047 +:105F00000910E00000010110002000524FF0B042E3 +:105F100008B5D2F8883003F00103C2F8883023B105 +:105F2000044A13680BB150689847BDE80840FFF772 +:105F300029BE00BF084A00204FF0B04208B5D2F891 +:105F4000883003F00203C2F8883023B1044A936812 +:105F50000BB1D0689847BDE80840FFF713BE00BFFB +:105F6000084A00204FF0B04208B5D2F8883003F05C +:105F70000403C2F8883023B1044A13690BB1506995 +:105F80009847BDE80840FFF7FDBD00BF084A002064 +:105F90004FF0B04208B5D2F8883003F00803C2F8D9 +:105FA000883023B1044A93690BB1D0699847BDE8A2 +:105FB0000840FFF7E7BD00BF084A00204FF0B0429D +:105FC00008B5D2F8883003F01003C2F8883023B146 +:105FD000044A136A0BB1506A9847BDE80840FFF7BE +:105FE000D1BD00BF084A00204FF0B04310B5D3F830 +:105FF000884004F47872C3F88820A30604D5124AB6 +:10600000936A0BB1D06A9847600604D50E4A136BA9 +:106010000BB1506B9847210604D50B4A936B0BB11B +:10602000D06B9847E20504D5074A136C0BB1506C4E +:106030009847A30504D5044A936C0BB1D06C9847DC +:10604000BDE81040FFF79EBD084A00204FF0B04366 +:1060500010B5D3F8884004F47C42C3F88820620568 +:1060600004D5164A136D0BB1506D9847230504D51E +:10607000124A936D0BB1D06D9847E00404D50F4AD6 +:10608000136E0BB1506E9847A10404D50B4A936E62 +:106090000BB1D06E9847620404D5084A136F0BB158 +:1060A000506F9847230404D5044A936F0BB1D06F07 +:1060B0009847BDE81040FFF765BD00BF084A0020C3 +:1060C00008B50348FCF75EFBBDE80840FFF75ABD82 +:1060D000E024002008B50348FCF706FCBDE80840B2 +:1060E000FFF750BD0025002008B5FFF79FFDBDE874 +:1060F0000840FFF747BD0000062108B50846FFF736 +:10610000E7F906210720FFF7E3F906210820FFF74A +:10611000DFF906210920FFF7DBF906210A20FFF746 +:10612000D7F906211720FFF7D3F906212820FFF71A +:10613000CFF909217A20FFF7CBF90A215C20FFF77C +:10614000C7F907213220FFF7C3F90C212520BDE84C +:106150000840FFF7BDB9000008B5FFF78DFD00F05E +:106160000FF8FCF7D9FDFCF7B1FFFCF783FEFDF754 +:1061700043FAFFF7CDFCBDE80840FFF789BB0000FC +:106180000023054A19460133102BC2E9001102F120 +:106190000802F8D1704700BF084A00200B460146AC +:1061A000184600F027B80000FEF7B8B9FFF7FCBFAB +:1061B000012838BF012010B504462046FEF76EF9CD +:1061C00030B900F007F808B900F00CF88047F4E7A0 +:1061D00010BD0000024B1868BFF35B8F704700BF13 +:1061E000884A002008B5062000F04AF80120FDF793 +:1061F0004FFE000010B5054C13462CB10A4601466F +:106200000220AFF3008010BD2046FCE70000000034 +:1062100010B501390244904201D1002005E0037815 +:1062200011F8014FA34201D0181B10BD0130F2E755 +:106230001F2938B504460D4604D9162303604FF0D4 +:10624000FF3038BD426C12B152F821304BB92046B4 +:1062500000F030F82A4601462046BDE8384000F0FC +:1062600017B8012B0AD0591C03D116230360012053 +:10627000E7E7002442F82540284698470020E0E759 +:10628000024B01461868FFF7D3BF00BF5C22002015 +:1062900038B5074D00230446084611462B60FDF72C +:1062A000FBFD431C02D12B6803B1236038BD00BF46 +:1062B0008C4A0020FDF7EABD034611F8012B03F8D4 +:1062C000012B002AF9D170470000000001000000F6 +:1062D00000010001000000000000000000000000BC +:1062E00052657175657374656420746F20657261A1 +:1062F0007365206D6F7265207468616E207765200C +:1063000063616E0A00457261736520436F6D6D6154 +:106310006E642052656365697665640A0050435473 +:1063200020444F4E453A2025640A000053544D3313 +:106330003248373F3F3F0053544D333248373433B0 +:106340002F37353300000000F82B002000250020F7 +:10635000773235712D647472000000000000000077 +:106360000000000000000000000000004D170008C1 +:10637000B11A0008B11A0008511700085517000893 +:10638000591700085D170008B11A0008B11A000873 +:10639000B11A00087517000879170008911700084E +:1063A00099170008A5170008A9170008AD170008DD +:1063B000E0240020010000000000000000000000B8 +:1063C000CD180008E51800084D170008B917000897 +:1063D00019190008D5170008B1190008E1190008BB +:1063E0005D170008D1170008BD170008CD17000879 +:1063F0007517000879170008911700089917000809 +:10640000A5170008A9170008AD1700080000000034 +:10641000000000004D180008B1170008B51700086B +:1064200053464450000000004A454445433A204644 +:1064300061696C656420746F2064657465637420A1 +:10644000666C617368206465766963653A202573BC +:106450000A004A454445433A204661696C65642018 +:10646000746F20636F6E66696720666C6173682065 +:106470006465766963653A2025730A004A45444598 +:10648000433A20446574656374656420466C6173A7 +:1064900068204465766963653A2025730A0045786B +:1064A0007420466C617368204E6F7420466F756E61 +:1064B000642100006D74323571007732357100004F +:1064C000B464000820BA0000BA640008EF4000007D +:1064D00050630008EF7000000000000000000000A2 +:1064E00091210008F1230008CD1A0008D11A0008F4 +:1064F000791B000859230008D51A0008D91A00088A +:1065000051220008491B0008B1220008B51F0008ED +:10651000E11A0008DD1A000881240008411B000868 +:106520000000000000000000452500084D2500087F +:1065300031250008392500085D250008612500087F +:106540004D444D41206661696C7572650000000024 +:1065500000960000000000000000000000000000A5 +:10656000000000000000000000000000D92C00081E +:10657000C52C0008012D0008ED2C0008F92C00089E +:10658000E52C0008D12C0008BD2C00080D2D0008BA +:1065900000000000F12D0008DD2D0008192E000874 +:1065A000052E0008112E0008FD2D0008E92D000819 +:1065B000D52D0008252E0008000000000100000075 +:1065C0000000000063300000C4650008E0290020DE +:1065D000F02B00204172647550696C6F7400254285 +:1065E0004F415244252D424C002553455249414CC0 +:1065F000250000000200000000000000113000082B +:106600008130000840004000A0440020B044002039 +:106610000200000000000000030000000000000075 +:10662000C93000080000000010000000C044002035 +:10663000000000000100000000000000B048002041 +:1066400001010200913F0008A13E00083D3F000803 +:10665000213F0008430000005C6600080902430077 +:10666000020100C0320904000001020201000524F9 +:106670000010010524010001042402020524060083 +:1066800001070582030800FF09040100020A000057 +:1066900000070501024000000705810240000000DC +:1066A00012000000A866000812011001020000405C +:1066B000091241570002010203010000040309040A +:1066C00025424F41524425005350526163696E6721 +:1066D0004837003031323334353637383941424368 +:1066E00044454600000000200000020002000000B7 +:1066F0000000003000000400000000000000002442 +:1067000000000800040000000004000000FC00007D +:1067100002000000000004300080000000000000C3 +:10672000000000380000010001000000400000529D +:1067300080000052C000005200010052400100528F +:1067400080010052C001005200020052400200527B +:1067500080020052C0020052000300524003005267 +:1067600080030052C00300520004005200000000E9 +:106770001D320008D5340008813500084000400073 +:10678000E8490020E849002001000000F849002005 +:10679000800000004001000008000000000100002F +:1067A00000040000080000006D61696E0069646CFF +:1067B000650000000000806A00000000AAAAAAAAE2 +:1067C00000000064FFFF00000000000000A00A00BD +:1067D000240020A100000000BAAABAAA00000051BB +:1067E000FFFF000000090000000900440000000055 +:1067F00000000000AAAAAAAA00000000FFFF0000F3 +:1068000000000000000000000000800A00000000FE +:10681000AAAAEAAF00000000FFFF0000000000008D +:10682000009099006000400000000000BAAAAAAAE7 +:1068300000004000F7FF0000000900000000000019 +:106840000000000000000000AAAAAAAA00000000A0 +:10685000FFFF00000000000000000000000000003A +:1068600000000000AAAAAAAA00000000FFFF000082 +:106870000000000000000000000000000000000018 +:10688000AAAAAAAA00000000FFFF00000000000062 +:10689000000000000000000000000000AAAAAAAA50 +:1068A00000000000FFFF00000000000000000000EA +:1068B0000000000000000000AAAAAAAA0000000030 +:1068C000FFFF0000000000000000000000000000CA +:1068D00000000000AAAAAAAA00000000FFFF000012 +:1068E0000000000000000000389AFF7F0100000057 +:1068F0002404000000000000000000000000E90087 +:10690000FF000000000000002C6300083F000000B2 +:1069100050040000376300083F00000000960000AC +:1069200000000800960000000008000004000000BD +:10693000BC6600080000000000000000000000002D +:1069400000000000000000000000000060220020A5 +:106950000000000000000000000000000000000037 +:106960000000000000000000000000000000000027 +:106970000000000000000000000000000000000017 +:106980000000000000000000000000000000000007 +:1069900000000000000000000000000000000000F7 +:1069A00000000000000000000000000000000000E7 :00000001FF From c7bd87ce33507c75745a459cd7d15e2ffcad457e Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 2 Feb 2023 17:35:32 +0000 Subject: [PATCH 076/287] waf: disable watchdogs on debug builds --- Tools/ardupilotwaf/boards.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 6333444d5bac04..1b3484301549dc 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -1032,7 +1032,7 @@ def configure_env(self, cfg, env): if cfg.env.SAVE_TEMPS: env.CXXFLAGS += [ '-S', '-save-temps=obj' ] - if cfg.options.disable_watchdog: + if cfg.options.disable_watchdog or cfg.env.DEBUG: cfg.msg("Disabling Watchdog", "yes") env.CFLAGS += [ '-DDISABLE_WATCHDOG' ] env.CXXFLAGS += [ '-DDISABLE_WATCHDOG' ] From 820f3b81d14e22ed782310bf2426fbee8e110cd0 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 2 Feb 2023 17:38:40 +0000 Subject: [PATCH 077/287] AP_FlashIface: add comment on alternate byte usage with fast read --- libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp b/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp index 47ed9198be06c8..8aedfc6455643a 100644 --- a/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp +++ b/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp @@ -930,7 +930,7 @@ bool AP_FlashIface_JEDEC::start_xip_mode(void** addr) // Set QSPI module for XIP mode AP_HAL::QSPIDevice::CommandHeader cmd; cmd.cmd = _desc.fast_read_ins; // generally 0xEB for 1-4-4 access - cmd.alt = 0xF0; // add M0-7 bits in alt to make up 32-bit address phase + cmd.alt = 0xF0; // add M0-7 bits in alt to make up 32-bit address phase, sec 8.2.11 W25Q64JV reference cmd.cfg = AP_HAL::QSPI::CFG_ADDR_SIZE_24 | AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | AP_HAL::QSPI::CFG_ADDR_MODE_FOUR_LINES | From b452701a2b78614b8a4d8f3f7b60cb67db85a54b Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 5 Feb 2023 08:47:47 +0000 Subject: [PATCH 078/287] AP_HAL_ChibiOS: make sure MCUCONF subtype is defined --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index d1410d50ae580e..e44d3b3e2f05c8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -840,7 +840,7 @@ def write_mcu_config(f): f.write('// MCU type (ChibiOS define)\n') f.write('#define %s_MCUCONF\n' % get_config('MCU')) mcu_subtype = get_config('MCU', 1) - if mcu_subtype.endswith('xx'): + if mcu_subtype[-1:] == 'x' or mcu_subtype[-2:-1] == 'x': f.write('#define %s_MCUCONF\n\n' % mcu_subtype[:-2]) f.write('#define %s\n\n' % mcu_subtype) f.write('// crystal frequency\n') From 0221b565a5456c53a27460dfffb8a45e300cd28d Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 5 Feb 2023 10:16:46 +0000 Subject: [PATCH 079/287] scripts: make sure configure_all.py detects periph builds correctly --- Tools/scripts/configure_all.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/configure_all.py b/Tools/scripts/configure_all.py index 2c28c8fc7ba3c7..45629955f59829 100755 --- a/Tools/scripts/configure_all.py +++ b/Tools/scripts/configure_all.py @@ -68,7 +68,7 @@ def is_ap_periph(board): hwdef = os.path.join('libraries/AP_HAL_ChibiOS/hwdef/%s/hwdef.dat' % board) try: r = open(hwdef, 'r').read() - if r.find('periph/hwdef.dat') != -1 or r.find('AP_PERIPH') != -1: + if r.find('periph/hwdef.dat') != -1 or r.find('periph/hwdef.inc') != -1 or r.find('AP_PERIPH') != -1: print("%s is AP_Periph" % board) return True except Exception as ex: From a56a2ec2c1305df038b1f59f2c3ccc428e9bd6b7 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 10 Feb 2023 15:15:22 +0000 Subject: [PATCH 080/287] AP_HAL_ChibiOS: correct SDC power saving --- libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h | 2 +- libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h index 82b4efa8ef20f5..9ab42b12605315 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h @@ -482,7 +482,7 @@ #define STM32_SDC_SDMMC_CLOCK_DELAY 10 #define STM32_SDC_SDMMC1_DMA_PRIORITY 3 #define STM32_SDC_SDMMC1_IRQ_PRIORITY 9 -#define STM32_SDC_SDMMC_PWRSAV FALSE +#define STM32_SDC_SDMMC_PWRSAV TRUE /* * SERIAL driver system settings. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py index 62d734a7e11804..86bee245e89c38 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py @@ -28,7 +28,7 @@ 'RAM_MAP' : [ (0x30000000, 256, 0), # SRAM1, SRAM2 (0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast - (0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops + (0x24000000, 512, 4), # AXI SRAM. (0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused) (0x30040000, 32, 0), # SRAM3. (0x38000000, 64, 1), # SRAM4. @@ -36,7 +36,7 @@ # alternative RAM_MAP needed for px4 bootloader compatibility 'ALT_RAM_MAP' : [ - (0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops + (0x24000000, 512, 4), # AXI SRAM. (0x30000000, 256, 0), # SRAM1, SRAM2 (0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast (0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused) From d22bb20782d2af74dec4e67506a0877628d1814f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 11 Feb 2023 10:57:57 +0000 Subject: [PATCH 081/287] AP_HAL_ChibiOS: SDMMCv1 scratchpad is no longer used --- libraries/AP_HAL_ChibiOS/sdcard.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/sdcard.cpp b/libraries/AP_HAL_ChibiOS/sdcard.cpp index ddc51177b27f66..eaedca7214f980 100644 --- a/libraries/AP_HAL_ChibiOS/sdcard.cpp +++ b/libraries/AP_HAL_ChibiOS/sdcard.cpp @@ -36,9 +36,6 @@ static bool sdcard_running; #if HAL_USE_SDC static SDCConfig sdcconfig = { -#if !defined(STM32H7) - NULL, -#endif SDC_MODE_4BIT, 0 }; From a115681373f93ed182bdc155320ce3235943ebe8 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Tue, 21 Feb 2023 11:03:13 +0000 Subject: [PATCH 082/287] AP_HAL_ChibiOS: add support for building USB MSD --- libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk | 10 ++++++++++ .../AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 3 +++ 4 files changed, 15 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat index 97617a3192af49..ce9c39a20559b9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat @@ -58,7 +58,7 @@ PA14 JTCK-SWCLK SWD define USB_USE_WAIT TRUE -define HAL_USE_USB_MSD TRUE +define HAL_USE_USB_MSD 1 define HAL_DEVICE_THREAD_STACK 2048 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat index f81a6003814da9..c122822bd8ec14 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat @@ -70,7 +70,7 @@ define HAL_NO_MONITOR_THREAD define HAL_DISABLE_LOOP_DELAY define USB_USE_WAIT TRUE -define HAL_USE_USB_MSD TRUE +define HAL_USE_USB_MSD 1 define HAL_DEVICE_THREAD_STACK 2048 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk index 29723c6866e0ea..3da8419dc39366 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk @@ -136,6 +136,11 @@ CSRC += $(HWDEF)/common/stubs.c \ $(HWDEF)/common/bouncebuffer.c \ $(HWDEF)/common/watchdog.c +ifeq ($(USE_USB_MSD),yes) +CSRC += $(CHIBIOS)/os/various/scsi_bindings/lib_scsi.c \ + $(CHIBIOS)/os/hal/src/hal_usb_msd.c +endif + # $(TESTSRC) \ # test.c ifneq ($(CRASHCATCHER),) @@ -179,6 +184,11 @@ INCDIR = $(CHIBIOS)/os/license \ ifneq ($(CRASHCATCHER),) INCDIR += $(CRASHCATCHER)/include endif + +ifeq ($(USE_USB_MSD),yes) +INCDIR += $(CHIBIOS)/os/various/scsi_bindings +endif + # # Project, sources and paths ############################################################################## diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index e44d3b3e2f05c8..e383f752a49518 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -942,6 +942,9 @@ def write_mcu_config(f): if result: intdefines[result.group(1)] = int(result.group(2)) + if intdefines.get('HAL_USE_USB_MSD',0) == 1: + build_flags.append('USE_USB_MSD=yes') + if have_type_prefix('CAN') and not using_chibios_can: enable_can(f) flash_size = get_config('FLASH_SIZE_KB', type=int) From 2c7698f7480f199cd4694a6b207ecd2ce0d58b1f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 2 Mar 2023 14:16:09 +0000 Subject: [PATCH 083/287] AP_HAL_ChibiOS: update MatekF405-CAN bootloader to fit --- .../AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef-bl.dat | 13 ------------- .../AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat | 2 +- 2 files changed, 1 insertion(+), 14 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef-bl.dat index 1f19d9056cb287..783bb4f089b6c4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef-bl.dat @@ -23,22 +23,9 @@ SERIAL_ORDER OTG1 USART1 PA9 USART1_TX USART1 PA10 USART1_RX USART1 -PA2 USART2_TX USART2 -PA3 USART2_RX USART2 - -PC10 USART3_TX USART3 -PC11 USART3_RX USART3 - -PA0 UART4_TX UART4 -PA1 UART4_RX UART4 - -PC12 UART5_TX UART5 -PD2 UART5_RX UART5 - PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 - # Add CS pins to ensure they are high in bootloader PA4 MPU_CS CS PB12 MAG_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat index 127439f7c8a2b7..8addf44a7f33cb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat @@ -7,7 +7,7 @@ MCU STM32F4xx STM32F405xx FLASH_RESERVE_START_KB 64 FLASH_SIZE_KB 1024 -# store parameters in pages 11 and 12 +# store parameters in pages 2 and 3 STORAGE_FLASH_PAGE 1 define HAL_STORAGE_SIZE 15360 From 99eb8cf141703f7425e669f98a07d1b38ad387a1 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 2 Mar 2023 14:17:33 +0000 Subject: [PATCH 084/287] bootloaders: update bootloaders for MatekF405-CAN --- Tools/bootloaders/MatekF405-CAN_bl.bin | Bin 16344 -> 16220 bytes Tools/bootloaders/MatekF405-CAN_bl.hex | 2036 ++++++++++++------------ 2 files changed, 1014 insertions(+), 1022 deletions(-) diff --git a/Tools/bootloaders/MatekF405-CAN_bl.bin b/Tools/bootloaders/MatekF405-CAN_bl.bin index fb1863ac14b77c04a3f6ffbbfdd84635d94963a6..8dd1e4a25e80519a283df02ec96c1ffe839602d7 100755 GIT binary patch literal 16220 zcmch84Rlk-weFlBSx1%u*)m|u4oDUx1`#4`2o6qzESY0tK}>LR3x>3k4at#-K_N-& zv}qAPX$Z896KLz$NlS5mNYVm!;@+6xhydyBUs?%pYoNIyC5d9(+#X|tj%8cteIp4% z(!O`!UF)sqwMH{%X3w6Pz4y%Q*?XI$5%c>D5yBIR@HA3KDt`(2MbzJzp1=LG-#4~> zzFc+(5qwC`B6TCZkMwz%|L$A2=%4!x{)@WL<9YW6n8q8*pNIQ@{k?qdKhO97^%(zC zeC!1x6D1zm{Hv16z>u(WA%1oEUAR>6I4%?N2c)~N&VTrimkA?yf~LtBnr zmeI2Fp3k;a%Y?lDUxxI%uilyJlV%PKW$&cDSoxzED<6+>@|z>o@_qK{OY^Fpb>0~) zQ+RzWa?{eB8@^0v%X7Cn?+V_7Rwt4YA?BRVz_9W@;QISW_Oi*#f8pfL-K+31&SS6;^>ZwPm9;JHEgypuT;_iCs z>)ouG$ScQ+to0sS6KB(g>m^&Fu5t``9;x?~^iXK6J|?oD zVFil8a+Ll~Jj%LBL9NGMLE$L;4EM|`Ls!0-D>3sNA-;Hzb0l0RS-|x>&YInA5;sWd zxhsL{lr^i-KdL6T=^;{JT9>=g^g!;$)eqIKTfMRNf!d9=KBpXDYrVC; zf>dro4OwaOnovXYJm2PDRm&HwcFPGxSbnCT6m13fUKF=O@(mS+9ug!Fb2E~vCS`(@ zunx-mJ%?X*lV)>)YDquvqC{kM^ygK^ruOciRWcUNlj%=VJ4x&A@%>f%uG9L!c#_tn z&Dimxo3xrdFI15ijG*VVAh8<#Emhbv={dm~&uQ`B#IVRYPsB-~L%y<=w6T^WgJhBr%ojBWAbZ8XRI(v= z?%4haWWo>mjcKP1oTq(WLZ6R9%wo-LllD!XPhbnv<}m*z1FHCS49={V{E{;*wtf<=E~~&`w9> z9iumQ=w&^pw+TTqLybNfUlS35@tp{n`_oXe<;P(Ec0h%j=>aw0gstb9VY|nSJSPO!36fEi%Vty=*M6QOtL0 z_BceoK=Trj=Z^9V17ajn0{kmRG|iVI?X>WaQ7$RS`%>fBbO5Mtx421W4@b5-cQt2C2F2JsCg+H zJZc=_En1Op<{`Dc${k{NgmSJ^(N0sZK6da8aBcI!5^zmBpi6LVLt-SHx0 zQ7Cx^5!|6_l#J(BGV&WSbKcc%!^U)FUn;$I{pZJK%43({Y-(twE z{Yo{x1Kv|s1(2H4#0erh%0DlqZ&9NiYCvYlu}+6m=&`@1b*GEDO=<2L#p19^ z@A@=uM*M|n7VSqp6(mTB8KhQxG<{?hJ5@GJ-1~a(7hIPvp&wMYEBWfV6+4X6&KujCnLd`O3OYO-O#qTPoXh50!M~F3VkRrsvM+EJ!|dv9VjFDU}V4rxd=# zC9~XdjMp6cV#?ClMUZNrZfX2y|cl1at6rWw->2McZgukFgiyMhSh5RpL^WEg z@*YM+3+egT?;!H<5xT$V+-ZM`lj0yCd;>Ri^B9JRFXEicUGD) z)sG)6Aw*t}d+Y9Vg2jB38vUYLeRaztrH-K#j<2On>D`c)oq|8pZ?v{L)5F$>TphQ_ z4((#zfL@C;)M%+1P4zefnt=ze;>Ig8_;M<2+U(F|S(ua&Bo@r`;g7YI!7|y*yqw4# z%!WiBU>uN}9QBuJk4T!{y~?^QvzQBM`~AoQ>6e{9jQBmjiU8wQrE9XdO-l2ysrLUN}AhG&WIpS*N2e1?b04+6!>|O;tlolp4)+2e~Q9%jMoEiJ@6Ka6f<{N?wN45 zNMxQ>qwV9&^B1H;d5gq(!2Lo3cYlQT`aa4ZL=0W&E~DpT}QpIHowk$lmASL3KymNPuBvAMdr?HE6GW$AB6D-^BTn)ZCt+=7hLeG^D8cf4lyF#6MmCyU+yxC+q+GIhBpw>cY(leiqa6 z7f>!i-kqwWbaP`T$A_{ju%FL|n;3nBfsP3Xhcl0cT98aubJ*2=1 zYO@7Q0WY$T>P6B_2G=s!hnp$3&N$g?6X_R!<>15gG*F|nRqn98X9mt4Lqf)=+^Eq< z##yWNQIeoMy_ZY6PWUM2^16A80I7dQoh9;v+35d$@FVS<`KIb&;-&YG8r>Q!>G}Nn zja}s%&M155o21Mpe%9o$p05I~oN2Q>&WdKd z>_a2$VM9+g^tXS1^BVmaxdY{8sCzm|mttDpjxvRNG6@IzG4hra+% zqAgunZVsoSi*lftnaSQf$*p-5d}wC&kii}7ERlSl;-FZ6JFauHd*A6N_52m zN!Q;T=MVdPmVqD7PKGTun+STzUa$>ZNq-!=2HWhddR$lJQVPhf$Fn-9_R->Ht;dwT z*<6ZWbS@=b+!kImb~G#Z+F$85--Ovf6Q8eAp3VH~CYfRI&K=vK+`EE~O1~-Zi2UTy zk{;|P3op|9C0`|0>sJ9~Ps#u93THL6)mO2Eosvr=y7 zWDjSCm8w};Vz$h#mI=r8O`o0CM`>R$do+Bke_}Crfveh9uPr!U&#j}{a6WX5g`eSz zDZ!ViH^@q6m<%q{6pD;|D!!_Nd5M;C@pF1s!=u$6oA@DCHx8}CTnkpoX^ z?KcUS^DFUDX^k&WO2c~cI+$igX5&l?_Y$=oQoeI-Ne%5gO7iT};2s#2YJFJ}nSCXc zw~Hw?ItIi1U^#m!qMKLJwL-Bt{+b#EGn!$PR#L8U=cP8^{nC;S-r~toqyBhu_b~F% z7(Ho^r0jnsJ(PEhyz+I%%K3@)SU*#I!n?hWt2LsO=zh2_=(;uH3g0=;L@`^;>44^m^=^pm^Ia>ikIfSc!7;xB^LU+* zZ4xUpS=(@i9P8%`ws{%((Qf%Q;NdHt{y<`8{>1kk#}`~nwpt4i_>7jtK!ma@|T!7Joe)Mi@_fUCcnl!W0AYCiWE{XN$N!N5je^;|I-%h2UK(9gx z+%ZE&ZX2nW+N4*z_d+&}vPZKZM4%@!@}EYN`CFrO9>$I|)V5TlS$CkXzbA2<7Jd+V zO{uc~Z9}VbXYgYE-jQ@AQOnr<^=!f4>aFYE zioAMd>lPxn1zx@4*z%L`UPZJswteB(lx24MS}3~k>J_qSd1xwd?b|dj)PChyJ!5O` ztCs+2{t|vG46iAbcC&c6f)wruxuo`bPP$lcLO;W%+e414taFcZ%W%`7weI$M)_Sp? zSWjTSbd)W_jfdzs^wn{)f8u>VL3!r7rpRlcAsuaEVm3RJyMdj^C)FecnFIwnNF=eM zSMduGez2NruV;YQ+Qi!o;iL>x3Z0BospTy7(hjA1g#~;}YA|$sV*Ae!YVABQQOv~l z=MbB~eG2odwBMA*$&(nfnBL3CMG8~MhgeuuvJctZtr45M1-AcOWhk){f|Uq|Xdfeb zyc#m4nMD@8K8*bmP<^qNuR~oqcnxY_C@%%|W~>!Z9kCxovaj>l23?X$tQu`htf2p+ z`#UCIZ~asPz7!w-NPoTl(_ZW17x7kl0_XgrNKHs3DY+%KyFzKD=Q=0Np5HggRs`EU zCoh~gPbeswm-<_{@a+wUA&)OQvrnCn@^*EN4qfI(v+ir`PSQ0wiW)6S%q%@2$rCSR zC-T(kVKs@liP=xQe)ez=aUFDbMIy=l;EE;l1+mZWi@!wZJDu*aY#T4mg50IqG$E!h zufx!zD`jn?eaU{-RR77J>z{jJvaLU?PwdSbXQM{XrEK%(A}4TOt^vP$!`Eg-cjF%; z#L7LkP2zB3KQBG&96ePlaUQ3~;92Ft$@$r~z8l+wE+KVp>c7EZw!CdZ$kt7FrqHw7 z2k(W4YG&KL)Sp4Dmm^{LB8;9|&k)uM84YUOXC>jW9Ep`oo*EBRz&_UJiARqfDZH7O z?RZbWE4lNZI?RicLN-xXC1Ec-IznaRqDuV?^!qC#2Yg!GNow@0IufD%?zo8vJnT{D zrDmKRSElaYH;hdhLdwwt;56<99&j=vYMlQujZGG6QD(YPKhJ4SEkj zAEY%qP7Votb_dnL4Ve9})g35N`yN+yk5nVAF|{~H`v4y#26ADyhqVgc-P;7%!M027 z(0W`-_8ivdQp)Ez@#~nQt8ytb<{Xz?O3oa%fKxK&5d7-r@TfP;X&*Ebipv5YR)P+& zBb--zJ{F)?mO{^B-RGqi?O|e_V1>)sM`fU`a;$VRDwIg^h zC1|E}QR^@Rf6k;TqgbODw*1JM7M?AFdXOyzls+B|``(bsO>=S!gLA}oSW0JsDs5^3 zUWQy{66Tu;TqWRv;WcO?R$_&p)9nI%{sdkaVB@m-T42)&QLmmv_fo5rUfv4bflE-R z-D~Kvig+g|hTCeObFiKQyx6!fm2O7PJhDgHD(TDjKyuZQ0^j?-=P;lB&JWIJ!Y*rY z=uB#~CYW3g{DBqkDMtgspg}w5?moo;o#MlhJ|*Arvc%=VXWf@w-iuj41J(TowRA3T zE2J5a_E+%|XXJAuPeZ1A`?-0AxcQSZwZTVheIZ6ZHqzkRH^A$vmTVIzoMJ)ANikB8 z>??%tNoY_q-e85nEK@=G*TTLx z2fDKXxxcIRutpR_=A~?$JI58~Ks@^3xGR4RdApy?Ck0kNXRY`Dx|4Z@oo^7so!@ox zgDlVVnegr~!hXstY(B3r8BCEJ5%4CYrzBUYMvG%fT}FT$Q9EE#$DhtJvy(c$el{1T zI_t#Z$rqBkzYso*8`svId;w7HpYKzngWUzQ2STyPXElEkv||3+F3qf|xbbjvPvLTN zQ~TRc1)sgCf>$m|&%`ERM!y`6A@Zb1N}Z`Zfbc zE7DJq=#Cb!lj70W$9~-jO>#chr0<3Ypr;7jk4K-U9s~GCVef{2My}9^8K~VqW?TB} z&O*q>d#ccpcKg-NLRfj#Xdk`|_^O|)?|V=AHoQ3BZnjpxr|jJ~w@K{2*-vF9sUgc1 zjC|sanRDlcwFPC6zj$=rn7=#MT_D2F&(x&iGj_v!pVwscYZpwI|87JmSek&W9&16| z!~Xo-CY_Eg`tAL!!sk<-L#mmYCG?xim%};pg#{-fkbw=%f?(tc$P``gbI5lf8NQ}Y z&qt!sC)ECWo*O$uWsuy-I)pBrJFn@HZZ#^aTDQqZW(R|5Rka>=aA#4i$0QXD2kJ~7 zq36xpaPI)#$~?G4=+dLl9`yOMszV>AOq_@jketJTm8N8$M2_#z^wk&2T~qopmSrrp zHhsN2WBEie!-_p#cb~$4T~v4*-e#~LFDi$31p4DW3NE@HVjhdg82cE~Pp}pSekgk5 z&~gTLlD?3>I+(NANx19&s8T=G40}%bag)BAF%L(wV6l_Kd@1!|&_4P?dP@{Ss=qX* zM!%w}(Qm3*RYTU(o{Qvsr)!uzLN#=w*XVN%2a1heO+x3Y1Kd8W6}SyV?pG-PpFo|6 z*I-iS-oRd`_cWyu9VZJ`WXMpN26nq_(H-8F(>cg&^7hR`RDuz0YeV*Gyw@>@yVN1; zs7H<3)p?@hGE>OS$?2ORGkoFQ8Rd;8)a3lwS?tpcFxuH+D|!~=#J&q-3u6pC7xGsA zPJY1$kyo@IgiC$aVaFq--cq0IlE9UE5&5%WZX)JLjWViD`l0jV5MY3#6gcvMq%Y_scdjbpAxW=WJS0u2| zIr)i$;?j081q{5txEod22NE$oMsQw@URL)xq5URWnZ3{zRcf!IXE+Dl&eY9Sol+hx zGDiy|)>rDQnw|R7diS~fEYn-l3S^Gm?JS{D z1eSPo_Yv&xJO|R>BWn>SMPs9`C5poj`|@Ph4<%B78)N}L;56RDoK_H%QTS$%<_bSfcv8tPp}NS^47K6IhU;rf8#|K)I*>OE zU7BTPoIWq9)$%@9{d(5jz8>%Lpn~-%kXe5h*TmRhg9y)dmp8V+gE`AxyCD%1RA1Ye z$k*34em+WQqQzxi>qy(=>h1_+_YV~YvtRCi#?e)dDoyX2G)?#l4 z=5i!f>^rYb&g(UlX&bruXYdEmJ-I zh{4&|tlVulmBQ@0#27J~lB8dhT85T1o|C3XX)>4g$TZfb87MPmhyig@Z0kt%r7{Cn z#GFtJc~~QZdy#7i{)%T}+|aYW?*@zSP8$sTTiO*Ol39yFU);qHu40xl3tgL5^eXu| zde_^K7+VfOM3*7A#>d>^o%VA_+pET1&+Tp#nAtmnHLgBot+^$~d5Lo|gAP^$o91tn zwZtOUB>45axG?ZEp|4ukr5!bu^Vc!cTyyUM?vm*gcN6ulY6g~0{fk2KEW@PiKakUr zEtfd%80-v-IYhm1>9}(WMGLsKKMrUEeDil$hl%SLa*E4(Nvp*>Hb_7#!V`8|W0rJ$ zJ>rpIFJ3jz)wq;dv&uM39DE4B(=&q5`x1M!^8e5Vx-!3)avSuL(c_kCu;U4#w6=G> zE4}P9N~b-!-45H1pu=kPY}l18IUDogvwv-LXt>_R6pggDyD$pCYNjno7}<1#XwRWZnf%m)fys>3uO{`Nqby z0f&)Cyod00?CYfZC;|~tn`QO-M-3Q zwNmG(e3gt&DcIGWBb}3)ofA%FnNIYR8A%;WUrFh_EAcL*HwbK(G5+#~r>&P*Zo}5! z;}t&?vWP6+4RTpdMQV?ME`HF()%cL_X6YkO74vUzm|$Ti=HrS%Hyf5n4tixe){S`! z+<-INfOTW1=(2-2uU0r@vI6q2LknFu&NbeFb>m!{FW_|^V+I-531xnczXvp*3!0nF z9h_$fVN&rOM6?H4=)3v2ojXEB`9gzx*L={4NB5C z%AX=f6$3dqz##UZFvy92QF3&F&Q}Kllm6D%EbT)K(`to(1{4bH8_)?Y<*yI&ldkmT zlI5eE zMFO2y9JdK!9%lJ5qIb+)!7FQ~jUd zQgwhMgB}-m#p}{BzwJbPn~^C%EFahEaOv6zmufqq1T0iPvv+YXFq`>eew2f6C9Q^U zk?`q)SosLJ}d^2flLX<*BozHkvmegKnEWcQX z_wWVl*NVI8yDuJXgQxYAb0s|(iO`sU6Vh?S0G#l+5*S@6j4m(U#C6<;q&FlPH$Y$T z-)guEI`!{W4SYf0!gnFwsqGDaYryMoO?w?;r%qGdrZ;6Z`v>sTn8Isu0`PR`=&43# zzATl-@h(QV*}Laj}iSxz5mpgq&#z`KRxT`0~-BG)1D=T!9C&|gN{jgXNyI8 z*VF$Ua3MX5w`qHWqu6nKd!1tedccRD9RGVNjUVW7_MM`m{WfA3YsK;CrLp#gHRWF_ zZ?C(*JObMro8S{S%3HuEBeglC7jxhi-*)mdymHk;A0=$VagVcs@{jT>y&%ac!<*m} z#-)5Jz^i?Q!k6mloo&q#W3WGiw#EN~w%}F-I6vi=)n~eCf8F1}gU|Ep1Y!nmA*mm_6N92rizZ+ z^3G}o9UR`#HoP=!FQ&K!UfrJL)u*F=Po<7?-0S_oAAmy^X8&Qa^ zRSo_Mnv;T6^(HS{a1NYGe$x`QmjMR;(S-f1E6>f;Q*Yz94zKb&SvL_@u%JTq*pvNy zG1dD|_NOg4*-y%U>iG~cfPYeLh$cMQFIf4(`OJi>nd<}a-BJ4uW4+)>ui_pf&ux~N z=Q^c#`dO>iEs5{+^9$n9j6Toc-O_f? z@1+wSz0c)!`?$K@K3AO{z6&~cq3dS%&6Osf!(%aHD+SR{aIxP^BF|7dMMx7!ID(@cPQVRD&rkG=ueg3METpP^6MxcNR>NLKA9^2 z0_6*-^3M_$cOw7S>xp+cVI2mnjsCC8gRyutJPI90p)c}ybT!U9x(37oZr3cW+CXPr zRWB89$A2v)ZF6Y-2f1KRM3U6~D#JaY>a1iLzTnmIx{P$!InQZj%&c3A*Wl(8D5XnI zU`Y3v3(kFYJ7OFt4QV_f;bIzS>KAB?3O&sxy4Oh1%!IQIz3_JXXuaGU%g4M$T zd(MNo57t2cB9Fk%4qs1VzOZW))A(NCD5|O+c9dnp(w0~~@@KVUy{!_pJhXadyIZ9! zIfESy5hmBuN+E{>MbtL;95>cmyNULzeQ>(Fc2hHYPRHAe;tFgwdGe}iq}BXb zZw_oB&oN`YxmB&6T$FS1Uq!iYOE|YGQ_98vndOHamo-@?Pj;0NZ=Ok<#uf|fF|t!; zF$d@on1L`m7Os5=BRgx?)ox7Wh{^OoeDS5J+JmnUzNlA4jaI|Hc8vzP zsWF~#)_UszJEh9lh@Oot6;^ytak6edbi##1UhkPn>HI`;6L_QkRTJn)c6WB8>Gf^HyTnfd%FizwN%6N3m*m$%o zJ|4{-SEJt>PmUQpN(ixPs&Yl9*kC)}Pcm7=iYtgXCqXJFoQRlZ8~tA&GJ6EIHTNzr zE)o|nUW{(Z@_c*KwNlab()`<3ts;!Mm=Hr5VGOl|Gpr_B!#wmNgvQ^~{zjgVU!=;p zDE}%|wxE10RVLq0bor;BUL*eZ3~3yxAL$Cx`$+E~btCBzS4KNcMvNJQ^aZ3@NDGiG zNE47o0J9W1g=6Rs{_5?71mFt@z-L8$$Yq{PVkXE3bmamOV-v$iBlJ^UUFlZsd zcaT4f2I9LlGZ@0~GgwwLBaJXx%{C4WA05vSHXR+c z8isYyY%9%37ScLuYiA4?i8ypwWnTnRmct}?PRFNKNS1paUB5w`Z(ne$tL$!KpI1~o zf5GhwOYSIhy2_V`Kthq-m=dd?tNq_4LT2U?;oUs^Pj`NjMynuOG|}}-$OFh7_@K0E z^!hdu-@1p^qfD3sQ)u=w{s@D3%pcJ&+{r(u3rvzP(S|bqhw{chO6Fugko*H^rTRT$c*Tn z`;$^s9&=}^Ma5P}wCaG4K*2avEx}gj;XH0q?0h`N5k)5sy^g1llGEq;*FH%RxpV(} z|J!~$`?dDkYp=ET-fOSD4^kuJmjq&_q#!00f+rr|0dW}0Zw#Nz{cirox|`Ffwe-D2n9Y2INdm!9c_CHPk&icP= z_dmt|zk%zYiWu@D5|K0!-um{Ea^F>EcQO1X!tY(zn7jXU1rZEyyMoXkAl!AW=)qV? z;A-{H0#~>E4A-2#B0|mXIP7FiwTRGX|IjAgb!}O^joRqDn!X#iB1L(W6909iTD-?P zt0JrNNp@MFM4~k#;p~dc8*+vULuHn;jlDB)H`KBaq%bm0uh8EBLyDgOt`j5aRp~2! z$x`Q6Np#lkvf(fimrJQtsoyCh#Sh;_2!T!`GX#Vf2u7Sgwj9z>mKP739LRVP^!tk& z!u-FB)$_mB?tNcM4)zK!aNYl*-P`?@_%mc_zM8r_k2_d~jD&brCd82m^yx%6%eh5N zB)xuvmolTAI&X^kdGBAm*$=LJ@c9S-@?iGXbz9rE{$(pEP8n5mq_}8Q#np7BIDgJg z4-$nxXG^Z^E=miiIFv)=A|ol%qfz_Nu%D2#JOYHPQxZ-HmuLwY`8yj^O{X{>(^|qyT5L8ore{DWSy(d zV~)oLC_yU?E(4U{ILov3?J1R0ojN{CFbhUg6O7~qt{F63TZZWzlM#~*>P^{*cOIlZx)3O-S^Otm0t4GT*yM zo3@u<3)7~5Ex)S#is9@WtZ6Te&_$XSTItI(Qcw^HeHljce-%Up{vht@!wJyTJR}}% zB8;1=kod$1X*2>g6{CPR@xGBgBQ=2KCnE{m>Q0<`b|i6-NJM#qp#ttOhvvAQ&xQ#L zX|zBa)99Vt1&Oi#oK^Q(0oFZ2SO-G%t&uR`KPZqnwC}4?Qg6i7Jn1|EsXZA_-KopW-UlP z`|Cj?y{a@Xu!_^ZF80V}a%=Jx7~0hmk0bCJoX_6!&GghND`M`0HV+UDNVSSbvB%*`%sFkhpJneHiO` z70k_>=jolW9uz>G6@m@YRS@eBAw^5pgO)5AMtM6Tr;cD+|2U2*Jb6TO0ExZB`Zw%S z`4rlu=l%$NecQsQw0Ko%@s`r!MWw|_rG;b4m&&+*q0~He1c^OLxoyfhrMz7!fBcB% za5~8Eo#CBaY#htpMB<#`yE)CFXTn&rehEufzV_e|kZj71NaGRAv7`Y8B)k0D{YvjY zRB-V}fNx1Xj$rBX$Y)1vAc@7pv?-}231-lQ#0=8RpfZc(=)DSjInX4)7?wwl9?`ZF zg~>t2tUZiZs9O{Xy>cYBDj;#zh#Yl}-&RhDe;u>@4Qt`NBUlUP9J!Gn2P8ZncSN!k zn(~!CrX8VL5^EW&{ zSR%#rQ@(cTO}u_QHcYphmZs$|zjpRb;^mc+MMQzeRET*K!VERoS`bf$PRPH+Kt2I6 z1jL09TsRLfkHq7v5Wg62cUvN24n9tx`G3D!Mjk;qFhhQ*mWUPU)t^eMeWmtihmo}| z`@WG~!$h!yO$)7-au6jD<};G<;6g5+3ziXi385tC3sM4VmQV|cSGFgJBC_DKP<3R) zONi`PwJ2M!z&?ie;RB$bKF~o}f6H)Rv3}It3OmaAZeQAXU-S)q(Rr#+q7(OnjFbIb ziuW^B=?9nI*pKzC1gBwpg0ogK+bqH-9+fkR`z1$kM$Y;kUxosc^k5!%{e*biL}FFq zU9iICS_RAYW|lceh;t?i1(ky+^bh%#7xGumcwvuu4#u$>0wMn46dFW48uD3@;4Q=H zrx4B&;`dJ>q;eVr73`<&hGv#Lr*#k_I)#khGTav9DE23;pt(H32sNYQd0jZw{Z+Az z5R*?8Lq8Z!D^e5_IyQuMsLlfZnu9}(P3a5p5YE%9q1S-+QF)fS;z=pTTG)v!jG1X@ zg0vj{Re%5}6j+C8b?PyN0c4~vdj0d9*}?}`HB?TryVG_>$F{NygSIP~5Z?l^3F7%7 z%3`Wa&Q*<4mV1TPVaCW_A*kosoZwqSzWXe}5+!GXn1a$-5GO#)1QwbdGm{;}9U88K zo!OT$Ol(=5{Y)ptA&J;D1iQhd?{RF{w!Q){vy1_{CT(_cNaUu zOPo89UFWqKyxn?k6f8sfVh!kw0|J>xhpI&%OF7$IF#5bP$f1?dFhZnFsf&E4F7j=i zDx|Kg^)yF(_S$$$Qpuy*YhmCCwAcEPrIn?Ee^~dyDxz>W47LQa`W-XVhlvyo$9J|4 zqngK9Vvr!zAww7Bj6Q?4o4EZSVKgrq(sEXSCpn5cV9*T{S!nJ^$XiA_D6W+ygOo&M zjfA~rSnn-W`$0A;ZZ|ibYkqeD_o?*bmfxJfW%*rr-6`j0*UQn*WhgQP2kdN<@at{7EBuAsL@AQS3 zi?bWl1I_AV>_dsxWe&x3gM?WE!He|+&j~z-iv1Z?87r`rU>KhZGX{z5 z_q2%xxx~!J;+u^J}cDlR1j-55^LWp z?mn;#8F$}-7#o{{jzPRC2N`!Mb3p@CXq35{xd~1;zrl-34ra>HB{J>IeR#vemU?gZ^8h~; zWIhGL1ZWTPw;%iFYGM-@l+bo$;+w0gX4=`d@q9zu_5bz;fW-FWcVNG`4to=1;6KCu zNr9!DbsHyPCvjT+%!(w(ldL9~DiKQ)b5`4kWznGRDx&gj&6jIXG;HlQHlO?&S?CG_ zS6A~}JyYn*XZc~!v5#Raq+l0P?F3JC>dQceh^#y#*u~S-86I+4!uFlK1ARANep9~c zrhE;uf!>w`rFHA0LZNV8rQ)7HKBYfq9al%tgEXu(r{paW-$R9b>|_zEQ^C%gF5W^F zhVW^lSe?;tQtRUFRD;C`iHBjo<<2vvycu%z1-bg#j)#`ouEudZs-D{KRwu{dFK^0k zY-7n#{w9=vODNV$zqCH*4A|5QgIW)){3ZG_OM)(#E;1>}0c7%-E+&)*N<<^^vJ%?} zH;yB|2W=qZ`{h^E4+*ONrzJi;kIMwz)QuJiuN;3Z?B!2|=ZLn1<+K*)TAnONYvd^Z zVHkR7V*FIO9NjK=f5pHWUH2Z=-B{V?cv;PR@8wOFt&f*+@8!&&EUSx`Eqm`L3n$BJ z;$@58i!8?Hs_9kJD`CEYZT8&AH0KA>x}uD#Y4MVlk#wa5&c*SPCq{HiNm`XIUh;oN zQk4=oCs*RxfW#k;Xq6ItKEgDA27Vr_7ns&ToCcl1G!j}!gFax|QgIq|0n=o{Y0!gW zf5i&w$7rrTFoh%XY3{VNew8*<>O8=*A&0YW6Dw-Ty7hINmH7U(n>D6fuwZ^F-Rb;T zT9?zt<_lzSS;bys>>fFT31PguCU>BpBif)uZMH0QeR{|5Ke>oXTb`= z_d_Gz*D#m3!XO~q5NpB#d93G*4BIWeD6I)rXQh53#7jQNZC>iesYM1#B?EKSmu zNDaB{iG&aR?l_d$z|PU3A(xG?wAxNfzJ(ObWyznx?G)6W*I5nM zPY*i-%%QOkPrjqWHRWRJxka2FO7@Q(&AOfYOt3oS=ugK!7jAdF?CKEKW_9p+oCNzT zZnbmllJG^iS-`WLhW#poo2}rsd2R*lDV(|wLv0yz18z6qP6OPp4yYM9x?zmvx-u^c zFhKw}>!`nu8_yQpYL$Xp>rZl^oL(24^mrS;i+`VQa+SD97gewAX8b!nc26rygmwx$ zyLJl1qMdwQHtWjtvL4FQ#u8_G1-lE+hGH3JOgFYC8Q5#R;NzgVsc`a7-TkWYYG;S= zvWHmO!PjPYxH7hz0b@?!lF;G0Taofi87MsftJ`vB;ZT4hXr`8AM^9k>-^m5%HBT7&1Qw0 zPfi#)t-?+1|8V^OnD}=5_5a`Fzj=>Jhh4)CmKVsg5U1~ebTPzT@iLq~0cl*97%N+d z(^MSJ9V=Ue;qHYrwyQx8yKnQSI4Rge?0hrd%M+j@)V2%`wP-lltG1%Sbp*!p_5|9W zuawY3(;uW^Ho3Pm5>!Gr0Z-KDjWenvJ{PuAplzVI`{r@${Em$uOZ$rqLh5#UZbr!TV{&d3$vTm-erMQ9hI>cpgFGkB5z1akp)w96cA81GYhS_|tBbLoPWx z#i`mxb7TwAiUxO)b2;=3#(`;jXgtwLw37Q{CG?PGE9NQY!R-_DF>m)5Ad`Fai22v) zh|vf}^G?wIq(`WMon(uv@{z6ek|sI2NXBx@eRzvV5J=1z-zBZ8!M);q%+Azw7k9%WP*G|fv2n&-j# zLQM@C=cR<0%AM{6bB~+8sCG8H6D+-MWTDpMvs<&f*9~58ND*L@gRF{f^T#xY<_sY$ zr|CE7PHG4ZR;lthLj2Lh>Q3S?PIZreSBrinVJ(OGGSEat{m*+;u=+$gW2=v9;PC|G z3&X(Tigd7g65^q8;xLY%0SzecB-$4$tKgGTjK|b5a9s;^o-_f?8wzIa zC6?-JgP=1G@^UzFVX?nPGTHtT?*pjG(FrTD^r#C$yXRh^w39aRdO6xK5t~Vb_}mz_ z;g3(muorh@8G^lalCV%-JhOXU&Gl4$Z@s;qa#KzArkITB_!^3GOZX3Ym8;bCn2Qjr zC78cnyv_q2KOQxBqx6qxl2 zjOsfu8Smh|jI^L!SgE`RrK%dAbQgr`8dXzi)8sgOQc(>ai(AMNES>l~hA9MVzuPX5 z+p`3pRAW?`Nv{TY89M{mg%&8w5^$L+Ue+QNS-r5|=)g+=7_Br&2ut;jVYkpOxZm9` zIchRQUY!xzFO^zV;to~mWh&Qpg)Dr5MdH+^wP(rsNc@X$`B?<<6Fvfd|J{deOqj!? zv3SEMrcu|ahSCFNYOu?o&u(Q0&ihkvzvMLTmnyCH%cSM=jje2P;F5d)u*3T0MwDMI z8Y$nEaUaJ0AHGC0v^3(~9hoj|e0d|*h&6G)ySLjv)U*SMoj(7NZAV2Ad^0=V1)4c4 zk^igETT+!3pFm%M_%-+6+_TsBhHX~}_Y3UIv;LveTbB0uhYoJ(062&B1f-@aEq6(G zS+T7=B**9{6#6O99c1ZnUvgX49}N44v|APhZP!Tq3+zhh6>af_=)r2L!%bLnF2X7R zDbjMuox6T-I7ZEmi1#R_2cMVUhO!EyOV}@!TUWqunHF=w$N{ABP#N||)*ZDA9d1gv z}MW7OB$MyOF(2nA_O&b3H=Z-V>u&hRD&3#f@Dtp2zx; zqq7v+k`z5I?oL4kWKAapilOgfYZI-76*1-epe(;jw-4~Z@{S4fb8a)QV%&+1Jv&CiDCP!Oj@J4~xL2H|c z{`Dk=!+s=uc9)}7G7`rmpE;ufuP03sVR1Np@|;dHy2- z?mM@B#80hAf)qg}@mllwhmGcD$qdrLysm$nDaZXF@&BCM1^wtj&lTSiHKG!+KT3-( z8li0d-=*qVRbW#v8$4jwB)kuIe?I%{hP4f^3qQ|#hMjQ+*4L!h1xrJ}lzdF*u+--Z z@3QytuMLoDx9dYG*++y3ao5Nm=rhlAwrnrN8$53aKWD$_I~T6^yu&63pA;@e z{4r^lk_$+WU0PPa!f$awLZw~GF6a^LlD2>}Qxa2v;5VV5V^EL0Ww~(gjBRqv4>|f* z8G%J6N0Z{a0Y1lI-Olo?cBL5QXx}L;k4fmOV3RU_ke1S#f%;(Fu3)+=I@L}Vq^{@d zcpY!&X{dew6h2|bWKV%EsDlQ9-bWb2j8EF zgjG&zFdc5N+gyNW(Rmll6FB9?cq92KDD~NU_;n57gW$-yE2Z@NiUXwSX;#h6;*vtE zT?bs*^(wxUZ{nFu;3`-l$Gh|mZwNVt26RQoDz?@5hd3rbB#)7^O?}LA~ zRcI14j#eIC5IDVMNkY8~8Qa)e{=WrQm!6jLxQS@h*y-c;?6v6euk^^`r7UjPp~<35?)>o< zmL4Q&;;aGA442o@5?Me?L^e@42y|Ru%fN%Tb|f~pz>g5X{$nky!m7E`V9y}LX&KbC zX)|KlGPM$0@?VS?xha+S#PI1zGPEY+t+m}Ts01kc({Lml%V7`Um&0F&Z7_!Q5HNnc zCM8!*sQ~Z&AcOFkQ8oAxNe^mKVuc+2iL4s>Xe$kxuC9o!Rm}ku;7h>U0X%2{9BmL@ zg@A202F{)n(T_%deH?c2B5J#)OAkJcMZlqn=r2Z5-qjGSTreN-T?0O+PDI}tEvUfI zK)=j%s&Bn^d@ig^a`Y_Zw2*Tz(475LYVkp6$$^`{0|#es=eibn!H4sNNwI~+GO&f; z$z5!`QO;GD-%gUJNE0a0G@>|=*RS=)8qgrX^nKM6DD3I+1s(Su!D z=j+)ziI|m`SX=tLdr67R&fJbI5ORm|2L6 zAf&(@R~7{P5()dWFHmD2E9=WL(#H4`;g;>8E;%a7aO3Ae^8x{NWgSlr?p{>K!^$1; z)f;%G`;;B_JbEMP?$X=^GsxwTEZXl$mKwNA&Y$auh6s2CvPv={kOP)QK!kozLs$jlAmD}rYRYgr z8D@Yc4{INB4zv(v_<`}l z{$WoO2`YoLg?8$X4-#9J^%a0+po6m8g89n6cGYr;m!o&eU`@}V<`d_d!QY-!mBQH! zP@*5m(m05GG?1XScyi8Kpq&LMaLNSSG)c`Ck0oMz$l|himf9^Yc=@$a&0|^0(P=UT zy9@(6{bZYk;OWC{=sRfZN8!nK_R9=l?BZ^d$fbq8SX*i0*4#PL{e=|W?G+w6L(uqCyj8~4L0G|6;AGChbp?1nLEEw)P+~{+0~)XmfY%RMc+!!09g9`L0%N?- zE*WbumN;ErWW)Fp{Dhf+7YB0mv`id`z1z}(7Rb>n@-s|uscMs>nE{6TN7y@4F@tV(6COQ)<_ObMtM7V)yWmRXqWh;T7c33H{hT%6W68?BO zV(@#s$1e!I9rQPoRYM*Uk(sd2i(6}xU-VJ;+5kk26m-r&+Zpy zajy*0iEAYK=&vPo5MIEYqnAg+*$$0kKiIN;;IF|LP#~h{m#PY{m@moI;z7H61L^G8 zfO&`O4#B*mwiEeYKlmg<^PG;x18i1kF5D1;RY=yk>l&4KLtW#|@8YJK?8dd8iRi`A zna)f6Ot{@a#mEA`cb>Lb_|1*g5n9*bF7%-MvGatb(3K24Su|ScxsVX!PXVNH9h&_b z+yr3X_D10YNh@4{-*gDsg0m~h*@11CLN|Ez@hwaT@9kDQu`XlU@jSDoBO8T`BwA)Y z%|MX+jz)Mf1}9HBx>!Ekh%6wZw4VXKqGDJl?+3hjG1=PFh{6}y9tn9MZ0rHqLeO04 z(+CZX0~_4+T8qv#%`;8Zsz*auo*$2V3?sBeCfs#b+{5?)Y@X8x;V)> z0Jh0#JLH!#m?KLe<$-v~KqED%C1IZGE^p|lm%4WW-)%mmWgA0o zEBEvzQ;(y8$C)W0`DAU1kN~eR$o!fh1>ug$JF1C%ePBB0Xso_mI+Grl3eUqpFZ1_$ zRD;@NG|v{S+^ZT~O|2zvw|`y(ZysRW)JXDGo&7aOB~X+Nvig&xU7{LXPN8{Af=PS# z?0bqK=I#zu+TU-a2b!tx=}Rt??5{V>-zI%d^S z28=p;HE3Pa^y(Ag>D8TKdVtfNkx;%lg76&5$24F)PrhotOi}MZeKR!`_DF!67CVKn zoA@*E$`V0#(CQ@sUrdklCOSbi5PJju;+$>8$=wgx5Vf;S8VI zWy{|cu)&Sr#=YqR+nDVjmc2E4HR85Yg%&KAffDefd|-zgZ~JMGeZD|JDUqLed}^pq zVv2D+oT_&OK_k)wcF_m-h^Y27VDP0F3QAR5c0US!hy1pgjq12)lDV-ryg%!fp%!Q)P}iL?#Iop=UTJuGW@-D2;RiuB%Y;Q0dJxzWfQg#~+e zW#X2^GK1r-(Q6Ug<8p0VC;oz+y<|~9dP@R8pP*v$p(Ix?ifcXg(FncKJaRN z6*Pgz>&q}c*I<4;Q;tu)rHz|CZ+K?frbT@BZFYerADoDOZyc~x%hBEMp#^E@`(a(& zSKgj5Gk{ZAXFi0uAKt3qo$^D7C!!CG-=-q_cb4O}$LM6Bi7D2J>XZS&67kk12ka4T ztvzzEc7R`)K=-?0rPOr(sQf_L6|(N*6J&D#$I>dWpnv-kngeTIVn<`UFnoL;>jN)o zRGr!HYD{YAxtcVc6jLZNBBmW5^1-X%mwd;EY_}wZ@LVK@e0N_E^bOdn^df76c2=ri z(wFP{KcmQgYzZ8nco|Xzq~4rxLkhpxJTx%}QWT^*CVoim>c5x}gSE;pK?=j>%k_}L zu(M@L!j7Sbj$&w|yg3}BSbqb>_l-O;y0-M$Gt7V!uN`yAh|P>CHG@8(xoF}s*F$?kY43*iP0$|m7`G;F`(F6@1SXIqB;+3mkX~vKUZMrkk_f9O zOcnz7NX)&JLW_qKf)aDuCcHd=rXsVJdzMwWOM`#g(+0QSZG4?D-EkjZ6HbFyrA&Yk zo+;fO_=yB((?NpV6+lVJgG4g+D`Ne!H&O#7sUf^VM3C-%h`nXk%a+8;mfTRb6jsmw z1Q#y@IIEv}p4dtk(xX&vuZwP{+{mO-ZiC}a?s(y?TBt`z>cppL{R}uodouYRI4ktTQc( zh8FO4Na_6<8T++LOV9S<-hLOha&_Ezlo;!1SnK$Kqoe*_2Y7A~oCy>;QKPh}R~c<@ zJq6N&cjNGW;R8ihO^U4SZm{JL+0etY4OoK6{H>(^cE-H$9St+RSZ+jNE89^|pZUyVbL_WcBcd0o5Kqd%;#Pq3wuMr|2`US zZb11`kY3tu7z*n6Uih}9m+$o$9L*lmh2K*sGXuCnSm2un@!&}~{n(LtwcFq#&F4Wv zu{=&;|CP_a+U+fK3U+><(9Hi{=;bvYyUXdJ>i2o<^&0S-V>rfdcACo#9@`Z;HOa1g zvl5ZFn!&G&(}s;u<~B6K?*{k+3eGv$_ncqTTX@4AxNE+Qy}#Lq)y0FA$1W_N0hf@@Lj}7scF0 zhMK*DF_iRi1KgOg*|`VF3^5}1CJlkJM_-xJZ_ zjKwS$>`CZ933CR&iNYhrZ>n&7|CGwC&8^DGLGc;dYt3!-VEr#TUysaft~&R5@VXM_ zIu~Oy@Y%-k=%d{V%|`m-Ebzx{x!kjI%jG`h%b%XB3~&&i91Na1@bV&4oo5YvBV=f( z7r|RoZ)hOnab3ge`nrZS5HK}Rr%(g&{f5n&O08gv_`F(PzXe5XUi_wdW}rIav+5tn zd;m_(;6JJ5k+`Z$p##q9RwqavaNJT^9kG?9f>%fx8N^Q|jPbm)To7`xo1Zn{r=8@B;f8*G z%+|T;0e)Jgt`S-{9w@Uw4tj-L5ONo3x<92-w;Ad-A1HeXa?mT}f{?3+98;;=0(D!U z9ps=_$OR!6>viV!KGi11&%kQ<$*9_t05j+u#02fhi$ zHXiMTZzdVP9IcobkDeJGkGjUkqbua`sA&S;u1sJUIraH*LW6B>sUvl>sr05NybX ztl+P=L71$gVj!p!>TyyFp$6)4da^%kV-f_3O17^5VU1_gmTf4Ptu9&V$equ^gQD8f zl@%pbxd5M<3*YbLAm+hL#0)`fhqB)Sjftckkpw!uC=r+ok5mYx%7OQ$svH6lbPh?X za@2@OQ0=7P(jk#15SauG6I29g!%-8CP#T1E*dx*iEl`4NiD@O@2c#qgMAB3u9j6Gb zaBbVLkt?z;o^LO?3t1N~DlA%j>utqLN?5z2lmjFf*^NONCFaI|6%ZQELd?0DAhTI9 z9S7Sr4%fVjE;IFJC7PO@j!%4uAI$@ZRo4(6fhOkNO23RE(v#4yWO}&l~;@ z;vp*SKmw`P>mFv1F%E^>VfiR^inQVt5XEuE>b@;jQvcgJg<`-ksUtU`{ZCmrHWA>P NR)q5Ke*Rzl{a@LDDi;6% diff --git a/Tools/bootloaders/MatekF405-CAN_bl.hex b/Tools/bootloaders/MatekF405-CAN_bl.hex index cbd76558ecc312..3ce4d5cfc57171 100644 --- a/Tools/bootloaders/MatekF405-CAN_bl.hex +++ b/Tools/bootloaders/MatekF405-CAN_bl.hex @@ -1,1024 +1,1016 @@ :020000040800F2 -:1000000000060020E50100080D0F0008110F000890 -:10001000690F0008110F00083D0F0008E7010008F4 -:10002000E7010008E7010008E7010008DD290008F2 -:10003000E7010008E7010008E7010008E701000800 -:10004000E7010008E7010008E7010008E7010008F0 -:10005000E7010008E7010008113A00083D3A0008EE -:10006000693A0008953A0008C13A0008E70100081B -:10007000E7010008E7010008E7010008E7010008C0 -:10008000E7010008E7010008E7010008E7010008B0 -:10009000E7010008E7010008E7010008ED3A000861 -:1000A000E7010008E7010008E7010008E701000890 -:1000B0002D380008E7010008E7010008E701000803 -:1000C000E7010008E7010008E7010008E701000870 -:1000D000E7010008391100084D11000861110008FE -:1000E000553B0008E7010008E7010008E7010008A8 -:1000F000E7010008E7010008E7010008E701000840 -:10010000E7010008E7010008E7010008E70100082F -:100110007511000889110008E7010008E7010008CF -:10012000E7010008E7010008E7010008E70100080F -:10013000E7010008E7010008E7010008E7010008FF -:10014000E7010008E7010008E7010008C9300008DE -:10015000E7010008E7010008E7010008E7010008DF -:10016000E7010008E7010008E7010008E7010008CF -:10017000E7010008E7010008E7010008E7010008BF -:10018000E7010008E7010008E7010008E7010008AF -:10019000E7010008E7010008E7010008E70100089F -:1001A000E7010008E7010008E7010008E70100088F -:1001B000E7010008E7010008E7010008E70100087F -:1001C000E7010008E7010008E7010008E70100086F -:1001D000E7010008E7010008E7010008E70100085F -:1001E000D50E000802E000F000F8FEE772B63948CC -:1001F00080F30888384880F3098838484EF608515B -:10020000CEF20001086040F20000CCF200004EF691 -:100210003471CEF200010860BFF34F8FBFF36F8FD0 -:1002200040F20000C0F2F0004EF68851CEF200011C -:100230000860BFF34F8FBFF36F8F4FF00000E1EE08 -:10024000100A4EF63C71CEF200010860062080F3E1 -:100250001488BFF36F8F02F0FFFB03F07DFA4FF0BD -:1002600055301F491B4A91423CBF41F8040BFAE745 -:100270001C49194A91423CBF41F8040BFAE71A495C -:100280001A4A1B4B9A423EBF51F8040B42F8040B2A -:10029000F8E700201749184A91423CBF41F8040B87 -:1002A000FAE702F0DDFB03F0B3FA144C144DAC4254 -:1002B00003DA54F8041B8847F9E700F03FF8114CC3 -:1002C000114DAC4203DA54F8041B8847F9E702F0F9 -:1002D000C5BB00000006002000220020000000082E -:1002E0000000002000060020B03F0008002200208F -:1002F00028220020282200206C440020E001000871 -:10030000E4010008E4010008E40100082DE9F04FD1 -:100310002DED108AC1F80CD0C3689D46BDEC108A43 -:10032000BDE8F08F002383F311882846A047002002 -:1003300001F0D8FF01F0FAFE00DFFEE71B4B6FF083 -:10034000090270B51A70032200245A700F229C70A3 -:10035000DC701C715C719C71DC711C725C729A7235 -:10036000DC7202F00DFB064602F032FB054650B986 -:100370000F4B9E4217D001339E4241F2883412BF88 -:10038000054600240125002002F004FB0DB100F019 -:1003900059F800F047FD00F0BDFB204600F0B0F832 -:1003A00000F050F8F9E70446EDE700BF28220020EE -:1003B000010007B008B500F02BFBA0F12003584264 -:1003C000584108BD07B5054B02211B88ADF8043024 -:1003D00001A800F089FB03B05DF804FB3C3C000879 -:1003E00010B5202383F311881248C3680BB101F0C4 -:1003F000FFFF0023104A0F484FF47A7101F0BCFF51 -:10040000002383F311880D4C236813B12368013B4B -:100410002360636813B16368013B6360084B1B781A -:1004200033B9636823B9022000F062FC32236360B1 -:1004300010BD00BF34220020E1030008502300203B -:100440004822002010B5254B254953F8042F0132CE -:1004500000D110BD8B42F8D1224C234B22689A4226 -:100460003AD9224B9B6803F1006303F580339A422B -:1004700032D2002000F068FB1D4B0220187000F003 -:1004800029FC1C4B1A6C00221A64196E1A66196E2C -:10049000596C5A64596E5A665A6E5A6942F0800213 -:1004A0005A615A6922F080025A615A691A6942F007 -:1004B00000521A611A6922F000521A611B6972B661 -:1004C0000D4A0E4B13601B682268202181F31188AE -:1004D0009D4683F30888104710BD00BFFCFF00084D -:1004E0001C00010804000108FFFF0008282200206A -:1004F000482200200038024008ED00E0000001081A -:100500002DE9F04F99B0B34C01902022FF2110A8A3 -:10051000A66800F029FCB04A1378A346A3B9AF48F7 -:100520000121C3601170202383F31188C3680BB1CC -:1005300001F05EFF0023AA4AA8484FF47A7101F047 -:100540001BFF002383F31188019B13B1A54B019A74 -:100550001A60A54AA349019F0292002313704B60C1 -:1005600099461C461D469846012000F0B3FB002F1B -:1005700000F012829B4B1B68002B40F00D8219B0DB -:10058000BDE8F08F0220FFF715FF002840F0FB8147 -:10059000019BB9F1000F08BF1F46944B1B88ADF8B3 -:1005A0002C3002210BA800F09FFADDE74FF47A709F -:1005B00000F02EFA031E0393EADB0220FFF7FAFE97 -:1005C00082460028E4D0039B581E042800F2DD81F7 -:1005D000DFE800F0030E1114170018A8052340F8F7 -:1005E000343D042100F080FA54464FF0000856E0F4 -:1005F00004217848F6E704217D48F3E704217D488B -:10060000F0E71C24204600F0A1FA04340B900421EA -:100610000BA800F069FA2C2CF4D1E5E7002DB7D037 -:10062000002CB5D00220FFF7C5FE0546002800F0DB -:10063000AF8101206C4C00F087FA0220207000F09E -:1006400049FB4FF000095FFA89FA504600F08CFA36 -:10065000074658B1504600F097FA09F10109002801 -:10066000F1D12C46A9460027634B97E701230220CE -:10067000237000F021FB3E46DBF808309E4206D294 -:10068000304600F063FA0130EBD10436F4E7029B08 -:1006900000261E70534BA9465E602C46374600F07C -:1006A000B7FB15B1002C18BF0027FFF78BFE5BE7E7 -:1006B000002D3FF46DAF002C3FF46AAF029B022087 -:1006C000187000F007FB322000F0A2F9B0F1000A28 -:1006D000C0F25E811AF0030540F05A81DBF8082071 -:1006E00006EB0A03934200F25381BAF5807F00F2D1 -:1006F0004F8155450DDA4FF47A7000F089F9049076 -:10070000049B002BC0F244813C4A049BAB5401354E -:10071000EFE7C820FFF74EFE0546002800F03881BD -:100720001F2E11D8C6F12004544528BF544610ABE3 -:1007300026F0030022463149184400F0EBFA224625 -:10074000FF212E4800F010FB4FEAAA0A5FFA8AF256 -:100750002A49304600F010FB0446002800F01A81B8 -:1007600006EB8A0605469AE70220FFF723FE0028DB -:100770003FF40EAF00F02EFA00283FF409AF4FF01F -:10078000000A5346DBF8082092451CD2BAF11F0F2D -:1007900012D8109A01320FD02AF0030218A90A4485 -:1007A00052F8202C0B92184604220BA900F0F0FB03 -:1007B0000AF1040A0346E5E75046039300F0C6F940 -:1007C000039B0B90EFE718A8042140F84C3D00F084 -:1007D0008BF964E7282200204C23002034220020DB -:1007E000E103000850230020482200203E3C00087E -:1007F0002C22002030220020403C00084C22002007 -:1008000018A8002340F8343D642100F039F900288D -:100810007FF4BEAE0220FFF7CDFD00283FF4B8AE56 -:100820000B9800F0C3F918AB43F8480D04211846A3 -:10083000CDE718A8002340F8343D642100F020F9EA -:1008400000287FF4A5AE0220FFF7B4FD00283FF496 -:100850009FAE0B9800F0B8F918AB43F8440DE5E7EC -:100860000220FFF7A7FD00283FF492AE00F0C2F986 -:1008700018AB43F8400DD9E70220FFF79BFD002895 -:100880003FF486AE0BA9142000F0BAF9824618A8EE -:10089000042140F83CAD00F027F951460BA896E73B -:1008A000322000F0B5F8B0F1000AFFF671AE1AF090 -:1008B000030F7FF46DAEDBF808200AEB08039342C8 -:1008C0003FF666AE0220FFF775FD00283FF460AEEC -:1008D0002AF0030AC244D0453FF4E1AE404600F09E -:1008E00035F904210A900AA800F0FEF808F104087E -:1008F000F1E74FF47A70FFF75DFD00283FF448AE52 -:1009000000F068F900283FF4AFAE109B01330CD023 -:10091000082210A9002000F02FFA00283FF4A4AE0E -:100920002022FF2110A800F01FFAFFF74BFD3748E7 -:1009300001F0DEFC23E6002D3FF42AAE002C3FF44C -:1009400027AE18A8002340F8343D642100F098F841 -:10095000824600287FF41CAE0220FFF72BFD002802 -:100960003FF416AE0390FFF72DFD41F2883001F001 -:10097000BFFC0B9800F08EFA00F04AFA039B574632 -:100980001C461D46F0E5054689E64FF00008FFE5E8 -:100990002546FDE52C4667E6002000F039F8049076 -:1009A000049B002BFFF6E3AD012000F085F9049BCA -:1009B000213B122B3FF6D8AD01A252F823F000BF25 -:1009C00085050008AD0500081D060008690500083A -:1009D0006905000869050008B1060008A1080008BB -:1009E00069070008010800083308000861080008CA -:1009F000690500087908000869050008F30800087F -:100A00009F0600086905000837090008A086010054 -:100A10002DE9F34702AE00244FF47A7506F8014D34 -:100A2000144FDFF85880454397F900305A1C5FFA9D -:100A300084F901D0A34212D158F82400036801229E -:100A4000D3F820A031462B46D047012807D10A4BC6 -:100A50009DF8070083F8009002B0BDE8F0870134EC -:100A6000022CE1D14FF4FA7001F042FC4FF0FF305C -:100A7000F2E700BF0022002098230020803C0008FD -:100A80002DE9F0474FF47A75144FDFF85880064689 -:100A90004D43002497F900305A1C5FFA84F901D0C5 -:100AA000A34210D158F8240003680422D3F820A0F0 -:100AB00031462B46D047042805D1094B83F80090D6 -:100AC0000020BDE8F0870134022CE3D14FF4FA7026 -:100AD00001F00EFC4FF0FF30BDE8F087002200204F -:100AE00098230020803C000830B4074B1A78074B4D -:100AF00053F822402368DD69054B0A46AC4601469F -:100B0000204630BC604700BF98230020803C00088E -:100B1000A086010070B501F037FE094C094E207027 -:100B2000002530682378834208D901F027FE336816 -:100B300005440133B5F5803F3360F2D370BD00BF8B -:100B4000992300205823002001F0CCBE00F1006062 -:100B500000F580300068704700F10060920000F5F9 -:100B6000803001F057BE0000054B1A68054B1B781A -:100B70009B1A834202D9104401F000BE0020704746 -:100B8000582300209923002038B5074D04462868D3 -:100B9000204401F0FBFD28B928682044BDE8384016 -:100BA00001F00CBE38BD00BF5823002010F0030335 -:100BB00008D1B0F5007F05D800F10050A0F508403D -:100BC0000068704700207047014BC058704700BF55 -:100BD000107AFF1F064991F8243033B10023082210 -:100BE000086A81F82430FFF7B7BF0120704700BFC3 -:100BF0005C230020014B1868704700BF002004E010 -:100C000070B52A4B1C68C4F30B03240C63B140F28B -:100C10001342934231D040F2194293422FD040F216 -:100C2000214293422DD10323214A0C2505FB0323A6 -:100C30005D6893F9082042F201039C4224D0B4F588 -:100C4000805F23D041F201039C4221D041F2030393 -:100C50009C421FD041F207039C4208BF3122441E30 -:100C60000C44013D0B46A3421ED215F9016F581CDE -:100C700096B1034600F8016CF5E70123D4E702239F -:100C8000D2E73F220B4DD6E73322E3E74122E1E7EB -:100C90005A22E4E75922E2E72C2584421D7001D94B -:100CA000981C5A70401A70BD1846FBE7002004E0FB -:100CB000503C0008443C0008022804D14FF0804218 -:100CC000034B9A6170470128FCD14FF00052F7E7BF -:100CD00000000240022804D14FF48042034B9A6185 -:100CE00070470128FCD14FF40052F7E700000240A2 -:100CF000022805D1064A536983F480435361704743 -:100D00000128FCD1024A536983F40053F6E700BF7F -:100D10000000024010B50023934203D0CC5CC454C1 -:100D20000133F9E710BD000030B5441E14F9010F7E -:100D30000B4660B193F90050854201F1010106D1E3 -:100D40001AB993F90020801A30BD013AEEE7002A63 -:100D5000F7D1104630BD000002460346981A13F939 -:100D6000011B0029FAD1704702440346934202D086 -:100D700003F8011BFAE770472DE9F047234C94F87C -:100D8000243005468846174683BB2E46DFF87C9004 -:100D9000C7B394F824302BB92022FF21484626629D -:100DA000FFF7E2FF94F82400C0F10805BD4228BF18 -:100DB0003D465FFA85FAAD0041462A4604EB8000C5 -:100DC000FFF7A8FF94F82430A7EB0A079A445FFACC -:100DD0008AFABAF1080F2E44A844FFB284F824A07E -:100DE000D6D1FFF7F7FE0028D2D108E0266A06EB3D -:100DF0008306B042CAD0FFF7EDFE0028C5D100201F -:100E0000BDE8F0870120BDE8F08700BF5C2300202B -:100E1000024B1A78024B1A70704700BF98230020CB -:100E20000022002038B5154C154D204600F01AFD63 -:100E30002946204600F042FD2D6812486A6DD2F81E -:100E4000043843F00203C2F8043801F051FA0E49A5 -:100E5000284600F03FFE6A6D0C48D2F804380C4971 -:100E600023F00203C2F80438A0424FF4E1330B60D0 -:100E700003D0BDE8384000F053BC38BD983C00209A -:100E8000883D000840420F00B03D00085424002077 -:100E90008423002038B50B4B1A780B4B53F82240B3 -:100EA0000A4B9C4205460CD0094B002118461422DF -:100EB000FFF75AFF056001462046BDE8384000F0C4 -:100EC0002FBC38BD98230020803C0008983C0020AF -:100ED0008423002070B50A4C1C263246002120468F -:100EE000FFF742FF0125074B636065703246002122 -:100EF000A019FFF739FF044B25776577236270BD92 -:100F00009C2300200E0002400D000240FEE700007E -:100F100000B59BB0EFF3098168226846FFF7FAFE3F -:100F2000EFF30583044B9A6BDA6A9A6A9A6A9A6AB3 -:100F30009A6A9A6A9B6AFEE700ED00E000B59BB0F2 -:100F4000EFF3098168226846FFF7E4FEEFF30583BB -:100F5000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A24 -:100F6000FEE700BF00ED00E000B59BB0EFF30981A4 -:100F700068226846FFF7CEFEEFF30583034B5A6BFA -:100F80009A6A9A6A9A6A9A6A9B6AFEE700ED00E09A -:100F900030B5084D0A4491420BD011F8013B0924A9 -:100FA0005840013CF7D040F300032B4083EA500047 -:100FB000F7E730BD2083B8ED002304491A465A50A4 -:100FC000C8180833802B4260F9D17047D423002021 -:100FD000026843681143016003B11847704700007D -:100FE000024AD36843F0C003D36070470010014049 -:100FF000024AD36843F0C003D36070470044004006 -:10100000024AD36843F0C003D360704700480040F1 -:10101000024AD36843F0C003D3607047004C0040DD -:10102000024AD36843F0C003D360704700500040C9 -:101030002DE9F041D0F85C64F7683368DA050546BD -:101040009CB20DD5202383F311884FF40071043036 -:10105000FFF7BEFF6FF480733360002383F31188C2 -:10106000202383F3118805F1040814F02F0333D1F2 -:1010700083F31188380615D5210613D5202383F371 -:10108000118805F1380000F0A9FA002846DA082195 -:10109000281DFFF79DFF4FF67F733B40F360002351 -:1010A00083F311887A060ED563060CD5202383F3CB -:1010B0001188EA6C2B6D9A4202D12B6C002B2FD138 -:1010C000002383F31188D5F86424D368002B31D032 -:1010D0001069BDE8F0411847230713D014F0080F3A -:1010E0000CBF00218021E00748BF41F02001A2078A -:1010F00048BF41F04001630748BF41F4807140465A -:10110000FFF766FFA406736805D595F860142846B6 -:10111000194000F013FB3468A4B2A6E77060BEE784 -:1011200027F040073F041021281D3F0CFFF750FF18 -:10113000F760C5E7BDE8F08108B50348FFF778FF21 -:10114000BDE8084001F05ABC5424002008B503480B -:10115000FFF76EFFBDE8084001F050BCBC2800203E -:1011600008B50348FFF764FFBDE8084001F046BC3E -:10117000242D002008B50348FFF75AFFBDE80840BA -:1011800001F03CBC8C31002008B50348FFF750FF4C -:10119000BDE8084001F032BCF435002010B5174C12 -:1011A000174A2046002100F099FA164BC4F85C3427 -:1011B000154C164A2046002100F090FA144BC4F852 -:1011C0005C34144C144A2046002100F087FA134B7B -:1011D000C4F85C34124C134A2046002100F07EFA19 -:1011E000114BC4F85C34114C114A0021204600F028 -:1011F00075FA104BC4F85C3410BD00BF54240020B5 -:10120000E10F000800100140BC280020F10F000889 -:1012100000440040242D0020011000080048004038 -:101220008C31002011100008004C0040F4350020E3 -:10123000211000080050004038B5494D037C0029BA -:1012400018BF0D46012B0446C0F8645410D1454B1D -:10125000984242D1444B5A6C42F010025A645A6E82 -:1012600042F010025A665B6E0B21252000F08EF8CA -:101270003E4BD4F85C249A422B6802D03C498A4207 -:101280006BD13C4901EB5301B1FBF3F3A98808048E -:1012900042BF23F0070003F0070343EA40039360D3 -:1012A000EB8843F040039BB213612B8943F00103A9 -:1012B0009BB2536141F4045343F02C03D36001F417 -:1012C000A05100231360B1F5806F136853680CBF01 -:1012D0007F23FF2384F8603438BD274B98420CD11C -:1012E000214B1A6C42F400321A641A6E42F4003236 -:1012F0001A661B6E0B212620B8E7204B98420CD1B2 -:10130000194B1A6C42F480221A641A6E42F480223D -:101310001A661B6E0B212720A8E7194B98420CD1A7 -:10132000114B1A6C42F400221A641A6E42F4002225 -:101330001A661B6E0B21342098E7124B984297D106 -:10134000094B1A6C42F480121A641A6E42F480122D -:101350001A661B6E0B21352088E70B4992E700BF08 -:10136000A83C00085424002000380240001001402E -:101370000014014000BD0105BC280020242D0020E0 -:101380008C310020F435002080DE800200F16043C3 -:1013900000F01F02400903F5614309018000C9B252 -:1013A00000F1604083F8001300F561400123934091 -:1013B000C0F8803103607047F8B515468268066949 -:1013C000AA420B46816938BF8568761AB542044641 -:1013D00007D218462A46FFF79DFCA3692B44A36158 -:1013E0000DE011D932461846FFF794FCAF1B3A4680 -:1013F000E1683044FFF78EFCE2683A44A261A368DA -:101400005B1BA3602846F8BD18462A46FFF782FCFE -:10141000E368E4E783682DE9F0410446934215460A -:10142000266938BF85684069361AB5420F4606D22C -:101430002A46FFF76FFC63692B4463610DE012D904 -:101440003246A5EB0608FFF765FC4246B919E0688D -:10145000FFF760FCE26842446261A3685B1BA36023 -:101460002846BDE8F0812A46FFF754FCE368E4E72C -:1014700010B50A440024C361029B00604060846090 -:10148000C160816141610261036210BD08B582697A -:101490004369934201D1826882B9826801328260D5 -:1014A0005A1C42611970426903699A4201D3C368A8 -:1014B0004361002100F038FF002008BD4FF0FF30ED -:1014C00008BD000070B5202304460E4683F3118842 -:1014D000A568A5B1A368A269013BA360531CA361E1 -:1014E00015782269934224BFE368A361E3690BB1D5 -:1014F00020469847002383F31188284670BD314663 -:10150000204600F001FF0028E2DA85F3118870BD63 -:101510002DE9F74F05460F4690469A46D0F81C90A5 -:10152000202686F311884FF0000B144664B1224642 -:1015300039462846FFF740FF034668B9514628461A -:1015400000F0E2FE0028F1D0002383F31188A8EB1D -:10155000040003B0BDE8F08FB9F1000F03D0019093 -:101560002846C847019B8BF31188E41A1F4486F371 -:101570001188DBE7C16081614161C3611144009B57 -:10158000006040608260016103627047F8B5044604 -:101590000E461746202383F31188A568A5B1A368DA -:1015A000013BA36063695A1C62611E702369626912 -:1015B0009A4224BFE3686361E3690BB12046984710 -:1015C000002080F31188F8BD3946204600F09CFECB -:1015D0000028E2DA85F31188F8BD000083694269CA -:1015E0009A4210B501D182687AB98268013282606C -:1015F0005A1C82611C7803699A4201D3C3688361D3 -:10160000002100F091FE204610BD4FF0FF3010BDCC -:101610002DE9F74F05460F4690469A46D0F81C90A4 -:10162000202686F311884FF0000B144664B1224641 -:1016300039462846FFF7EEFE034668B9514628466C -:1016400000F062FE0028F1D0002383F31188A8EB9C -:10165000040003B0BDE8F08FB9F1000F03D0019092 -:101660002846C847019B8BF31188E41A1F4486F370 -:101670001188DBE7026843681143016003B1184732 -:10168000704700001430FFF743BF00004FF0FF33F6 -:101690001430FFF73DBF00003830FFF7B9BF00003E -:1016A0004FF0FF333830FFF7B3BF00001430FFF7BF -:1016B00009BF00004FF0FF311430FFF703BF0000F7 -:1016C0003830FFF763BF00004FF0FF323830FFF7CC -:1016D0005DBF000000207047FFF760BD37B50F4BBE -:1016E0000360002343608360C360012304460374E6 -:1016F000154600900B464FF4007200F15C01143067 -:10170000FFF7B6FE00942B464FF4007204F51771F4 -:1017100004F13800FFF72EFF03B030BDBC3C0008D9 -:1017200010B52023044683F31188FFF785FD0223BB -:101730002374002383F3118810BD000038B5C369FA -:1017400004460D461BB904210844FFF793FF2946C0 -:1017500004F11400FFF79AFE002806DA201D4FF46A -:101760008061BDE83840FFF785BF38BD0268436837 -:101770001143016003B118477047000013B5446B73 -:10178000D4F894341A681178042915D1217C0229DF -:1017900012D11979128901238B4013420CD101A96E -:1017A00004F14C0001F0E0FED4F89444019B21794F -:1017B0000246206800F0DAF902B010BD143001F0E2 -:1017C00063BE00004FF0FF33143001F05DBE000037 -:1017D0004C3001F035BF00004FF0FF334C3001F0CA -:1017E0002FBF0000143001F031BE00004FF0FF3178 -:1017F000143001F02BBE00004C3001F001BF00009E -:101800004FF0FF324C3001F0FBBE0000D0F89424C2 -:1018100038B5136819780429054601D0012038BD70 -:10182000017C0229FAD112795C89012090400440A0 -:10183000F4D105F1140001F0C3FD02460028EDD0FB -:10184000D5F894544FF480732868697900F07CF9D6 -:10185000204638BD406BFFF7D9BF0000002070471D -:10186000704700007FB5124B036000234360836024 -:10187000C360012502260F4B0574044602900193B4 -:1018800000F18402294600964FF48073143001F071 -:1018900073FD094B0193029400964FF4807304F595 -:1018A0002372294604F14C0001F03AFE04B070BDE9 -:1018B000E43C0008551800087D1700080B6820223A -:1018C00082F311880A7903EB820290614A79093226 -:1018D00043F822008A7912B103EB82039861022354 -:1018E0000374C0F89414002383F311887047000038 -:1018F00038B5037F044613B190F85430ABB9201DBE -:1019000001250221FFF732FF04F1140025776FF063 -:10191000010100F015FD84F8545004F14C006FF003 -:101920000101BDE8384000F00BBD38BD10B5012104 -:1019300004460430FFF71AFF0023237784F854305D -:1019400010BD000038B504460025143001F02CFD10 -:1019500004F14C00257701F0FBFD201D84F8545064 -:101960000121FFF703FF2046BDE83840FFF74EBFD7 -:1019700090F8443003F06003202B19D190F84520F3 -:10198000212A0AD0222A4FF000030ED0202A0FD19C -:10199000084A82630722C26304E0064B836307237D -:1019A000C36300230364012070478363C363F9E7C3 -:1019B0000020704701220020D0F8943437B51A680F -:1019C0001178042904461AD1017C022917D119790A -:1019D000128901238B40134211D100F14C05284696 -:1019E00001F076FE58B101A9284601F0BDFDD4F8FA -:1019F0009444019B21790246206800F0B7F803B0B7 -:101A000030BD000000EB8103F7B59C6905460E462A -:101A1000F4B1202383F3118805EB8607201D0821EC -:101A2000FFF7A4FEFB685B691B684C3413B12046CA -:101A300001F0A8FD01A9204601F096FD024648B13B -:101A4000019B3146284600F091F8002383F311886A -:101A500003B0F0BDFB685A691268002AF5D01B8AF2 -:101A6000013B1340F1D105F14402EAE7093138B5F1 -:101A700050F82140DCB1202383F31188D4F894245A -:101A80001368527903EB8203DB689B695D6845B19B -:101A900004216018FFF76AFE294604F1140001F0E2 -:101AA00099FC2046FFF7B2FE002383F3118838BD6E -:101AB0007047000001F05AB801230370002343600F -:101AC000C36183620362C362436203630381438130 -:101AD0007047000038B50446202383F311880025A1 -:101AE0004160C56005614561856101F04FF80223E1 -:101AF000237085F3118838BD70B500EB810305466E -:101B00005069DA600E46144618B110220021FFF722 -:101B10002BF9A06918B110220021FFF725F93146F1 -:101B20002846BDE8704001F0FBB80000028902F0D1 -:101B300001020281428902F0010242810022026117 -:101B40004261826101F080B9F0B400EB8104478901 -:101B5000E4680125A4698D403D434581236000234D -:101B6000A2606360F0BC01F09BB90000F0B400EB30 -:101B700081040789E468012564698D403D4305813E -:101B800023600023A2606360F0BC01F015BA00007E -:101B900070B50223002504460370A0F84C5080F86D -:101BA0004E5080F84F5005814581C5600561456103 -:101BB000856180F8345001F04FF863681B6823B1E9 -:101BC00029462046BDE87040184770BD436802783A -:101BD0001B6880F85020052202700BB104211847C1 -:101BE00070470000436890F850201B6802700BB1EA -:101BF000052118477047000090F8343070B504464E -:101C000013B1002380F8343004F14402204601F07F -:101C10003DF963689B6863BB94F8445015F0600617 -:101C200015D194F8453005F07F0545EA032540F2CB -:101C300002339D4200F00E815BD8022D00F0DC8063 -:101C40003FD8002D00F08780012D00F0CF800021CB -:101C5000204601F073FB0021204601F065FB63681C -:101C60001B6813B1062120469847062384F83430B8 -:101C700070BD204698470028CED094F84B2094F8A9 -:101C80004A3043EA0223E26B934238BFE36394F99C -:101C90004430E56B002B4FF0200380F2FD80002DD7 -:101CA00000F0EC80092284F8342083F311880021AD -:101CB000E36BA26B2046FFF759FF002383F31188E3 -:101CC00070BDB5F5817F00F0B180B5F5407F49D09A -:101CD000B5F5807FBBD194F84630012BB7D1B4F86D -:101CE0004C3023F00203A4F84C30A663E66326646C -:101CF000C3E740F201639D421ED8B5F5C06F3BD2E9 -:101D0000B5F5A06FA3D1B4F84430B3F5A06F0ED1F0 -:101D100094F8463084F84E30204600F0F5FF6368B2 -:101D20001B6813B101212046984703232370002329 -:101D3000A363E3632364A0E7B5F5106F32D040F6E8 -:101D400002439D4252D0B5F5006F80D104F14F039C -:101D5000A363012324E004F14C03A3630223E363A0 -:101D600025648AE794F84630012B7FF470AFB4F80D -:101D70004C3043F00203B6E794F84920616894F8C8 -:101D800048304D6894F8471043EA0223204694F8FF -:101D90004620A84700283FF45AAF4368A36303686E -:101DA000E363A4E72378042B10D1202383F3118865 -:101DB0002046FFF7BBFE86F31188636884F84F6006 -:101DC0001B68032121700BB12046984794F84630D8 -:101DD000002BACD084F84F300423237063681B6859 -:101DE000002BA4D0022120469847A0E7374BA363DD -:101DF0000223E36300239DE794F8481011F0800F5D -:101E0000204601F00F010ED001F032F8012806D073 -:101E100002287FF41CAF2E4BA363E06367E72D4BD2 -:101E2000A363E56363E701F015F8EFE794F8463044 -:101E3000002B7FF40CAF94F8483013F00F013FF4FF -:101E400076AF1A06204602D501F08CFA6FE701F052 -:101E50007FFA6CE794F84630002B7FF4F8AE94F8E4 -:101E6000483013F00F013FF462AF1B06204602D545 -:101E700001F064FA5BE701F057FA58E7142284F89E -:101E8000342083F311882B462A4629462046FFF743 -:101E90005BFE85F3118870BD5DB1152284F8342096 -:101EA00083F311880021E36BA26B2046FFF74CFE01 -:101EB00003E70B2284F8342083F311882B462A464B -:101EC00029462046FFF752FEE3E700BF143D000815 -:101ED0000C3D0008103D000838B590F83430044639 -:101EE000152B29D8DFE803F03E28282828283E288B -:101EF000280B293928282828282828283E3E90F809 -:101F00004B1090F84A20C36B42EA01229A4214D93E -:101F1000C268128AB3FBF2F502FB15356DB92023B6 -:101F200083F311882B462A462946FFF71FFE85F3C7 -:101F300011880A2384F8343038BD142384F83430EF -:101F4000202383F3118800231A4619462046FFF701 -:101F5000FBFD002383F3118838BD036C03B1984760 -:101F60000023E7E7002101F0E9F90021204601F014 -:101F7000DBF963681B6813B10621204698470623E6 -:101F8000D8E7000090F83420152A38B5044622D846 -:101F90000123934040F6416213421DD113F4801592 -:101FA0000FD19B0217D50B2380F83430202383F305 -:101FB00011882B462A462946FFF7D8FD85F311885C -:101FC00038BDC3689B695B682BB9036C03B1984744 -:101FD000002384F8343038BD002101F0AFF900212E -:101FE000204601F0A1F963681B6813B10621204661 -:101FF00098470623EDE70000024B00221B605B6060 -:102000009A6070475C3A0020002303748268054B95 -:102010001B6899689142FBD25A6803604260106065 -:10202000586070475C3A002008B5202383F311887C -:10203000037C032B05D0042B0DD02BB983F311881F -:1020400008BD436900221A604FF0FF334361FFF778 -:10205000DBFF0023F2E790E80C001A60026853608F -:10206000F2E70000002303748268054B1B6899683F -:102070009142FBD85A680360426010605860704714 -:102080005C3A0020054B19690874186802681A60E8 -:102090005360186101230374FEF738B95C3A0020DD -:1020A00030B54B1C87B005460A4C10D023690A4A4C -:1020B00001A800F061F92846FFF7E4FF049B13B183 -:1020C00001A800F095F92369586907B030BDFFF702 -:1020D000D9FFF8E75C3A00202920000838B50C4DFC -:1020E00041612B6981689A689142044603D8BDE832 -:1020F0003840FFF789BF1846FFF786FF01232C61A0 -:10210000014623742046BDE83840FEF7FFB800BF03 -:102110005C3A0020044B1A681B6990689B689842DF -:1021200094BF0020012070475C3A002010B5084C95 -:10213000236820691A6822605460012223611A749E -:10214000FFF790FF01462069BDE81040FEF7DEB8BA -:102150005C3A0020FEE7000010B5174CFFF74CFF7B -:1021600000F0FCF880221549204600F081F8012398 -:1021700044F8180C0374124B124AD96821F4E06138 -:102180000904090C0A431049DA60CA6842F08072F7 -:10219000CA600E490A6842F001020A601022DA772A -:1021A000202283F82220002383F3118862B6084896 -:1021B000BDE8104000F07EB8843A0020183D0008C9 -:1021C00000ED00E00003FA05F0ED00E0001000E093 -:1021D000203D00082DE9F84F1F4C4FF000086569BD -:1021E00004F11407C1464FF08043266A5B6AAA686F -:1021F0009E1B96421DD34FF0200AAA68236AD5F889 -:102200000CB0134423622B68BB425F60A6EB02064E -:102210006361C5F80C8001D101F084FA89F311885B -:102220002869D8478AF311886569AB689E42E4D271 -:10223000D9E76269BA420CD0916823628E1B96601E -:10224000A86802282CBF1818981CBDE8F84F01F0A8 -:102250006FBABDE8F88F00BF5C3A0020034B5968A5 -:102260005A68521A9042FBD8704700BF001000E035 -:102270008260022202740022427470478368A3F1D4 -:102280007C0243F80C2C026943F83C2C426943F869 -:10229000382C074A43F81C2CC26843F8102C022241 -:1022A00003F8082C002203F8072CA3F1180070474C -:1022B0002503000810B5202383F31188FFF7DEFF04 -:1022C00000210446FFF70AFF002383F3118820460C -:1022D00010BD0000024B1B6958610F20FFF7D2BEF2 -:1022E0005C3A0020202383F31188FFF7F3BF00003E -:1022F00008B50146202383F311880820FFF7D0FE9C -:10230000002383F3118808BD49B1064B42681B695D -:1023100018605A60136043600420FFF7C1BE4FF09D -:10232000FF3070475C3A00200368984206D01A6874 -:102330000260506059611846FFF766BE70470000A2 -:1023400038B504460D462068844200D138BD036884 -:1023500023605C604561FFF757FEF4E7054B03F12E -:1023600014025A619A614FF0FF32DA6100221A6258 -:10237000704700BF5C3A0020F8B503614FF080431E -:10238000C2605C6A194B1A46022952F8145F38BFC2 -:102390000221954206461F460AD1586198611C6287 -:1023A0000560456081600819BDE8F84001F0B2B9E8 -:1023B000186AAB68241A0C1902D3E41A2D6804E0D9 -:1023C0009C4202D2204401F0B3F9AB689C42F4D89D -:1023D0006B68736035601E606E60B460A9684FF012 -:1023E000FF33091BA960FB61F8BD00BF5C3A002008 -:1023F00010B41B4C234653F8141F814210D041687F -:1024000002680A60026851609A424FF00001C160A0 -:1024100003D0936881680B4493605DF8044B704768 -:102420000A68626100209A425360C86003D15DF877 -:10243000044B01F077B993688868034493604FF0C8 -:102440008042206A526A121A9342E6D9991A0129E7 -:1024500098BF931C18445DF8044B01F069B900BFA4 -:102460005C3A002000207047FEE700007047000043 -:102470004FF0FF3070470000022906D0032906D034 -:102480000129064818BF0020704705487047032AF5 -:102490009ABF044800EBC200002070470C3E0008C1 -:1024A000C03D00080822002070B59AB001AD064674 -:1024B00008462946144600F095F82846FEF74CFCDD -:1024C000C0B2431C5B0086E81800237003236370CE -:1024D000002302341946DAB2904204F1020401D812 -:1024E0001AB070BDEA5C04F8022C04F8011C013338 -:1024F000F1E7000008B5202383F311880348FFF7B4 -:102500005BFA002383F3118808BD00BF983C0020CC -:1025100010B50446052916D8DFE801F01615031694 -:10252000161D202383F311880E4A0121FFF7E4FAD8 -:1025300020460D4A0221FFF7DFFA0C48FFF702FAA6 -:10254000002383F3118810BD202383F311880748EB -:10255000FFF7CEF9F4E7202383F311880348FFF750 -:10256000E5F9EDE7403D0008643D0008983C002097 -:1025700038B50C4D0C4C0D492A4604F10800FFF704 -:1025800093FF05F1CA0204F110000949FFF78CFF1F -:1025900005F5CA7204F118000649BDE83840FFF796 -:1025A00083BF00BF6041002008220020903D00084A -:1025B0009A3D0008A53D000870B5044608460D4642 -:1025C000FEF7CAFBC6B22046013403780BB91846A1 -:1025D00070BD32462946FEF7A7FB0028F3D1012043 -:1025E00070BD00002DE9F04704460D46FEF7B4FB30 -:1025F0002C49C6B22046FFF7DFFF08B10636F6B217 -:1026000029492046FFF7D8FF08B11036F6B2632EED -:102610000BD8DFF89080DFF89090244FDFF898A077 -:10262000267846B92E70BDE8F08721462846BDE8D9 -:10263000F04701F0FBBA252E2FD107224146204654 -:10264000FEF772FB70B91A4B2A4603F10C0153F8DE -:10265000040B42F8040B8B42F9D11B78137007343A -:102660000D35DDE7082249462046FEF75DFBA0B99F -:10267000104BAA1C13F8011F09095345C95D02F844 -:10268000021C197801F00F0102F10202C95D02F883 -:10269000031CEFD118350834C2E72E700134013520 -:1026A000BEE700BF2C3E0008A53D0008423E0008E2 -:1026B000343E00080F7AFF1F1B7AFF1FBFF34F8FB6 -:1026C000024AD368DB03FCD4704700BF003C0240E1 -:1026D00008B5094B1B7873B9FFF7F0FF074B1A6970 -:1026E000002ABFBF064A5A6002F188325A601A684F -:1026F00022F480621A6008BDBE430020003C024004 -:102700002301674508B50B4B1B7893B9FFF7D6FF3C -:10271000094B1A6942F000421A611A6842F4805269 -:102720001A601A6822F480521A601A6842F48062B1 -:102730001A6008BDBE430020003C02400B2870B563 -:1027400013D80B4A0B4C137863B90B4E4FF0006152 -:1027500044F8231056F8235001330C2B2944F7D1A9 -:102760000123137054F8200070BD002070BD00BF1D -:10277000F0430020C0430020543E0008014B53F8B2 -:1027800020007047543E00080C2070470B2810B5FD -:10279000044601D9002010BDFFF7D0FF064B53F8C7 -:1027A00024301844C21A0BB9012010BD126801323E -:1027B000F0D1043BF6E700BF543E00080B2810B5EB -:1027C000044621D8FFF77AFFFFF782FF0F4AF32371 -:1027D000D360C300DBB243F4007343F00203136120 -:1027E000136943F480331361FFF768FFFFF7A6FF17 -:1027F000074B53F8241000F0DDF8FFF783FF204665 -:10280000BDE81040FFF7C2BF002010BD003C0240F1 -:10281000543E00082DE9F84312F00103154640D15B -:102820008218B2F1016F3CD22C4B1B6813F00103EC -:1028300037D02B4CFFF74CFFF323E360FFF73EFF4D -:1028400040F20127032D01D9830713D0244C0F46F2 -:10285000401A40F20118EB1B0B44012B00EB07065A -:10286000236924D823F001032361FFF74BFF0120E4 -:10287000BDE8F883236923F44073236123693B4354 -:10288000236151F8046B0660BFF34F8FFFF716FF0B -:1028900003689E4208D0236923F001032361FFF7F8 -:1028A00031FF0020BDE8F883043D0430CAE723F47B -:1028B00040732361236943EA08032361B94637F86B -:1028C000023B3380BFF34F8FFFF7F8FE3688B9F82D -:1028D0000030B6B2B342BED0DDE700BF00380240E0 -:1028E000003C0240084908B50B7828B153B9FFF7FE -:1028F000EFFE01230B7008BD23B1BDE8084008704E -:10290000FFF700BF08BD00BFBE43002010B5024462 -:10291000064B0439D2B2904200D110BD441C00B223 -:1029200053F8200041F8040FE0B2F4E750280040CB -:10293000104B30B51C6F240407D41C6F44F4007492 -:102940001C671C6F44F400441C670B4C236843F461 -:10295000807323600244094B0439D2B2904200D103 -:1029600030BD441C00B251F8045F43F82050E0B27F -:10297000F4E700BF003802400070004050280040DB -:1029800007B5012201A90020FFF7C0FF019803B09D -:102990005DF804FB13B50446FFF7F2FFA04206D032 -:1029A00002A9012241F8044D0020FFF7C1FF02B047 -:1029B00010BD000070470000034B1B689B0042BF26 -:1029C000024B01221A70704774380240F143002014 -:1029D000014B1878704700BFF1430020064A536846 -:1029E00023F001035360EFF30983683383F309880D -:1029F000002383F31188704730EF00E010B52023E7 -:102A000083F31188104B5B6813F4006318D0F1EE68 -:102A1000103AEFF309844FF0807344F84C3C0B4BB1 -:102A2000DB6844F8083CA4F1680383F30988FFF7E6 -:102A300071FB18B1064B44F8503C10BD054BFAE74A -:102A400083F3118810BD00BF00ED00E030EF00E01F -:102A5000350300083803000870470000FEE7000057 -:102A6000084A094B09498B4204D3094A0021934281 -:102A700005D3704752F8040F43F8040BF3E743F80B -:102A8000041BF4E7D43F00086C4400206C44002091 -:102A90006C440020836D30B500229D68446D114662 -:102AA0004FF0FF3004EB421301329542C3F8001996 -:102AB000C3F81019C3F80809C3F8001BC3F8101BAA -:102AC000C3F8080BEED24FF00113C4F81C3830BD28 -:102AD000890141F02001016103699B06FCD41220A9 -:102AE000FFF7BCBB204B03EB80022DE9F047D2F887 -:102AF0000CE05D6DDEF81420461CD2F800C005EB3A -:102B0000063605EB4018516861450BD3D5F83428DB -:102B1000012303FA00F022EA0000C5F83408184641 -:102B2000BDE8F087BEF81040ACEB0103A34228BF1C -:102B30002346D8F81849A4B2B3EB840F10D8946890 -:102B40001F46A4F1040959F804AFC6F800A0042FE9 -:102B500001D9043FF7E71C440B4494605360D2E76B -:102B60000020BDE8F08700BFF443002010B5054CFD -:102B70002046FEF7A1FF4FF0A0436365024BA3651B -:102B800010BD00BFF4430020A83E00080378012BCD -:102B900070B5054650D12A4B446D98421BD1294B44 -:102BA0005A6B42F080025A635A6D42F080025A65B5 -:102BB0005A6D5A6942F080025A615A6922F08002C5 -:102BC0005A610E2143205B69FEF7E0FB1E4BE36078 -:102BD0001E4BC4F800380023C4F8003EC023236015 -:102BE0006E6D4FF40413A3633369002BFCDA0123E9 -:102BF00033610C20FFF732FB3369DB07FCD4122072 -:102C0000FFF72CFB3369002BFCDA0026A660284670 -:102C1000FFF740FF6B68C4F81068DB68C4F81468FD -:102C2000C4F81C684BB90A4BA3614FF0FF336361D2 -:102C3000A36843F00103A36070BD064BF4E700BF37 -:102C4000F4430020003802404014004003002002FA -:102C5000003C30C0083C30C0F8B5446D054600214A -:102C60002046FFF735FFA96D00234FF001128F6852 -:102C7000C4F834384FF00066C4F81C284FF0FF3019 -:102C800004EB431201339F42C2F80069C2F8006BA3 -:102C9000C2F80809C2F8080BF2D20B686A6DEB653E -:102CA000636210231361166916F01006FBD112201F -:102CB000FFF7D4FAD4F8003823F4FE63C4F80038E0 -:102CC000A36943F4402343F01003A3610923C4F82C -:102CD0001038C4F814380A4BEB604FF0C043C4F806 -:102CE000103B084BC4F8003BC4F81069C4F8003925 -:102CF000EB6D03F1100243F48013EA65A362F8BDA3 -:102D0000843E000840800010426D90F84E10D2F8CA -:102D1000003823F4FE6343EA0113C2F80038704719 -:102D20002DE9F0410EB200EB86080D46D8F80C10E4 -:102D30000F6807F00303022B50D0032B50D03D4AFD -:102D40003D4F012B18BF1746446D4FEA451E04EB5B -:102D50000E030022C3F8102B8A6905F1100C002A1B -:102D600040D04A8A05F158035B013A43E2500123FF -:102D7000D4F81C2803FA0CF31343A6444A69C4F898 -:102D80001C380023CEF8103905F13F03002A39D052 -:102D90000A8A898B9208012988BF4A43C16D04EBD6 -:102DA0008303561841EA0242C66529465A60204606 -:102DB000FFF78EFED8F80C301B8A43EA85531F4379 -:102DC00005F148035B01E7500123D4F81C2803FAFE -:102DD00005F51543C4F81C58BDE8F081174FB3E75B -:102DE000174FB1E704EB4613D3F8002B22F400424F -:102DF000C3F8002BD4F81C28012303FA0CF322EAB1 -:102E00000303BAE704EB83030E4A5A6004EB461649 -:102E100029462046FFF75CFED6F8003923F400432C -:102E2000C6F80039D4F81C38012202FA05F523EA65 -:102E30000505CFE700800010008004100080081016 -:102E400000800C1000040002826D1268C265FFF75A -:102E500021BE00005831436D49015B5813F4004016 -:102E600004D013F4001F14BF01200220704700009B -:102E70004831436D49015B5813F4004004D013F40A -:102E8000001F14BF012002207047000000EB8101E9 -:102E9000CB68196A0B6813604B6853607047000079 -:102EA00000EB810330B5DD68AA691368D36019B9F6 -:102EB000402B84BF402313606B8A1468426D1C440E -:102EC000013CB4FBF3F46343033323F0030302EB4D -:102ED000411043EAC44343F0C043C0F8103B2B68A1 -:102EE00003F00303012B09B20ED1D2F8083802EB2C -:102EF000411013F4807FD0F8003B14BF43F080539F -:102F000043F00053C0F8003B02EB4112D2F8003B03 -:102F100043F00443C2F8003B30BD00002DE9F0410E -:102F2000244D6E6D06EB40130446D3F8087BC3F8BE -:102F3000087B38070AD5D6F81438190706D505EBEB -:102F400084032146DB6828465B689847FA072FD53B -:102F5000D6F81438DB072BD505EB8403D968CCB938 -:102F60008B69488A5E68B6FBF0F200FB12628AB990 -:102F70001868DA6890420DD2121A83E814002023F0 -:102F800083F311880B482146FFF78AFF84F31188E9 -:102F9000BDE8F081012303FA04F26B8923EA0203FE -:102FA0006B81CB6823B121460248BDE8F041184748 -:102FB000BDE8F081F443002000EB810370B5DD68CB -:102FC000436D6C692668E6604A0156BB1A444FF4AB -:102FD0000020C2F810092A6802F00302012A0AB28E -:102FE0000ED1D3F8080803EB421410F4807FD4F814 -:102FF000000914BF40F0805040F00050C4F80009B0 -:1030000003EB4212D2F8000940F00440C2F8000974 -:10301000D3F83408012202FA01F10143C3F834184D -:1030200070BD19B9402E84BF4020206020682E8AD0 -:10303000841940F00050013C1A44B4FBF6F440EA15 -:10304000C440C6E7F8B504461E48456D05EB441379 -:10305000D3F80869C3F80869F10717D5D5F810380F -:10306000DA0713D500EB8403D9684B691F68DA6867 -:10307000974218D2D21B00271A605F60202383F387 -:1030800011882146FFF798FF87F31188330617D57B -:10309000D5F834280123A340134211D02046BDE8BF -:1030A000F840FFF71FBD012303FA04F2038923EA66 -:1030B000020303818B68002BE8D021469847E5E79F -:1030C000F8BD00BFF443002096482DE9F84F456D48 -:1030D0006E69AB691E4016F4805F6E61044605D0D0 -:1030E000FEF756FDBDE8F84FFFF788BC002E12DA58 -:1030F000D5F8003E8B489B071EBFD5F8003E23F055 -:103100000303C5F8003ED5F8043823F00103C5F8E1 -:103110000438FEF767FD370502D58248FEF756FDF5 -:10312000B0040CD5D5F8083813F0060FEB6823F47B -:1031300070530CBF43F4105343F4A053EB603107BA -:1031400004D56368DB680BB176489847F2025AD41D -:10315000B3020CD5D4F85480DFF8C8A100274FF093 -:103160000109A36D9B68F9B28B4280F08780F70656 -:1031700019D5616D0A6AC2F30A1702F00F0302F44F -:10318000F012B2F5802F00F0A180B2F5402F0AD1E5 -:1031900004EB830301F58051DB68186A00231A46AB -:1031A0009F4240F087803003D5F8184813D5E103DB -:1031B00002D50020FFF7B2FEA20302D50120FFF7DF -:1031C000ADFE630302D50220FFF7A8FE270302D558 -:1031D0000320FFF7A3FE750384D5E00702D5002086 -:1031E000FFF730FFA10702D50120FFF72BFF620791 -:1031F00002D50220FFF726FF23077FF573AF0320D8 -:10320000FFF720FF6EE7D4F85480DFF818A10027FD -:103210004FF00109A36D9B685FFA87FB5B4597D36D -:1032200008EB4B13D3F8002902F44022B2F5802FAB -:1032300022D1D3F80029002A1EDAD3F8002942F05F -:103240009042C3F80029D3F80029002AFBDB594635 -:10325000606DFFF73DFC228909FA0BF322EA0303B4 -:10326000238104EB8B03DB689B6813B159465046FE -:1032700098475846FFF736FC0137CBE708EB411279 -:10328000D2F8003B03F44023B3F5802F10D1D2F8DD -:10329000003B002B0CDA628909FA01F322EA0303EE -:1032A000638104EB8103DB68DB680BB15046984710 -:1032B000013756E79C0708BF0A68072B98BF0270C2 -:1032C00003F101039CBF120A013069E7023304EBEA -:1032D000830201F58051526890690268D0F808C0F5 -:1032E0004068A2EB000E0022104697420AD104EB80 -:1032F000830463689B699A683A449A605A681744E1 -:103300005F6050E712F0030F08BF0868964588BF5A -:103310008CF8000002F1010284BF000A0CF1010CDC -:10332000E3E700BFF4430020436D03EB4111D1F804 -:10333000003B43F40013C1F8003B7047436D03EBBF -:103340004111D1F8003943F40013C1F80039704736 -:10335000436D03EB4111D1F8003B23F40013C1F896 -:10336000003B7047436D03EB4111D1F8003923F462 -:103370000013C1F80039704730B5039C0172043363 -:1033800004FB0325C361049B03630021059B0060CC -:103390004060C16042610261856104624262816293 -:1033A000C162436330BD00000022416A4161016196 -:1033B000C2608262C2626FF00101FEF7C1BF00000D -:1033C00003694269934203D1C2680AB10020704781 -:1033D000181D704703691960C2680132C260C26972 -:1033E000134482690361934224BF436A036100214D -:1033F000FEF79ABF38B504460D46E3683BB16269F3 -:10340000131D1268A3621344E362002038BD237ABF -:1034100033B929462046FEF777FF0028EDDA38BD9C -:103420006FF00100FBE70000C368C269013BC360A5 -:103430004369134482694361934224BF436A4361F1 -:1034400000238362036B03B11847704770B52023D4 -:10345000044683F31188866A3EB9FFF7CBFF054621 -:1034600018B186F31188284670BDA36AE26A13F882 -:10347000015BA362934202D32046FFF7D5FF0023EE -:1034800083F31188EFE700002DE9F84F04460E465C -:1034900090469946202787F311880025AA46D4F83C -:1034A00028B0BBF1000F09D149462046FFF7A2FF23 -:1034B00020B18BF311882846BDE8F88FA16AE36A32 -:1034C000A8EB050B5B1A9B4528BF9B46BBF1400F41 -:1034D0001BD9334601F1400251F8040B43F8040BA9 -:1034E0009142F9D1A36A40334036A3624035A26AC3 -:1034F000E36A9A4202D32046FFF796FF8AF31188C7 -:103500004545D8D287F31188C9E730465A46FDF7BA -:1035100001FCA36A5B445E44A3625D44E7E70000EC -:1035200010B5029C0172043303FB0421C361002324 -:103530008362C362039B0363049B00604060C460BA -:1035400042610261816104624262436310BD000016 -:10355000026AC260426A4261026100228262C26201 -:103560006FF00101FEF7ECBE436902699A4203D194 -:10357000C2680AB100207047184650F8043B0B603F -:1035800070470000C368C2690133C36043691344D4 -:1035900082694361934224BF436A43610021FEF77D -:1035A000C3BE000038B504460D46E3683BB123694D -:1035B0001A1DA262E2691344E362002038BD237A37 -:1035C00033B929462046FEF79FFE0028EDDA38BDC4 -:1035D0006FF00100FBE7000003691960C268013A5F -:1035E000C260C269134482690361934224BF436A83 -:1035F000036100238362036B03B118477047000027 -:1036000070B5202304460E4683F31188856A35B9C8 -:103610001146FFF7C7FF10B185F3118870BDA36A8B -:103620001E70A36AE26A01339342A36204D3E16984 -:1036300020460439FFF7D0FF002080F3118870BDC9 -:103640002DE9F84F04460D4691469A464FF0200862 -:1036500088F311880026B346A76A4FB95146204621 -:10366000FFF7A0FF20B187F311883046BDE8F88F3F -:10367000A06AE76AA9EB06033F1A9F4228BF1F46CC -:10368000402F1BD905F1400355F8042B40F8042BBB -:103690009D42F9D1A36A4033A3624036A26AE36A2D -:1036A0009A4204D3E16920460439FFF795FF8BF372 -:1036B00011884E45D9D288F31188CDE729463A467C -:1036C000FDF728FBA36A3B443D44A3623E44E5E783 -:1036D000026943699A4203D1C3681BB9184670470F -:1036E0000023FBE7836A002BF8D0043B9B1AF5D03C -:1036F0001360C368013BC360C3691A4483690261F4 -:103700009A4224BF436A0361002383620123E5E7F1 -:1037100000F0A0B84FF08043002258631A610222E3 -:10372000DA6070474FF080430022DA607047000093 -:103730004FF08043586370474B6843608B688360E9 -:10374000CB68C3600B6943614B6903628B69436259 -:103750000B6803607047000008B5224B22481A69C5 -:1037600040F2FF110A431A611A6922F4FF7222F033 -:1037700001021A611A691A6B0A431A631A6D0A4325 -:103780001A651A4A1B6D1146FFF7D6FF184802F159 -:103790001C01FFF7D1FF174802F13801FFF7CCFFFA -:1037A000154802F15401FFF7C7FF144802F17001F8 -:1037B000FFF7C2FF124802F18C01FFF7BDFF11486D -:1037C00002F1A801FFF7B8FF0F4802F1C401FFF7AB -:1037D000B3FF0E4802F1E001FFF7AEFFBDE808407D -:1037E00000F0A2B80038024000000240B43E0008D9 -:1037F0000004024000080240000C02400010024099 -:103800000014024000180240001C02400020024048 -:1038100008B500F0F9F9FEF79FFCFFF7CDF8BDE819 -:103820000840FEF7A5BE0000704700004FF080433F -:1038300010B51A69920708D500241C61202383F370 -:103840001188FEF7C7FC84F31188BDE81040FFF72C -:10385000D5B80000104B1A6C42F001021A641A6EBF -:1038600042F001021A660D4A1B6E936843F0010391 -:1038700093604FF0804353229A624FF0FF32DA6236 -:1038800000229A615A63DA605A6001225A61082163 -:103890001A601C20FDF77ABD00380240002004E0C9 -:1038A0001F4B1A696FEAC2526FEAD2521A611A6943 -:1038B000C2F308021A614FF0FF301A695A69586161 -:1038C00000215A6959615A691A6A62F080521A6273 -:1038D0001A6A02F080521A621A6A5A6A58625A6A5E -:1038E00059625A6A1A6C42F080521A641A6E42F097 -:1038F00080521A661A6E0B4A106840F4807010608D -:10390000186F00F44070B0F5007F1EBF4FF4803098 -:1039100018671967536823F40073536000F054B9B3 -:103920000038024000700040304B4FF080521A6463 -:103930002F4A4FF4404111601A6842F001021A60A8 -:103940001A689207FCD59A6822F003029A60274B06 -:1039500019469A6812F00C02FBD1186800F0F900C1 -:1039600018609A601A6842F480321A600B689B03F0 -:10397000FCD54B6F43F001034B671C4B5A6F90070C -:10398000FCD51C4A5A601A6842F080721A60184AC4 -:1039900053685904FCD5154B1A689201FCD5164A98 -:1039A0009A60164B1A68164B9A42164B1BD1164A50 -:1039B0001168164A914216D140F205121A600B4B5B -:1039C0009A6842F002029A609A6802F00C02082A91 -:1039D000FAD15A6C42F480425A645A6E42F48042E0 -:1039E0005A665B6E704740F20572E7E700380240A6 -:1039F000007000400854400700948838002004E01C -:103A000011640020003C024000ED00E041C20F4183 -:103A1000084A08B5536911680B4003F0010353616C -:103A200023B1054A13680BB150689847BDE80840B8 -:103A3000FEF7E4BF003C0140D4230020084A08B54B -:103A4000536911680B4003F00203536123B1054A27 -:103A500093680BB1D0689847BDE80840FEF7CEBF29 -:103A6000003C0140D4230020084A08B5536911687E -:103A70000B4003F00403536123B1054A13690BB1F2 -:103A800050699847BDE80840FEF7B8BF003C0140C8 -:103A9000D4230020084A08B5536911680B4003F08D -:103AA0000803536123B1054A93690BB1D069984764 -:103AB000BDE80840FEF7A2BF003C0140D42300202F -:103AC000084A08B5536911680B4003F010035361AD -:103AD00023B1054A136A0BB1506A9847BDE8084004 -:103AE000FEF78CBF003C0140D4230020174B10B5DB -:103AF0005C691A68144004F478725A61A30604D50C -:103B0000134A936A0BB1D06A9847600604D5104AED -:103B1000136B0BB1506B9847210604D50C4A936B7D -:103B20000BB1D06B9847E20504D5094A136C0BB171 -:103B3000506C9847A30504D5054A936C0BB1D06C23 -:103B40009847BDE81040FEF759BF00BF003C014058 -:103B5000D42300201A4B10B55C691A68144004F491 -:103B60007C425A61620504D5164A136D0BB1506D43 -:103B70009847230504D5134A936D0BB1D06D984730 -:103B8000E00404D50F4A136E0BB1506E9847A104A0 -:103B900004D50C4A936E0BB1D06E9847620404D5DD -:103BA000084A136F0BB1506F9847230404D5054A98 -:103BB000936F0BB1D06F9847BDE81040FEF71EBF62 -:103BC000003C0140D4230020062108B50846FDF73B -:103BD000DDFB06210720FDF7D9FB06210820FDF7B4 -:103BE000D5FB06210920FDF7D1FB06210A20FDF7B0 -:103BF000CDFB06211720FDF7C9FB06212820BDE8D3 -:103C00000840FDF7C3BB000008B5FFF749FEFDF70C -:103C1000D3F9FDF761FDFDF74DFFFDF721FEFFF73D -:103C200003FEBDE80840FFF773BD0000034611F82E -:103C3000012B03F8012B002AF9D17047121012133F -:103C40001211000053544D3332463F3F3F000000F5 -:103C500000000000443C00083F0000001304000086 -:103C6000883C00083F00000019040000923C000856 -:103C70003F000000210400009C3C00083F000000C1 -:103C8000983C00205424002053544D3332463430A5 -:103C9000780053544D3332463432780053544D3308 -:103CA00032463434365858000096000000000000B8 -:103CB0000000000000000000000000000000000004 -:103CC000A11600088D160008C9160008B5160008D0 -:103CD000C1160008AD1600089916000885160008E0 -:103CE000D516000800000000D9170008C517000805 -:103CF00001180008ED170008F9170008E51700087B -:103D0000D1170008BD1700085D180008000000006A -:103D100001000000000000006D61696E00000000FD -:103D2000383D0008A03A0020983C00200100000027 -:103D3000552100080000000069646C650000000067 -:103D40000200000000000000051A00086D1A0008BB -:103D500040004000304100204041002002000000AF -:103D6000000000000300000000000000B11A00087D -:103D70000000000010000000504100200000000082 -:103D80000100000000000000F443002001010200D7 -:103D90004172647550696C6F740025424F41524402 -:103DA000252D424C002553455249414C2500000029 -:103DB000112500087924000871190008F52400086D -:103DC00043000000C83D000809024300020100C092 -:103DD000320904000001020201000524001001055F -:103DE00024010001042402020524060001070582C3 -:103DF000030800FF09040100020A00000007050192 -:103E0000024000000705810240000000120000008F -:103E1000143E00081201100102000040091241572F -:103E200000020102030100000403090425424F417E -:103E3000524425004D6174656B463430352D434145 -:103E40004E0030313233343536373839414243440D -:103E50004546000000400000004000000040000017 -:103E6000004000000000010000000200000002000D -:103E7000000002000000020000000200000002003A -:103E80000000020000000000F91B0008D91E000815 -:103E9000851F000840004000544400205444002086 -:103EA0000100000064440020800000004001000088 -:103EB00003000000AA01A81600000000AAAAAAAAEE -:103EC00055011400FF9F00008877000070A70A00CA -:103ED0000000000100000000AAAAAAAA0000000138 -:103EE000FFFF000000000000000000000000A01222 -:103EF00000000000AAAAAAAA00005011FFFF0000BB -:103F00000000000000770800200000000000000012 -:103F1000AAAAAAAA10000000FFFF000000080000E3 -:103F2000000000000000000000000000AAAAAAAAE9 -:103F300000000000FFFF0000000000000000000083 -:103F40000000000000000000AAAAAAAA00000000C9 -:103F5000FFFF000000000000000000000000000063 -:103F600000000000AAAAAAAA00000000FFFF0000AB -:103F70000000000000000000000000000000000041 -:103F80000A00000000000000030000000000000024 -:103F90000000000000000000000000000000000021 -:103FA0000000000000000000000000000000000011 -:103FB000FF0096000000000804000000283E0008F2 -:103FC00000000000000000000000000000000000F1 -:083FD0000000000000000000E9 +:1000000000060020E1010008D10E0008890E00085A +:10001000B10E0008890E0008A90E0008E3010008CF +:10002000E3010008E3010008E30100089936000835 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E301000841390008693900089C +:1000600091390008B9390008E1390008E3010008B6 +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008093A000851 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000F13A0008E3010008E3010008E301000849 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008DD3A0008E3010008E30100083D +:1000E0006D3A0008E3010008E3010008E30100089D +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E30100084D2E000868 +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6384880F30888B5 +:1001F000374880F3098837483749086040F20000E3 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F02F0E6FA8F +:1002500002F0C2FA03F0BEF94FF055301F491B4AB5 +:1002600091423CBF41F8040BFAE71D49184A9142FC +:100270003CBF41F8040BFAE71A491B4A1B4B9A4250 +:100280003EBF51F8040B42F8040BF8E70020184970 +:10029000184A91423CBF41F8040BFAE702F0A0FA79 +:1002A00003F0ECF9144C154DAC4203DA54F8041B7E +:1002B0008847F9E700F042F8114C124DAC4203DADE +:1002C00054F8041B8847F9E702F088BA00060020BA +:1002D000002200200000000808ED00E000000020DF +:1002E00000060020103F0008002200204C220020C1 +:1002F00050220020F0300020E0010008E00100085A +:10030000E0010008E00100082DE9F04F2DED108A12 +:10031000C1F80CD0C3689D46BDEC108ABDE8F08FD3 +:10032000002383F311882846A047002001F0F0FD48 +:10033000FEE701F059FD00DFFEE7000038B502F0EE +:100340001BFA054602F03EFA0446D8B90F4B9D420F +:100350001AD001339D4218BF044641F2883504BFCC +:1003600001240025002002F011FA0CB100F076F80B +:1003700000F028FD00F0BAFB284600F0C3F800F0BA +:100380006DF8F9E70025EDE70546EBE7010007B05A +:1003900008B500F077FBA0F120035842584108BD92 +:1003A00007B541F21203022101A8ADF8043000F0B4 +:1003B00087FB03B05DF804FB38B5302383F3118865 +:1003C000174803680BB101F06FFE164A144800236A +:1003D0004FF47A7101F05EFE002383F31188124C12 +:1003E000236813B12368013B2360636813B163681A +:1003F000013B63600D4D2B7833B963687BB90220F4 +:1004000000F052FC322363602B78032B07D1636822 +:100410002BB9022000F048FC4FF47A73636038BDBA +:1004200050220020B9030008702300206822002019 +:10043000084B187003280CD8DFE800F00805020804 +:10044000022000F021BC022000F00EBC024B002272 +:100450005A6070476822002070230020244B254AF0 +:1004600010B51C461968013140D004339342F9D1CC +:100470006268214B9A4239D9204B9B6803F1006393 +:1004800003F580339A4231D2002000F049FB02206C +:10049000FFF7CEFF1A4B1A6C00221A64196E1A6607 +:1004A000196E596C5A64596E5A665A6E5A6942F0FE +:1004B00080025A615A6922F080025A615A691A69A7 +:1004C00042F000521A611A6922F000521A611B6947 +:1004D00072B64FF0E0233021C3F8084DD4E9003262 +:1004E00081F311889D4683F30888104710BD00BF33 +:1004F0000000010820000108FFFF00080022002082 +:10050000003802402DE9F04F93B0AA4B0090202212 +:10051000FF210AA89D6800F0FFFBA74A1378A3B942 +:10052000A648012103601170302383F3118803680A +:100530000BB101F0B9FDA24AA04800234FF47A7133 +:1005400001F0A8FD002383F31188009B13B19D4B9C +:10055000009A1A609C4A009C1378032B1EBF00234C +:100560001370984A4FF0000A18BF5360D34656469E +:10057000D146012000F088FB24B1924B1B68002B70 +:1005800000F01182002000F07DFA0390039B002B05 +:10059000F2DB012000F068FB039B213B162BE8D81F +:1005A00001A252F823F000BF050600082D0600083E +:1005B000C1060008730500087305000873050008EC +:1005C0004B0700081B0900083508000897080008B9 +:1005D000BF080008E508000873050008F7080008D0 +:1005E0007305000869090008A506000873050008DE +:1005F000AD09000811060008A506000873050008EB +:10060000970800080220FFF7C3FE002840F0F5819C +:10061000009B0221BAF1000F08BF1C4605A841F259 +:100620001233ADF8143000F04BFAA2E74FF47A70B1 +:1006300000F028FA071EEBDB0220FFF7A9FE0028D6 +:10064000E6D0013F052F00F2DA81DFE807F0030A68 +:100650000D10133605230593042105A800F030FA88 +:1006600017E054480421F9E758480421F6E75848B0 +:100670000421F3E74FF01C08404600F053FA08F15C +:1006800004080590042105A800F01AFAB8F12C0F0F +:10069000F2D1012000FA07F747EA0B0B5FFA8BFB58 +:1006A0004FF0000900F084FB26B10BF00B030B2B7D +:1006B00008BF0024FFF774FE5BE746480421CDE73E +:1006C000002EA5D00BF00B030B2BA1D10220FFF7BE +:1006D0005FFE074600289BD0012000F021FA02208F +:1006E000FFF7A6FE00265FFA86F8404600F028FADB +:1006F000044690B10021404600F032FA013600284D +:10070000F1D1BA46044641F21213022105A8ADF810 +:1007100014303E4600F0D4F92BE70120FFF788FEA5 +:100720002546244B9B68AB4207D9284600F0FAF9CE +:10073000013040F067810435F3E7234B00251D703D +:10074000204BBA465D603E46ACE7002E3FF460AFFA +:100750000BF00B030B2B7FF45BAF0220FFF768FE5F +:10076000322000F08FF9B0F10008FFF651AF18F019 +:1007700003077FF44DAF0F4A926808EB05039342DD +:100780003FF646AFB8F5807F3FF742AF124B01937B +:10079000B84523DD4FF47A7000F074F90390039AA2 +:1007A000002AFFF635AF019B039A03F8012B0137AE +:1007B000EDE700BF002200206C2300205022002023 +:1007C000B9030008702300206822002004220020C2 +:1007D000082200200C2200206C220020C820FFF7F5 +:1007E000D7FD074600283FF413AF1F2D11D8C5F1E0 +:1007F000200242450AAB25F0030028BF4246834948 +:100800000192184400F062FA019A8048FF2100F03A +:1008100083FA4FEAA8037D490193C8F3870228466B +:1008200000F082FA064600283FF46DAF019B05EB0D +:10083000830537E70220FFF7ABFD00283FF4E8AE61 +:1008400000F0BAF900283FF4E3AE0027B846704B39 +:100850009B68BB4218D91F2F11D80A9B01330ED0B9 +:1008600027F0030312AA134453F8203C0593404693 +:10087000042205A900F02EFB04378046E7E738463E +:1008800000F050F90590F2E7CDF81480042105A896 +:1008900000F016F906E70023642104A8049300F091 +:1008A00005F900287FF4B4AE0220FFF771FD00289F +:1008B0003FF4AEAE049800F067F90590E6E7002338 +:1008C000642104A8049300F0F1F800287FF4A0AE9E +:1008D0000220FFF75DFD00283FF49AAE049800F077 +:1008E00063F9EAE70220FFF753FD00283FF490AEDA +:1008F00000F072F9E1E70220FFF74AFD00283FF41B +:1009000087AE05A9142000F06DF904210746049074 +:1009100004A800F0D5F83946B9E7322000F0B2F863 +:10092000071EFFF675AEBB077FF472AE384A9268B9 +:1009300007EB090393423FF66BAE0220FFF728FD59 +:1009400000283FF465AE27F003074F44B9453FF454 +:10095000A9AE484600F0E6F80421059005A800F08D +:10096000AFF809F10409F1E74FF47A70FFF710FDD1 +:1009700000283FF44DAE00F01FF9002844D00A9B38 +:1009800001330BD008220AA9002000F0CDF900287D +:100990003AD02022FF210AA800F0BEF9FFF700FD9F +:1009A0001C4801F0BBFA13B0BDE8F08F002E3FF4F5 +:1009B0002FAE0BF00B030B2B7FF42AAE0023642128 +:1009C00005A8059300F072F8074600287FF420AED2 +:1009D0000220FFF7DDFC804600283FF419AEFFF748 +:1009E000DFFC41F2883001F099FA059800F02AFA0C +:1009F000464600F0DDF93C46BBE5064652E64FF0C0 +:100A0000000905E6BA467EE637467CE66C22002001 +:100A100000220020A08601002DE9F84F4FF47A73E0 +:100A2000DFF85880DFF8589006460D4602FB03F7C2 +:100A3000002498F900305A1C5FFA84FA01D0A342CE +:100A400012D159F8240003682A46D3F820B0314661 +:100A50003B46D847854207D1074B012083F800A0C9 +:100A6000BDE8F88F0124E4E7002CFBD04FF4FA70C6 +:100A700001F054FA0020F3E7B823002010220020F0 +:100A80001422002007B50023024601210DF10700C2 +:100A90008DF80730FFF7C0FF20B19DF8070003B0C5 +:100AA0005DF804FB4FF0FF30F9E700000A4608B597 +:100AB0000421FFF7B1FF80F00100C0B2404208BD41 +:100AC00030B4074B0A461978064B53F82140236887 +:100AD000DD69054B0146AC46204630BC604700BF8F +:100AE000B823002014220020A086010070B501F078 +:100AF00035FD094E094D3080002428683388834233 +:100B000008D901F025FD2B6804440133B4F5803F7A +:100B10002B60F2D370BD00BFBA23002078230020E1 +:100B200001F0DEBD00F1006000F580300068704724 +:100B300000F10060920000F5803001F05DBD000022 +:100B4000054B1A68054B1B889B1A834202D9104437 +:100B500001F0FEBC0020704778230020BA2300205B +:100B600038B5084D044629B128682044BDE838400E +:100B700001F00EBD2868204401F0F2FC0028F3D0FB +:100B800038BD00BF7823002010F003030AD1B0F570 +:100B9000047F05D200F10050A0F51040D0F80038D5 +:100BA000184670470023FBE700F10050A0F5104005 +:100BB000D0F8100A70470000064991F8243033B18C +:100BC0000023086A81F824300822FFF7B1BF012012 +:100BD000704700BF7C230020014B1868704700BF9E +:100BE000002004E0F0B51C4B024618681B4BC0F314 +:100BF0000B050424000C1E88AE421BD15C6893F9DF +:100C00000850174B05261F88874208BF93F90250EA +:100C1000013E03F10403F6D1013A0A44013C0B46BC +:100C200093420ED214F9016F581C66B100F8016CA2 +:100C30000346F5E7013C03F10C03DCD1094C3F25E9 +:100C4000DFE7184605E02C2490421C7001D2981C66 +:100C50005D70401AF0BD00BF002004E0E03B0008DA +:100C6000CC3B0008A03B0008022804D1054B4FF004 +:100C700080429A6170470128FCD1024B4FF000522C +:100C8000F7E700BF00000240022804D1054B4FF4F3 +:100C900080429A6170470128FCD1024B4FF4005208 +:100CA000F7E700BF00000240022805D1064A536959 +:100CB00083F48043536170470128FCD1024A536991 +:100CC00083F40053F6E700BF0000024010B5002394 +:100CD000934203D0CC5CC4540133F9E710BD00004B +:100CE00010B5013810F9013F3BB191F900409C4229 +:100CF00003D11AB10131013AF4E71AB191F9002098 +:100D0000981A10BD1046FCE703460246D01A12F9A5 +:100D1000011B0029FAD1704702440346934202D0D6 +:100D200003F8011BFAE770472DE9F8431F4D1446FD +:100D300095F824200746884652BBDFF870909CB394 +:100D400095F824302BB92022FF2148462F62FFF767 +:100D5000E3FF95F82400C0F10802A24228BF224612 +:100D6000D6B24146920005EB8000FFF7AFFF95F841 +:100D70002430A41B1E44F6B2082E17449044E4B25B +:100D800085F82460DBD1FFF717FF0028D7D108E0F2 +:100D90002B6A03EB82038342CFD0FFF70DFF0028BD +:100DA000CBD10020BDE8F8830120FBE77C230020A5 +:100DB000024B1A78024B1A70704700BFB82300200C +:100DC0001022002038B5194C194D204600F0E6FBE2 +:100DD0002946204600F00EFC2D6816486A6DD2F8B0 +:100DE000043843F00203C2F8043801F097F81249BE +:100DF000284600F005FD6A6D104DD2F804382868C9 +:100E00000F4923F00203C2F80438A0424FF4E13343 +:100E10000B6001D000F022FB6868A04204D0BDE85E +:100E20003840074900F01ABB38BD00BF98280020A1 +:100E3000F83C000840420F00003D0008142200204A +:100E4000A423002070B50C4B0C4D1E780C4B55F8AC +:100E500026209A4204460DD00A4B0021142218463F +:100E6000FFF75AFF0460014655F82600BDE87040C0 +:100E700000F0F4BA70BD00BFB82300201422002097 +:100E800098280020A423002000B59BB0EFF309812F +:100E900068226846FFF71AFFEFF30583014B9B6B4F +:100EA000FEE700BF00ED00E008B5FFF7EDFF000032 +:100EB00000B59BB0EFF3098168226846FFF706FF93 +:100EC000EFF30583014B5B6BFEE700BF00ED00E035 +:100ED000FEE7000030B5094D0A4491420DD011F8EB +:100EE000013B5840082340F30004013B2C4013F021 +:100EF000FF0384EA5000F6D1EFE730BD2083B8ED60 +:100F0000026843681143016003B11847704700004D +:100F1000024AD36843F0C003D36070470010014019 +:100F200010B5084C084A0021204600F075FA074B1E +:100F3000C4F85C3203F1454303F52D43C4F8603235 +:100F400010BD00BFBC230020110F0008001001409D +:100F5000234A037C002918BF0A46012B30B5C0F88C +:100F600068220CD11F4B984209D11F4B596C41F09C +:100F700010015964596E41F0100159665B6EB2F967 +:100F800004501468D0F86032D0F85C12002D03EBE6 +:100F90005403B3FBF4F3BEBF23F0070503F00703CC +:100FA00043EA450394888B60D38843F040030B6188 +:100FB000138943F001034B6144F4045343F02C03C1 +:100FC000CB6004F4A05400230B60B4F5806F0B6871 +:100FD0004B680CBF7F23FF2380F8643230BD00BF15 +:100FE000103C0008BC230020003802402DE9F041ED +:100FF000D0F85C62F7683368DA0504469DB20DD517 +:10100000302383F311884FF480610430FFF778FFB9 +:101010006FF480733360002383F31188302383F3EC +:10102000118804F1040815F02F033AD183F31188D5 +:10103000380615D5290613D5302383F3118804F11A +:10104000380000F065F900284EDA0821201DFFF76E +:1010500057FF4FF67F733B40F360002383F3118803 +:101060007A0616D56B0614D5302383F31188D4E99C +:1010700013239A420AD1236C43B127F040073F045F +:101080001021201D3F0CFFF73BFFF760002383F387 +:101090001188D4F86822D36843B3BDE8F0411069E1 +:1010A00018472B0714D015F0080F0CBF00214FF480 +:1010B0008071E80748BF41F02001AA0748BF41F00E +:1010C00040016B0748BF41F080014046FFF718FF21 +:1010D000AD06736805D594F864122046194000F0F7 +:1010E000CBF93568ADB29EE77060B6E7BDE8F08138 +:1010F000F8B5154682680669AA420B46816938BF71 +:101100008568761AB54204460BD218462A46FFF780 +:10111000DDFDA3692B44A361A3685B1BA360284684 +:10112000F8BD0CD918463246FFF7D0FDAF1BE16879 +:101130003A463044FFF7CAFDE3683B44EBE7184604 +:101140002A46FFF7C3FDE368E5E7000083689342A2 +:10115000F7B51546044638BF8568D0E90460361AED +:10116000B5420BD22A46FFF7B1FD63692B44636198 +:10117000A36828465B1BA36003B0F0BD0DD93246BF +:101180000191FFF7A3FD0199E068AF1B3A46314496 +:10119000FFF79CFDE3683B44E9E72A46FFF796FD2D +:1011A000E368E4E710B50A440024C361029B84604D +:1011B000C0E90000C0E90511C1600261036210BD11 +:1011C00008B5D0E90532934201D1826882B98268BC +:1011D000013282605A1C42611970D0E904329A428D +:1011E00024BFC3684361002100F0B4FE002008BDA5 +:1011F0004FF0FF30FBE7000070B5302304460E4689 +:1012000083F31188A568A5B1A368A269013BA36017 +:10121000531CA36115782269934224BFE368A3613C +:10122000E3690BB120469847002383F311882846D1 +:1012300007E03146204600F07DFE0028E2DA85F323 +:10124000118870BD2DE9F74F04460E4617469846A3 +:10125000D0F81C904FF0300A8AF311884FF0000B41 +:10126000154665B12A4631462046FFF741FF034641 +:1012700060B94146204600F05DFE0028F1D0002311 +:1012800083F31188781B03B0BDE8F08FB9F1000F2C +:1012900003D001902046C847019B8BF31188ED1ABB +:1012A0001E448AF31188DCE7C0E90511C160C361FF +:1012B0001144009B8260C0E9000001610362704735 +:1012C000F8B504460D461646302383F31188A76807 +:1012D000A7B1A368013BA36063695A1C62611D70DA +:1012E000D4E904329A4224BFE3686361E3690BB135 +:1012F00020469847002080F3118807E031462046B9 +:1013000000F018FE0028E2DA87F31188F8BD00002B +:10131000D0E905239A4210B501D182687AB9826872 +:10132000013282605A1C82611C7803699A4224BF90 +:10133000C3688361002100F00DFE204610BD4FF010 +:10134000FF30FBE72DE9F74F04460E461746984657 +:10135000D0F81C904FF0300A8AF311884FF0000B40 +:10136000154665B12A4631462046FFF7EFFE034693 +:1013700060B94146204600F0DDFD0028F1D0002391 +:1013800083F31188781B03B0BDE8F08FB9F1000F2B +:1013900003D001902046C847019B8BF31188ED1ABA +:1013A0001E448AF31188DCE7026843681143016038 +:1013B00003B11847704700001430FFF743BF000027 +:1013C0004FF0FF331430FFF73DBF00003830FFF718 +:1013D000B9BF00004FF0FF333830FFF7B3BF000054 +:1013E0001430FFF709BF00004FF0FF311430FFF752 +:1013F00003BF00003830FFF763BF00004FF0FF323B +:101400003830FFF75DBF0000012914BF6FF01300F3 +:1014100000207047FFF784BD37B515460E4A0260BD +:1014200000224260C0E902220122044602740B46F7 +:10143000009000F15C014FF480721430FFF7B2FEAF +:1014400000942B464FF4807204F5AE7104F138001D +:10145000FFF72AFF03B030BD243C000810B530234D +:10146000044683F31188FFF773FD022323740020E1 +:1014700080F3118810BD000038B5C36904460D46DD +:101480001BB904210844FFF78FFF294604F114001B +:10149000FFF796FE002806DA201D4FF40061BDE834 +:1014A0003840FFF781BF38BD0268436811430160CF +:1014B00003B118477047000013B5446BD4F8943457 +:1014C0001A681178042915D1217C022912D11979C1 +:1014D000128901238B4013420CD101A904F14C0065 +:1014E00001F034FFD4F89444019B2179024620682E +:1014F00000F0D0F902B010BD143001F0B7BE00000A +:101500004FF0FF33143001F0B1BE00004C3001F059 +:1015100089BF00004FF0FF334C3001F083BF000063 +:10152000143001F085BE00004FF0FF31143001F09F +:101530007FBE00004C3001F055BF00004FF0FF327D +:101540004C3001F04FBF00000020704710B5D0F8BC +:1015500094341A6811780429044617D1017C0229B1 +:1015600014D15979528901238B4013420ED1143082 +:1015700001F018FE024648B1D4F894444FF4807349 +:1015800061792068BDE8104000F072B910BD00001C +:10159000406BFFF7DBBF0000704700007FB5124BC8 +:1015A000036000234360C0E90233012502260F4B8C +:1015B000057404460290019300F1840229460096C6 +:1015C0004FF48073143001F0C9FD094B0294CDE94A +:1015D000006304F523724FF48073294604F14C0034 +:1015E00001F090FE04B070BD4C3C0008911500085D +:1015F000B91400080B68302282F311880A7903EBD2 +:10160000820290614A79093243F822008A7912B144 +:1016100003EB820398610223C0F894140374002042 +:1016200080F311887047000038B5037F044613B17A +:1016300090F85430ABB9201D01250221FFF734FF8B +:1016400004F1140025776FF0010100F08FFC84F89D +:10165000545004F14C006FF00101BDE8384000F037 +:1016600085BC38BD10B5012104460430FFF71CFFCE +:101670000023237784F8543010BD000038B50446A9 +:101680000025143001F082FD04F14C00257701F0B3 +:1016900051FE201D84F854500121FFF705FF20461C +:1016A000BDE83840FFF752BF90F8443003F06003C4 +:1016B000202B07D190F84520212A4FF0000303D8B2 +:1016C0001F2A06D800207047222AFBD1C0E90E331A +:1016D00003E0034A82630722C26303640120704768 +:1016E0001C22002037B5D0F894341A6811780429E8 +:1016F00004461AD1017C022917D1197912890123D4 +:101700008B40134211D100F14C05284601F0D2FE66 +:1017100058B101A9284601F019FED4F89444019B60 +:1017200021790246206800F0B5F803B030BD000012 +:10173000F0B500EB810385B09E6904460D46FEB10D +:10174000302383F3118804EB8507301D0821FFF750 +:10175000ABFEFB685B691B6806F14C001BB1019096 +:1017600001F002FE019803A901F0F0FD024648B124 +:10177000039B2946204600F08DF8002383F311884F +:1017800005B0F0BDFB685A691268002AF5D01B8AC3 +:10179000013B1340F1D104F14402EAE7093138B5C5 +:1017A00050F82140DCB1302383F31188D4F894241D +:1017B0001368527903EB8203DB689B695D6845B16E +:1017C00004216018FFF770FE294604F1140001F0AF +:1017D000F3FC2046FFF7BAFE002383F3118838BDDF +:1017E0007047000001F052B8012303700023C0E9E4 +:1017F0000133C36183620362C36243620363704760 +:1018000038B50446302383F311880025C0E9035519 +:10181000C0E90555416001F049F80223237085F3C2 +:101820001188284638BD000070B500EB81030546DD +:101830005069DA600E46144618B110220021FFF7F5 +:101840006BFAA06918B110220021FFF765FA314642 +:101850002846BDE8704001F0F3B80000826802F04D +:10186000011282600022C0E90422826101F074B991 +:10187000F0B400EB81044789E4680125A4698D4038 +:101880003D43458123600023A2606360F0BC01F00A +:101890008FB90000F0B400EB81040789E4680125EA +:1018A00064698D403D43058123600023A26063602D +:1018B000F0BC01F009BA000070B50223002504460F +:1018C0000370C0E90255C0E90455C564856180F81C +:1018D000345001F051F863681B6823B12946204653 +:1018E000BDE87040184770BD0378052B10B504465D +:1018F0000AD080F850300523037043681B680BB191 +:10190000042198470023A36010BD00000178052939 +:1019100006D190F85020436802701B6803B1184745 +:101920007047000070B590F83430044613B10023BE +:1019300080F8343004F14402204601F02FF9636846 +:101940009B68B3B994F8443013F0600535D000219A +:10195000204601F0CFFB0021204601F0C1FB636867 +:101960001B6813B1062120469847062384F83430BB +:1019700070BD204698470028E4D0B4F84A30E26BA6 +:101980009A4288BFE36394F94430E56B002B4FF033 +:10199000300380F20381002D00F0F280092284F8E8 +:1019A000342083F311880021D4E90E232046FFF769 +:1019B00071FF002383F31188DAE794F8452003F0E0 +:1019C0007F0343EA022340F20232934200F0C580D3 +:1019D00021D8B3F5807F48D00DD8012B3FD0022B02 +:1019E00000F09380002BB2D104F14C02A2630222DA +:1019F000E2632364C1E7B3F5817F00F09B80B3F518 +:101A0000407FA4D194F84630012BA0D1B4F84C30DB +:101A100043F0020332E0B3F5006F4DD017D8B3F5B1 +:101A2000A06F31D0A3F5C063012B90D8636894F800 +:101A300046205E6894F84710B4F848302046B04716 +:101A4000002884D04368A3630368E3631AE0B3F516 +:101A5000106F36D040F6024293427FF478AF5C4B71 +:101A6000A3630223E3630023C3E794F84630012B0A +:101A70007FF46DAFB4F84C3023F00203C4E90E5587 +:101A8000A4F84C30256478E7B4F84430B3F5A06F7F +:101A90000ED194F8463084F84E30204600F0C4FF52 +:101AA00063681B6813B10121204698470323237004 +:101AB0000023C4E90E339CE704F14F03A363012321 +:101AC000C3E72378042B10D1302383F311882046F9 +:101AD000FFF7C4FE85F311880321636884F84F5033 +:101AE00021701B680BB12046984794F84630002BB4 +:101AF000DED084F84F300423237063681B68002B0A +:101B0000D6D0022120469847D2E794F848301D06E7 +:101B100003F00F0120460AD501F032F8012804D065 +:101B200002287FF414AF2B4B9AE72B4B98E701F078 +:101B300019F8F3E794F84630002B7FF408AF94F8D7 +:101B4000483013F00F01B3D01A06204602D501F039 +:101B5000E5FAADE701F0D8FAAAE794F84630002B91 +:101B60007FF4F5AE94F8483013F00F01A0D01B06B7 +:101B7000204602D501F0BEFA9AE701F0B1FA97E7E4 +:101B8000142284F8342083F311882B462A462946F0 +:101B90002046FFF76DFE85F31188E9E65DB1152259 +:101BA00084F8342083F311880021D4E90E232046E1 +:101BB000FFF75EFEFDE60B2284F8342083F31188E4 +:101BC0002B462A4629462046FFF764FEE3E700BF7E +:101BD0007C3C0008743C0008783C000838B590F85C +:101BE00034300446002B3ED0063BDAB20F2A34D8FC +:101BF0000F2B32D8DFE803F0373131082232313190 +:101C00003131313131313737C56BB0F84A309D420F +:101C100014D2C3681B8AB5FBF3F203FB12556DB9EE +:101C2000302383F311882B462A462946FFF732FEDC +:101C300085F311880A2384F834300EE0142384F8E5 +:101C40003430302383F3118800231A461946204686 +:101C5000FFF70EFE002383F3118838BD036C03B138 +:101C600098470023E7E70021204601F043FA0021CE +:101C7000204601F035FA63681B6813B1062120463F +:101C800098470623D7E7000010B590F83430142B9E +:101C9000044629D017D8062B05D001D81BB110BD9A +:101CA000093B022BFBD80021204601F023FA00213A +:101CB000204601F015FA63681B6813B1062120461F +:101CC0009847062319E0152BE9D10B2380F834300F +:101CD000302383F3118800231A461946FFF7DAFDF3 +:101CE000002383F31188DAE7C3689B695B68002BE4 +:101CF000D5D1036C03B19847002384F83430CEE784 +:101D000000230375826803691B6899689142FBD2BE +:101D10005A68036042601060586070470023037582 +:101D2000826803691B6899689142FBD85A6803600E +:101D3000426010605860704708B50846302383F34E +:101D400011880B7D032B05D0042B0DD02BB983F309 +:101D5000118808BD8B6900221A604FF0FF33836140 +:101D6000FFF7CEFF0023F2E7D1E9003213605A609B +:101D7000F3E70000FFF7C4BF054BD9680875186882 +:101D800002681A60536001220275D860FEF7BCBA7F +:101D90002826002030B50C4BDD684B1C87B004466C +:101DA0000FD02B46094A684600F074F92046FFF729 +:101DB000E3FF009B13B1684600F076F9A86907B00D +:101DC00030BDFFF7D9FFF9E728260020391D0008AC +:101DD000044B1A68DB6890689B68984294BF0020A7 +:101DE0000120704728260020084B10B51C68D868D1 +:101DF00022681A60536001222275DC60FFF78EFFB3 +:101E000001462046BDE81040FEF77EBA2826002095 +:101E1000044B1A68DB6892689B689A4201D9FFF705 +:101E2000E3BF70472826002038B5074C074908480B +:101E3000012300252370656001F074FB02232370E9 +:101E400085F3118838BD00BF90280020843C00082D +:101E50002826002000F05EB9EFF3118020B9EFF3DF +:101E60000583302282F311887047000010B530B925 +:101E7000EFF30584C4F3080414B180F3118810BD96 +:101E8000FFF7C6FF84F31188F9E70000034A5168A1 +:101E900053685B1A9842FBD8704700BF001000E0FF +:101EA0008B60022308618B82084670478368A3F128 +:101EB000840243F8142C026943F8442C426943F825 +:101EC000402C094A43F8242CC26843F8182C0222FB +:101ED00003F80C2C002203F80B2C044A43F8102CB6 +:101EE000A3F12000704700BF21030008282600202E +:101EF00008B5FFF7DBFFBDE80840FFF73BBF000078 +:101F0000024BDB6898610F20FFF736BF28260020C0 +:101F1000302383F31188FFF7F3BF000008B50146B3 +:101F2000302383F311880820FFF734FF002383F365 +:101F3000118808BD064BDB6839B1426818605A60E9 +:101F4000136043600420FFF725BF4FF0FF30704758 +:101F5000282600200368984206D01A680260506064 +:101F600099611846FFF706BF7047000038B5044670 +:101F70000D462068844200D138BD036823605C6050 +:101F80008561FFF7F7FEF4E710B503689C68A2428D +:101F90000CD85C688A600B604C602160596099685D +:101FA0008A1A9A604FF0FF33836010BD1B68121BC2 +:101FB000ECE700000A2938BF0A2170B504460D4637 +:101FC0000A26601901F0A8FA01F094FA041BA54250 +:101FD00003D8751C2E460446F3E70A2E04D9BDE843 +:101FE0007040012001F0DEBA70BD0000F8B5144B5E +:101FF0000D46D96103F1100141600A2A1969826016 +:1020000038BF0A22016048601861A818144601F020 +:1020100075FA0A2701F06EFA431BA342064606D35F +:102020007C1C281901F078FA27463546F2E70A2F7A +:1020300004D9BDE8F840012001F0B4BAF8BD00BFF2 +:1020400028260020F8B506460D4601F053FA0F4A3F +:10205000134653F8107F9F4206D12A460146304668 +:10206000BDE8F840FFF7C2BFD169BB68441A2C191C +:1020700028BF2C46A34202D92946FFF79BFF2246E0 +:1020800031460348BDE8F840FFF77EBF2826002010 +:102090003826002010B4C0E9032300235DF8044B68 +:1020A0004361FFF7CFBF000010B5194C2369984278 +:1020B0000DD0D0E90032816813605A609A680A44F2 +:1020C0009A60002303604FF0FF33A36110BD2346E5 +:1020D000026843F8102F53600022026022699A427E +:1020E00003D1BDE8104001F011BA936881680B4438 +:1020F000936001F0FFF92269E1699268441AA242F3 +:10210000E4D91144BDE81040091AFFF753BF00BFDE +:10211000282600202DE9F047DFF8BC8008F11007E1 +:102120002C4ED8F8105001F0E5F9D8F81C40AA68F8 +:10213000031B9A423ED81444D5E900324FF00009FF +:10214000C8F81C4013605A60C5F80090D8F81030E9 +:10215000B34201D101F0DAF989F31188D5E90331ED +:1021600028469847302383F311886B69002BD8D019 +:1021700001F0C0F96A69A0EB04094A4582460DD214 +:10218000022001F00FFA0022D8F81030B34208D133 +:1021900051462846BDE8F047FFF728BF121A2244EF +:1021A000F2E712EB090938BF4A4629463846FFF7DD +:1021B000EBFEB5E7D8F81030B34208D01444211A2A +:1021C000C8F81C00A960BDE8F047FFF7F3BEBDE802 +:1021D000F08700BF38260020282600200020704706 +:1021E000FEE70000704700004FF0FF30704700002E +:1021F00002290CD0032904D00129074818BF002068 +:102200007047032A05D8054800EBC2007047044810 +:1022100070470020704700BF5C3D00082C22002062 +:10222000103D000870B59AB00546084601A914464D +:1022300000F0C2F801A8FEF767FD431C5B00C5E98A +:1022400000340022237003236370C6B201AB023452 +:102250001046D1B28E4204F1020401D81AB070BD0A +:1022600013F8011B04F8021C04F8010C0132F0E71A +:1022700008B5302383F311880348FFF733FA0023AE +:1022800083F3118808BD00BF9828002090F84430DF +:1022900003F01F02012A07D190F845200B2A03D131 +:1022A0000023C0E90E3315E003F06003202B08D1B2 +:1022B000B0F848302BB990F84520212A03D81F2ABE +:1022C00004D8FFF7F1B9222AEBD0FAE7034A826378 +:1022D0000722C26303640120704700BF232200204D +:1022E00007B5052917D8DFE801F0191603191920D9 +:1022F000302383F31188104A01900121FFF794FAEB +:1023000001980E4A0221FFF78FFA0D48FFF7B6F940 +:10231000002383F3118803B05DF804FB302383F3BB +:1023200011880748FFF780F9F2E7302383F311881B +:102330000348FFF797F9EBE7B03C0008D43C0008EE +:102340009828002038B50C4D0C4C0D492A4604F154 +:102350000800FFF767FF05F1CA0204F11000094900 +:10236000FFF760FF05F5CA7204F118000649BDE8E1 +:102370003840FFF757BF00BF602D00202C220020FF +:10238000903C00089A3C0008A53C000870B5044643 +:1023900008460D46FEF7B8FCC6B220460134037865 +:1023A0000BB9184670BD32462946FEF799FC002845 +:1023B000F3D10120F6E700002DE9F04705460C4671 +:1023C000FEF7A2FC2B49C6B22846FFF7DFFF08B193 +:1023D0000636F6B228492846FFF7D8FF08B110366E +:1023E000F6B2632E0BD8DFF88C80DFF88C90234F89 +:1023F000DFF894A02E7846B92670BDE8F08729460C +:102400002046BDE8F04701F0C3BB252E2ED10722A0 +:1024100041462846FEF764FC70B9194B224603F189 +:102420000C0153F8040B42F8040B8B42F9D11B78D2 +:10243000137007350D34DDE7082249462846FEF7BC +:102440004FFC98B90F4BA21C197809090232C95DDB +:1024500002F8041C13F8011B01F00F015345C95D7C +:1024600002F8031CF0D118340835C3E704F8016BF7 +:102470000135BFE77C3D0008A53C0008923D0008FF +:10248000843D0008107AFF1F1C7AFF1FBFF34F8F97 +:10249000024AD368DB03FCD4704700BF003C024013 +:1024A00008B5094B1B7873B9FFF7F0FF074B1A69A2 +:1024B000002ABFBF064A5A6002F188325A601A6881 +:1024C00022F480621A6008BDBE2F0020003C02404A +:1024D0002301674508B50B4B1B7893B9FFF7D6FF6F +:1024E000094B1A6942F000421A611A6842F480529C +:1024F0001A601A6822F480521A601A6842F48062E4 +:102500001A6008BDBE2F0020003C02400B28F0B529 +:1025100016D80C4C0C4923787BB90C4D0E460C2375 +:102520004FF0006255F8047B46F8042B013B13F092 +:10253000FF033A44F6D10123237051F82000F0BD87 +:102540000020FCE7F02F0020C02F0020A43D000851 +:10255000014B53F820007047A43D00080C20704741 +:102560000B2810B5044601D9002010BDFFF7CEFF9F +:10257000064B53F824301844C21A0BB90120F4E773 +:1025800012680132F0D1043BF6E700BFA43D000819 +:102590000B2838B5044628D8FFF75EFCFFF776FF16 +:1025A000FFF77EFF124AF323D360E300DBB243F46C +:1025B000007343F002031361136943F48033136122 +:1025C00005462046FFF762FFFFF7A0FF094B53F8CF +:1025D000241000F0E9F82846FFF77CFFFFF746FCDF +:1025E0002046BDE83840FFF7BBBF002038BD00BF24 +:1025F000003C0240A43D000812F001032DE9F04127 +:1026000005460E4614464BD18218B2F1016F61D8CF +:10261000314B1B6813F001035CD0304FFFF71CFCFB +:10262000FFF73EFFF323FB60FFF730FF314640F238 +:102630000128032C18D824F00104284E0C446D1AEC +:1026400040F20118A142336905EB01072AD123F0BA +:1026500001033361FFF73EFFFFF708FC0120BDE8EF +:10266000F081043C0435E4E7AB07E4D13B6923F493 +:1026700040733B613B6943EA08033B6151F8046BDB +:102680002E60BFF34F8FFFF701FF2B689E42E8D00B +:102690003B6923F001033B61FFF71CFFFFF7E6FBFB +:1026A0000020DCE723F440733361336943EA080315 +:1026B00033610B883B80BFF34F8FFFF7E7FE3F8806 +:1026C00031F8023BBFB2BB42BCD0336923F00103F7 +:1026D0003361E1E71846C2E700380240003C02409F +:1026E000084908B50B7828B11BB9FFF7D9FE0123BB +:1026F0000B7008BD002BFCD0BDE808400870FFF748 +:10270000E9BE00BFBE2F002010B50244064BD2B276 +:10271000904200D110BD441C00B253F8200041F893 +:10272000040BE0B2F4E700BF502800400F4B30B577 +:102730001C6F240407D41C6F44F400741C671C6FC6 +:1027400044F400441C670A4C236843F480732360FC +:102750000244084BD2B2904200D130BD441C00B2BA +:1027600051F8045B43F82050E0B2F4E7003802402F +:10277000007000405028004007B5012201A9002048 +:10278000FFF7C2FF019803B05DF804FB13B50446E0 +:10279000FFF7F2FFA04205D0012201A90020019419 +:1027A000FFF7C4FF02B010BD70470000034B1A686A +:1027B0001AB9034AD2F874281A607047F42F00201F +:1027C0000030024008B5FFF7F1FF024B1868C0F374 +:1027D000407008BDF42F002070470000FEE70000A5 +:1027E0000A4B0B480B4A90420BD30B4BDA1C121AC4 +:1027F000C11E22F003028B4238BF00220021FEF7E7 +:102800008BBA53F8041B40F8041BECE75C3F00084C +:10281000F0300020F0300020F03000207047000041 +:1028200070B5D0E915439E6800224FF0FF3504EBE8 +:1028300042135101D3F800090028BEBFD3F80009A4 +:1028400040F08040C3F80009D3F8000B0028BEBF59 +:10285000D3F8000B40F08040C3F8000B013263183E +:102860009642C3F80859C3F8085BE0D24FF0011351 +:10287000C4F81C3870BD0000890141F020010161DD +:1028800003699B06FCD41220FFF700BB10B5054C72 +:102890002046FEF7A9FF4FF0A0436365024BA365F6 +:1028A00010BD00BFF82F0020F83D000870B5037878 +:1028B000012B054650D12A4B446D98421BD1294B20 +:1028C0005A6B42F080025A635A6D42F080025A6598 +:1028D0005A6D5A6942F080025A615A6922F08002A8 +:1028E0005A610E2143205B6900F022FC1E4BE3601D +:1028F0001E4BC4F800380023C4F8003EC0232360F8 +:102900006E6D4FF40413A3633369002BFCDA0123CB +:1029100033610C20FFF7BAFA3369DB07FCD41220CD +:10292000FFF7B4FA3369002BFCDA0026A6602846CC +:10293000FFF776FF6B68C4F81068DB68C4F81468AA +:10294000C4F81C684BB90A4BA3614FF0FF336361B5 +:10295000A36843F00103A36070BD064BF4E700BF1A +:10296000F82F0020003802404014004003002002ED +:10297000003C30C0083C30C0F8B5446D054600212D +:102980002046FFF779FFA96D00234FF001128F68F1 +:10299000C4F834384FF00066C4F81C284FF0FF30FC +:1029A00004EB431201339F42C2F80069C2F8006B86 +:1029B000C2F80809C2F8080BF2D20B686A6DEB6521 +:1029C000636210231361166916F01006FBD1122002 +:1029D000FFF75CFAD4F8003823F4FE63C4F800383B +:1029E000A36943F4402343F01003A3610923C4F80F +:1029F0001038C4F814380A4BEB604FF0C043C4F8E9 +:102A0000103B084BC4F8003BC4F81069C4F8003907 +:102A1000EB6D03F1100243F48013EA65A362F8BD85 +:102A2000D43D000840800010426D90F84E10D2F85E +:102A3000003823F4FE6343EA0113C2F800387047FC +:102A40002DE9F84300EB8103456DDA68166806F05E +:102A50000306731E022B05EB41130C4680460FFA4A +:102A600081F94FEA41104FF00001C3F8101B4FF0FD +:102A7000010104F1100398BFB60401FA03F3916950 +:102A80008EBF334E06F1805606F5004600293AD037 +:102A9000578A04F15801490137436F50D5F81C1883 +:102AA0000B43C5F81C382B180021C3F810195369C3 +:102AB0000127611EA7409BB3138A928B9B08012AB2 +:102AC00088BF5343D8F85C20981842EA034301F1C9 +:102AD000400205EB8202C8F85C002146536028469C +:102AE000FFF7CAFE08EB8900C3681B8A43EA8453D8 +:102AF000483464011E432E51D5F81C381F43C5F8D5 +:102B00001C78BDE8F88305EB4917D7F8001B21F4C2 +:102B10000041C7F8001BD5F81C1821EA0303C0E7E1 +:102B200004F13F0305EB83030A4A5A602846214615 +:102B3000FFF7A2FE05EB4910D0F8003923F400435B +:102B4000C0F80039D5F81C3823EA0707D7E700BFDB +:102B50000080001000040002826D1268C265FFF759 +:102B60005FBE00005831436D49015B5813F40040CB +:102B700004D013F4001F0CBF022001207047000096 +:102B80004831436D49015B5813F4004004D013F4FD +:102B9000001F0CBF022001207047000000EB8101E4 +:102BA000CB68196A0B6813604B685360704700006C +:102BB00000EB810330B5DD68AA691368D36019B9E9 +:102BC000402B84BF402313606B8A1468426D1C4401 +:102BD000013CB4FBF3F46343033323F0030302EB40 +:102BE000411043EAC44343F0C043C0F8103B2B6894 +:102BF00003F00303012B09B20ED1D2F8083802EB1F +:102C0000411013F4807FD0F8003B14BF43F0805391 +:102C100043F00053C0F8003B02EB4112D2F8003BF6 +:102C200043F00443C2F8003B30BD00002DE9F04101 +:102C3000244D6E6D06EB40130446D3F8087BC3F8B1 +:102C4000087B38070AD5D6F81438190706D505EBDE +:102C500084032146DB6828465B689847FA071FD53E +:102C6000D6F81438DB071BD505EB8403D968CCB93B +:102C70008B69488A5A68B2FBF0F600FB16228AB9C3 +:102C80001868DA6890420DD2121AC3E90024302382 +:102C900083F311880B482146FFF78AFF84F31188DC +:102CA000BDE8F081012303FA04F26B8923EA0203F1 +:102CB0006B81CB68002BF3D021460248BDE8F04180 +:102CC000184700BFF82F002000EB810370B5DD68C6 +:102CD000436D6C692668E6604A0156BB1A444FF49E +:102CE0000020C2F810092A6802F00302012A0AB281 +:102CF0000ED1D3F8080803EB421410F4807FD4F807 +:102D0000000914BF40F0805040F00050C4F80009A2 +:102D100003EB4212D2F8000940F00440C2F8000967 +:102D2000D3F83408012202FA01F10143C3F8341840 +:102D300070BD19B9402E84BF4020206020682E8AC3 +:102D40008419013CB4FBF6F440EAC44040F0005062 +:102D50001A44C6E72DE9F8433B4D6E6D06EB401370 +:102D60000446D3F80889C3F8088918F0010F4FEA20 +:102D700040171AD0D6F81038DB0716D505EB8003BC +:102D8000D9684B691868DA68904230D2121A4FF04D +:102D900000091A60C3F80490302383F31188214698 +:102DA0002846FFF791FF89F3118818F0800F1CD097 +:102DB000D6F834380126A640334216D005EB8403FA +:102DC0006D6DD3F80CC0DCF814200134E4B2D2F8F5 +:102DD00000E005EB04342F445168714515D3D5F854 +:102DE000343823EA0606C5F83468BDE8F8830123C1 +:102DF00003FA04F22B8923EA02032B818B68002B50 +:102E0000D3D0214628469847CFE7BCF81000AEEB58 +:102E10000103834228BF0346D7F8180980B2B3EBF9 +:102E2000800FE2D89068A0F1040959F8048FC4F823 +:102E30000080A0EB09089844B8F1040FF5D81844B5 +:102E40000B4490605360C7E7F82F00202DE9F74F3F +:102E5000A24C656D6E69AB691E4016F480586E61B8 +:102E600007D02046FEF728FD03B0BDE8F04F00F084 +:102E700047BC002E12DAD5F8003E98489B071EBFCB +:102E8000D5F8003E23F00303C5F8003ED5F804381A +:102E900023F00103C5F80438FEF738FD370505D5E2 +:102EA0008E48FFF7BDFC8D48FEF71EFDB0040CD523 +:102EB000D5F8083813F0060FEB6823F470530CBFF5 +:102EC00043F4105343F4A053EB6031071BD5636800 +:102ED000DB681BB9AB6923F00803AB612378052BD2 +:102EE0000CD1D5F8003E7D489A071EBFD5F8003EAC +:102EF00023F00303C5F8003EFEF708FD6368DB68B6 +:102F00000BB176489847F30274D4B70227D5D4F8AA +:102F10005490DFF8C8B100274FF0010A09EB4712BF +:102F2000D2F8003B03F44023B3F5802F11D1D2F83F +:102F3000003B002B0DDA62890AFA07F322EA030349 +:102F4000638104EB8703DB68DB6813B139465846BD +:102F50009847A36D01379B68FFB29F42DED9F00608 +:102F600017D5676D3A6AC2F30A1002F00F0302F434 +:102F7000F012B2F5802F00F08580B2F5402F08D115 +:102F800004EB83030022DB681B6A07F5805790423D +:102F90006AD13003D5F8184813D5E10302D50020D3 +:102FA000FFF744FEA20302D50120FFF73FFE6303B3 +:102FB00002D50220FFF73AFE270302D50320FFF7D0 +:102FC00035FE75037FF550AFE00702D50020FFF70F +:102FD000C1FEA10702D50120FFF7BCFE620702D5A2 +:102FE0000220FFF7B7FE23077FF53EAF0320FFF770 +:102FF000B1FE39E7636DDFF8E4A0019300274FF0DD +:103000000109A36D9B685FFA87FB9B453FF67DAF87 +:10301000019B03EB4B13D3F8001901F44021B1F5E8 +:10302000802F1FD1D3F8001900291BDAD3F800191B +:1030300041F09041C3F80019D3F800190029FBDBD7 +:103040005946606DFFF718FC218909FA0BF321EA54 +:103050000303238104EB8B03DB689B6813B15946A0 +:10306000504698470137CCE7910708BFD7F8008052 +:10307000072A98BF03F8018B02F1010298BF4FEABB +:10308000182884E7023304EB830207F5805752685F +:10309000D2F818C0DCF80820DCE9001CA1EB0C0C0D +:1030A000002188420AD104EB830463689B699A6813 +:1030B00002449A605A6802445A606AE711F0030FAA +:1030C00008BFD7F800808C4588BF02F8018B01F15A +:1030D000010188BF4FEA1828E3E700BFF82F00205E +:1030E000436D03EB4111D1F8003B43F40013C1F8E9 +:1030F000003B7047436D03EB4111D1F8003943F4B5 +:103100000013C1F800397047436D03EB4111D1F84A +:10311000003B23F40013C1F8003B7047436D03EB01 +:103120004111D1F8003923F40013C1F80039704778 +:1031300000F1604303F561430901C9B283F800134C +:10314000012200F01F039A4043099B0003F16043F2 +:1031500003F56143C3F880211A60704730B5039CC2 +:103160000172043304FB0325C0E90653049B036387 +:103170000021059BC160C0E90000C0E90422C0E94C +:103180000842C0E90A11436330BD0000416A0022D1 +:10319000C0E90411C0E90A22C2606FF00101FEF724 +:1031A000E5BE0000D0E90432934201D1C2680AB9F9 +:1031B000181D70470020704703691960C26801320A +:1031C000C260C269134482690361934224BF436AA7 +:1031D00003610021FEF7BEBE38B504460D46E36824 +:1031E0003BB16269131D1268A3621344E3620020BD +:1031F00007E0237A33B929462046FEF79BFE0028D4 +:10320000EDDA38BD6FF00100FBE70000C368C2696A +:10321000013BC3604369134482694361934224BF05 +:10322000436A436100238362036B03B1184770470D +:1032300070B53023044683F31188866A3EB9FFF7E0 +:10324000CBFF054618B186F31188284670BDA36AE6 +:10325000E26A13F8015BA362934202D32046FFF7B0 +:10326000D5FF002383F31188EFE700002DE9F84F25 +:1032700004460E46174698464FF0300989F31188E8 +:103280000025AA46D4F828B0BBF1000F09D1414669 +:103290002046FFF7A1FF20B18BF311882846BDE837 +:1032A000F88FD4E90A12A7EB050B521A934528BFF1 +:1032B0009346BBF1400F1BD9334601F1400251F850 +:1032C000040B43F8040B9142F9D1A36A4033403612 +:1032D000A3624035D4E90A239A4202D32046FFF77D +:1032E00095FF8AF31188BD42D8D289F31188C9E7C6 +:1032F00030465A46FDF7EAFCA36A5B445E44A3628B +:103300005D44E7E710B5029C0172043303FB04211E +:10331000C0E906130023C0E90A33039B0363049B3F +:10332000C460C0E90000C0E90422C0E90842436368 +:1033300010BD0000026AC260426AC0E90422002295 +:10334000C0E90A226FF00101FEF710BED0E90423A4 +:103350009A4201D1C26822B9184650F8043B0B606A +:10336000704700231846FAE7C368C2690133C36097 +:103370004369134482694361934224BF436A4361B2 +:103380000021FEF7E7BD000038B504460D46E368AE +:103390003BB123691A1DA262E2691344E362002073 +:1033A00007E0237A33B929462046FEF7C3FD0028FB +:1033B000EDDA38BD6FF00100FBE70000036919602A +:1033C000C268013AC260C2691344826903619342D0 +:1033D00024BF436A036100238362036B03B1184770 +:1033E0007047000070B530230D460446114683F344 +:1033F0001188866A2EB9FFF7C7FF10B186F31188CE +:1034000070BDA36A1D70A36AE26A01339342A3628E +:1034100004D3E16920460439FFF7D0FF002080F390 +:103420001188EDE72DE9F84F04460D469046994680 +:103430004FF0300A8AF311880026B346A76A4FB9C5 +:1034400049462046FFF7A0FF20B187F31188304698 +:10345000BDE8F88FD4E90A073A1AA8EB06079742A5 +:1034600028BF1746402F1BD905F1400355F8042B00 +:1034700040F8042B9D42F9D1A36A4033A362403641 +:10348000D4E90A239A4204D3E16920460439FFF7BC +:1034900095FF8BF311884645D9D28AF31188CDE781 +:1034A00029463A46FDF712FCA36A3B443D44A36219 +:1034B0003E44E5E7D0E904239A4217D1C3689BB1A3 +:1034C000836A8BB1043B9B1A0ED01360C368013B27 +:1034D000C360C3691A44836902619A4224BF436A84 +:1034E0000361002383620123184670470023FBE732 +:1034F00000F030B94FF08043586A70474FF0804376 +:10350000002258631A610222DA6070474FF080434C +:103510000022DA60704700004FF080435863704724 +:10352000FEE7000070B51B4B01630025044686B022 +:10353000586085620E4600F0BFF804F11003C4E93C +:1035400004334FF0FF33C4E90635C4E90044A560F5 +:10355000E562FFF7CFFF2B460246C4E9082304F1DA +:1035600034010D4A256580232046FEF799FC01238E +:10357000E0600A4A0375009272680192B268CDE970 +:103580000223074B6846CDE90435FEF7B1FC06B0CF +:1035900070BD00BF90280020043E0008093E0008CE +:1035A00021350008024AD36A1843D062704700BF31 +:1035B000282600204B6843608B688360CB68C3601B +:1035C0000B6943614B6903628B6943620B6803605B +:1035D0007047000008B5264B26481A6940F2FF11D3 +:1035E0000A431A611A6922F4FF7222F001021A6179 +:1035F0001A691A6B0A431A631A6D0A431A651E4A3E +:103600001B6D1146FFF7D6FF02F11C0100F580602B +:10361000FFF7D0FF02F1380100F58060FFF7CAFF25 +:1036200002F1540100F58060FFF7C4FF02F1700160 +:1036300000F58060FFF7BEFF02F18C0100F58060AD +:10364000FFF7B8FF02F1A80100F58060FFF7B2FFB5 +:1036500002F1C40100F58060FFF7ACFF02F1E00168 +:1036600000F58060FFF7A6FFBDE8084000F0EEB867 +:103670000038024000000240103E000808B500F08B +:1036800067FAFEF7D1FBFFF791F8BDE80840FEF7B7 +:1036900059BE000070470000EFF3098305494A6BEB +:1036A00022F001024A63683383F30988002383F31D +:1036B0001188704700EF00E0302080F3118862B677 +:1036C0000C4B0D4AD96821F4E0610904090C0A4346 +:1036D000DA60D3F8FC20094942F08072C3F8FC207C +:1036E0000A6842F001020A602022DA7783F8220099 +:1036F000704700BF00ED00E00003FA05001000E095 +:1037000010B5302383F311880E4B5B6813F400630C +:1037100014D0F1EE103AEFF30984683C4FF0807357 +:10372000E361094BDB6B236684F30988FEF750FBEA +:1037300010B1064BA36110BD054BFBE783F3118865 +:10374000F9E700BF00ED00E000EF00E03303000800 +:10375000360300080F4B1A6C42F001021A641A6E0D +:1037600042F001021A660C4A1B6E936843F0010393 +:1037700093604FF0804353229A624FF0FF32DA6237 +:1037800000229A615A63DA605A6001225A611A6013 +:10379000704700BF00380240002004E04FF0804234 +:1037A00008B51169D3680B40D9B2C9439B071161B1 +:1037B00007D5302383F31188FEF74CFB002383F3F6 +:1037C000118808BD1F4B1A696FEAC2526FEAD252C4 +:1037D0001A611A69C2F308021A614FF0FF301A69C0 +:1037E0005A69586100215A6959615A691A6A62F026 +:1037F00080521A621A6A02F080521A621A6A5A6A6F +:1038000058625A6A59625A6A1A6C42F080521A64B3 +:103810001A6E42F080521A661A6E0B4A106840F413 +:1038200080701060186F00F44070B0F5007F1EBF0C +:103830004FF4803018671967536823F4007353609E +:1038400000F05EB90038024000700040334B4FF08A +:1038500080521A64324A4FF4404111601A6842F0B3 +:1038600001021A601A689107FCD59A6822F00302D7 +:103870009A602A4B9A6812F00C02FBD1196801F089 +:10388000F90119609A601A6842F480321A601A6865 +:103890009203FCD55A6F42F001025A671F4B5A6FD0 +:1038A0009007FCD51F4A5A601A6842F080721A606D +:1038B0001B4A53685904FCD5184B1A689201FCD571 +:1038C000194A9A60194B1A68194B9A42194B21D11F +:1038D000194A1168194A91421CD140F205121A6026 +:1038E000144A136803F00F03052BFAD10B4B9A68A7 +:1038F00042F002029A609A6802F00C02082AFAD199 +:103900005A6C42F480425A645A6E42F480425A66BB +:103910005B6E704740F20572E1E700BF003802407D +:10392000007000400854400700948838002004E0EC +:1039300011640020003C024000ED00E041C20F4154 +:10394000074A08B5536903F00103536123B1054ADF +:1039500013680BB150689847BDE80840FFF7D0BE28 +:10396000003C014070300020074A08B5536903F05D +:103970000203536123B1054A93680BB1D06898479D +:10398000BDE80840FFF7BCBE003C0140703000209D +:10399000074A08B5536903F00403536123B1054A8C +:1039A00013690BB150699847BDE80840FFF7A8BEFE +:1039B000003C014070300020074A08B5536903F00D +:1039C0000803536123B1054A93690BB1D069984745 +:1039D000BDE80840FFF794BE003C01407030002075 +:1039E000074A08B5536903F01003536123B1054A30 +:1039F000136A0BB1506A9847BDE80840FFF780BED4 +:103A0000003C014070300020164B10B55C6904F496 +:103A100078725A61A30604D5134A936A0BB1D06A2F +:103A20009847600604D5104A136B0BB1506B98474A +:103A3000210604D50C4A936B0BB1D06B9847E20575 +:103A400004D5094A136C0BB1506C9847A30504D5F3 +:103A5000054A936C0BB1D06C9847BDE81040FFF756 +:103A60004FBE00BF003C014070300020194B10B524 +:103A70005C6904F47C425A61620504D5164A136DF0 +:103A80000BB1506D9847230504D5134A936D0BB1C4 +:103A9000D06D9847E00404D50F4A136E0BB1506EF9 +:103AA0009847A10404D50C4A936E0BB1D06E984789 +:103AB000620404D5084A136F0BB1506F9847230472 +:103AC00004D5054A936F0BB1D06F9847BDE81040FD +:103AD000FFF716BE003C01407030002008B50348D7 +:103AE000FDF784FABDE80840FFF70ABEBC230020BA +:103AF00008B5FFF753FEBDE80840FFF701BE000020 +:103B0000062108B50846FFF713FB06210720FFF73B +:103B10000FFB06210820FFF70BFB06210920FFF70A +:103B200007FB06210A20FFF703FB06211720FFF7FA +:103B3000FFFA06212820FFF7FBFA07211C20FFF7D8 +:103B4000F7FABDE808400C212520FFF7F1BA000084 +:103B500008B5FFF737FE00F00DF8FDF75BFCFDF749 +:103B600041FEFDF719FDFFF795FDBDE80840FFF7A1 +:103B7000BFBC00000023054A19460133102BC2E9DF +:103B8000001102F10802F8D1704700BF7030002028 +:103B9000034611F8012B03F8012B002AF9D17047D5 +:103BA00053544D3332463F3F3F00000053544D3392 +:103BB00032463430780053544D3332463432780034 +:103BC00053544D33324634343658580001203300B4 +:103BD0000010410001105A00031059000710310075 +:103BE00000000000A03B00083F000000130400009C +:103BF000AC3B00083F00000019040000B63B000881 +:103C00003F00000021040000C03B00083F0000000E +:103C1000009600000000000000000000000000000E +:103C20000000000000000000D5130008C1130008C8 +:103C3000FD130008E9130008F5130008E11300085C +:103C4000CD130008B9130008091400080000000093 +:103C500015150008011500083D1500082915000874 +:103C600035150008211500080D150008F914000885 +:103C700049150008000000000100000000000000DD +:103C800063300000803C000880260020902800203F +:103C90004172647550696C6F740025424F41524403 +:103CA000252D424C002553455249414C250000002A +:103CB0000200000000000000311700089D170008F6 +:103CC00040004000302D0020402D00200200000068 +:103CD000000000000300000000000000E1170008E1 +:103CE0000000000010000000502D00200000000027 +:103CF0000100000000000000F82F00200101020078 +:103D0000E1220008F12100088D220008712200083C +:103D100043000000183D000809024300020100C0F2 +:103D2000320904000001020201000524001001050F +:103D30002401000104240202052406000107058273 +:103D4000030800FF09040100020A00000007050142 +:103D50000240000007058102400000001200000040 +:103D6000643D000812011001020000400912415791 +:103D700000020102030100000403090425424F412F +:103D8000524425004D6174656B463430352D4341F6 +:103D90004E003031323334353637383941424344BE +:103DA00045460000004000000040000000400000C8 +:103DB00000400000000001000000020000000200BE +:103DC00000000200000002000000020000000200EB +:103DD000000002000000000025190008DD1B00089B +:103DE000891C000840004000583000205830002056 +:103DF0000100000068300020800000004001000049 +:103E0000030000006D61696E0069646C650000006C +:103E10000001A81600000000AAAAAAAA0001140026 +:103E2000FF9F00000000000070A70A0000000001D2 +:103E300000000000AAAAAAAA00000001FFFF0000DB +:103E40000000000000000000000000100000000062 +:103E5000AAAAAAAA00000010FFFF000000000000AC +:103E6000000000000000000000000000AAAAAAAAAA +:103E700000000000FFFF0000000000000000000044 +:103E80000000000000000000AAAAAAAA000000008A +:103E9000FFFF000000000000000000000000000024 +:103EA00000000000AAAAAAAA00000000FFFF00006C +:103EB0000000000000000000000000000000000002 +:103EC000AAAAAAAA00000000FFFF0000000000004C +:103ED0000000000000000000000000000A000000D8 +:103EE00000000000030000000000000000000000CF +:103EF00000000000000000000000000000000000C2 +:103F000000000000000000000000000000000000B1 +:103F1000F60300000000000000000F000000000099 +:103F2000FF00000098280020BC230020009600001D +:103F300000000800960000000008000004000000D7 +:103F4000783D0008000000000000000000000000B4 +:0C3F500000000000000000000000000065 :00000001FF From ca5dc2ba90a3f592cfce7f7f0fbb05bbb1581e05 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 10 Mar 2023 16:47:17 +0000 Subject: [PATCH 085/287] IO_Firmware: rebuild iofirmware --- .../iofirmware_f103_8MHz_highpolh.bin | Bin 40964 -> 41164 bytes .../iofirmware_f103_8MHz_lowpolh.bin | Bin 40964 -> 41164 bytes Tools/IO_Firmware/iofirmware_highpolh.bin | Bin 40956 -> 41148 bytes Tools/IO_Firmware/iofirmware_lowpolh.bin | Bin 40956 -> 41148 bytes 4 files changed, 0 insertions(+), 0 deletions(-) diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin index 6e4fbea04f5f5bc89b216fc18af3db8f086a3579..d148daded7da40e20b0d889b2ba85bd5cd1449d1 100755 GIT binary patch delta 10724 zcmZ{Kdwf$x_V~=bH|cF@Y3Kv`pn8)~Xensgf)omvCgt{#Lc!uLpsP16kDIn&5Jdzr zEd>Q(6&Tzvlx3~rDj>U3YIZ3Yf>Qm8t6v))3e*S6`Yi?h?kyB^`$~RilH%i!Up}A7 z%$%7yGjm>Z=FHuAiuvR{X8VM=Z}%bovy@-bgZp>POo{7lLVWtGh@S^(J*0!L?x@be z7k2EMGJNIph@bHS;y2O!wH^QW_>NQ2EfQWG=^9sDcZ=UV7XBmQe{2aaF+$y~gw5Vt zkG;ezoxQwr8q$`&a^*pjP?B1@!!q4lpmM|dI@3y$e^pC`w$Zjm%S`V)Xth96JCTs| zn?AhqD&ShumsplK`>=(*JYVHXQa2a%b|PhKFs>}_4lo3RNm~&@3=-yYNI*Ko^FN|1 z01+r``w_%b_%=w}A?XsyUxt|?b_W8T5lRKQFf5VI{Att4&eG5z3NYgJ{z8#mo`UHK#d3scA*tAGBedbWVhDXr6akUXAI%cv;K( zSR2N-$r;_7czMgp5nCCT(`_2diO<~{v3Y}h&+H0^Q8~p{*f%&DqUCjQ@>X+&6!b3$?sptWen>|8ucZBs zhvY}3*BnO21F}`w09f`r76C@9f}#AHTv6h%DrT7QDs;Rky{wu{-#J+2e)a*G$$bb_ z0OG39(4Elz>Tid_$T}EV4@-A?ke9S2+&9KFW+PM|>#2LPP9Cn;Nc-fmrPt(g1x1?` zjIK#%)h0xQ#FX;gj#=_!yhA;?y@D*u6zU%6p#lx zya)1&fTE4exVsIl=Y#3)sDLd(O$B1zg z4|wC!Iq@!WgqUEeMq0%jX!&GZ4`yoLXn8;L5W~FwM$3u`=P?u4-%@x_28MMlzxOl~ z(?@bl$8j3@(X=0%$d2r)NUqz2h2@;Gg$!ovBZ>!Uxq+nTjKk|&X6M|E@h4brlYno8$E(i#1C5K$#(- zWOI^6c`k^J@v}|xTdP<(Ro-2sQ3m@nL`L~8AS?$+&F-RpIlA;6;j&$$wD+217Bp*j z5$)j%_&evrj6ysZ3&^Pgza9zYC?u%B1Z+!^okhq?+jMSCnUNfv{5+EyBsurZ#7~oz z_l?6#$e#Q1XV${ri-#eh3_4O2I{%rMC@Sk!#TB}l4!l*qWo&e@W3&WsJ5 z$fkdEG+W$Y-l0Bx>fLTGHnrWSN~hwkN5_tAN9m=b<5c{wjk9=fz53l;Jo(3?+{D|y zZzWcrvm)LyqTMJ9V#i~rWyH)M~`l4nBg&VTb zzPF~z&MA|F5v5nH7jFk50#6Zv48KIY-M%nW9tatY_t z4d0sfSbT?$?`Lmy9F6E>Z*5c`cDAV($&>lU0^o5!r81UIUy zoydr1wyE1qfP?$ghsS8TKSG@HWq+nCOXm7;H=g=|x}99g&(Ha0-G4k(2-a61eqxtu z{rItH(bvT+AxB$of8?TsO23$6%Po1gn~mkY!$hH$h|}w)t`=f_Z&_k|Ynzv~ek%*L zo@=U=Rn~dm?G|Eh_}*6&>N-24npveXcxPcYkXcw72~O8fo%ZxU0Qu-kyVQqGTvoJq zidf$B(No41N!Quf=ytuBA$Bec`fGzZ_ttwasE19474g;&AXmx48CKx+z8Rw!wwC;3 z#(f&=iZtsi(mf;XZdA)E0|D4!?dlY)$9>wLjMuen*5axakZYHci8IS%k6`uyQgQ;j z)B`4%oNS$W_k#zV8`VS3;a4bZpJkVq>psB7bVsnMYdVf@1Xv_2`;du_OAnmrq`jEQ z`z+;36noJNwYjwQqW8z6KOUu)_`qD8zEM3$f-^^rIH=R~u{WcvY&T|;yc9a_{&Cqy zu=%I8aTxIZ_aMc#wV9G3G9PC}U)%+ov^AIapn?N3r?m7^lD$P-_a_=xn>1pynAOa~ zE+YeUrqw27gpop<`h$s?)}|`tpZCvjJ#4xG_*T!o(2B?1A^qvW|4pV+F;d0(!K}#k z$`w?W;w@Y|GGqcrS>?)LSloZ~sUBF90CHwJ--(TVomVAnyt<4kBg*<$JJQqMp1}`0 zCw3_X8ZlNJDaMv@x2LVquNd#beN4v9X%<~OzGp*-Z^J@dquXn-XhM7i#Bge_3#w$V zIT`>OaI_oa=%PSp6?}24@L|DA>wH=PrYQiZzg8`*T zD=;R!)T)NWmMTyam>DX@WPX7;bG3lRKi-bVini-1MYglLMb@)NwctXWJBrDHKdihf zm~rOlqwUyOO*{otq8}Ex@p|70HR(!5?M{mj`TYRfm>|9kl96diy+5P&Xn)_$O6ysk zRX!c~H{aRGjsO1QA^8rRRo)-?s&wu%JrC^dQGciT!)~Mpc}Pm0*D4XiDOgK;T{*cl$h;Vbv4?YB*q;U~B6#uWnQGvduTy_}A6x z*$lvEW{w;Q^Q-ht4n>O2s)?IT-L< zQwoqUtTei0BBzWwNwp*zTr@b}&6NL$(`Y9^T?=&-3^HZZeT&BCb~39db3}&>d)9qt zuWD|DQju_pxQfQb=}u6`_dMttJuc{>MU;7XbSjt$;DIfmtxana6(8b{$iDfxjQm#1+4&5EkF{L*9n0WWa%sVT(F@JOm$k8r`?>BP5C*SXXJ(W? zkVI+9@D4dOWr1Zu0T1MYtJETCQKHGfyElL@*dU`U{3WAg^)rf}oRQKPT|c=dNn_`N z@5{Tb>*AZ);(&i!KQ>xd(eX0C8D;DV9$dGHC&&uB0bd|H>~{PDxn*C%95_rCRgR8V z)$t&lTz4H}m7A&{=6OCMTPky1qyL6@#l7iBgvk7j7w!@_UDF~)u?%oxd-KcJShTO# zBy6O)Iswc_(EnL5Y9AwZPEJ=MP_`IhL%SGd_JBsrXcb`o`vx*Z%@M_eh5kwg_C#KfMh`ULC)ypa8P9OwyM!cIdF^XBm0`H-v>|^A5 zRSL%_NG1H@#mQTPf(YZi(_zg>a28?kkdmFwqKjnH;!LXy6o_nQ6zK%TmFLFY0*ZmT zi~BiIXolT)3m7Zk4${5Tx#GpRHM|%-{(v{yz?P&q8Rc)Jd$AsOlK3SPA6;@nl6(Ch z2QtN8|G6Ne*n)ljh+Zt_iCD?+r)}>BvY~B6koI^VdQ1zJE6>d9_4Cm4rmA1Vh*xUB z_lOHc|O+=dwCwG)hTl)SR!_l!A6)Fs8P`LLbEkQn8i6L4gfrf_56jfWM>{E15w~{6?K$2dN3t_Vdl@)%$B^&B_oHyh~FL-Qcz7 z)zL>Zgi+@7FA__{PrI;Ivo}vfF9-aYy#j0?2{2skjDSnJ@)FAM-iZSInbLJALhu=s z>G{3+NQ}rG&>UoxrKEFd7JiPzFPr#i53~j$@nTdfqwvS^cCqus*)w7wHAemM(0V>OCT3yD0 z5?cuqJQu&#+TNus?Yh{0#fY5Nw-Q{uy?72)4ny zCJc*(NnRTQuJLYuo6LD^Eu05u9;;z?zfJCQo=kiK7N~QxWdisuc#yGOm2{pS61g%z zvSlDbpDG~bZ8Cf1I=G0RS^1vpqNfM?2mL)>r+auAHLzKQf>ls?!sSo^$kULmV>Ga}C7athm`V?>lgoS@~z3-L~5@!e_T#aug^S zU$S3vB!^1LB>4C+*CLzM9&u$6^g+sox`m;9Tb=lm%o6)Kdx30qM9ZJS{j}#6&L@=( zGR{9&`LF5KK@1YaNX_&2eazSPoBM+nEWh&#DNlRnf7ZIyAqA_MlbP zp1M_K)tnL={jRGU$8zoOb~CXspa)ezQ^j^Q2`;NBc3gXeq99!c+b(2KbUdKrSnY3M zbpSK75MKDDUk|DRELGfZVOD@y<14YT!j6pbc3X{639{!T7oCW0A65gCTPqfCGR8}a zCox1T=4V>4IZx7ddarycm&6zQ^*V#m#k7RLY!w7zKDWrsn*%w>Cr!&wvsFt$As z{x$8+B2B1`VU$ibRN|N$ozax>Fu@(9k&q%=%JxEy_&tMu|8}=RT!23A`^2R+dmIHlbp?CudmRbsa=W@)*RJj|;T!XD zbAM0w9?7@4KrsXTMr_#$C5#u^iF38!s#E`L(s_8m@wrb!$=y?@zXWvn3{K(0pow%f zbgy(3>{=!(31~+>Pd3=Ji4vQW65?Ke<-rn{N$aSgRd*p$0~n$iye_cBzB@A^3Tq-Z|OYLcLj? zBdI7WBB4D|;bWt{NDpgSc`c&YTc8N|P$)O!nh3K{9=%6U1aQ zQXUwXEdTB3E1gd1ADw`)p85&YPOcp?VUL`k6yVJvpmPW~{{$tgRi+L`2Y7D{4&Eym z9+H#12E!!@>laGc5oJx0QXn{snG_JO22$`;GJc;t^pqZ-ChMP?6@j;HIhq9UGfz!% z>D*zPb)jEt)0V;=!^j)ky0}~f|Jq!g=N*_WBvysU>;$XDff(ibCIG`m`B*VpKfY80 z7P7I=2<42@Cc74Dq;H(o-*7H<{#6e8OM{j2RoUlYZ_Hy``nzwv zC1uGqa>cfLB=X49qbE7dLH{T(^3oMg-V8SjNK_1+?v0KrIZaMiVl`>f(sk+b@G_!06H(SQpZR8N{ByEjo-C(X(%M(aWb_(Sq!41G8E+?#u1TID zh`WpWwETq|TJ41@d9Ne2S%AxfQjk>iYc{?!#4)v%u1M#O51kDq3fx0T2XR|Yq(WRE1^sFtV?=_{SqF8U z=a;sie|A4>G{Pv_lRCb?ZYv>OYmF{?`UU+joVbJiw8TCUc3(L$tQaWWCKpHz(g!fp zU-}uqw+XOifD`*`Y)b|poM*TyRY?Zto!P?UPdn-*JoQp#cokvX;a3Sfh8x+3Z@0-4 ztZjh&aX=B$OOJ`Xx^5I+Mq1ZpO&;vu@5n0LZ{IIxh!3UimsC&mr6e&2JTImH?bK=F zx3Z}aE7$w4%K3#iI+Mil&~lX|KQj)0Mhc!u8+EGRB3_ZZld*CF`dACEchVki^5iqQ zxPlyfCVRv^0njKr{c{d;@Qb~J(=-r8uWeWSv{T&eO)@7nc#g)iHGMc%EPaZ6V7FDy%ER~ z1q0f}bw7b2e2;?utRQ>D1P;L|u#vwe=hZMv9}lziw~W)n&5MpUJ`Tbik%lpjT?cBAM^T{4PtLH$hA+?1E#4uEFFEOP01wBmY~Dk+Ae$ z7q%e7dtI!N-fbzVX;ffHvW@S{rzI+K$e}Y+$z*Gi3#{AKF(zCUmBsoRs*~XiauyBC z(n5KwmGuF6Dv=_!($04tPlEn`2a)pc-Z1rf52@W?aD5USBmbu}w$$nVT-Jyt1D$xm96AKf<2qT3J!&hW8V2CjKnH zAn&rMXBWxCq*7^wv=BU1xH=h6bs^Lsv36%sp1WR7wQ=HCE_q(dK}(#Eb>Ljqp6A&r z?SNgaYu08Z_a!zxjC3x?w%eZFn+FYF*x) zB~Y=a0>PKE4r006+qiyzw~oU(jZgAkG$z~|DaYUvtMe2CbC7X^TnChGaHPt61 z;LC`2x<|~Zue>GK!y_Um?y#^I={-B>U+GPP(a#34%cy~P z=NMCuL>Iz@7J?xdy>e(7PFTjl<6$Y_Y$+f$+vU9=^SiuApfW=jNOw0{z9`?>8Qs^H zAj0KAjrd!v;;%OMY-n>8VWc|&X`=;S3i>a3!$_&>)B~p)WStx5gX<(kUyiVSDO=^H zN&ybD(NdvAotcVYQ#B}?Fz}1KlQ*9m=c0_s0bB@SqsgsI``I%;GG#i zw%4m;;h`;qiL!rJjk|U1HhZZZJ|L*X-4j?|{8y#U!-`QUICrZB!kvZ(>4oDYLhW5R zyFeADzuLW+El?*-XB~`Ope~+nb(p78IBSD%N2Z^a8E{cggP-+YDsm02Jm~*6uZOnfRMcj>D_iU9YW+RTvIhZR2}rMdN-_dl)`Wu z0?ss5a@`X&SE>(KVtu;+Q-13%7_&Em@tzN1axIc#L&hrT|NTi;z6uPQ7wG(z@(2AL z5O9hrHR*NkvoifyVpq)$`BixNu7{WJ?b7zDp#MX7yrO0x9PSIV0uSja58_Zf)XsY} zwhmd}%u2f}S%6PJS?&Tq;*K?8MI;N&$dDq{!!m}Sq`T0>6iw%Glq>B9e2|c-aS3f1$mfX`4YqbacSG;UUv7-tbC5s$p6`hWiu&oi!oUqn9-Ep(Wi#Oo7xnX}m)!k1l+WdCY z*hU#oYm_E9_RDOu({sKH?yJ%~$rw6x1@U|ro4vb;erjWPpv)WX)YcpfQf85}FH9SE zrjHdDv?ey+=wvc`e7r#~QeX8XKvBlG?Mb2`bTQsWa<@(#5eq@r2sbj|gE|rK4EjsR z%B{I$J^>|}0LoO}(^OEdpt*2qKIU`>{XY(t_pDtRV~d&7;UFJv9b5VJV1}rNBRRa8 zA7GdQNe5m3JJdC@G}3n70p3bK*F&9-h?3FLOmC@-b4n#RAt9y<)**CU-x*7%IT#un zYm24R%-uFNwUGiIM@BlC-(NrI^ibIf4Iw+WRV1r0DGvje1liKFVBJq8S#Ds=d*CaC zZNDGMC4x6#OI?%NT>8@?Y6`$`afzh*k0}gFB+vcPK(j-Cyayc7OMkpKSuk9FszEg% z$|6L+wPO1;2*kle^e-A2aKpqG#hh=BSEyX78PX4(p8%zFFvp!l#g4JDr703yN`n%7 zsEwR_apb5MEbO`0EcoIg>Vkk(q)l*qlN&FlxoBB|j~bpo!W&}XOP8SkeU(P@qxTjh zb0lW(r(MXYA)j_JBZK~B17XV`L$8_vctF$Ffi`nc``wT?D~J&g&kuA`&m7S&XKc?M zSs-bu>Z^uBuWaytGuXDSs9X+=8oi`a11_>9`K=uc%O0 z`d4X5)nDQ5K4xH*d_`g*z(kMmY)4cnEGk}+BW-Bsr(N7+yd50u0lKtl1KK0bkZGp; zx(3dA9?X%_@o1#xB(N|vddrUGu8%#TGThv>dg?y} z{Js5JeS{G3--euryc_aJ$bW=93i2+;L(H1+AD#`;z9rTK)~PA zAMghtO&bXKCqaE@An1QFv=um{j+tS{NI}QS$&))1$NkTV`;#$@53>&r!M?D?111GowLXwzIO_cVH%KZ;W}Z1h?jsiFV4!6!Ij+fk z2p)b9z`NODNX?M`3CRQLG^8_-K7;f*q>h$9?D?n0HTfmP>mmICQVFC7Ar(NH2q_to z1JZK4V+ESP<#F6}K3bPBS{Rc)7MwHqjo~l^VMD)Yh)0?xp(+zX33RVR4-rkk@sK5j uyBt^$grT!zaqSX1Ca6Wk^-4jcb6LTRcj8zua7pffS2@)o~wGCTv}dH>J+qQBonn3ou#@>b+V z*R3aBHP)DgQoGhae3P;_qj4vE~vjNJ~#STZ!x*Cd9k)#mU*s4K(zp< zT}T+4JN8#?cx5Z_8r2_>AGz?|TnpQ=Smok2X7_a=Wus4*AGYw_U*ULVZ8Kt!P{<(x z=@5?)l<Y{gv9f`%L;$haCNoj0|5( zrH+T>CGcD#cgj|!iVgDDgP@L~zBgC4IjoAAwb|>TVY{?bHJSE0SYG>iA)B<< zVRYm|^X<^Q9@yON>hDkdoSPK{YXqo{C1RL=i{y zVdnF}#xXHdFivXBj9tSTuY@5%*A$i?mK&aJK#n7gF01^~X z2imSz>*Zie=r&eMA#Bd7EhkaJoy%>nrw>gZK-Gq z5yPh)aD^vu;&?Gkj5L)Yt#a*7;}?^AF>~^*#*dQ@F--4UjVq^Kz|8Uf#;oay7+)YO zW}IP~`betjI1VL0n(DDYwxyH?3M;rC6Xuj6awkO}Fy{`uD+@_N>SUbVxG;4B#_?oD zTAEgQ8}SzolDE?)F%Q2@{+{+abL4IE*gf}WZ+-{yJSaO=^#EI(yh~nE{)z>+Rawwi zwNi1ZM)^oZek$Km$RnY$DdGNvf;8#4Bf<885G!evZ~HWgmJHl8!#Q)%+z_E3lcP~G z2lEY)xf`Q3%5)z#Ml3YRhu5%joLrl&QT{uSC^E{oUSS1b%4@SvID+#&5O&!$%7H$U z%z|mvX44jKucvD@sj8S_p;?`*Dc(=)>GvjduK1^VK!~u6a@!i}<;DR|&kl99>8cdbaHX76mh|Dd zT#rIdq$lI0q$}MXH0usB&d8Y~Z&iy)(d-$(t9teZ=T?}=F__eTD31WBO=CsIIqCkF zW6zthffLz;vqw|JD)TnA_|(ZBE;O#qtv-Az{CaTcm^PG<7ay+T&ubR&uJvk1A-?y= zqujLH?yC~3zqum964qvv1@ZC|wb@8eTku@mqu>sArySQXf=`?$-t5A&wLOaVf8C=N z`h>#{qy3@sQah)F_yY1e<)Z^0&ml*>+Frrgun=p%+(jo#MPastqK)K}Ir@;|LS`;A zO}T_K=z?#}c_Jb%j2~ccT|OGn&)%w0iz`~yHu6-4F|%_8YwcY2isgp8b4426rXC)% z%5h(fy1D`x@w`^G)&xAbFWq>erspi;lzjt9&SaVE$31xVC+eHzQbtDVe}DSvC#nQ5 z6d`_Ew`zUmiD1#)%`78F8*iU=(v3=JPqn4xp6p>mc~_8lrJRWORnA^5gt`w~Lfp?a zEN{LlUny_7rdnBLf$LF>JpR%S zwb;ZZ2fJp81-)mV>0A+goed3c(~F7XJIj5Z$9<_Y*1ImM2Tb3th_HSFr9zg>wSuho z%pJ>|DJOrMJ5$519B0*#p1I>DoGNFPPrb0h$DfYHdfc!5*?3*cCO>Li38i)tnKrK= z^Z;fLASKniL#;Ex;AGRh2@lp))TsL^Mqi=0J(e9VuBVO-=?P%t)?PkZ1Gqq#_C6Es zm*73oMO!iV?y(doqu6#AycJSvyX(iJKOUvNxULW<)Tn!jZ{FCjy*f=ldvlbP?ZIrc zi()6wpPX_4n}2>T90R}qxkI^aYM|Q?n1Pdn+jpq@O}2)DUX*!2=9Ddcbj#|AbAFU@ zwMioei^&aVVU_1W`C%(f$Ot`!R`oj*GpAL(Mn0TB*I8`30sK}MUTnsbN49>;o&SxY zS}{h&8NTGeHp5D)OA!{X4H=R^qO5Z0&XBtQ=vG@`P6Fte=|UGa_IGtk*jT@u8Y4>n zybbAT>zD3)+BL0P$<&CU;utYBpSyj}+N&$3IB`Fdcyo?L*M_H8`Q;Ymml|DOqebJF zD=>y*d!0`qyUj89HPU2G0H1r=9FtURVqgnG+9P7)!q!=LsQwNic z#~C&96rRg~QH;wpMiw=zEmUo(0d0gMfvPcCoM}#4Eubl@+wdgOc0D%R79O_L`qfb_ z#1Q9?VshXQtH%2h&mDcF4I8JBmdshf#R4})?>?bMU%6Jk-6913b&%Z^DeeT#NV3Gu zzgB*9p#Nrx^(&rL{xtX<-_^xU`M&*-Jc4JH&4XWe)%652c*-}Ikn*nql-S|MGd0uy z(20R%TXMnCg<7NFnP4r#$H=qRI7WGgyl$Pcq!=M(#sDkAKB3)>KF_~= zmsM1_z}i_(G3V9Dtw@a+`I+tbm<~TkaD8` z>uxUfYB{qr*P)P@tYqu4VV{V8V$ep2|EQ}u4LC4u6qt?^Bir$fD&{Nolx~lT5PQSQ zo?Sfj#-W(3oC>Ium$I^p>P@WT<5BWFH|n7(tPc+a6~-_dP~k@U{Ig|R2bJ{>b)P^i z54Q!*!BdvBb3LaYK6g zm^jk%Ukj{Gg`b~q5s_XHIpwUk;Agz1w9;oZuFA0CgwE1}-t}v;eik0vubNG>Z0QB{ zk8(W+P;yr1qpjV{)64AN+iO%yAy#}|%A+otQ{MK@uyMD)05`0d0>BJ=O;c^H-SeJq zRi~zyZ?X~lRZ|KB_|%liwpNvME^1ZNQ{DNnwH2cPV3Gi05F4_|$^lsx|vnAyo@_Luxo3;(=DxluAbk zhT1);SUKozxu#?yAt*06cN(XB(L$}{2OZo8cxL!hRGcjWUi6KMb!jLjdA z1=&eqyB#&EsQcDl+OSKmQL}|Nh%z9hZa$?6R||DX3qkxj>(yY z&yqzslhgj-^LBB{$IYDb4M1&kMN_b-g_ukbqd)}j-eJTI7QJW^X{@@@g;P0YEjgT% zjZ4U_9A|)XjBntS9`bB%oc5lBh;KhYcID1tItR%=bLWH)VGvKJa0McY?gPY-HwULQ z{vpqW8TlX?pZ_#|gzU_pfQuTN@)u#|v;Ic@eux44`Wn3j|A!6V0X)}5zB(Vkri;8uu;&CA~g6us={#o=XjwX8+r!mJ4HGZ|2VKCo#@pmkP?c`GNpXiNd$xdx( z>HydC1Huq@>&%RjOroS&qjx*vVv8-snLKP4+@+REOQQq>-$XA9)iO%P|7MiFen$C( zoRh{e-}IAfk~FCfB457Ax-O!D&GC9R4`8Ep4efsn@Ql)XoQKeD;5b=nH{kckHoF}c zlUw#>jCzTD(ay^xZRdzvOpWYHpUM@*QrzaKF>dVqxLZ3nR^qI0F)vI*w79}nLnrz6PpDXKXEWo z)ErS-urSbtT&LF{Uf09{KK72+^KO5u+KO~72+e9@WloHHJVdM|8Kpa8KRJOA>@(t< zI1{6ADi-(_&V-fQE^@szmcvS`kMNH^8nehJh|u4)8Rm?HifjxKQcOif_DQng(Io5A z6TBGMz$g!#puEzXaF2jOVC*>qoG3KF>U#u?m3QvYwbQX8#PGGe7(C^GE7-v1##S)O zgQVwCJ${EoESvVoj1!XF=lRT=B=&jE`xxbxx8D=chsAUeE1CgHJLydUT9}Wv_!wGz z>n%{8U)1N}ef^%Bs(vja*3pp1jFrCQYRf4w3LV^s7-h!^M%hpPvh4TFH7`+@d4WieR+lQ4Oy`1K>{%mYisT=C0ptkvvJ7tv0yC#g?>1^gR0ban;6 zEnRsHC4y29r2&4R`#PK+nD8Er^_0wwM?ysIfaV~h6qByUlHtx3v3%MiSwJlS;KfnR zjMCqXr(n0g6hH@?L7HICQR0+ls*|3+>0rqfEwK7#YR?SVJfr-(Pb;Ftn{AM;n5q{K zSrT1Spe^=NE&7K1W%<~+V}tjAKd5No4JlBL^Y_Kd+>=)Ty@03^Nu4Ep7YCMLP~uTza3^uKdG>Bv};@XWGj7^Qh&893Q= zlX;l37S7c1^}jQv54Wj6^~-A12Z6q8U^!4KOw@s|Hl+;H zH>1+!HR>u38oWa4AJ^k&$tUoXNf$hSPXbryu}G3v#L(r6E8f>eg4bUAKIvak$Xvfe z@>iNhFjXt(IVq8EVsm_+Z+tD+c+keTU29?0L%0jWxHnxJ@8Uii#%*`i-o>37#%**R zxQqMSFz!XyvAei;hjCB3&JN*1Vc>nk$TC;^`{e#7p2LgDxhKk*Ywwep6(2<{h6(DL z*n9!vmd^(nTc@OJxj+I}WdyDm4A933NO6#btJc9q{M@S3rJuE2fc8F5uPePNIG;

rSjXsOo#GhrB*w5QDWve3?ZlArka0V%_tU@ zE{Z6@#v(g1M%aVOjf#&wFKsYJzy?LyE;%w424AvYa>V#+G4>dT9x!!XA$}Tnm&V~C z8i%)c0Vk=bl$4$?jd--ECZq-&!tCTSyv`$5JA;^+;7C~;v2uNTH4K9B2MPSQ|gsNVgy?2+%4 z*U09Zp%LRO@onU@XHCwCoE%rCV#ZsuOCe7d)DW6en=NaDEeltqQguH{5bK3p5&+}dvxgY}7dl3fcP@a6u=wmN%#J(1 z9JiV6tt)E0UHM1=(Lqb2z0|Q(u9vwq0x9wbWCHqLUyY1{SYJ_E@s{lK zc)cZZxXtZgZ!BUP2YPNDmXhUi85xtMBD|U8JR3hQ-R$#x_7R<5!%K*N0boS#6-`;h z`Rv#UA47tjW}$y25(v0-O%eXpE+I>v%f@wN?{l-9SP!>W))M%JnX?J0R@I=3&O*jY z6{Ugvuc9k~81+czb4Stb6=wW&MK+uzE^K5Wb#p<-yD-*S71oL(0(d&osqJJw5h_N9`cDN%0l)nj4}Ob<_l%-ii& zd8)M)I6gKw)FQn_AR*6>#Sf8$=acbevgrAkxW5nlHExc0RW@Z|$!3 z3I?=;>vq~;H0>xFrg0vmNxPsnFd&{+S@YKI=PH*vfR-OdCsRZ5?RC9hAmFmsv z!T*omc)lbnDvjD!uz~JBlh-SA@OJW_$|&4OZdX2q*OKz}({L+!W4&>-u`feBVTqM- z+n+6om&j-93t>azs>Z?Q&8`}k&Geb!imO&HmH8gb@35r1BE_hzZtxG3H_XPb6r3C^ zVM&uy={Vhu8Du!!%^K-VkzR%99a|uKs>V(|Qx;?0stTslC8Lrd+9->$XxtUqLCIRE zZ?dv(WVDtbWnwc`H=^pCIrIoyNwQl(Dl z5$?8bl$u!zxP8{LTKOuBxYekC$kLA!%PZW^}wI zQI5&wozm3Ouexk>hQF--ly79^qij{+v{M^)S%TdxOoFvzp(2}cR7*IOvB#EwEJc^z z?xOe4p;ZD8QcyECW2<9muVNf{c8vXCbG+OkziDAg$F*gaZ*Rti^-{DPYiHzGsYqhV zYayg!OOdibMer?dZ%v$YucUPO#p!oc8e6nut7vDr$M&IM5Tq4FX5Uuq8`Y=+Rk*Nv@_jY+AdIX$^#jzF#kZX|Ik4*Mce+LYm5@4(Xip8Eg%JO8fn%NpXbuut+SL78N=B!A`4K2 z|97DFUsPaZob;xU{I?uVqr5>CP%M1NG)UM`Z?A@7|9dO2`nqFc#x4tUDG|b;c1Us7 zIjBfg&-fE`C8j1@JSPS%eCdd;?XY819?h8-^$Q^W3qEdlL<4Adm%}pmU-NGRk$1k+sm3)Z2ZYH9n2_TdrllTF;T=-~A3c z^G!ZTI7Bzl%bL&A;er$o_^*GusHLn2@m0&ZCY*titEG^RfP9Nw?pimh_xSuR5d17l!numLn((B!SR zFLE&UOgnEcw4LJI>!aY#qKIQOvq?1E< z>fc7&-gHPMTu-8=uIzv%)a|5po6)=jy6g^MTo)iI9|3`KsNZGzJPSW!<$4er>+SLj za%d7h&t=Hh2nL-$S;*&YcPuX7ChxW2w)ODgc&k)c>VwSG(4fEg0KN%}L;ZPBk$FRO z=SIFoW83Y}H?UH12@8bOk7yt;vfZqRWT62WVx>%&#;F#nJGl*7n+249MB_N%Ohyai9lC;y zrY0UNS{4sK#!d8jKJm#QkiYvN#`59&R5#jv_%UkDw7tg0_QW%1x&sU__0**$$gu0K zzUZ1DL^KBFk+SoSH(`&0+aH$KORSV732*|{%9*im_?=i$iLND14s^!-Fs!YtOkKjL ztX+~t_Ma(6%KVIkZA5|+bQO6wZ*qFTm%AZE80vralM!K^F3h}-&W%8bWRxECgYPiwGB=x#^gI=WZ z=XSuN#H(%5q5%?8NU@NDP1C|Uk5^;|G$8{%s1xyapJyD|vMFt%5D8}!m|{V1U1ouT z3X$^eu?lc1=k65rKDR2w7IOdYGV+gyYT3Enc6 zD}-_Uf6yqL%#rjh>8TF`g0;o1jcdsJ`H+FJ#e$=wIAlU_HHej`G&4Pw7UnjW`al__ z6-SbNTMP^opKh5BA=T|IGh%dxj%TV>1Kms)`Vq8j6^os`$vx z<3;fQC^NthUEC4G%P`0YP$@7rHZN9U^OnLO(l8CSPzbQ;njV&OEkZ1Bj*+Wkw^`Ws z9Tt3kDI{a4r=@MFrww>*oRiiS_*cP8M|i_%aU7`b>nbOjDHPDB&$VX;v&0rWGd2;L90UaM94x1Mf{kDXF*5Ud>sJ}m4e-`Ss!}YhIUNu~I zZ+j%L;3L>afA87bS2!bwC~zCn>iH%fQqe(!T77`v^#nl4L&-uJ2&Hd8s~-jB0F+~) z^bF9WOsh|XdJkm!=>hi_Z(zz7nq9!XR=Eq>@KjI0C`-l7--$Hrb8s3TziJcV0&Gq4}Ng}TO*)!8;Qjk^a1`PwB z;qiFM=Ol(X_E+-1#KK@-JF=W?= znq}u+g=qlv0DKM54R8_QG{AcRcK}w{9V^iotBK>%`CwgSbiAN9fDn=6(Z`q3vJlo* t2*;-Y>Vo0@((AC+p`QRMhcKC2m#w)+_Bk=xQkNDi!xY=$Uo*7P{{?TLUONB) diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin index 97759cc3419c39a4a9607adae0baaba3b0126eda..b3036b63edd7aa9b7923c3a1cfd56442b0b8c5c3 100755 GIT binary patch delta 10724 zcmZ{Kdwf$x_V~=bH|cF@Y3Kv`pn8)~Xensgf)omvCgt{#Lc!uLpsP16kDIn&5Jdzr zEd>Q(6&Tzvlx3~rDj>U3YIZ3Yf>Qm8t6v))3e*S6`Yi?h?kyB^`$~RilH%i!Up}A7 z%$%7yGjm>Z=FHuAiuvR{X8VM=Z}%bovy@-bgZp>POo{7lLVWtGh@S^(J*0!L?x@be z7k2EMGJNIph@bHS;y2O!wH^QW_>NQ2EfQWG=^9sDcZ=UV7XBmQe{2aaF+$y~gw5Vt zkG;ezoxQwr8q$`&a^*pjP?B1@!!q4lpmM|dI@3y$e^pC`w$Zjm%S`V)Xth96JCTs| zn?AhqD&ShumsplK`>=(*JYVHXQa2a%b|PhKFs>}_4lo3RNm~&@3=-yYNI*Ko^FN|1 z01+r``w_%b_%=w}A?XsyUxt|?b_W8T5lRKQFf5VI{Att4&eG5z3NYgJ{z8#mo`UHK#d3scA*tAGBedbWVhDXr6akUXAI%cv;K( zSR2N-$r;_7czMgp5nCCT(`_2diO<~{v3Y}h&+H0^Q8~p{*f%&DqUCjQ@>X+&6!b3$?sptWen>|8ucZBs zhvY}3*BnO21F}`w09f`r76C@9f}#AHTv6h%DrT7QDs;Rky{wu{-#J+2e)a*G$$bb_ z0OG39(4Elz>Tid_$T}EV4@-A?ke9S2+&9KFW+PM|>#2LPP9Cn;Nc-fmrPt(g1x1?` zjIK#%)h0xQ#FX;gj#=_!yhA;?y@D*u6zU%6p#lx zya)1&fTE4exVsIl=Y#3)sDLd(O$B1zg z4|wC!Iq@!WgqUEeMq0%jX!&GZ4`yoLXn8;L5W~FwM$3u`=P?u4-%@x_28MMlzxOl~ z(?@bl$8j3@(X=0%$d2r)NUqz2h2@;Gg$!ovBZ>!Uxq+nTjKk|&X6M|E@h4brlYno8$E(i#1C5K$#(- zWOI^6c`k^J@v}|xTdP<(Ro-2sQ3m@nL`L~8AS?$+&F-RpIlA;6;j&$$wD+217Bp*j z5$)j%_&evrj6ysZ3&^Pgza9zYC?u%B1Z+!^okhq?+jMSCnUNfv{5+EyBsurZ#7~oz z_l?6#$e#Q1XV${ri-#eh3_4O2I{%rMC@Sk!#TB}l4!l*qWo&e@W3&WsJ5 z$fkdEG+W$Y-l0Bx>fLTGHnrWSN~hwkN5_tAN9m=b<5c{wjk9=fz53l;Jo(3?+{D|y zZzWcrvm)LyqTMJ9V#i~rWyH)M~`l4nBg&VTb zzPF~z&MA|F5v5nH7jFk50#6Zv48KIY-M%nW9tatY_t z4d0sfSbT?$?`Lmy9F6E>Z*5c`cDAV($&>lU0^o5!r81UIUy zoydr1wyE1qfP?$ghsS8TKSG@HWq+nCOXm7;H=g=|x}99g&(Ha0-G4k(2-a61eqxtu z{rItH(bvT+AxB$of8?TsO23$6%Po1gn~mkY!$hH$h|}w)t`=f_Z&_k|Ynzv~ek%*L zo@=U=Rn~dm?G|Eh_}*6&>N-24npveXcxPcYkXcw72~O8fo%ZxU0Qu-kyVQqGTvoJq zidf$B(No41N!Quf=ytuBA$Bec`fGzZ_ttwasE19474g;&AXmx48CKx+z8Rw!wwC;3 z#(f&=iZtsi(mf;XZdA)E0|D4!?dlY)$9>wLjMuen*5axakZYHci8IS%k6`uyQgQ;j z)B`4%oNS$W_k#zV8`VS3;a4bZpJkVq>psB7bVsnMYdVf@1Xv_2`;du_OAnmrq`jEQ z`z+;36noJNwYjwQqW8z6KOUu)_`qD8zEM3$f-^^rIH=R~u{WcvY&T|;yc9a_{&Cqy zu=%I8aTxIZ_aMc#wV9G3G9PC}U)%+ov^AIapn?N3r?m7^lD$P-_a_=xn>1pynAOa~ zE+YeUrqw27gpop<`h$s?)}|`tpZCvjJ#4xG_*T!o(2B?1A^qvW|4pV+F;d0(!K}#k z$`w?W;w@Y|GGqcrS>?)LSloZ~sUBF90CHwJ--(TVomVAnyt<4kBg*<$JJQqMp1}`0 zCw3_X8ZlNJDaMv@x2LVquNd#beN4v9X%<~OzGp*-Z^J@dquXn-XhM7i#Bge_3#w$V zIT`>OaI_oa=%PSp6?}24@L|DA>wH=PrYQiZzg8`*T zD=;R!)T)NWmMTyam>DX@WPX7;bG3lRKi-bVini-1MYglLMb@)NwctXWJBrDHKdihf zm~rOlqwUyOO*{otq8}Ex@p|70HR(!5?M{mj`TYRfm>|9kl96diy+5P&Xn)_$O6ysk zRX!c~H{aRGjsO1QA^8rRRo)-?s&wu%JrC^dQGciT!)~Mpc}Pm0*D4XiDOgK;T{*cl$h;Vbv4?YB*q;U~B6#uWnQGvduTy_}A6x z*$lvEW{w;Q^Q-ht4n>O2s)?IT-L< zQwoqUtTei0BBzWwNwp*zTr@b}&6NL$(`Y9^T?=&-3^HZZeT&BCb~39db3}&>d)9qt zuWD|DQju_pxQfQb=}u6`_dMttJuc{>MU;7XbSjt$;DIfmtxana6(8b{$iDfxjQm#1+4&5EkF{L*9n0WWa%sVT(F@JOm$k8r`?>BP5C*SXXJ(W? zkVI+9@D4dOWr1Zu0T1MYtJETCQKHGfyElL@*dU`U{3WAg^)rf}oRQKPT|c=dNn_`N z@5{Tb>*AZ);(&i!KQ>xd(eX0C8D;DV9$dGHC&&uB0bd|H>~{PDxn*C%95_rCRgR8V z)$t&lTz4H}m7A&{=6OCMTPky1qyL6@#l7iBgvk7j7w!@_UDF~)u?%oxd-KcJShTO# zBy6O)Iswc_(EnL5Y9AwZPEJ=MP_`IhL%SGd_JBsrXcb`o`vx*Z%@M_eh5kwg_C#KfMh`ULC)ypa8P9OwyM!cIdF^XBm0`H-v>|^A5 zRSL%_NG1H@#mQTPf(YZi(_zg>a28?kkdmFwqKjnH;!LXy6o_nQ6zK%TmFLFY0*ZmT zi~BiIXolT)3m7Zk4${5Tx#GpRHM|%-{(v{yz?P&q8Rc)Jd$AsOlK3SPA6;@nl6(Ch z2QtN8|G6Ne*n)ljh+Zt_iCD?+r)}>BvY~B6koI^VdQ1zJE6>d9_4Cm4rmA1Vh*xUB z_lOHc|O+=dwCwG)hTl)SR!_l!A6)Fs8P`LLbEkQn8i6L4gfrf_56jfWM>{E15w~{6?K$2dN3t_Vdl@)%$B^&B_oHyh~FL-Qcz7 z)zL>Zgi+@7FA__{PrI;Ivo}vfF9-aYy#j0?2{2skjDSnJ@)FAM-iZSInbLJALhu=s z>G{3+NQ}rG&>UoxrKEFd7JiPzFPr#i53~j$@nTdfqwvS^cCqus*)w7wHAemM(0V>OCT3yD0 z5?cuqJQu&#+TNus?Yh{0#fY5Nw-Q{uy?72)4ny zCJc*(NnRTQuJLYuo6LD^Eu05u9;;z?zfJCQo=kiK7N~QxWdisuc#yGOm2{pS61g%z zvSlDbpDG~bZ8Cf1I=G0RS^1vpqNfM?2mL)>r+auAHLzKQf>ls?!sSo^$kULmV>Ga}C7athm`V?>lgoS@~z3-L~5@!e_T#aug^S zU$S3vB!^1LB>4C+*CLzM9&u$6^g+sox`m;9Tb=lm%o6)Kdx30qM9ZJS{j}#6&L@=( zGR{9&`LF5KK@1YaNX_&2eazSPoBM+nEWh&#DNlRnf7ZIyAqA_MlbP zp1M_K)tnL={jRGU$8zoOb~CXspa)ezQ^j^Q2`;NBc3gXeq99!c+b(2KbUdKrSnY3M zbpSK75MKDDUk|DRELGfZVOD@y<14YT!j6pbc3X{639{!T7oCW0A65gCTPqfCGR8}a zCox1T=4V>4IZx7ddarycm&6zQ^*V#m#k7RLY!w7zKDWrsn*%w>Cr!&wvsFt$As z{x$8+B2B1`VU$ibRN|N$ozax>Fu@(9k&q%=%JxEy_&tMu|8}=RT!23A`^2R+dmIHlbp?CudmRbsa=W@)*RJj|;T!XD zbAM0w9?7@4KrsXTMr_#$C5#u^iF38!s#E`L(s_8m@wrb!$=y?@zXWvn3{K(0pow%f zbgy(3>{=!(31~+>Pd3=Ji4vQW65?Ke<-rn{N$aSgRd*p$0~n$iye_cBzB@A^3Tq-Z|OYLcLj? zBdI7WBB4D|;bWt{NDpgSc`c&YTc8N|P$)O!nh3K{9=%6U1aQ zQXUwXEdTB3E1gd1ADw`)p85&YPOcp?VUL`k6yVJvpmPW~{{$tgRi+L`2Y7D{4&Eym z9+H#12E!!@>laGc5oJx0QXn{snG_JO22$`;GJc;t^pqZ-ChMP?6@j;HIhq9UGfz!% z>D*zPb)jEt)0V;=!^j)ky0}~f|Jq!g=N*_WBvysU>;$XDff(ibCIG`m`B*VpKfY80 z7P7I=2<42@Cc74Dq;H(o-*7H<{#6e8OM{j2RoUlYZ_Hy``nzwv zC1uGqa>cfLB=X49qbE7dLH{T(^3oMg-V8SjNK_1+?v0KrIZaMiVl`>f(sk+b@G_!06H(SQpZR8N{ByEjo-C(X(%M(aWb_(Sq!41G8E+?#u1TID zh`WpWwETq|TJ41@d9Ne2S%AxfQjk>iYc{?!#4)v%u1M#O51kDq3fx0T2XR|Yq(WRE1^sFtV?=_{SqF8U z=a;sie|A4>G{Pv_lRCb?ZYv>OYmF{?`UU+joVbJiw8TCUc3(L$tQaWWCKpHz(g!fp zU-}uqw+XOifD`*`Y)b|poM*TyRY?Zto!P?UPdn-*JoQp#cokvX;a3Sfh8x+3Z@0-4 ztZjh&aX=B$OOJ`Xx^5I+Mq1ZpO&;vu@5n0LZ{IIxh!3UimsC&mr6e&2JTImH?bK=F zx3Z}aE7$w4%K3#iI+Mil&~lX|KQj)0Mhc!u8+EGRB3_ZZld*CF`dACEchVki^5iqQ zxPlyfCVRv^0njKr{c{d;@Qb~J(=-r8uWeWSv{T&eO)@7nc#g)iHGMc%EPaZ6V7FDy%ER~ z1q0f}bw7b2e2;?utRQ>D1P;L|u#vwe=hZMv9}lziw~W)n&5MpUJ`Tbik%lpjT?cBAM^T{4PtLH$hA+?1E#4uEFFEOP01wBmY~Dk+Ae$ z7q%e7dtI!N-fbzVX;ffHvW@S{rzI+K$e}Y+$z*Gi3#{AKF(zCUmBsoRs*~XiauyBC z(n5KwmGuF6Dv=_!($04tPlEn`2a)pc-Z1rf52@W?aD5USBmbu}w$$nVT-Jyt1D$xm96AKf<2qT3J!&hW8V2CjKnH zAn&rMXBWxCq*7^wv=BU1xH=h6bs^Lsv36%sp1WR7wQ=HCE_q(dK}(#Eb>Ljqp6A&r z?SNgaYu08Z_a!zxjC3x?w%eZFn+FYF*x) zB~Y=a0>PKE4r006+qiyzw~oU(jZgAkG$z~|DaYUvtMe2CbC7X^TnChGaHPt61 z;LC`2x<|~Zue>GK!y_Um?y#^I={-B>U+GPP(a#34%cy~P z=NMCuL>Iz@7J?xdy>e(7PFTjl<6$Y_Y$+f$+vU9=^SiuApfW=jNOw0{z9`?>8Qs^H zAj0KAjrd!v;;%OMY-n>8VWc|&X`=;S3i>a3!$_&>)B~p)WStx5gX<(kUyiVSDO=^H zN&ybD(NdvAotcVYQ#B}?Fz}1KlQ*9m=c0_s0bB@SqsgsI``I%;GG#i zw%4m;;h`;qiL!rJjk|U1HhZZZJ|L*X-4j?|{8y#U!-`QUICrZB!kvZ(>4oDYLhW5R zyFeADzuLW+El?*-XB~`Ope~+nb(p78IBSD%N2Z^a8E{cggP-+YDsm02Jm~*6uZOnfRMcj>D_iU9YW+RTvIhZR2}rMdN-_dl)`Wu z0?ss5a@`X&SE>(KVtu;+Q-13%7_&Em@tzN1axIc#L&hrT|NTi;z6uPQ7wG(z@(2AL z5O9hrHR*NkvoifyVpq)$`BixNu7{WJ?b7zDp#MX7yrO0x9PSIV0uSja58_Zf)XsY} zwhmd}%u2f}S%6PJS?&Tq;*K?8MI;N&$dDq{!!m}Sq`T0>6iw%Glq>B9e2|c-aS3f1$mfX`4YqbacSG;UUv7-tbC5s$p6`hWiu&oi!oUqn9-Ep(Wi#Oo7xnX}m)!k1l+WdCY z*hU#oYm_E9_RDOu({sKH?yJ%~$rw6x1@U|ro4vb;erjWPpv)WX)YcpfQf85}FH9SE zrjHdDv?ey+=wvc`e7r#~QeX8XKvBlG?Mb2`bTQsWa<@(#5eq@r2sbj|gE|rK4EjsR z%B{I$J^>|}0LoO}(^OEdpt*2qKIU`>{XY(t_pDtRV~d&7;UFJv9b5VJV1}rNBRRa8 zA7GdQNe5m3JJdC@G}3n70p3bK*F&9-h?3FLOmC@-b4n#RAt9y<)**CU-x*7%IT#un zYm24R%-uFNwUGiIM@BlC-(NrI^ibIf4Iw+WRV1r0DGvje1liKFVBJq8S#Ds=d*CaC zZNDGMC4x6#OI?%NT>8@?Y6`$`afzh*k0}gFB+vcPK(j-Cyayc7OMkpKSuk9FszEg% z$|6L+wPO1;2*kle^e-A2aKpqG#hh=BSEyX78PX4(p8%zFFvp!l#g4JDr703yN`n%7 zsEwR_apb5MEbO`0EcoIg>Vkk(q)l*qlN&FlxoBB|j~bpo!W&}XOP8SkeU(P@qxTjh zb0lW(r(MXYA)j_JBZK~B17XV`L$8_vctF$Ffi`nc``wT?D~J&g&kuA`&m7S&XKc?M zSs-bu>Z^uBuWaytGuXDSs9X+=8oi`a11_>9`K=uc%O0 z`d4X5)nDQ5K4xH*d_`g*z(kMmY)4cnEGk}+BW-Bsr(N7+yd50u0lKtl1KK0bkZGp; zx(3dA9?X%_@o1#xB(N|vddrUGu8%#TGThv>dg?y} z{Js5JeS{G3--euryc_aJ$bW=93i2+;L(H1+AD#`;z9rTK)~PA zAMghtO&bXKCqaE@An1QFv=um{j+tS{NI}QS$&))1$NkTV`;#$@53>&r!M?D?111GowLXwzIO_cVH%KZ;W}Z1h?jsiFV4!6!Ij+fk z2p)b9z`NODNX?M`3CRQLG^8_-K7;f*q>h$9?D?n0HTfmP>mmICQVFC7Ar(NH2q_to z1JZK4V+ESP<#F6}K3bPBS{Rc)7MwHqjo~l^VMD)Yh)0?xp(+zX33RVR4-rkk@sK5j uyBt^$grT!zaqSX1Ca6Wk^-4jcb6LTRcj8zua7pffS2@)o~wGCTv}dH>J+qQBonn3ou#@>b+V z*R3aBHP)DgQoGhae3P;_qj4vE~vjNJ~#STZ!x*Cd9k)#mU*s4K(zp< zT}T+4JN8#?cx5Z_8r2_>AGz?|TnpQ=Smok2X7_a=Wus4*AGYw_U*ULVZ8Kt!P{<(x z=@5?)l<Y{gv9f`%L;$haCNoj0|5( zrH+T>CGcD#cgj|!iVgDDgP@L~zBgC4IjoAAwb|>TVY{?bHJSE0SYG>iA)B<< zVRYm|^X<^Q9@yON>hDkdoSPK{YXqo{C1RL=i{y zVdnF}#xXHdFivXBj9tSTuY@5%*A$i?mK&aJK#n7gF01^~X z2imSz>*Zie=r&eMA#Bd7EhkaJoy%>nrw>gZK-Gq z5yPh)aD^vu;&?Gkj5L)Yt#a*7;}?^AF>~^*#*dQ@F--4UjVq^Kz|8Uf#;oay7+)YO zW}IP~`betjI1VL0n(DDYwxyH?3M;rC6Xuj6awkO}Fy{`uD+@_N>SUbVxG;4B#_?oD zTAEgQ8}SzolDE?)F%Q2@{+{+abL4IE*gf}WZ+-{yJSaO=^#EI(yh~nE{)z>+Rawwi zwNi1ZM)^oZek$Km$RnY$DdGNvf;8#4Bf<885G!evZ~HWgmJHl8!#Q)%+z_E3lcP~G z2lEY)xf`Q3%5)z#Ml3YRhu5%joLrl&QT{uSC^E{oUSS1b%4@SvID+#&5O&!$%7H$U z%z|mvX44jKucvD@sj8S_p;?`*Dc(=)>GvjduK1^VK!~u6a@!i}<;DR|&kl99>8cdbaHX76mh|Dd zT#rIdq$lI0q$}MXH0usB&d8Y~Z&iy)(d-$(t9teZ=T?}=F__eTD31WBO=CsIIqCkF zW6zthffLz;vqw|JD)TnA_|(ZBE;O#qtv-Az{CaTcm^PG<7ay+T&ubR&uJvk1A-?y= zqujLH?yC~3zqum964qvv1@ZC|wb@8eTku@mqu>sArySQXf=`?$-t5A&wLOaVf8C=N z`h>#{qy3@sQah)F_yY1e<)Z^0&ml*>+Frrgun=p%+(jo#MPastqK)K}Ir@;|LS`;A zO}T_K=z?#}c_Jb%j2~ccT|OGn&)%w0iz`~yHu6-4F|%_8YwcY2isgp8b4426rXC)% z%5h(fy1D`x@w`^G)&xAbFWq>erspi;lzjt9&SaVE$31xVC+eHzQbtDVe}DSvC#nQ5 z6d`_Ew`zUmiD1#)%`78F8*iU=(v3=JPqn4xp6p>mc~_8lrJRWORnA^5gt`w~Lfp?a zEN{LlUny_7rdnBLf$LF>JpR%S zwb;ZZ2fJp81-)mV>0A+goed3c(~F7XJIj5Z$9<_Y*1ImM2Tb3th_HSFr9zg>wSuho z%pJ>|DJOrMJ5$519B0*#p1I>DoGNFPPrb0h$DfYHdfc!5*?3*cCO>Li38i)tnKrK= z^Z;fLASKniL#;Ex;AGRh2@lp))TsL^Mqi=0J(e9VuBVO-=?P%t)?PkZ1Gqq#_C6Es zm*73oMO!iV?y(doqu6#AycJSvyX(iJKOUvNxULW<)Tn!jZ{FCjy*f=ldvlbP?ZIrc zi()6wpPX_4n}2>T90R}qxkI^aYM|Q?n1Pdn+jpq@O}2)DUX*!2=9Ddcbj#|AbAFU@ zwMioei^&aVVU_1W`C%(f$Ot`!R`oj*GpAL(Mn0TB*I8`30sK}MUTnsbN49>;o&SxY zS}{h&8NTGeHp5D)OA!{X4H=R^qO5Z0&XBtQ=vG@`P6Fte=|UGa_IGtk*jT@u8Y4>n zybbAT>zD3)+BL0P$<&CU;utYBpSyj}+N&$3IB`Fdcyo?L*M_H8`Q;Ymml|DOqebJF zD=>y*d!0`qyUj89HPU2G0H1r=9FtURVqgnG+9P7)!q!=LsQwNic z#~C&96rRg~QH;wpMiw=zEmUo(0d0gMfvPcCoM}#4Eubl@+wdgOc0D%R79O_L`qfb_ z#1Q9?VshXQtH%2h&mDcF4I8JBmdshf#R4})?>?bMU%6Jk-6913b&%Z^DeeT#NV3Gu zzgB*9p#Nrx^(&rL{xtX<-_^xU`M&*-Jc4JH&4XWe)%652c*-}Ikn*nql-S|MGd0uy z(20R%TXMnCg<7NFnP4r#$H=qRI7WGgyl$Pcq!=M(#sDkAKB3)>KF_~= zmsM1_z}i_(G3V9Dtw@a+`I+tbm<~TkaD8` z>uxUfYB{qr*P)P@tYqu4VV{V8V$ep2|EQ}u4LC4u6qt?^Bir$fD&{Nolx~lT5PQSQ zo?Sfj#-W(3oC>Ium$I^p>P@WT<5BWFH|n7(tPc+a6~-_dP~k@U{Ig|R2bJ{>b)P^i z54Q!*!BdvBb3LaYK6g zm^jk%Ukj{Gg`b~q5s_XHIpwUk;Agz1w9;oZuFA0CgwE1}-t}v;eik0vubNG>Z0QB{ zk8(W+P;yr1qpjV{)64AN+iO%yAy#}|%A+otQ{MK@uyMD)05`0d0>BJ=O;c^H-SeJq zRi~zyZ?X~lRZ|KB_|%liwpNvME^1ZNQ{DNnwH2cPV3Gi05F4_|$^lsx|vnAyo@_Luxo3;(=DxluAbk zhT1);SUKozxu#?yAt*06cN(XB(L$}{2OZo8cxL!hRGcjWUi6KMb!jLjdA z1=&eqyB#&EsQcDl+OSKmQL}|Nh%z9hZa$?6R||DX3qkxj>(yY z&yqzslhgj-^LBB{$IYDb4M1&kMN_b-g_ukbqd)}j-eJTI7QJW^X{@@@g;P0YEjgT% zjZ4U_9A|)XjBntS9`bB%oc5lBh;KhYcID1tItR%=bLWH)VGvKJa0McY?gPY-HwULQ z{vpqW8TlX?pZ_#|gzU_pfQuTN@)u#|v;Ic@eux44`Wn3j|A!6V0X)}5zB(Vkri;8uu;&CA~g6us={#o=XjwX8+r!mJ4HGZ|2VKCo#@pmkP?c`GNpXiNd$xdx( z>HydC1Huq@>&%RjOroS&qjx*vVv8-snLKP4+@+REOQQq>-$XA9)iO%P|7MiFen$C( zoRh{e-}IAfk~FCfB457Ax-O!D&GC9R4`8Ep4efsn@Ql)XoQKeD;5b=nH{kckHoF}c zlUw#>jCzTD(ay^xZRdzvOpWYHpUM@*QrzaKF>dVqxLZ3nR^qI0F)vI*w79}nLnrz6PpDXKXEWo z)ErS-urSbtT&LF{Uf09{KK72+^KO5u+KO~72+e9@WloHHJVdM|8Kpa8KRJOA>@(t< zI1{6ADi-(_&V-fQE^@szmcvS`kMNH^8nehJh|u4)8Rm?HifjxKQcOif_DQng(Io5A z6TBGMz$g!#puEzXaF2jOVC*>qoG3KF>U#u?m3QvYwbQX8#PGGe7(C^GE7-v1##S)O zgQVwCJ${EoESvVoj1!XF=lRT=B=&jE`xxbxx8D=chsAUeE1CgHJLydUT9}Wv_!wGz z>n%{8U)1N}ef^%Bs(vja*3pp1jFrCQYRf4w3LV^s7-h!^M%hpPvh4TFH7`+@d4WieR+lQ4Oy`1K>{%mYisT=C0ptkvvJ7tv0yC#g?>1^gR0ban;6 zEnRsHC4y29r2&4R`#PK+nD8Er^_0wwM?ysIfaV~h6qByUlHtx3v3%MiSwJlS;KfnR zjMCqXr(n0g6hH@?L7HICQR0+ls*|3+>0rqfEwK7#YR?SVJfr-(Pb;Ftn{AM;n5q{K zSrT1Spe^=NE&7K1W%<~+V}tjAKd5No4JlBL^Y_Kd+>=)Ty@03^Nu4Ep7YCMLP~uTza3^uKdG>Bv};@XWGj7^Qh&893Q= zlX;l37S7c1^}jQv54Wj6^~-A12Z6q8U^!4KOw@s|Hl+;H zH>1+!HR>u38oWa4AJ^k&$tUoXNf$hSPXbryu}G3v#L(r6E8f>eg4bUAKIvak$Xvfe z@>iNhFjXt(IVq8EVsm_+Z+tD+c+keTU29?0L%0jWxHnxJ@8Uii#%*`i-o>37#%**R zxQqMSFz!XyvAei;hjCB3&JN*1Vc>nk$TC;^`{e#7p2LgDxhKk*Ywwep6(2<{h6(DL z*n9!vmd^(nTc@OJxj+I}WdyDm4A933NO6#btJc9q{M@S3rJuE2fc8F5uPePNIG;

rSjXsOo#GhrB*w5QDWve3?ZlArka0V%_tU@ zE{Z6@#v(g1M%aVOjf#&wFKsYJzy?LyE;%w424AvYa>V#+G4>dT9x!!XA$}Tnm&V~C z8i%)c0Vk=bl$4$?jd--ECZq-&!tCTSyv`$5JA;^+;7C~;v2uNTH4K9B2MPSQ|gsNVgy?2+%4 z*U09Zp%LRO@onU@XHCwCoE%rCV#ZsuOCe7d)DW6en=NaDEeltqQguH{5bK3p5&+}dvxgY}7dl3fcP@a6u=wmN%#J(1 z9JiV6tt)E0UHM1=(Lqb2z0|Q(u9vwq0x9wbWCHqLUyY1{SYJ_E@s{lK zc)cZZxXtZgZ!BUP2YPNDmXhUi85xtMBD|U8JR3hQ-R$#x_7R<5!%K*N0boS#6-`;h z`Rv#UA47tjW}$y25(v0-O%eXpE+I>v%f@wN?{l-9SP!>W))M%JnX?J0R@I=3&O*jY z6{Ugvuc9k~81+czb4Stb6=wW&MK+uzE^K5Wb#p<-yD-*S71oL(0(d&osqJJw5h_N9`cDN%0l)nj4}Ob<_l%-ii& zd8)M)I6gKw)FQn_AR*6>#Sf8$=acbevgrAkxW5nlHExc0RW@Z|$!3 z3I?=;>vq~;H0>xFrg0vmNxPsnFd&{+S@YKI=PH*vfR-OdCsRZ5?RC9hAmFmsv z!T*omc)lbnDvjD!uz~JBlh-SA@OJW_$|&4OZdX2q*OKz}({L+!W4&>-u`feBVTqM- z+n+6om&j-93t>azs>Z?Q&8`}k&Geb!imO&HmH8gb@35r1BE_hzZtxG3H_XPb6r3C^ zVM&uy={Vhu8Du!!%^K-VkzR%99a|uKs>V(|Qx;?0stTslC8Lrd+9->$XxtUqLCIRE zZ?dv(WVDtbWnwc`H=^pCIrIoyNwQl(Dl z5$?8bl$u!zxP8{LTKOuBxYekC$kLA!%PZW^}wI zQI5&wozm3Ouexk>hQF--ly79^qij{+v{M^)S%TdxOoFvzp(2}cR7*IOvB#EwEJc^z z?xOe4p;ZD8QcyECW2<9muVNf{c8vXCbG+OkziDAg$F*gaZ*Rti^-{DPYiHzGsYqhV zYayg!OOdibMer?dZ%v$YucUPO#p!oc8e6nut7vDr$M&IM5Tq4FX5Uuq8`Y=+Rk*Nv@_jY+AdIX$^#jzF#kZX|Ik4*Mce+LYm5@4(Xip8Eg%JO8fn%NpXbuut+SL78N=B!A`4K2 z|97DFUsPaZob;xU{I?uVqr5>CP%M1NG)UM`Z?A@7|9dO2`nqFc#x4tUDG|b;c1Us7 zIjBfg&-fE`C8j1@JSPS%eCdd;?XY819?h8-^$Q^W3qEdlL<4Adm%}pmU-NGRk$1k+sm3)Z2ZYH9n2_TdrllTF;T=-~A3c z^G!ZTI7Bzl%bL&A;er$o_^*GusHLn2@m0&ZCY*titEG^RfP9Nw?pimh_xSuR5d17l!numLn((B!SR zFLE&UOgnEcw4LJI>!aY#qKIQOvq?1E< z>fc7&-gHPMTu-8=uIzv%)a|5po6)=jy6g^MTo)iI9|3`KsNZGzJPSW!<$4er>+SLj za%d7h&t=Hh2nL-$S;*&YcPuX7ChxW2w)ODgc&k)c>VwSG(4fEg0KN%}L;ZPBk$FRO z=SIFoW83Y}H?UH12@8bOk7yt;vfZqRWT62WVx>%&#;F#nJGl*7n+249MB_N%Ohyai9lC;y zrY0UNS{4sK#!d8jKJm#QkiYvN#`59&R5#jv_%UkDw7tg0_QW%1x&sU__0**$$gu0K zzUZ1DL^KBFk+SoSH(`&0+aH$KORSV732*|{%9*im_?=i$iLND14s^!-Fs!YtOkKjL ztX+~t_Ma(6%KVIkZA5|+bQO6wZ*qFTm%AZE80vralM!K^F3h}-&W%8bWRxECgYPiwGB=x#^gI=WZ z=XSuN#H(%5q5%?8NU@NDP1C|Uk5^;|G$8{%s1xyapJyD|vMFt%5D8}!m|{V1U1ouT z3X$^eu?lc1=k65rKDR2w7IOdYGV+gyYT3Enc6 zD}-_Uf6yqL%#rjh>8TF`g0;o1jcdsJ`H+FJ#e$=wIAlU_HHej`G&4Pw7UnjW`al__ z6-SbNTMP^opKh5BA=T|IGh%dxj%TV>1Kms)`Vq8j6^os`$vx z<3;fQC^NthUEC4G%P`0YP$@7rHZN9U^OnLO(l8CSPzbQ;njV&OEkZ1Bj*+Wkw^`Ws z9Tt3kDI{a4r=@MFrww>*oRiiS_*cP8M|i_%aU7`b>nbOjDHPDB&$VX;v&0rWGd2;L90UaM94x1Mf{kDXF*5Ud>sJ}m4e-`Ss!}YhIUNu~I zZ+j%L;3L>afA87bS2!bwC~zCn>iH%fQqe(!T77`v^#nl4L&-uJ2&Hd8s~-jB0F+~) z^bF9WOsh|XdJkm!=>hi_Z(zz7nq9!XR=Eq>@KjI0C`-l7--$Hrb8s3TziJcV0&Gq4}Ng}TO*)!8;Qjk^a1`PwB z;qiFM=Ol(X_E+-1#KK@-JF=W?= znq}u+g=qlv0DKM54R8_QG{AcRcK}w{9V^iotBK>%`CwgSbiAN9fDn=6(Z`q3vJlo* t2*;-Y>Vo0@((AC+p`QRMhcKC2m#w)+_Bk=xQkNDi!xY=$Uo*7P{{?TLUONB) diff --git a/Tools/IO_Firmware/iofirmware_highpolh.bin b/Tools/IO_Firmware/iofirmware_highpolh.bin index 414d51ef0e554f09f534930787200babfc2cd327..3f308f141ffa125992bddcbd44efdfd4370b7e9c 100755 GIT binary patch delta 10668 zcmZ{K3wTpS+VIRdC+TTPX?lZRKu!`0Ed@QVB0HLfws|&AuBC zzrZUu`grA^P+sgWSMD_nCF!Nxt#f?^DmSXXdwfai&%V;3ZJfQ?I^VYtTCGsjZX~4q zq7SdU4!G9zCzmDP{hF1%yjbN*(l;0Nbt7eKD4{Ij7BCEhN!t-Z3=%3hBp^NF`R~vb zfCv;;cNp;$z70wf6n!%J(<~%Nl`$X6MAEe|LLy;eADqSL zUQr(xMwPsxt~bXNM=5LijH21V7c+;w-?%JM%46-w_pLU9lg^0{4$t#u+e@)s7(dju zG0u(|+(*voU&X81*2HgR+%AuK5+^=$BYyKH`S!ajohIcJTj|*3Y>*epsq#|!J~>e~ zDRFF~G}=_}%oIyEM9XYH^L?rGrE{SiBO8@CCWh8GB*3^%W`Fj)23Kp!mH5nqV%F_Hh<}4mAlwQGLv^7 zsszMU;h{UA`_*3#g^_hIvK~lxd6AEFB;7gDJh2fzAMUMNS0|4)Xr#UJq|$HXas}xu z3P#^ZAF3^g2+3*XyPON;U9wgdWs96C3rZZyl=eF14bx=Yj}%$D2<^AvP~U*$1C|15 zx3fe(Cp7~_i=mzdUsh!kEWep-NuIzUU)%oVgUr}PUSw)i2Xb;-FQ{gQF;L-Xl_KIy zImE;dwT(%gg7JNA1!-$plRg2Y?};yqFG(oYD%!sI5<%1|Odn&^mk1_dyjEF8J|3SH zOZ#=ag815aBwQr1w>2>F{ba{&xyeM$dYtNRN-@gP`QpV?7`}mAy3L+SyYf*;P(UH* z@LqUd1QZ=)-h=_%OJ)gq_$XN=Jcb9`z82PChVLUwj7!Ee9YTD|GZ>YEW>T@PwvG`?W=94vko%ME3dY#o_YZ@2?K3~w`XFYY}FlS znAm=jYd(gv$am&_*i5$PR7G?64vq3jpIK(X zwssZK9{)WY>|P8r3W?w^;7x7#m1wBPAVCE&V0((}DndTmruS&dOyt0fXPNX6$-Q$v z{vBC!=Vbf<*?s4n`L(e2;!#K_gMkQ^yBXwD2=yo7{XQTnu|;IH1Q1c=r=ZUQfVIG6 zQ~yR1W?sW88Jbyz_Y+6{j11H2f2pqtiPjjuy>*}5HV_Q#1kdw@l-MfNa>|}QJdX>g zuI+ICOHa3Erz!QMfHpo8TX`nwxpf6 zU?V588E22=h?^|i)#ay71h}~LPQNOhO1P$r8`Ft0O2;Lr_#cf6cwfExWd)w`-4Slu zP5&1XYsg)lXpQeQ$%5GR@U9}@lo!v#0To~NUzO8aZ^1L?i{E$SS=xZA{kK2n?vQX@ zHaYgxR5>`MAQV-4RX#Eh3|^D>saIT_9SdoWu5L;!6@|qbhg!%xvkkG!E0}rAH02VW zLl=Bw_QQ!?dVYYt(RC!MpS{tjE_ZdP7s}fDQ-H^;G8k%9 z*SnAj&+ky1%z%UYz>gc&X&1;9Kf^QQJcu6IdgJ9-|!zVRf3I`h@aM@ z+Ri&B z^?sw;SmjyYiGUDy-G5q5s_X8KX=Rnwp<9Ig8gv#&BcZv5S+jrl79byYX{Wl}%w_9* zGsW`WvyYipr(9#>be#qQc0rzWvFkREK*(&(Wo9Eq4{Iu59l@h?DsJ?Hh|d_AB9f7YjVzE zZ294d1Pu7RLloQAR?3FxIXGK)aVIR&-df&^3iivK;_IU z$-{J}^=4#(kwS<1t(lqKp(^C>cg=GzH(v*Q>nlEL$CGcd{+~ntPNiBgM#XbN+0mUV zR#RO{v~r!um<1ALm2Zb4>i(Ty^#V--=$ZLKH#YTmUzM=w>O<5RQT9JNk%9JpZ|L3b zX+27TMvN23h;e1y&DoC|R!?!`ekSw#*;aigzI{_zZll6dqswcvYQk~_#1OYPgjBM} zl8Qej9!m!J+%8LM)^algEQr0BnAWA=VB4vFa;59Y?LcN%l+~A5+vPl?CY{3b7%+NT6y=78h8u)(dFLBb|7XXup>1(#%!4`hjqSS%uC%)m~yP%zbMcHHM2Q(7;!4SatC`swpUjv%GA|I;2W*HFv6SmIPk zYGJlb9`T9je;KqHGC=BT)&LAl8%5{i%%qF>`X=T>^{jrciV%C<#-3dq`QlJ&VX+J9 zY&>P@MJ{kQ z#xHV#i=&o8vdgz3C9A(g<+i~HVpx!+IcNr>A>|9kPCh7{SL@7~V!LHm5#SL3kGa{J z;$J&%f*+gEq((3fI_mia85sxbU{u|?ZfZ84U3wSH@-<3d)V_9XIx61k`SAkVohm=O z%qoK7iku>Z%74IXtLj1~)0#W&IK#A(F%|wGJlLofn)B>=!+ESS2S4#`flF$AsBq-w+HLBBhbg0F-SUEUMJuMP+rMePMx#J}AQ47#P0tT_$LS>6WA*PHbWIAj? zoJKnp>RM>)BsoP{@m+GGD(b& zie^IQrYW9@KOysqC+EEs8t&$lf46fAbBt3?w7WbyQ49H&ASMHQM-MaN(^i9M7HJ;3 z*@tsE8&F*9|b zt@rL;n)mjU-_Ir#9z^_xq~G6#?W{znSb2~vt6VmE=~39SjDTJ_NKRM2i_elRi}M)y zP}|AH41yiQ< zI0&03QCc?LY~($gAoXjIQ8xaBQ3?haC3fIe!iP}M!-=az6u6=_i%)-}MT|0OfLxHI zj0#ACd5>*FVk=ub9Nad5O}4cZuMBWTnR}dv49-TDI!yRF+30ZK7V^2{ft>x&nhz)~ z8PRr&I<C`qe2^{Q`3l3mJZ-UI+C-RS@&NXUV!1d1J@Dj(ElM^x-Ixd7T$-8zE!~ z@vWGU(>)_Yi9$JIlpXD4l&V3EnAtAC++~nuY7Q%2EDUrb-|K4;uZMXVWj=|kdOg4A zI6}Z-#Cte1qx?$60`H}@B49P`Hyk|GFNk_CO*6D&tY~Pbtz%TuTeULvr4VgGzPUga z5?npNPg?+&U=sBnw9%sZWHDGcUtSmULdOraZ(ZkM%QH~yGl(S^(1HWcUL*%OmirtHW z@MTaK<=k-yj^*iP&mI;aKr%|>Kx!!~CZy+!DJ5u!5%^Hjhn2fRocOuAxDHASl%@-< z8P)r07A(jVlY9@RAH2?MFR0@VYY3yP99Slnh#&M|t!7WYh+Z5HX7vfMfZGAX)$ST z=^*Y;$&jUFwcgqOeXAZwhlgY3`4d>#I>?DAQ|Y`{<)&tdN35B? zT);DTI1@&FM=m{7#Egq0M)?|jjdq>{5AuOC9a4oJX8}C3t5aiN3jNT1%Yr{43#$vj zUyYQ7E)vM>bX&dihi$lTBLf&t9P`z`$ac@x1Kw%d~V5fXje}tVIfxYFM`y=es2<$aq z*^jWdMqn@dmj4KQZ3MQtynyK%m~k zmI;uKj2&X^S0%l-m)vyCiGFV|%8)J~%?8+Cd)B<|{$Fn|^rs%*!ZV%o*d-uk?*MR_oIW_k#8EDXo#bs3~|Up!y72NMe(qYpLXJG zi}Lq6hkchd-tVwqauz5UUvgY>riN>&XwGz+v>z0WR^J2 zI|^i*Qz!ouww=8<@Eo$DLB?~=ulPrGr4$9nQ8*hZ+v*sYWosQhOuEOZRpK~2mF;Av zvVNN)ur@`{e&E#n9NLT4+Is8OmQ`~~obH4>faAE%69Fa;2K1szXsT>dQ(zB@;wE=S zDGJhOvYkREMaKg=j@AAGRtGQ(tNA&s7gYh4D(;ss8^COdE3m23flP@GdyPp6vFD{6 zIuYABss<*vRjz#6lqf0QGF* zD;)6sXrzSYf%J?8-MJc5xloy~k2BeNKQf+i;-}K2%Tk&Hw=P>53*6TFb@t0nqk@^s zjxMLGCG6D$JpsW;MjEJ+%o>OXz!269r>I``9b{6#373_BGaVELt zPIZ_0NFP_hUSG^o-9ghj)t&m2K9drqVU;M>c5MN>bMsc|{AMb?QI5ndRDbM_!d|Y@ zrc7o3At4jj+p>6+^ybaFheyeFS?6<`LZ&+Pk7l!%hbiCpYp9fZ>kOBGZ|^|RZ2=>t z#3Q|%2~*8J!DOcZ(_v~eW%)7(WveID+T`F!;P|YlARWpm(Me zWk)4-CM$fL&W8*z^%^3r8|zl;FjBr4dR@C#)_k;6{i9wGQ!PmO?cfag^&@}oc1dq_ z!}xldd{8I(#EAc@K2Dbyfw@Lt(s3$mn@n?tF38XtoV-sk-Y2K{jK)h6HY}B}Gsc!C zrNN0SX3{|28l1%XSPDK(?t9Dt3E{@a7DVA~TaKg@HIVlno9WhjA`a_|0j*tI+R?+9 zcvD9Ymxth~&C`3|gz3V1R){S5;IcT-t2}=$NMx*^6?F!4sRrC*Q@;u7x0kj!wD7g1 zf13S@|qx*xr`PwwrbLNBK=oTW^cI%H*h`m8vQSJ@Vcs zb9n?#vlqdEJ~Ejakx3BuxvE@$kwd}KkVC#IpL4eM39!{$1X}z34U`$ySV#}4##-2z zZHJ_6xkg5&Y{|aO+RH7X+MDgzy3MNS7@P7oTjLPKYZ5i4P;itl8Tsf6XKaQY2o!3w zE>9zQ<9B1HGtQ+FJ+}TCGrb5|WvXkHPDlW7>*(( z7zHHDdq>dCRTjLS?m~|Eu!(gc)2SYucdCcYvpHyf847-NECRQI z^bsVlW)mk;{VtF~!7uw66B10WI{4Ome`*T_XAZC?6JVn~A(#ExxKJ=}fFbM#gPX?A zQ1H>?xA32l*heEdEhk3I4Q1Hn0;xfI2j<#5zyQXl0beF0?mwTad=Sp~j8~;9$>_Q@ zUu66lXT5}HU0M;LBZ50}S%D{VxA)_l9r9FL2OwV#D8feTH5>Ke4GT6h{kZqEY`n%X zr=iC};@^;s17v7JYWi0LZ=}x_zmUy^Sov(=sywIgdUuLA1=6*TNzRj#!7i3QIezS$ z16J{h97x5=8_>sAc&(fEI6$6%G7ndhx1Y?3zkL`C(p#>C%&>=ml+jGsjq@f1hfwC1 zm+9S*3-$-Wa!wpAjum%_o$9!za>Y#U-)Ml-qWX=1j{4Ee{K;CFw{{|_Qs@JK`pekto@*tpTrrbj}-u^}#?13b?TBe-wd z>rP*~rY{SQLn!RYVU(%8ER2WqJ_ofXq*S%%dqcsr6QCV+ARHIfzn^BM+Gia6|7qW| zB)-n183f%QPiEDXjNREccYJgp3cnXX$S6*fYuhUz^YW10b?fjGB(8oMVm zdsq|Q?ou|U>4g2Mpn zv?Hnuh8IH0SA7w^?dJkNeK<4pB`8j!~RsC?8JW48+;-#gK z!NQd(_yL3(Bo@3tzNcPJw{zmBZh2wb0c(Pvb>ckMk?-9qZHHBDXw_yX`Tad8cXM^3 zv8YUZibE`5gA$Sz;*Y3%#~ND?~*7@ln?Kv_x^%)SQvz zD*p(PKk?#Zh>|}uelzclv2T*QfWg@tyTGJKC|aUP_VE9E_YMRZ7;HU68Zcs*vJV zkur)DG^V?EOGP^X_H(BY;16*%e&?6)&Y&zhRV78V#E;dK1V5d_i8rics)en2VH&o2rS7AvAV^WT;#~Ex-tm z`SLxn_D|(;^3&=>WRxqVGzl9&ks1N7`#(3L8>UoGoYQP&E@guCya~s!H1_0M)Zmq4 zVa|ATR7+(0xMvT?b!LmQ7!4`sTu44c!Sf-sC$UwAadZ3kS4V*#2?gH^^@TaQ>P5u6 zJn{F`uec%C!v!HHZnv@*>GnDlT;ofD(NBf2+oXZB%!%e+i4wwu3BhpCyk>+97m%^{ zSVZKUJq=W(N!|krzS9TUEhqyekgjf=d{Mr&GP?b!#0^tXXf@R>nP ziMALi40yswY^0n$l?2D2@M8zMWZv`0TbzB@LvUCQH|%HoStDala}9_2PWz$J%KG;I z+=#Ce;HhaaleN!gxwlGN!Ck!FqswDVde7EI$kI&b9QEoXxJ1ijVjN#qoKv6*b6*OqWDC^kb6F=N7pN=e z+MJeI6wcb=ry+CC$PA>aXMD)_b~m!R>%3VpUB*1fEj|Pg^w{awo=R z$N4+qm_O`X!gklBX29_`3wu?KA618fYfnUMj&c~bNg$b)64V4Bmu z6UOX`Vtg0EnB2>xxUgpm1%G{#m9K(;77lm+%=kmWE+0ZMrDlWP^PxJmXnnQ-;jmwj8_Z0Cu1di*DMXLTT zV%5&+G*4=l@$6=4s&k*rwz|9*dSI6-EtE_Wb)bTHp@+@cRYWr(hZAL8@1&08K!{3$ zTzhWz-BCXtJlvP4I<4aPXZKWe$kmC8pGS+I%3~CEj|uTOQSrTJNglyTGH}QS200ArovW|u23aUWLYe!w4Q1H8<^4=%b#M)!;>2i`QTPIEWY$#JS zKyZyL=35x1K+!|j{|DMniQk)0E9pmhA6sNpxQhGB5Jc3LV zb1=AW$mOM462?sqY^$Wd3D`E4Q(>NwA9--Z{QTTpE*YY?J^k_Y*3usiQfmg^Lt)5_ zEYwF$X=eg;R^}#`yQrGBA^4fo^F{_}cPg;`lc|Mj*z%1b(k^Dvc@#^l=Lc{6OK^!@MyTezg(`o>n=rvsJgJ zAeAGrdp_tvE)DshhZz$JJ~SBd1Tyrh8HCF)LmgNz2VcJ$xmOUxC^(oO?xra+I^ zrc(U`Qs$|^)$MV+e9!}j~5@8 z7!GO%wT38RIEdlR!+U5zYlwz-AG~AWeG}ee;T;&DbZHHlP`?hB8a!z7q2cJ_p`b84 z97Kb|!5Ana6bpR+36|0vUJ1mcqtju*NI^%-$+{h5GcJWk-%4)h_eb0#@1+=TjQIKA zk=7mM>0b}yrYsTf`XTt)uvtMitsgWV;#x5HDoH1)jO#GDlUSJp!);HHW16h{;0AX; zT!*~|r4`EGp?IO3f$|=de?s{el&-el>^`J%-~9sOXF*v9#Q|j%l%-G>K*@np4`r3Z zxf)I7@;PoUuhS=u6DDR%f=mqlCUO{#UBiDmIH@#GM^$Fv3SH^QWkU;yJM39uI|cs; oLucp8+6U;EkQR}(e=g8G`B2D>iTBTWx)dOOGyHxCel>{x4|6h{%K!iX delta 10565 zcmZ{K3w%>W*7(f5H|Z@+Y5D;ALT(ZYEd@ENF0dHE+0zMFQ zQ)pdrK?SC|2)JLd;POzHQtMJ6hDY_&bzK|5wZOW9RZB(PTPWuCLGE`ZZIS){|9^hJ zxifQS&Y3ea=bSlnCdW@QgFa@<)aWl?L;RhcP?aNWQi2knRg7{l%2?dFTiOwDNxxNL^ zYKNqDAz@s>xLf-0$}XTawm-HgZvLAEcJ};2l}p-~*Vl!VjheA2dj6ZYz<8yu6){LC z;gEogh(`!=sGs;V;wfx1q%Dx-IP%8`YuMAlU{{!OKlwajHuG(e#2AX0ZEhkN8klcl z2ot$%W};z_x<-g7h{)fgK4A@0X7rgwtBKEN4tXzE+rpGNt;qL-eu(DKcsMjpP4n)^ z3m8W=KNID|%zvxouf{jUKb;8vXx3&piHxxD%^7X z12QsyDOI>1kQc#sk=!Xelnrb|s2l-h4CUPgveWHQY^>AO2pv15msP8Ex0_Y&VGCp? z>jC7HcDpU^0_eUCx;Fxuo2Vho8o=BD%x8N^TioePXZ%%-!dm0?VD zZ}f_ZxZ@8pUko;nO_+l5UClX(t69s%Xe1b0qKl#nV)FIM-&8@2F3>9Zps8@2xx!arx zv@0Km1O?=QqW40c3MAsloCyOsm&_EhFi%zpPvWBHZ-teZIi!*@bJ^I72N2)zJB)Vi zMSRUc#9JYi9c=!nYGOb5(68X{Ehy}7Wqas{b!Sz@%r#wV%WSGLl8&Fpkk(A8IxU_kG z<^+tB$%?Ejz48X)&+aF0WKCioe1rTw>lNnE8)Vs?_vUT>6XJOgb}H&&&Lnwy0|TidqjUs?6#%K)o_EY`D11lQ z;nFGZ^jT#VRBL-4?eX8iK-WST@tYVh6_8UE-V+YxQAo&#>0oEPT%Ct}w9VL}E3%ON zcRk0P4wB62bFqo6oIV*xl2@nCo_icR=SLu+2oOtPx*K7Ca-sY*5x4u&3W5F*Cl$3b`?(0`DQN?7LDrSNucWC&b!E`JGLTa`Ql-r(RuUy(Gmp zU994irG0n~*Q1bQ+39#O>B@FR%(#IpcjV8Kx2R>LbmkpEt9ItIo-M%05nyT$bnC}fyW7|UuszobvWSnkQZ6`f(4Q`M$b~oSQv6 z^WQ)H^b-|=XG#%2ty^{c{!xSI?`D>g!_C(}^w5P$>Bw|u6&&wjqj+D0c(ICzch}5Z zB}DlT+9UmIn;vexBwwuZURE8fvcPw|M~J%OKc&XibajntVwG%dgfSDyEU-qjyG=9i zeCk~wo_wxeEwggz2Hy;^xc9>+J6FVi&qf*AO=7C}r-!w`axL?Y^}f&5eb%p6#5&%G zTp^3*IAE_|n=_6%T}9rVGhN3%GTxyhJ#)rSI8ntap9Nut%b!TZCfu+8+48-fO3HLWt*Qu{pkG@D@ui5K;Tu%cV*%QVlt+{Zx z4q)NH_Ul%PmlQnKMSC%Ky=E^~MzI|}sFl#x4&RT5e>_ZWaYG4CsZ)0oZSJ_}-9}wM zdv%n9?ZIrkk3uKkGdW`)w*9;|1_M3s4N7fO6J3Vz**M+MQLpZ?I-81nQO-V@Q(o<( zOV&s{_l&Wuvg$;GnBMdu%_Bu@=J8cPgCuy;zfX%&NOGqoTGOz@Z9kGc?(d!)b>OU`DID9*> zc_Ga1J5#mOeOiq>f#)!w6ytL&aSyesUMjX!fi}XCK*g9W%(11d63~=Y?Rb*t{5~F~NlI(MIlrhk3djS}_D90H1rZ`IR5%QEHiBbMUUU5uWRECg}GQf(k zPH1Pd7WhKDprVp_j?O9yIitpHLCTncG?5YWMWl=!s8?-5XO(W-1Mabf>&51QtJk2P zF4B7||AT>270S2m#!n1K|TnE0gf%!~5 zVSG(Rh`r)qKU_Fe<4{6wel?WIbGdn?jaF9Cc$7ZZk9w#Gn_|L2gaiE{5pJg6Kia3A zr+ZzmzAg~^gYDt7@RUUzT+fM7ev#{Gk5~j=F5iTdwEhB>+YA`QG%ro}x)qd$6wezs z`E}upT4PNWTW#C(fQ|rktUK)S{?*A7{Mdpf)q!$QtQY2`q`Y1OST%p`qH6Q6b02_O z?xFmJHMU~Q5pksF7xNs`6@FHcT|_29_h3fol8iG80Xm^oa!uA*zh)0u}*Pv*Z&5#cWMR)x@XOp>}>0v`$U^+ z%Sg{{Q*$%w)ZQ&^YTSZ0HF*J6{t=`@a@Un=PWfGMJm8uE_hLpE;C_>l2)JtjH#sxG z*{1daPHHBlGBuOE+LzU)T0^zLd!d25uT3@FSEmZw+SEHUv2q|tEiDoZg@yu7`NE5Q zR0Do6g0s(K8{J!^Y0O0GkQuNIaXLK@Wj(aLLo)KxqIbIMRMGggtDttS)~B{*cVcpPaQ?3wCizM=PiFLVCNky2T*s z!QT?ZF|fSv-eAOM?IzJGQa^N~4`*`92J(meJiMHImG4Q_xAIM#64qLsrv-X_T0r%U zO55RMoTaJ>G5OT(xN|?^JNA*^70hCO93-a-X2lFa5KkGq2tGvjJ~Fy+7M|T)Q0T*q zyq}CJdICRA))!5{?&jS^3ovuGzqxmQFUD+hckx4POg)fX7x&^l*vU$Ch7o^c=G(hEau38=Jysd4Cb3p{)%OA6?wnx4|qcJZx+3*kIEn5dVW9{ z+-#$b0p}M>Ge+-pCnc8I%W`;FLAX1K(&9S>Gv7k*2DLIu$NyxMr~yW~&_CkvArxrg z#1$gyxu~~_&tBFeM(OP*XC*160UThy#j!57iOmlNHVP9F1mKJ^>KG3mTr^qa zvf$I?8J7z`LcVe>%}}8=8%Wwx!kspC;%ub!t5c}>_1ukE<-l;c2FiQD>(BPalgG=m z#w~vn@k-0Hhr&eWEnc{7n2|!_E1!^Y`mPiu3}uL6PE^k*_YdmC)K&q;o;#Q->JBMh zEDUrZ-&?B@Z-j9f#Y&3W-3+}L zDVkb2D^|{Hq_<*8!owPELcYzw780uSFnCA_)zx{&$;u^ZldECs;Z2MpAEN_gx8NQD zMZ&-(1Dq%{!DM>`j1@0Axg-fcM7~^N!ha&#l4%dkJ0{6}fwRFhu`lqY#wa&}{ekE{ zEM|*XNgAMS9|SX?ElHz2{sujM2o@_(FX#)zX#Igf)wG5Y8>n+*!%EaK)q4U|#0WPZ zMmcbdQI3*LOMlH=4U%t`=6m)4;|Cxy%JE}xI2I=rJ$Fce1Cmjm7)U5&#h9dQF}?t8 zGs8L*^kIe7IPoiWVGX1PNL$V}ee15Mnl~?1jPor^I&g*8pH<@z=?J6zYGAQgAb!$~ z^}3zeB6>L(Nb3_|0#}2a*x3~Z7joq#L=G+spKy^b-f$2g_ATnrDLEStMT*=$-F`-S zgq&HHj?0O*Y+7zMv^pU1;;2?eF&@QJus@UwAYn&gA3?Flh*Mgr#6|Ys4k}&kg^9OP z#RhQ&oU47L`r)|yBZ5>gdi%cXqDb5y$AFiT)-=8KYLgLI{QKaYU>mBvyg38%@ga1q zlpe>*foRYh|G8-V+8QXBXd2pjc;M|wZOkL?`0lD@3?O{Olk;rb{KZp z_w-HJUx#7)e4B5=P7K5T=-YJ@_U zHhQdqfZJf~H5=SG{b_%$bGtp-?{J=T=O`GTbDeW1gh~mn1h)ww39clMdydoL(p|h8 zy5_gjZ)v;uv&<6L8CQ<%a2w#Z*?SGoCgrsajMUp!nOK@%L0xYStf>fNTh+R@z{wmZDgi`3>H!?Of z{Si!8iLMa4hDnd~BXg}gQ93Urx*}o9dVi$zyxXi`=Dh2IyE<Y8UeKtO0{l7276^ayBH46T5{>JdzMmz(yrD^oEVU^k5TSmXZdMBBwIh`^E7?zFdhV2!2R7hh*IaD=S{+Rq?{z5 zJ~0l|wd;uqse6NgVM=G!UBVf8b~6~e9HTovFFh=_eT>3K8GOi8VbJsyf*g<#dguvy1x z9Lv}eUWCALn_|GX2K+SGb$SW#FZmEj#ArL=DJQv7G?JRq9c*hUdwsDpAovSqhS zna{38Y4N^D5vOzF33XSA!9NL>eU{%~N)aYHcew4nHTE5@oghi5KTU4wFk3|DZwB4HR4Tr%$_UoMn(|Pw~0R}fyi8ukrxdQ4>XF?@_ zPJ&&_q$h(M!G2q*94&Sk0GIct2ob=x`6k=PT6utn`5)FfCkr5C!z8bEQE%&3f({w= zB;yO<6gk|yPcT0q$NS9Ya}qW!l1|E_9EnmQL^v^%2;$~&8(S9L4EZizmmrU}426O> zkguMkCKs=n7q))W^M~W}9Ay5Q8OdtPq@r@U)D7;t{|z}H-zBe>ZC9gW$J>+J$=6R= zV`KC4eL0E^Z^^5Ga9BiBRQ`67v^K%R=WoyJ*XuvOqUS!ZkaxNxnmB+Ao%#Nwf(U_m zUk$j##uk0ZI=wo;Tew1ttF4={AWK`fF3aep?I@RSIJ<^}tWuA9U5-xxQ>`*J@q|Iz^LuvE%nuo$5y5#6> zsOXd|Zkk(M74F4yqs(Oy2!h`y6WHj+T4WK##_Eddy|NYv2Fqo?`*5G|f635)%1`v> zgHpO&B_m6^bYJP_oL+7L6{d6-*_@*outPb?R=EVRTk>AcwrK(HdqXSG^c>=!fkY*w zx+T|LA&-|+lqlVJY1z6IdGy40Y|FvooRZ0*r{cnmEwQ2HT0~Z^&BG0(b?pofHX&sK zYY%_b#yN#dhiW#)=ORmuin2gfE}@Iz81+cDj}D{jD{S})dQEuUhb=6Gvrcs5tP|aA zmcvCIKrN7XYzXcES)tzL$iqU8qy^#!7>fmPsIf76e`(Wh3#=GmZ)v&}Q46@qiggwb zJ=?Uvft%z{OYCF+IfPTrk!oR>;{(XTm^&qN_0T~7Np0RBXd$##+|oW|4Qt)&B|P(7 z`4EGYHoS{WtOI88MDF%}e7#Mc>S%)jN`OSjV0s0!F?6B8W~Lwao|4VqbId8|F^|l7 zI{mIs2O8b!xs9$yIaPchsZmnBhI8>^COA^32L7BhOS~jobHRrg=#*#YUg?S#r$9>! zdF|=RckLdi0L+S;nAAKP&dn0{UJ2u|vTeXFUX*(hu<`=nIqL|N-zNfRm&6)O0 zM)ci5IGnx3ie`oT0JwhwdGwh%j4nvtekK_#_*cIjLoPmJz~2(=xq~GCc1pxquL>7| zNQfEZGpgr$9>esw z&;oa8>>(>S2OK5t2A);xgG=1*%U;|!z8*UY0=WY zG>B19SWOV6>dy<~i+gKaRQ!?h>(*?q7AQXs5?2GXtEtTWGAfn0WrP18i3@x}o~^Oy z+Q2+u@>Wg3xNUuRj}Pw&!yok^WELmN%Ues}C}}2<>mSE!NbUM*xQ#Tew~V&*%@&W@ z6J^}~M|ulyAv`4dXFG9^H`Op~C@# zA(`T2gM=krevSKNH)fFeWH)P}cT;-T`Ud(5ArV8CQ}Stv3LA18ZB!;tS0*^NsDkxm z`KWYocq$X@I)8OuM7kczn;fhkSsdj^nFx1zy7BZn$I0*5k-ys8NhZ|BdOEa;^1r)A z9znD~yM~mGzM-w*y-|hLEw8wBu&tDr-b&79@F%oV9iX>`>he+GLzecT)aw^|E2rA7 zRa(C1*lWWY^CQ?}%6WunY)O(|1wUq&yg{zFtDh~FS;;OLr83Fr@xlWrSPg_~B^GQ3 zy&oq!YvkA5`OW+6F@B31XIWg?-dc%Ha$S=?J=WjejWTm8W2MEgqkhd%xm`X8gm>6~ zIHS8r+h_}dJ9MgO61BhyZF#v~7?O~SM=b8W5~Y}4)hSJ__^iuAIs9ezC$y27k8*B+ zGbXcXhuz?3feF@yh3Y)UT`S>C#+6ugN{X+z-bHV~L$mya#@9D#jDzc>v1N;UX!R1@ zcxHlYe`~UQUfyMAD#o|xRBgMh6`R*f@p7VzkrSm-iK*HSrkSlk$~+aKiKMkI$+KHh zx_%J>oipCOMKxP-Rt>YOITq>wl2gF?)+;o@KK+G{Z6KjhznG+-CKX=I3e$YLt zkOuNgA+DhX&T8Dw*d|(kxc{KLtTGI2lot3%Q$wr#V?E-lTcYpHDQ|YKhZjN4BW|^` z9rQx21y=gvfxzqVM4}VlaY4AxN*Os7Vgy5E`DI{32u0P@z^6xtB!hD%f+TH`cgox0 z)dCC*$P8tW&dwq?xJM>Nr`71v0;@Hhcq>&8QYvqm-JYWqnQzeoXSDbxdhgT%=Y0@; zLR#P-KB`IUVJ~ZCV+)>*(rcy2^I=7HxzSx#9uImED>)?U=9FpxsRT(721B#{e~Iq~ znH6y+BD0^1^3d)4={?vO6zrn*I=V;;{1dG5_CBOs9MA%r2a)o0Uya#NKwWN!8sW@U z;|-@>7`z4nt{Y3>5T>$O{w|HlarsE8I)Z$0u}GK-X9JCe6hY3nta_Jqc7VZ}4)5)k z`(dn*2|=TkhSq;yi>?vitE+{0!EDxuhs~f4g067AYk`|_<+ylP zi3|0lG8@WAq$vX8pNWaJ_G}+ABjqP=dpEW?)a0p+Jr6Ptb?Q{cjb(@W;8eTYp_WbM z3LWa*Q%}i_5O4tD@FCyHq@gg{*>21xCT{oGHv*yi!BhI^#*p4o+4@|Acpl^*1&8KK zwQZ<1q_eZB&a#yd0gsJJH-aVOETH*rdflX}vqd#Qbex47t}`9 zrE;z(Ro76t&mQIXQ01Q8S`R2Y!x-OLcut4~-#;p3>a@W8_gJ|RHjNE-g*JGI2`zBJ z2Y)yjc2oGmZSI9tTjkw$+`b;3ythat72q%3!up79!{QJ=527=7sD0T+-m7!&beo!3 zsjQrZhRpY+Cx;xAaTxKpVN9G+jMZ?$vKC307kW`*=?}FtpbUY}pmslxR z65x>9F6Sh^8Zv67;^*Q}AmfXVaMIZT+xjsh8U0MKeUpKyS#yo2Er~9<9y`Ye8nbAA)<^w7__> zcT?6xAr1*kK+7Nmu%K8$B}jSmNHy4zk8TwAu3Z`FjJ$VeB^lf_sr)EJ_e^lU5AD7U z(DES}p=)EPYj|O}v%V6Xo&m169`q@!AX%F0E0l3&p`-NZbGdV&JL3#5Yu0<|})L;Dm$A@6T4O(=mushwM@v4x+(xqc$veg$LrCkDxQ;n!my zgjUv>v?i&k@aF?&#+e9K??L#})C-ABSsXd~f|+Ljdf|5PS0i7%0~^Vl7iqNO{ueFG zmjh(&i{eAiA1#GHYS|$D&@~9_A_K*dL>HQIvW1BfTeuh~OT%q&LJDC{W6Ohbfn7-C zZ3*&*M0z~b+wqyj5G11Zl=cOCN+!HC-b2d@{JY_~L%eykI3A?)6_pb^nhZPFCvYTk z=ly0K`J@|Ff6~p20o58DQZp*Wwn2DHGu424Q+tvzY(E7t4C4CWGb!0e_!gu*)Tagh z0`^x6YJu=jP(%xS3GG9IqLJb)v+)mP)0UUQzIzXG*tU?Ewx)!&50~dd`RH)@DJbt5 zF7Ji%i^FCA)`!9$fQ#i2_RMW7Ji<^5T)^}uzJ-T4`M5#7DNG0kVj<@tkAgfL@(9RB zK^_MAILO&SdS2;GsZhQFuMl*14+g{YZv@r^g8}nkFfbL84C((s{W#2N2fU;4;M+4t zs_8kQpd-a3g^WuX2w{&HwIw$nZ79WS!|QOGxJYr*91U+t6Y=(+1JgCDf*g83$PL(p zKp;pyCJD@&eQVB0HLfws|&AuBC zzrZUu`grA^P+sgWSMD_nCF!Nxt#f?^DmSXXdwfai&%V;3ZJfQ?I^VYtTCGsjZX~4q zq7SdU4!G9zCzmDP{hF1%yjbN*(l;0Nbt7eKD4{Ij7BCEhN!t-Z3=%3hBp^NF`R~vb zfCv;;cNp;$z70wf6n!%J(<~%Nl`$X6MAEe|LLy;eADqSL zUQr(xMwPsxt~bXNM=5LijH21V7c+;w-?%JM%46-w_pLU9lg^0{4$t#u+e@)s7(dju zG0u(|+(*voU&X81*2HgR+%AuK5+^=$BYyKH`S!ajohIcJTj|*3Y>*epsq#|!J~>e~ zDRFF~G}=_}%oIyEM9XYH^L?rGrE{SiBO8@CCWh8GB*3^%W`Fj)23Kp!mH5nqV%F_Hh<}4mAlwQGLv^7 zsszMU;h{UA`_*3#g^_hIvK~lxd6AEFB;7gDJh2fzAMUMNS0|4)Xr#UJq|$HXas}xu z3P#^ZAF3^g2+3*XyPON;U9wgdWs96C3rZZyl=eF14bx=Yj}%$D2<^AvP~U*$1C|15 zx3fe(Cp7~_i=mzdUsh!kEWep-NuIzUU)%oVgUr}PUSw)i2Xb;-FQ{gQF;L-Xl_KIy zImE;dwT(%gg7JNA1!-$plRg2Y?};yqFG(oYD%!sI5<%1|Odn&^mk1_dyjEF8J|3SH zOZ#=ag815aBwQr1w>2>F{ba{&xyeM$dYtNRN-@gP`QpV?7`}mAy3L+SyYf*;P(UH* z@LqUd1QZ=)-h=_%OJ)gq_$XN=Jcb9`z82PChVLUwj7!Ee9YTD|GZ>YEW>T@PwvG`?W=94vko%ME3dY#o_YZ@2?K3~w`XFYY}FlS znAm=jYd(gv$am&_*i5$PR7G?64vq3jpIK(X zwssZK9{)WY>|P8r3W?w^;7x7#m1wBPAVCE&V0((}DndTmruS&dOyt0fXPNX6$-Q$v z{vBC!=Vbf<*?s4n`L(e2;!#K_gMkQ^yBXwD2=yo7{XQTnu|;IH1Q1c=r=ZUQfVIG6 zQ~yR1W?sW88Jbyz_Y+6{j11H2f2pqtiPjjuy>*}5HV_Q#1kdw@l-MfNa>|}QJdX>g zuI+ICOHa3Erz!QMfHpo8TX`nwxpf6 zU?V588E22=h?^|i)#ay71h}~LPQNOhO1P$r8`Ft0O2;Lr_#cf6cwfExWd)w`-4Slu zP5&1XYsg)lXpQeQ$%5GR@U9}@lo!v#0To~NUzO8aZ^1L?i{E$SS=xZA{kK2n?vQX@ zHaYgxR5>`MAQV-4RX#Eh3|^D>saIT_9SdoWu5L;!6@|qbhg!%xvkkG!E0}rAH02VW zLl=Bw_QQ!?dVYYt(RC!MpS{tjE_ZdP7s}fDQ-H^;G8k%9 z*SnAj&+ky1%z%UYz>gc&X&1;9Kf^QQJcu6IdgJ9-|!zVRf3I`h@aM@ z+Ri&B z^?sw;SmjyYiGUDy-G5q5s_X8KX=Rnwp<9Ig8gv#&BcZv5S+jrl79byYX{Wl}%w_9* zGsW`WvyYipr(9#>be#qQc0rzWvFkREK*(&(Wo9Eq4{Iu59l@h?DsJ?Hh|d_AB9f7YjVzE zZ294d1Pu7RLloQAR?3FxIXGK)aVIR&-df&^3iivK;_IU z$-{J}^=4#(kwS<1t(lqKp(^C>cg=GzH(v*Q>nlEL$CGcd{+~ntPNiBgM#XbN+0mUV zR#RO{v~r!um<1ALm2Zb4>i(Ty^#V--=$ZLKH#YTmUzM=w>O<5RQT9JNk%9JpZ|L3b zX+27TMvN23h;e1y&DoC|R!?!`ekSw#*;aigzI{_zZll6dqswcvYQk~_#1OYPgjBM} zl8Qej9!m!J+%8LM)^algEQr0BnAWA=VB4vFa;59Y?LcN%l+~A5+vPl?CY{3b7%+NT6y=78h8u)(dFLBb|7XXup>1(#%!4`hjqSS%uC%)m~yP%zbMcHHM2Q(7;!4SatC`swpUjv%GA|I;2W*HFv6SmIPk zYGJlb9`T9je;KqHGC=BT)&LAl8%5{i%%qF>`X=T>^{jrciV%C<#-3dq`QlJ&VX+J9 zY&>P@MJ{kQ z#xHV#i=&o8vdgz3C9A(g<+i~HVpx!+IcNr>A>|9kPCh7{SL@7~V!LHm5#SL3kGa{J z;$J&%f*+gEq((3fI_mia85sxbU{u|?ZfZ84U3wSH@-<3d)V_9XIx61k`SAkVohm=O z%qoK7iku>Z%74IXtLj1~)0#W&IK#A(F%|wGJlLofn)B>=!+ESS2S4#`flF$AsBq-w+HLBBhbg0F-SUEUMJuMP+rMePMx#J}AQ47#P0tT_$LS>6WA*PHbWIAj? zoJKnp>RM>)BsoP{@m+GGD(b& zie^IQrYW9@KOysqC+EEs8t&$lf46fAbBt3?w7WbyQ49H&ASMHQM-MaN(^i9M7HJ;3 z*@tsE8&F*9|b zt@rL;n)mjU-_Ir#9z^_xq~G6#?W{znSb2~vt6VmE=~39SjDTJ_NKRM2i_elRi}M)y zP}|AH41yiQ< zI0&03QCc?LY~($gAoXjIQ8xaBQ3?haC3fIe!iP}M!-=az6u6=_i%)-}MT|0OfLxHI zj0#ACd5>*FVk=ub9Nad5O}4cZuMBWTnR}dv49-TDI!yRF+30ZK7V^2{ft>x&nhz)~ z8PRr&I<C`qe2^{Q`3l3mJZ-UI+C-RS@&NXUV!1d1J@Dj(ElM^x-Ixd7T$-8zE!~ z@vWGU(>)_Yi9$JIlpXD4l&V3EnAtAC++~nuY7Q%2EDUrb-|K4;uZMXVWj=|kdOg4A zI6}Z-#Cte1qx?$60`H}@B49P`Hyk|GFNk_CO*6D&tY~Pbtz%TuTeULvr4VgGzPUga z5?npNPg?+&U=sBnw9%sZWHDGcUtSmULdOraZ(ZkM%QH~yGl(S^(1HWcUL*%OmirtHW z@MTaK<=k-yj^*iP&mI;aKr%|>Kx!!~CZy+!DJ5u!5%^Hjhn2fRocOuAxDHASl%@-< z8P)r07A(jVlY9@RAH2?MFR0@VYY3yP99Slnh#&M|t!7WYh+Z5HX7vfMfZGAX)$ST z=^*Y;$&jUFwcgqOeXAZwhlgY3`4d>#I>?DAQ|Y`{<)&tdN35B? zT);DTI1@&FM=m{7#Egq0M)?|jjdq>{5AuOC9a4oJX8}C3t5aiN3jNT1%Yr{43#$vj zUyYQ7E)vM>bX&dihi$lTBLf&t9P`z`$ac@x1Kw%d~V5fXje}tVIfxYFM`y=es2<$aq z*^jWdMqn@dmj4KQZ3MQtynyK%m~k zmI;uKj2&X^S0%l-m)vyCiGFV|%8)J~%?8+Cd)B<|{$Fn|^rs%*!ZV%o*d-uk?*MR_oIW_k#8EDXo#bs3~|Up!y72NMe(qYpLXJG zi}Lq6hkchd-tVwqauz5UUvgY>riN>&XwGz+v>z0WR^J2 zI|^i*Qz!ouww=8<@Eo$DLB?~=ulPrGr4$9nQ8*hZ+v*sYWosQhOuEOZRpK~2mF;Av zvVNN)ur@`{e&E#n9NLT4+Is8OmQ`~~obH4>faAE%69Fa;2K1szXsT>dQ(zB@;wE=S zDGJhOvYkREMaKg=j@AAGRtGQ(tNA&s7gYh4D(;ss8^COdE3m23flP@GdyPp6vFD{6 zIuYABss<*vRjz#6lqf0QGF* zD;)6sXrzSYf%J?8-MJc5xloy~k2BeNKQf+i;-}K2%Tk&Hw=P>53*6TFb@t0nqk@^s zjxMLGCG6D$JpsW;MjEJ+%o>OXz!269r>I``9b{6#373_BGaVELt zPIZ_0NFP_hUSG^o-9ghj)t&m2K9drqVU;M>c5MN>bMsc|{AMb?QI5ndRDbM_!d|Y@ zrc7o3At4jj+p>6+^ybaFheyeFS?6<`LZ&+Pk7l!%hbiCpYp9fZ>kOBGZ|^|RZ2=>t z#3Q|%2~*8J!DOcZ(_v~eW%)7(WveID+T`F!;P|YlARWpm(Me zWk)4-CM$fL&W8*z^%^3r8|zl;FjBr4dR@C#)_k;6{i9wGQ!PmO?cfag^&@}oc1dq_ z!}xldd{8I(#EAc@K2Dbyfw@Lt(s3$mn@n?tF38XtoV-sk-Y2K{jK)h6HY}B}Gsc!C zrNN0SX3{|28l1%XSPDK(?t9Dt3E{@a7DVA~TaKg@HIVlno9WhjA`a_|0j*tI+R?+9 zcvD9Ymxth~&C`3|gz3V1R){S5;IcT-t2}=$NMx*^6?F!4sRrC*Q@;u7x0kj!wD7g1 zf13S@|qx*xr`PwwrbLNBK=oTW^cI%H*h`m8vQSJ@Vcs zb9n?#vlqdEJ~Ejakx3BuxvE@$kwd}KkVC#IpL4eM39!{$1X}z34U`$ySV#}4##-2z zZHJ_6xkg5&Y{|aO+RH7X+MDgzy3MNS7@P7oTjLPKYZ5i4P;itl8Tsf6XKaQY2o!3w zE>9zQ<9B1HGtQ+FJ+}TCGrb5|WvXkHPDlW7>*(( z7zHHDdq>dCRTjLS?m~|Eu!(gc)2SYucdCcYvpHyf847-NECRQI z^bsVlW)mk;{VtF~!7uw66B10WI{4Ome`*T_XAZC?6JVn~A(#ExxKJ=}fFbM#gPX?A zQ1H>?xA32l*heEdEhk3I4Q1Hn0;xfI2j<#5zyQXl0beF0?mwTad=Sp~j8~;9$>_Q@ zUu66lXT5}HU0M;LBZ50}S%D{VxA)_l9r9FL2OwV#D8feTH5>Ke4GT6h{kZqEY`n%X zr=iC};@^;s17v7JYWi0LZ=}x_zmUy^Sov(=sywIgdUuLA1=6*TNzRj#!7i3QIezS$ z16J{h97x5=8_>sAc&(fEI6$6%G7ndhx1Y?3zkL`C(p#>C%&>=ml+jGsjq@f1hfwC1 zm+9S*3-$-Wa!wpAjum%_o$9!za>Y#U-)Ml-qWX=1j{4Ee{K;CFw{{|_Qs@JK`pekto@*tpTrrbj}-u^}#?13b?TBe-wd z>rP*~rY{SQLn!RYVU(%8ER2WqJ_ofXq*S%%dqcsr6QCV+ARHIfzn^BM+Gia6|7qW| zB)-n183f%QPiEDXjNREccYJgp3cnXX$S6*fYuhUz^YW10b?fjGB(8oMVm zdsq|Q?ou|U>4g2Mpn zv?Hnuh8IH0SA7w^?dJkNeK<4pB`8j!~RsC?8JW48+;-#gK z!NQd(_yL3(Bo@3tzNcPJw{zmBZh2wb0c(Pvb>ckMk?-9qZHHBDXw_yX`Tad8cXM^3 zv8YUZibE`5gA$Sz;*Y3%#~ND?~*7@ln?Kv_x^%)SQvz zD*p(PKk?#Zh>|}uelzclv2T*QfWg@tyTGJKC|aUP_VE9E_YMRZ7;HU68Zcs*vJV zkur)DG^V?EOGP^X_H(BY;16*%e&?6)&Y&zhRV78V#E;dK1V5d_i8rics)en2VH&o2rS7AvAV^WT;#~Ex-tm z`SLxn_D|(;^3&=>WRxqVGzl9&ks1N7`#(3L8>UoGoYQP&E@guCya~s!H1_0M)Zmq4 zVa|ATR7+(0xMvT?b!LmQ7!4`sTu44c!Sf-sC$UwAadZ3kS4V*#2?gH^^@TaQ>P5u6 zJn{F`uec%C!v!HHZnv@*>GnDlT;ofD(NBf2+oXZB%!%e+i4wwu3BhpCyk>+97m%^{ zSVZKUJq=W(N!|krzS9TUEhqyekgjf=d{Mr&GP?b!#0^tXXf@R>nP ziMALi40yswY^0n$l?2D2@M8zMWZv`0TbzB@LvUCQH|%HoStDala}9_2PWz$J%KG;I z+=#Ce;HhaaleN!gxwlGN!Ck!FqswDVde7EI$kI&b9QEoXxJ1ijVjN#qoKv6*b6*OqWDC^kb6F=N7pN=e z+MJeI6wcb=ry+CC$PA>aXMD)_b~m!R>%3VpUB*1fEj|Pg^w{awo=R z$N4+qm_O`X!gklBX29_`3wu?KA618fYfnUMj&c~bNg$b)64V4Bmu z6UOX`Vtg0EnB2>xxUgpm1%G{#m9K(;77lm+%=kmWE+0ZMrDlWP^PxJmXnnQ-;jmwj8_Z0Cu1di*DMXLTT zV%5&+G*4=l@$6=4s&k*rwz|9*dSI6-EtE_Wb)bTHp@+@cRYWr(hZAL8@1&08K!{3$ zTzhWz-BCXtJlvP4I<4aPXZKWe$kmC8pGS+I%3~CEj|uTOQSrTJNglyTGH}QS200ArovW|u23aUWLYe!w4Q1H8<^4=%b#M)!;>2i`QTPIEWY$#JS zKyZyL=35x1K+!|j{|DMniQk)0E9pmhA6sNpxQhGB5Jc3LV zb1=AW$mOM462?sqY^$Wd3D`E4Q(>NwA9--Z{QTTpE*YY?J^k_Y*3usiQfmg^Lt)5_ zEYwF$X=eg;R^}#`yQrGBA^4fo^F{_}cPg;`lc|Mj*z%1b(k^Dvc@#^l=Lc{6OK^!@MyTezg(`o>n=rvsJgJ zAeAGrdp_tvE)DshhZz$JJ~SBd1Tyrh8HCF)LmgNz2VcJ$xmOUxC^(oO?xra+I^ zrc(U`Qs$|^)$MV+e9!}j~5@8 z7!GO%wT38RIEdlR!+U5zYlwz-AG~AWeG}ee;T;&DbZHHlP`?hB8a!z7q2cJ_p`b84 z97Kb|!5Ana6bpR+36|0vUJ1mcqtju*NI^%-$+{h5GcJWk-%4)h_eb0#@1+=TjQIKA zk=7mM>0b}yrYsTf`XTt)uvtMitsgWV;#x5HDoH1)jO#GDlUSJp!);HHW16h{;0AX; zT!*~|r4`EGp?IO3f$|=de?s{el&-el>^`J%-~9sOXF*v9#Q|j%l%-G>K*@np4`r3Z zxf)I7@;PoUuhS=u6DDR%f=mqlCUO{#UBiDmIH@#GM^$Fv3SH^QWkU;yJM39uI|cs; oLucp8+6U;EkQR}(e=g8G`B2D>iTBTWx)dOOGyHxCel>{x4|6h{%K!iX delta 10565 zcmZ{K3w%>W*7(f5H|Z@+Y5D;ALT(ZYEd@ENF0dHE+0zMFQ zQ)pdrK?SC|2)JLd;POzHQtMJ6hDY_&bzK|5wZOW9RZB(PTPWuCLGE`ZZIS){|9^hJ zxifQS&Y3ea=bSlnCdW@QgFa@<)aWl?L;RhcP?aNWQi2knRg7{l%2?dFTiOwDNxxNL^ zYKNqDAz@s>xLf-0$}XTawm-HgZvLAEcJ};2l}p-~*Vl!VjheA2dj6ZYz<8yu6){LC z;gEogh(`!=sGs;V;wfx1q%Dx-IP%8`YuMAlU{{!OKlwajHuG(e#2AX0ZEhkN8klcl z2ot$%W};z_x<-g7h{)fgK4A@0X7rgwtBKEN4tXzE+rpGNt;qL-eu(DKcsMjpP4n)^ z3m8W=KNID|%zvxouf{jUKb;8vXx3&piHxxD%^7X z12QsyDOI>1kQc#sk=!Xelnrb|s2l-h4CUPgveWHQY^>AO2pv15msP8Ex0_Y&VGCp? z>jC7HcDpU^0_eUCx;Fxuo2Vho8o=BD%x8N^TioePXZ%%-!dm0?VD zZ}f_ZxZ@8pUko;nO_+l5UClX(t69s%Xe1b0qKl#nV)FIM-&8@2F3>9Zps8@2xx!arx zv@0Km1O?=QqW40c3MAsloCyOsm&_EhFi%zpPvWBHZ-teZIi!*@bJ^I72N2)zJB)Vi zMSRUc#9JYi9c=!nYGOb5(68X{Ehy}7Wqas{b!Sz@%r#wV%WSGLl8&Fpkk(A8IxU_kG z<^+tB$%?Ejz48X)&+aF0WKCioe1rTw>lNnE8)Vs?_vUT>6XJOgb}H&&&Lnwy0|TidqjUs?6#%K)o_EY`D11lQ z;nFGZ^jT#VRBL-4?eX8iK-WST@tYVh6_8UE-V+YxQAo&#>0oEPT%Ct}w9VL}E3%ON zcRk0P4wB62bFqo6oIV*xl2@nCo_icR=SLu+2oOtPx*K7Ca-sY*5x4u&3W5F*Cl$3b`?(0`DQN?7LDrSNucWC&b!E`JGLTa`Ql-r(RuUy(Gmp zU994irG0n~*Q1bQ+39#O>B@FR%(#IpcjV8Kx2R>LbmkpEt9ItIo-M%05nyT$bnC}fyW7|UuszobvWSnkQZ6`f(4Q`M$b~oSQv6 z^WQ)H^b-|=XG#%2ty^{c{!xSI?`D>g!_C(}^w5P$>Bw|u6&&wjqj+D0c(ICzch}5Z zB}DlT+9UmIn;vexBwwuZURE8fvcPw|M~J%OKc&XibajntVwG%dgfSDyEU-qjyG=9i zeCk~wo_wxeEwggz2Hy;^xc9>+J6FVi&qf*AO=7C}r-!w`axL?Y^}f&5eb%p6#5&%G zTp^3*IAE_|n=_6%T}9rVGhN3%GTxyhJ#)rSI8ntap9Nut%b!TZCfu+8+48-fO3HLWt*Qu{pkG@D@ui5K;Tu%cV*%QVlt+{Zx z4q)NH_Ul%PmlQnKMSC%Ky=E^~MzI|}sFl#x4&RT5e>_ZWaYG4CsZ)0oZSJ_}-9}wM zdv%n9?ZIrkk3uKkGdW`)w*9;|1_M3s4N7fO6J3Vz**M+MQLpZ?I-81nQO-V@Q(o<( zOV&s{_l&Wuvg$;GnBMdu%_Bu@=J8cPgCuy;zfX%&NOGqoTGOz@Z9kGc?(d!)b>OU`DID9*> zc_Ga1J5#mOeOiq>f#)!w6ytL&aSyesUMjX!fi}XCK*g9W%(11d63~=Y?Rb*t{5~F~NlI(MIlrhk3djS}_D90H1rZ`IR5%QEHiBbMUUU5uWRECg}GQf(k zPH1Pd7WhKDprVp_j?O9yIitpHLCTncG?5YWMWl=!s8?-5XO(W-1Mabf>&51QtJk2P zF4B7||AT>270S2m#!n1K|TnE0gf%!~5 zVSG(Rh`r)qKU_Fe<4{6wel?WIbGdn?jaF9Cc$7ZZk9w#Gn_|L2gaiE{5pJg6Kia3A zr+ZzmzAg~^gYDt7@RUUzT+fM7ev#{Gk5~j=F5iTdwEhB>+YA`QG%ro}x)qd$6wezs z`E}upT4PNWTW#C(fQ|rktUK)S{?*A7{Mdpf)q!$QtQY2`q`Y1OST%p`qH6Q6b02_O z?xFmJHMU~Q5pksF7xNs`6@FHcT|_29_h3fol8iG80Xm^oa!uA*zh)0u}*Pv*Z&5#cWMR)x@XOp>}>0v`$U^+ z%Sg{{Q*$%w)ZQ&^YTSZ0HF*J6{t=`@a@Un=PWfGMJm8uE_hLpE;C_>l2)JtjH#sxG z*{1daPHHBlGBuOE+LzU)T0^zLd!d25uT3@FSEmZw+SEHUv2q|tEiDoZg@yu7`NE5Q zR0Do6g0s(K8{J!^Y0O0GkQuNIaXLK@Wj(aLLo)KxqIbIMRMGggtDttS)~B{*cVcpPaQ?3wCizM=PiFLVCNky2T*s z!QT?ZF|fSv-eAOM?IzJGQa^N~4`*`92J(meJiMHImG4Q_xAIM#64qLsrv-X_T0r%U zO55RMoTaJ>G5OT(xN|?^JNA*^70hCO93-a-X2lFa5KkGq2tGvjJ~Fy+7M|T)Q0T*q zyq}CJdICRA))!5{?&jS^3ovuGzqxmQFUD+hckx4POg)fX7x&^l*vU$Ch7o^c=G(hEau38=Jysd4Cb3p{)%OA6?wnx4|qcJZx+3*kIEn5dVW9{ z+-#$b0p}M>Ge+-pCnc8I%W`;FLAX1K(&9S>Gv7k*2DLIu$NyxMr~yW~&_CkvArxrg z#1$gyxu~~_&tBFeM(OP*XC*160UThy#j!57iOmlNHVP9F1mKJ^>KG3mTr^qa zvf$I?8J7z`LcVe>%}}8=8%Wwx!kspC;%ub!t5c}>_1ukE<-l;c2FiQD>(BPalgG=m z#w~vn@k-0Hhr&eWEnc{7n2|!_E1!^Y`mPiu3}uL6PE^k*_YdmC)K&q;o;#Q->JBMh zEDUrZ-&?B@Z-j9f#Y&3W-3+}L zDVkb2D^|{Hq_<*8!owPELcYzw780uSFnCA_)zx{&$;u^ZldECs;Z2MpAEN_gx8NQD zMZ&-(1Dq%{!DM>`j1@0Axg-fcM7~^N!ha&#l4%dkJ0{6}fwRFhu`lqY#wa&}{ekE{ zEM|*XNgAMS9|SX?ElHz2{sujM2o@_(FX#)zX#Igf)wG5Y8>n+*!%EaK)q4U|#0WPZ zMmcbdQI3*LOMlH=4U%t`=6m)4;|Cxy%JE}xI2I=rJ$Fce1Cmjm7)U5&#h9dQF}?t8 zGs8L*^kIe7IPoiWVGX1PNL$V}ee15Mnl~?1jPor^I&g*8pH<@z=?J6zYGAQgAb!$~ z^}3zeB6>L(Nb3_|0#}2a*x3~Z7joq#L=G+spKy^b-f$2g_ATnrDLEStMT*=$-F`-S zgq&HHj?0O*Y+7zMv^pU1;;2?eF&@QJus@UwAYn&gA3?Flh*Mgr#6|Ys4k}&kg^9OP z#RhQ&oU47L`r)|yBZ5>gdi%cXqDb5y$AFiT)-=8KYLgLI{QKaYU>mBvyg38%@ga1q zlpe>*foRYh|G8-V+8QXBXd2pjc;M|wZOkL?`0lD@3?O{Olk;rb{KZp z_w-HJUx#7)e4B5=P7K5T=-YJ@_U zHhQdqfZJf~H5=SG{b_%$bGtp-?{J=T=O`GTbDeW1gh~mn1h)ww39clMdydoL(p|h8 zy5_gjZ)v;uv&<6L8CQ<%a2w#Z*?SGoCgrsajMUp!nOK@%L0xYStf>fNTh+R@z{wmZDgi`3>H!?Of z{Si!8iLMa4hDnd~BXg}gQ93Urx*}o9dVi$zyxXi`=Dh2IyE<Y8UeKtO0{l7276^ayBH46T5{>JdzMmz(yrD^oEVU^k5TSmXZdMBBwIh`^E7?zFdhV2!2R7hh*IaD=S{+Rq?{z5 zJ~0l|wd;uqse6NgVM=G!UBVf8b~6~e9HTovFFh=_eT>3K8GOi8VbJsyf*g<#dguvy1x z9Lv}eUWCALn_|GX2K+SGb$SW#FZmEj#ArL=DJQv7G?JRq9c*hUdwsDpAovSqhS zna{38Y4N^D5vOzF33XSA!9NL>eU{%~N)aYHcew4nHTE5@oghi5KTU4wFk3|DZwB4HR4Tr%$_UoMn(|Pw~0R}fyi8ukrxdQ4>XF?@_ zPJ&&_q$h(M!G2q*94&Sk0GIct2ob=x`6k=PT6utn`5)FfCkr5C!z8bEQE%&3f({w= zB;yO<6gk|yPcT0q$NS9Ya}qW!l1|E_9EnmQL^v^%2;$~&8(S9L4EZizmmrU}426O> zkguMkCKs=n7q))W^M~W}9Ay5Q8OdtPq@r@U)D7;t{|z}H-zBe>ZC9gW$J>+J$=6R= zV`KC4eL0E^Z^^5Ga9BiBRQ`67v^K%R=WoyJ*XuvOqUS!ZkaxNxnmB+Ao%#Nwf(U_m zUk$j##uk0ZI=wo;Tew1ttF4={AWK`fF3aep?I@RSIJ<^}tWuA9U5-xxQ>`*J@q|Iz^LuvE%nuo$5y5#6> zsOXd|Zkk(M74F4yqs(Oy2!h`y6WHj+T4WK##_Eddy|NYv2Fqo?`*5G|f635)%1`v> zgHpO&B_m6^bYJP_oL+7L6{d6-*_@*outPb?R=EVRTk>AcwrK(HdqXSG^c>=!fkY*w zx+T|LA&-|+lqlVJY1z6IdGy40Y|FvooRZ0*r{cnmEwQ2HT0~Z^&BG0(b?pofHX&sK zYY%_b#yN#dhiW#)=ORmuin2gfE}@Iz81+cDj}D{jD{S})dQEuUhb=6Gvrcs5tP|aA zmcvCIKrN7XYzXcES)tzL$iqU8qy^#!7>fmPsIf76e`(Wh3#=GmZ)v&}Q46@qiggwb zJ=?Uvft%z{OYCF+IfPTrk!oR>;{(XTm^&qN_0T~7Np0RBXd$##+|oW|4Qt)&B|P(7 z`4EGYHoS{WtOI88MDF%}e7#Mc>S%)jN`OSjV0s0!F?6B8W~Lwao|4VqbId8|F^|l7 zI{mIs2O8b!xs9$yIaPchsZmnBhI8>^COA^32L7BhOS~jobHRrg=#*#YUg?S#r$9>! zdF|=RckLdi0L+S;nAAKP&dn0{UJ2u|vTeXFUX*(hu<`=nIqL|N-zNfRm&6)O0 zM)ci5IGnx3ie`oT0JwhwdGwh%j4nvtekK_#_*cIjLoPmJz~2(=xq~GCc1pxquL>7| zNQfEZGpgr$9>esw z&;oa8>>(>S2OK5t2A);xgG=1*%U;|!z8*UY0=WY zG>B19SWOV6>dy<~i+gKaRQ!?h>(*?q7AQXs5?2GXtEtTWGAfn0WrP18i3@x}o~^Oy z+Q2+u@>Wg3xNUuRj}Pw&!yok^WELmN%Ues}C}}2<>mSE!NbUM*xQ#Tew~V&*%@&W@ z6J^}~M|ulyAv`4dXFG9^H`Op~C@# zA(`T2gM=krevSKNH)fFeWH)P}cT;-T`Ud(5ArV8CQ}Stv3LA18ZB!;tS0*^NsDkxm z`KWYocq$X@I)8OuM7kczn;fhkSsdj^nFx1zy7BZn$I0*5k-ys8NhZ|BdOEa;^1r)A z9znD~yM~mGzM-w*y-|hLEw8wBu&tDr-b&79@F%oV9iX>`>he+GLzecT)aw^|E2rA7 zRa(C1*lWWY^CQ?}%6WunY)O(|1wUq&yg{zFtDh~FS;;OLr83Fr@xlWrSPg_~B^GQ3 zy&oq!YvkA5`OW+6F@B31XIWg?-dc%Ha$S=?J=WjejWTm8W2MEgqkhd%xm`X8gm>6~ zIHS8r+h_}dJ9MgO61BhyZF#v~7?O~SM=b8W5~Y}4)hSJ__^iuAIs9ezC$y27k8*B+ zGbXcXhuz?3feF@yh3Y)UT`S>C#+6ugN{X+z-bHV~L$mya#@9D#jDzc>v1N;UX!R1@ zcxHlYe`~UQUfyMAD#o|xRBgMh6`R*f@p7VzkrSm-iK*HSrkSlk$~+aKiKMkI$+KHh zx_%J>oipCOMKxP-Rt>YOITq>wl2gF?)+;o@KK+G{Z6KjhznG+-CKX=I3e$YLt zkOuNgA+DhX&T8Dw*d|(kxc{KLtTGI2lot3%Q$wr#V?E-lTcYpHDQ|YKhZjN4BW|^` z9rQx21y=gvfxzqVM4}VlaY4AxN*Os7Vgy5E`DI{32u0P@z^6xtB!hD%f+TH`cgox0 z)dCC*$P8tW&dwq?xJM>Nr`71v0;@Hhcq>&8QYvqm-JYWqnQzeoXSDbxdhgT%=Y0@; zLR#P-KB`IUVJ~ZCV+)>*(rcy2^I=7HxzSx#9uImED>)?U=9FpxsRT(721B#{e~Iq~ znH6y+BD0^1^3d)4={?vO6zrn*I=V;;{1dG5_CBOs9MA%r2a)o0Uya#NKwWN!8sW@U z;|-@>7`z4nt{Y3>5T>$O{w|HlarsE8I)Z$0u}GK-X9JCe6hY3nta_Jqc7VZ}4)5)k z`(dn*2|=TkhSq;yi>?vitE+{0!EDxuhs~f4g067AYk`|_<+ylP zi3|0lG8@WAq$vX8pNWaJ_G}+ABjqP=dpEW?)a0p+Jr6Ptb?Q{cjb(@W;8eTYp_WbM z3LWa*Q%}i_5O4tD@FCyHq@gg{*>21xCT{oGHv*yi!BhI^#*p4o+4@|Acpl^*1&8KK zwQZ<1q_eZB&a#yd0gsJJH-aVOETH*rdflX}vqd#Qbex47t}`9 zrE;z(Ro76t&mQIXQ01Q8S`R2Y!x-OLcut4~-#;p3>a@W8_gJ|RHjNE-g*JGI2`zBJ z2Y)yjc2oGmZSI9tTjkw$+`b;3ythat72q%3!up79!{QJ=527=7sD0T+-m7!&beo!3 zsjQrZhRpY+Cx;xAaTxKpVN9G+jMZ?$vKC307kW`*=?}FtpbUY}pmslxR z65x>9F6Sh^8Zv67;^*Q}AmfXVaMIZT+xjsh8U0MKeUpKyS#yo2Er~9<9y`Ye8nbAA)<^w7__> zcT?6xAr1*kK+7Nmu%K8$B}jSmNHy4zk8TwAu3Z`FjJ$VeB^lf_sr)EJ_e^lU5AD7U z(DES}p=)EPYj|O}v%V6Xo&m169`q@!AX%F0E0l3&p`-NZbGdV&JL3#5Yu0<|})L;Dm$A@6T4O(=mushwM@v4x+(xqc$veg$LrCkDxQ;n!my zgjUv>v?i&k@aF?&#+e9K??L#})C-ABSsXd~f|+Ljdf|5PS0i7%0~^Vl7iqNO{ueFG zmjh(&i{eAiA1#GHYS|$D&@~9_A_K*dL>HQIvW1BfTeuh~OT%q&LJDC{W6Ohbfn7-C zZ3*&*M0z~b+wqyj5G11Zl=cOCN+!HC-b2d@{JY_~L%eykI3A?)6_pb^nhZPFCvYTk z=ly0K`J@|Ff6~p20o58DQZp*Wwn2DHGu424Q+tvzY(E7t4C4CWGb!0e_!gu*)Tagh z0`^x6YJu=jP(%xS3GG9IqLJb)v+)mP)0UUQzIzXG*tU?Ewx)!&50~dd`RH)@DJbt5 zF7Ji%i^FCA)`!9$fQ#i2_RMW7Ji<^5T)^}uzJ-T4`M5#7DNG0kVj<@tkAgfL@(9RB zK^_MAILO&SdS2;GsZhQFuMl*14+g{YZv@r^g8}nkFfbL84C((s{W#2N2fU;4;M+4t zs_8kQpd-a3g^WuX2w{&HwIw$nZ79WS!|QOGxJYr*91U+t6Y=(+1JgCDf*g83$PL(p zKp;pyCJD@&e Date: Wed, 22 Mar 2023 08:46:54 +0000 Subject: [PATCH 086/287] ChibiOS: update to ChibiOS 21.11.3 stable --- modules/ChibiOS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/ChibiOS b/modules/ChibiOS index 1ec9f168b2e64a..9e1f723e9f5047 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit 1ec9f168b2e64a043470a87225b405e79d187354 +Subproject commit 9e1f723e9f5047442a7383499eb1182c4afefdbb From 80a03737178177ad22e6d20e31dd6ba7fef586a4 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 22 Mar 2023 22:22:03 -0600 Subject: [PATCH 087/287] AP_DDS: Bump to using latest MicroXRCEDDSGen * Adds -cs argument to fix case sensitive issue with PoseStamped * Adds support for uint8_t type alias * Updated the copies of IDL to remove these mods, matching upstream * Solves #23302 Signed-off-by: Ryan Friedman --- libraries/AP_DDS/Idl/NavSatFix.idl | 14 +++++++------- libraries/AP_DDS/Idl/NavSatStatus.idl | 10 +++++----- libraries/AP_DDS/Idl/PoseStamped.idl | 9 ++------- libraries/AP_DDS/wscript | 2 +- 4 files changed, 15 insertions(+), 20 deletions(-) diff --git a/libraries/AP_DDS/Idl/NavSatFix.idl b/libraries/AP_DDS/Idl/NavSatFix.idl index 57de832cb9e5ff..cfe9024ed18a27 100644 --- a/libraries/AP_DDS/Idl/NavSatFix.idl +++ b/libraries/AP_DDS/Idl/NavSatFix.idl @@ -1,4 +1,4 @@ -// generated from rosidl_adapter/resource/msg.idl.em +/// generated from rosidl_adapter/resource/msg.idl.em // with input from sensor_msgs/msg/NavSatFix.msg // generated code does not contain a copyright notice @@ -11,10 +11,10 @@ module sensor_msgs { module NavSatFix_Constants { @verbatim (language="comment", text= "If the covariance of the fix is known, fill it in completely. If the" "\n" "GPS receiver provides the variance of each measurement, put them" "\n" "along the diagonal. If only Dilution of Precision is available," "\n" "estimate an approximate covariance from that.") - const octet COVARIANCE_TYPE_UNKNOWN = 0; - const octet COVARIANCE_TYPE_APPROXIMATED = 1; - const octet COVARIANCE_TYPE_DIAGONAL_KNOWN = 2; - const octet COVARIANCE_TYPE_KNOWN = 3; + const uint8 COVARIANCE_TYPE_UNKNOWN = 0; + const uint8 COVARIANCE_TYPE_APPROXIMATED = 1; + const uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2; + const uint8 COVARIANCE_TYPE_KNOWN = 3; }; @verbatim (language="comment", text= "Navigation Satellite fix for any Global Navigation Satellite System" "\n" @@ -59,9 +59,9 @@ module sensor_msgs { "" "\n" "Beware: this coordinate system exhibits singularities at the poles.") @unit (value="m^2") - double position_covariance[9]; + double__9 position_covariance; - octet position_covariance_type; + uint8 position_covariance_type; }; }; }; diff --git a/libraries/AP_DDS/Idl/NavSatStatus.idl b/libraries/AP_DDS/Idl/NavSatStatus.idl index f320c9d9d604f2..a19fa90235325b 100644 --- a/libraries/AP_DDS/Idl/NavSatStatus.idl +++ b/libraries/AP_DDS/Idl/NavSatStatus.idl @@ -8,16 +8,16 @@ module sensor_msgs { module NavSatStatus_Constants { @verbatim (language="comment", text= "unable to fix position") - const char STATUS_NO_FIX = -1; + const int8 STATUS_NO_FIX = -1; @verbatim (language="comment", text= "unaugmented fix") - const char STATUS_FIX = 0; + const int8 STATUS_FIX = 0; @verbatim (language="comment", text= "with satellite-based augmentation") - const char STATUS_SBAS_FIX = 1; + const int8 STATUS_SBAS_FIX = 1; @verbatim (language="comment", text= "with ground-based augmentation") - const char STATUS_GBAS_FIX = 2; + const int8 STATUS_GBAS_FIX = 2; @verbatim (language="comment", text= "Bits defining which Global Navigation Satellite System signals were" "\n" "used by the receiver.") const uint16 SERVICE_GPS = 1; @@ -34,7 +34,7 @@ module sensor_msgs { "type and the last time differential corrections were received. A" "\n" "fix is valid when status >= STATUS_FIX.") struct NavSatStatus { - char status; + int8 status; uint16 service; }; diff --git a/libraries/AP_DDS/Idl/PoseStamped.idl b/libraries/AP_DDS/Idl/PoseStamped.idl index 9af9d0a30bb08b..e69efef37ab4ac 100644 --- a/libraries/AP_DDS/Idl/PoseStamped.idl +++ b/libraries/AP_DDS/Idl/PoseStamped.idl @@ -2,14 +2,9 @@ // with input from geometry_msgs/msg/PoseStamped.msg // generated code does not contain a copyright notice -#include "Point.idl" -#include "Quaternion.idl" +#include "Pose.idl" #include "Header.idl" -struct Pose { - geometry_msgs::msg::Point position; - geometry_msgs::msg::Quaternion orientation; -}; module geometry_msgs { module msg { @verbatim (language="comment", text= @@ -17,7 +12,7 @@ module geometry_msgs { struct PoseStamped { std_msgs::msg::Header header; - Pose pose; + geometry_msgs::msg::Pose pose; }; }; }; diff --git a/libraries/AP_DDS/wscript b/libraries/AP_DDS/wscript index f74060c0e4f72c..0efd551a62e03a 100644 --- a/libraries/AP_DDS/wscript +++ b/libraries/AP_DDS/wscript @@ -103,7 +103,7 @@ def build(bld): # build IDL file source=idl, target=gen, - rule=f"{bld.env.MICROXRCEDDSGEN[0]} -replace -d {os.path.join(gen_path, 'generated')} {idl}", + rule=f"{bld.env.MICROXRCEDDSGEN[0]} -cs -replace -d {os.path.join(gen_path, 'generated')} {idl}", group='dynamic_sources', ) bld.env.AP_LIB_EXTRA_SOURCES['AP_DDS'] += [os.path.join('generated', gen_c)] From c983c856d0ba2d462ccd80f28862eea74db3ea38 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 22 Mar 2023 00:10:54 -0600 Subject: [PATCH 088/287] .pre-commit: Add xmllint for AP_DDS xml file Signed-off-by: Ryan Friedman --- .pre-commit-config.yaml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 51091fb001a50c..9cd87421bcf78e 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -36,6 +36,11 @@ repos: - id: check-xml - id: check-yaml + - repo: https://github.com/lsst-ts/pre-commit-xmllint + rev: v1.0.0 + hooks: + - id: format-xmllint + files: libraries/AP_DDS/dds_xrce_profile.xml # Disable isort and mypy temporarily due to config conflicts # # Use to sort python imports by name and put system import first. # - repo: https://github.com/pycqa/isort From b5bbfe8011e1c2ca4c9449d8bb4fa3fcde8e0334 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Thu, 16 Mar 2023 23:11:07 +0000 Subject: [PATCH 089/287] SRV_Channel: add method have_32_channels Signed-off-by: Rhys Mainwaring --- libraries/SRV_Channel/SRV_Channel.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index 6e0a1edd8759fa..230a379ce4a24d 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -573,6 +573,15 @@ class SRV_Channels { return channel_function(channel) == SRV_Channel::k_alarm_inverted; } + // return true if 32 channels are enabled + static bool have_32_channels() { +#if NUM_SERVO_CHANNELS >= 17 + return _singleton->enable_32_channels.get() > 0; +#else + return false; +#endif + } + private: static bool disabled_passthrough; From c3b576a72fe4dcf77135b1edeb701ad0c5bf27a4 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Thu, 16 Mar 2023 17:49:29 +0000 Subject: [PATCH 090/287] SITL: enable 32 servos in SITL_JSON Signed-off-by: Rhys Mainwaring SITL: update JSON readme - Update servo data packet section for 32 channel output. Signed-off-by: Rhys Mainwaring --- libraries/SITL/SIM_JSON.cpp | 31 +++++++++++++++++++------- libraries/SITL/SIM_JSON.h | 9 +++++++- libraries/SITL/examples/JSON/readme.md | 17 ++++++++++++-- 3 files changed, 46 insertions(+), 11 deletions(-) diff --git a/libraries/SITL/SIM_JSON.cpp b/libraries/SITL/SIM_JSON.cpp index 0d37e7529adad5..5c32227d5d4592 100644 --- a/libraries/SITL/SIM_JSON.cpp +++ b/libraries/SITL/SIM_JSON.cpp @@ -27,6 +27,7 @@ #include #include #include +#include #define UDP_TIMEOUT_MS 100 @@ -100,20 +101,34 @@ void JSON::set_interface_ports(const char* address, const int port_in, const int */ void JSON::output_servos(const struct sitl_input &input) { - servo_packet pkt; - pkt.frame_rate = rate_hz; - pkt.frame_count = frame_counter; - for (uint8_t i=0; i<16; i++) { - pkt.pwm[i] = input.servos[i]; + size_t pkt_size = 0; + ssize_t send_ret = -1; + if (SRV_Channels::have_32_channels()) { + servo_packet_32 pkt; + pkt.frame_rate = rate_hz; + pkt.frame_count = frame_counter; + for (uint8_t i=0; i<32; i++) { + pkt.pwm[i] = input.servos[i]; + } + pkt_size = sizeof(pkt); + send_ret = sock.sendto(&pkt, pkt_size, target_ip, control_port); + } else { + servo_packet_16 pkt; + pkt.frame_rate = rate_hz; + pkt.frame_count = frame_counter; + for (uint8_t i=0; i<16; i++) { + pkt.pwm[i] = input.servos[i]; + } + pkt_size = sizeof(pkt); + send_ret = sock.sendto(&pkt, pkt_size, target_ip, control_port); } - size_t send_ret = sock.sendto(&pkt, sizeof(pkt), target_ip, control_port); - if (send_ret != sizeof(pkt)) { + if ((size_t)send_ret != pkt_size) { if (send_ret <= 0) { printf("Unable to send servo output to %s:%u - Error: %s, Return value: %ld\n", target_ip, control_port, strerror(errno), (long)send_ret); } else { - printf("Sent %ld bytes instead of %lu bytes\n", (long)send_ret, (unsigned long)sizeof(pkt)); + printf("Sent %ld bytes instead of %lu bytes\n", (long)send_ret, (unsigned long)pkt_size); } } } diff --git a/libraries/SITL/SIM_JSON.h b/libraries/SITL/SIM_JSON.h index 3f1aeab5e7a80f..22582f0ae48083 100644 --- a/libraries/SITL/SIM_JSON.h +++ b/libraries/SITL/SIM_JSON.h @@ -44,13 +44,20 @@ class JSON : public Aircraft { private: - struct servo_packet { + struct servo_packet_16 { uint16_t magic = 18458; // constant magic value uint16_t frame_rate; uint32_t frame_count; uint16_t pwm[16]; }; + struct servo_packet_32 { + uint16_t magic = 29569; // constant magic value + uint16_t frame_rate; + uint32_t frame_count; + uint16_t pwm[32]; + }; + // default connection_info_.ip_address const char *target_ip = "127.0.0.1"; diff --git a/libraries/SITL/examples/JSON/readme.md b/libraries/SITL/examples/JSON/readme.md index 15e66fb25dc18e..47b4a85674c53d 100644 --- a/libraries/SITL/examples/JSON/readme.md +++ b/libraries/SITL/examples/JSON/readme.md @@ -14,13 +14,26 @@ Data is output from SITL in a binary format: uint16 pwm[16] ``` -The magic value is a constant of 18458, this is used to confirm the packet is from ArduPilot, in the future this may also be used for protocol versioning. +The magic value is a constant of 18458, this is used to confirm the packet is from ArduPilot and is used for protocol versioning. + +The number of output channels may be increased to 32 by setting the parameter +SERVO_32_ENABLE = 1. The SITL output packet is then + +``` + uint16 magic = 29569 + uint16 frame_rate + uint32 frame_count + uint16 pwm[32] +``` + +and uses a magic value 29569. + The frame rate represents the time step the simulation should take, this can be changed with the SIM_RATE_HZ ArduPilot parameter. The physics backend is free to ignore this value, a maximum time step size would typically be set. The SIM_RATE_HZ should value be kept above the vehicle loop rate, by default this 400hz on copter and quadplanes and 50 hz on plane and rover. The frame_count will increment for each output frame sent by ArduPilot, this count can be used to detect lost or duplicate frames. This count will be reset when SITL is re-started allowing the physics backend to reset the vehicle. If not input data is received after 10 seconds ArduPilot will re-send the output frame without incrementing the counter. This allows the physics model to be restarted and re-connect. Note that this may fill up the input buffer of the physics backend after some time. -PWM is a array of 16 servo values in micro seconds, typically in the 1000 to 2000 range as set by the servo output functions. +PWM is a array of 16 (or 32) servo values in micro seconds, typically in the 1000 to 2000 range as set by the servo output functions. SITL input Data is received from the physics backend in a plain text JSON format. The data must contain the following fields: From 18dc37eef836710fabed2bb664b94f87f89462b8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Mar 2023 21:26:55 +1100 Subject: [PATCH 091/287] Tools: blacklist build of CubeOrangePlus-SimOnHardware bootloader Just as we do the CubeOrange equivalent; this uses the CubeOrangePlus bootloader --- Tools/scripts/size_compare_branches.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index 9e719910c17125..55f57761dc5418 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -120,6 +120,7 @@ def __init__(self, # TODO: find a way to get this information from board_list: self.bootloader_blacklist = set([ 'CubeOrange-SimOnHardWare', + 'CubeOrangePlus-SimOnHardWare', 'fmuv2', 'fmuv3-bdshot', 'iomcu', From 863656b037204bc1d96c48d89b1809a5092fd691 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Sat, 11 Mar 2023 11:42:42 -0700 Subject: [PATCH 092/287] AP_DDS: Add multi-topic support with NavSatFix * Implement NavSatFix message * Support covariance * Set frame ID to WGS-84 * Closes #23284 Signed-off-by: Ryan Friedman --- libraries/AP_DDS/AP_DDS_Client.cpp | 193 +++++++++++++++++++++----- libraries/AP_DDS/AP_DDS_Client.h | 24 ++-- libraries/AP_DDS/AP_DDS_Topic_Table.h | 16 ++- libraries/AP_DDS/dds_xrce_profile.xml | 25 ++++ 4 files changed, 215 insertions(+), 43 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 2df813a0f8221b..e6a2571b87a60b 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -2,6 +2,7 @@ #if AP_DDS_ENABLED +#include #include #include #include @@ -9,6 +10,11 @@ #include "AP_DDS_Client.h" #include "generated/Time.h" +static constexpr uint16_t DELAY_TIME_TOPIC_MS = 10; +static constexpr uint16_t DELAY_NAV_SAT_FIX_TOPIC_MS = 1000; +static constexpr uint8_t GPS_INSTANCE_NO = 0; // Use primary GPS +static char WGS_84_FRAME_ID[] = "WGS-84"; + AP_HAL::UARTDriver *dds_port; @@ -31,6 +37,83 @@ void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg) } +void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg) +{ + // Add a lambda that takes in navsatfix msg and populates the cov + // Make it constexpr if possible + // https://www.fluentcpp.com/2021/12/13/the-evolutions-of-lambdas-in-c14-c17-and-c20/ + // constexpr auto times2 = [] (sensor_msgs_msg_NavSatFix* msg) { return n * 2; }; + + + update_topic(msg.header.stamp); + strcpy(msg.header.frame_id, WGS_84_FRAME_ID); + msg.status.service = 0; // SERVICE_GPS + msg.status.status = -1; // STATUS_NO_FIX + + if (!AP::gps().is_healthy()) { + msg.status.status = -1; // STATUS_NO_FIX + msg.status.service = 0; // No services supported + msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN + return; + } + + + //! @todo What about glonass, compass, galileo? + //! This will be properly designed and implemented to spec in #23277 + msg.status.service = 1; // SERVICE_GPS + + const auto status = AP::gps().status(GPS_INSTANCE_NO); + switch (status) { + case AP_GPS::NO_GPS: + case AP_GPS::NO_FIX: + msg.status.status = -1; // STATUS_NO_FIX + msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN + return; + case AP_GPS::GPS_OK_FIX_2D: + case AP_GPS::GPS_OK_FIX_3D: + msg.status.status = 0; // STATUS_FIX + msg.position_covariance_type = 1; // COVARIANCE_TYPE_APPROXIMATED + break; + case AP_GPS::GPS_OK_FIX_3D_DGPS: + msg.status.status = 1; // STATUS_SBAS_FIX + msg.position_covariance_type = 1; // COVARIANCE_TYPE_APPROXIMATED + break; + case AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT: + case AP_GPS::GPS_OK_FIX_3D_RTK_FIXED: + msg.status.status = 2; // STATUS_SBAS_FIX + msg.position_covariance_type = 1; // COVARIANCE_TYPE_APPROXIMATED + // RTK provides "rtk_accuracy" member, should it be used for the covariance? + break; + default: + //! @todo Can we not just use an enum class and not worry about this condition? + break; + } + const auto loc = AP::gps().location(GPS_INSTANCE_NO); + msg.latitude = loc.lat * 1E-7; + msg.longitude = loc.lng * 1E-7; + + int32_t alt_cm; + if (!loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_cm)) { + // With absolute frame, this condition is unlikely + msg.status.status = -1; // STATUS_NO_FIX + msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN + return; + } + msg.altitude = alt_cm / 100.0; + + // Calculate covariance: https://answers.ros.org/question/10310/calculate-navsatfix-covariance/ + // https://github.com/ros-drivers/nmea_navsat_driver/blob/indigo-devel/src/libnmea_navsat_driver/driver.py#L110-L114 + //! @todo This calculation will be moved to AP::gps and fixed in #23259 + //! It is a placeholder for now matching the ROS1 nmea_navsat_driver behavior + const auto hdop = AP::gps().get_hdop(GPS_INSTANCE_NO); + const auto hdopSq = hdop * hdop; + const auto vdop = AP::gps().get_vdop(GPS_INSTANCE_NO); + const auto vdopSq = vdop * vdop; + msg.position_covariance[0] = hdopSq; + msg.position_covariance[4] = hdopSq; + msg.position_covariance[8] = vdopSq; +} + /* class constructor @@ -107,64 +190,108 @@ bool AP_DDS_Client::create() const char* participant_ref = "participant_profile"; const auto participant_req_id = uxr_buffer_create_participant_ref(&session, reliable_out, participant_id,0,participant_ref,UXR_REPLACE); - // Topic - const uxrObjectId topic_id = { - .id = topics[0].topic_id, - .type = UXR_TOPIC_ID - }; - const char* topic_ref = topics[0].topic_profile_label; - const auto topic_req_id = uxr_buffer_create_topic_ref(&session,reliable_out,topic_id,participant_id,topic_ref,UXR_REPLACE); - - // Publisher - const uxrObjectId pub_id = { - .id = topics[0].pub_id, - .type = UXR_PUBLISHER_ID - }; - const char* pub_xml = ""; - const auto pub_req_id = uxr_buffer_create_publisher_xml(&session,reliable_out,pub_id,participant_id,pub_xml,UXR_REPLACE); - - // Data Writer - const char* data_writer_ref = topics[0].dw_profile_label; - const auto dwriter_req_id = uxr_buffer_create_datawriter_ref(&session,reliable_out,dwriter_id,pub_id,data_writer_ref,UXR_REPLACE); - - //Status requests - constexpr uint8_t nRequests = 4; - const uint16_t requests[nRequests] = {participant_req_id, topic_req_id, pub_req_id, dwriter_req_id}; + //Participant requests + constexpr uint8_t nRequestsParticipant = 1; + const uint16_t requestsParticipant[nRequestsParticipant] = {participant_req_id}; constexpr int maxTimeMsPerRequestMs = 250; - constexpr int requestTimeoutMs = nRequests * maxTimeMsPerRequestMs; - uint8_t status[nRequests]; - if (!uxr_run_session_until_all_status(&session, requestTimeoutMs, requests, status, nRequests)) { + constexpr int requestTimeoutParticipantMs = nRequestsParticipant * maxTimeMsPerRequestMs; + uint8_t statusPartipant[nRequestsParticipant]; + if (!uxr_run_session_until_all_status(&session, requestTimeoutParticipantMs, requestsParticipant, statusPartipant, nRequestsParticipant)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Partipant session request failure"); // TODO add a failure log message sharing the status results return false; } + for (size_t i = 0 ; i < ARRAY_SIZE(topics); i++) { + // Topic + const uxrObjectId topic_id = { + .id = topics[i].topic_id, + .type = UXR_TOPIC_ID + }; + const char* topic_ref = topics[i].topic_profile_label; + const auto topic_req_id = uxr_buffer_create_topic_ref(&session,reliable_out,topic_id,participant_id,topic_ref,UXR_REPLACE); + + // Publisher + const uxrObjectId pub_id = { + .id = topics[i].pub_id, + .type = UXR_PUBLISHER_ID + }; + const char* pub_xml = ""; + const auto pub_req_id = uxr_buffer_create_publisher_xml(&session,reliable_out,pub_id,participant_id,pub_xml,UXR_REPLACE); + + // Data Writer + const char* data_writer_ref = topics[i].dw_profile_label; + const auto dwriter_req_id = uxr_buffer_create_datawriter_ref(&session,reliable_out,topics[i].dw_id,pub_id,data_writer_ref,UXR_REPLACE); + + // Status requests + constexpr uint8_t nRequests = 3; + const uint16_t requests[nRequests] = {topic_req_id, pub_req_id, dwriter_req_id}; + constexpr int requestTimeoutMs = nRequests * maxTimeMsPerRequestMs; + uint8_t status[nRequests]; + if (!uxr_run_session_until_all_status(&session, requestTimeoutMs, requests, status, nRequests)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Topic/Pub/Writer session request failure for index 'TODO'"); + for (int s = 0 ; s < nRequests; s++) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Status '%d' result '%u'", s, status[s]); + } + // TODO add a failure log message sharing the status results + return false; + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"XRCE Client: Topic/Pub/Writer session pass for index 'TOOO'"); + } + } + return true; } -void AP_DDS_Client::write() +void AP_DDS_Client::write_time_topic() { WITH_SEMAPHORE(csem); if (connected) { ucdrBuffer ub; - uint32_t topic_size = builtin_interfaces_msg_Time_size_of_topic(&time_topic, 0); - uxr_prepare_output_stream(&session,reliable_out,dwriter_id,&ub,topic_size); + const uint32_t topic_size = builtin_interfaces_msg_Time_size_of_topic(&time_topic, 0); + uxr_prepare_output_stream(&session,reliable_out,topics[0].dw_id,&ub,topic_size); const bool success = builtin_interfaces_msg_Time_serialize_topic(&ub, &time_topic); if (!success) { // TODO sometimes serialization fails on bootup. Determine why. - // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); + // AP_HAL::panic("FATAL: XRCE_Client failed to serialize\n"); } - } +} +void AP_DDS_Client::write_nav_sat_fix_topic() +{ + WITH_SEMAPHORE(csem); + if (connected) { + ucdrBuffer ub; + const uint32_t topic_size = sensor_msgs_msg_NavSatFix_size_of_topic(&nav_sat_fix_topic, 0); + uxr_prepare_output_stream(&session,reliable_out,topics[1].dw_id,&ub,topic_size); + const bool success = sensor_msgs_msg_NavSatFix_serialize_topic(&ub, &nav_sat_fix_topic); + if (!success) { + // TODO sometimes serialization fails on bootup. Determine why. + // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); + } + } } void AP_DDS_Client::update() { WITH_SEMAPHORE(csem); - update_topic(time_topic); - write(); + const auto cur_time_ms = AP_HAL::millis64(); + + if (cur_time_ms - last_time_time_ms > DELAY_TIME_TOPIC_MS) { + update_topic(time_topic); + last_time_time_ms = cur_time_ms; + write_time_topic(); + } + + if (cur_time_ms - last_nav_sat_fix_time_ms > DELAY_NAV_SAT_FIX_TOPIC_MS) { + update_topic(nav_sat_fix_topic); + last_nav_sat_fix_time_ms = cur_time_ms; + write_nav_sat_fix_topic(); + } + connected = uxr_run_session_time(&session, 1); } diff --git a/libraries/AP_DDS/AP_DDS_Client.h b/libraries/AP_DDS/AP_DDS_Client.h index 706ccd758e6a85..4303ea526aec11 100644 --- a/libraries/AP_DDS/AP_DDS_Client.h +++ b/libraries/AP_DDS/AP_DDS_Client.h @@ -6,6 +6,7 @@ #include "ucdr/microcdr.h" #include "generated/Time.h" #include "AP_DDS_Generic_Fn_T.h" +#include "generated/NavSatFix.h" #include #include @@ -39,12 +40,7 @@ class AP_DDS_Client // Topic builtin_interfaces_msg_Time time_topic; - - // Data Writer - const uxrObjectId dwriter_id = { - .id = 0x01, - .type = UXR_DATAWRITER_ID - }; + sensor_msgs_msg_NavSatFix nav_sat_fix_topic; HAL_Semaphore csem; @@ -52,6 +48,13 @@ class AP_DDS_Client bool connected = true; static void update_topic(builtin_interfaces_msg_Time& msg); + static void update_topic(sensor_msgs_msg_NavSatFix& msg); + + // The last ms timestamp AP_DDS wrote a Time message + uint64_t last_time_time_ms; + // The last ms timestamp AP_DDS wrote a NavSatFix message + uint64_t last_nav_sat_fix_time_ms; + public: // Constructor @@ -61,15 +64,17 @@ class AP_DDS_Client //! @brief Initialize the client's transport, uxr session, and IO stream(s) //! @return True on successful initialization, false on failure - bool init() WARN_IF_UNUSED; + bool init() WARN_IF_UNUSED; //! @brief Set up the client's participants, data read/writes, // publishers, subscribers //! @return True on successful creation, false on failure bool create() WARN_IF_UNUSED; - //! @brief Serialize the current data state and publish to to the IO stream(s) - void write(); + //! @brief Serialize the current time state and publish to to the IO stream(s) + void write_time_topic(); + //! @brief Serialize the current nav_sat_fix state and publish to to the IO stream(s) + void write_nav_sat_fix_topic(); //! @brief Update the internally stored DDS messages with latest data void update(); @@ -80,6 +85,7 @@ class AP_DDS_Client struct Topic_table { const uint8_t topic_id; const uint8_t pub_id; + const uxrObjectId dw_id; const char* topic_profile_label; const char* dw_profile_label; Generic_serialize_topic_fn_t serialize; diff --git a/libraries/AP_DDS/AP_DDS_Topic_Table.h b/libraries/AP_DDS/AP_DDS_Topic_Table.h index 8f8134d086fe85..1b8b12badba494 100644 --- a/libraries/AP_DDS/AP_DDS_Topic_Table.h +++ b/libraries/AP_DDS/AP_DDS_Topic_Table.h @@ -1,6 +1,9 @@ -// #include "Generated/Time.h" // might change to brackets for include path +#include "generated/Time.h" +#include "generated/NavSatFix.h" + #include "AP_DDS_Generic_Fn_T.h" +#include "uxr/client/client.h" // Code generated table based on the enabled topics. // Mavgen is using python, loops are not readable. @@ -11,10 +14,21 @@ const struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = { { .topic_id = 0x01, .pub_id = 0x01, + .dw_id = uxrObjectId{.id=0x01, .type=UXR_DATAWRITER_ID}, .topic_profile_label = "time__t", .dw_profile_label = "time__dw", .serialize = Generic_serialize_topic_fn_t(&builtin_interfaces_msg_Time_serialize_topic), .deserialize = Generic_deserialize_topic_fn_t(&builtin_interfaces_msg_Time_deserialize_topic), .size_of = Generic_size_of_topic_fn_t(&builtin_interfaces_msg_Time_size_of_topic), }, + { + .topic_id = 0x02, + .pub_id = 0x02, + .dw_id = uxrObjectId{.id=0x02, .type=UXR_DATAWRITER_ID}, + .topic_profile_label = "navsatfix0__t", + .dw_profile_label = "navsatfix0__dw", + .serialize = Generic_serialize_topic_fn_t(&sensor_msgs_msg_NavSatFix_serialize_topic), + .deserialize = Generic_deserialize_topic_fn_t(&sensor_msgs_msg_NavSatFix_deserialize_topic), + .size_of = Generic_size_of_topic_fn_t(&sensor_msgs_msg_NavSatFix_size_of_topic), + }, }; diff --git a/libraries/AP_DDS/dds_xrce_profile.xml b/libraries/AP_DDS/dds_xrce_profile.xml index ae091652b3ebbd..6672867662ed4a 100644 --- a/libraries/AP_DDS/dds_xrce_profile.xml +++ b/libraries/AP_DDS/dds_xrce_profile.xml @@ -30,4 +30,29 @@ + + rt/ROS2_NavSatFix0 + sensor_msgs::msg::dds_::NavSatFix_ + + KEEP_LAST + 20 + + + + PREALLOCATED_WITH_REALLOC + + + RELIABLE + + + + NO_KEY + rt/ROS2_NavSatFix0 + sensor_msgs::msg::dds_::NavSatFix_ + + KEEP_LAST + 20 + + + From ee59d527e8790334f19cfd2442e89e522317ca3d Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 24 Mar 2023 14:06:26 -0600 Subject: [PATCH 093/287] AP_DDS: Fix spelling in participant name Signed-off-by: Ryan Friedman --- libraries/AP_DDS/AP_DDS_Client.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index e6a2571b87a60b..bb40fc270dddd9 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -196,9 +196,9 @@ bool AP_DDS_Client::create() constexpr int maxTimeMsPerRequestMs = 250; constexpr int requestTimeoutParticipantMs = nRequestsParticipant * maxTimeMsPerRequestMs; - uint8_t statusPartipant[nRequestsParticipant]; - if (!uxr_run_session_until_all_status(&session, requestTimeoutParticipantMs, requestsParticipant, statusPartipant, nRequestsParticipant)) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Partipant session request failure"); + uint8_t statusParticipant[nRequestsParticipant]; + if (!uxr_run_session_until_all_status(&session, requestTimeoutParticipantMs, requestsParticipant, statusParticipant, nRequestsParticipant)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Participant session request failure"); // TODO add a failure log message sharing the status results return false; } From a610474cdc19960ca7b442eef3d1557a185f037e Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 24 Mar 2023 14:15:54 -0600 Subject: [PATCH 094/287] AP_DDS: Parametrize the GPS instance number Signed-off-by: Ryan Friedman --- libraries/AP_DDS/AP_DDS_Client.cpp | 20 ++++++++++++-------- libraries/AP_DDS/AP_DDS_Client.h | 2 +- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index bb40fc270dddd9..4d29969de54ae1 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -12,7 +12,6 @@ static constexpr uint16_t DELAY_TIME_TOPIC_MS = 10; static constexpr uint16_t DELAY_NAV_SAT_FIX_TOPIC_MS = 1000; -static constexpr uint8_t GPS_INSTANCE_NO = 0; // Use primary GPS static char WGS_84_FRAME_ID[] = "WGS-84"; AP_HAL::UARTDriver *dds_port; @@ -37,20 +36,24 @@ void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg) } -void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg) +void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance) { // Add a lambda that takes in navsatfix msg and populates the cov // Make it constexpr if possible // https://www.fluentcpp.com/2021/12/13/the-evolutions-of-lambdas-in-c14-c17-and-c20/ // constexpr auto times2 = [] (sensor_msgs_msg_NavSatFix* msg) { return n * 2; }; + // assert(instance >= GPS_MAX_RECEIVERS); + if (instance >= GPS_MAX_RECEIVERS) { + return; + } update_topic(msg.header.stamp); strcpy(msg.header.frame_id, WGS_84_FRAME_ID); msg.status.service = 0; // SERVICE_GPS msg.status.status = -1; // STATUS_NO_FIX - if (!AP::gps().is_healthy()) { + if (!AP::gps().is_healthy(instance)) { msg.status.status = -1; // STATUS_NO_FIX msg.status.service = 0; // No services supported msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN @@ -62,7 +65,7 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg) //! This will be properly designed and implemented to spec in #23277 msg.status.service = 1; // SERVICE_GPS - const auto status = AP::gps().status(GPS_INSTANCE_NO); + const auto status = AP::gps().status(instance); switch (status) { case AP_GPS::NO_GPS: case AP_GPS::NO_FIX: @@ -88,7 +91,7 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg) //! @todo Can we not just use an enum class and not worry about this condition? break; } - const auto loc = AP::gps().location(GPS_INSTANCE_NO); + const auto loc = AP::gps().location(instance); msg.latitude = loc.lat * 1E-7; msg.longitude = loc.lng * 1E-7; @@ -105,9 +108,9 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg) // https://github.com/ros-drivers/nmea_navsat_driver/blob/indigo-devel/src/libnmea_navsat_driver/driver.py#L110-L114 //! @todo This calculation will be moved to AP::gps and fixed in #23259 //! It is a placeholder for now matching the ROS1 nmea_navsat_driver behavior - const auto hdop = AP::gps().get_hdop(GPS_INSTANCE_NO); + const auto hdop = AP::gps().get_hdop(instance); const auto hdopSq = hdop * hdop; - const auto vdop = AP::gps().get_vdop(GPS_INSTANCE_NO); + const auto vdop = AP::gps().get_vdop(instance); const auto vdopSq = vdop * vdop; msg.position_covariance[0] = hdopSq; msg.position_covariance[4] = hdopSq; @@ -287,7 +290,8 @@ void AP_DDS_Client::update() } if (cur_time_ms - last_nav_sat_fix_time_ms > DELAY_NAV_SAT_FIX_TOPIC_MS) { - update_topic(nav_sat_fix_topic); + constexpr uint8_t instance = 0; + update_topic(nav_sat_fix_topic, instance); last_nav_sat_fix_time_ms = cur_time_ms; write_nav_sat_fix_topic(); } diff --git a/libraries/AP_DDS/AP_DDS_Client.h b/libraries/AP_DDS/AP_DDS_Client.h index 4303ea526aec11..3037cceb0f8897 100644 --- a/libraries/AP_DDS/AP_DDS_Client.h +++ b/libraries/AP_DDS/AP_DDS_Client.h @@ -48,7 +48,7 @@ class AP_DDS_Client bool connected = true; static void update_topic(builtin_interfaces_msg_Time& msg); - static void update_topic(sensor_msgs_msg_NavSatFix& msg); + static void update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance); // The last ms timestamp AP_DDS wrote a Time message uint64_t last_time_time_ms; From 9633950098e51b355024a88e638109d39dc6ef19 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 24 Mar 2023 14:20:15 -0600 Subject: [PATCH 095/287] AP_DDS: Use GPS semaphore Signed-off-by: Ryan Friedman --- libraries/AP_DDS/AP_DDS_Client.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 4d29969de54ae1..8dacb4825397f7 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -53,7 +53,10 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i msg.status.service = 0; // SERVICE_GPS msg.status.status = -1; // STATUS_NO_FIX - if (!AP::gps().is_healthy(instance)) { + auto &gps = AP::gps(); + WITH_SEMAPHORE(gps.get_semaphore()); + + if (!gps.is_healthy(instance)) { msg.status.status = -1; // STATUS_NO_FIX msg.status.service = 0; // No services supported msg.position_covariance_type = 0; // COVARIANCE_TYPE_UNKNOWN @@ -65,7 +68,7 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i //! This will be properly designed and implemented to spec in #23277 msg.status.service = 1; // SERVICE_GPS - const auto status = AP::gps().status(instance); + const auto status = gps.status(instance); switch (status) { case AP_GPS::NO_GPS: case AP_GPS::NO_FIX: @@ -91,7 +94,7 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i //! @todo Can we not just use an enum class and not worry about this condition? break; } - const auto loc = AP::gps().location(instance); + const auto loc = gps.location(instance); msg.latitude = loc.lat * 1E-7; msg.longitude = loc.lng * 1E-7; @@ -108,9 +111,9 @@ void AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i // https://github.com/ros-drivers/nmea_navsat_driver/blob/indigo-devel/src/libnmea_navsat_driver/driver.py#L110-L114 //! @todo This calculation will be moved to AP::gps and fixed in #23259 //! It is a placeholder for now matching the ROS1 nmea_navsat_driver behavior - const auto hdop = AP::gps().get_hdop(instance); + const auto hdop = gps.get_hdop(instance); const auto hdopSq = hdop * hdop; - const auto vdop = AP::gps().get_vdop(instance); + const auto vdop = gps.get_vdop(instance); const auto vdopSq = vdop * vdop; msg.position_covariance[0] = hdopSq; msg.position_covariance[4] = hdopSq; From 10c74f3a44ab4f23fbb9a8610c377108b86850e9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Mar 2023 11:23:36 +1100 Subject: [PATCH 096/287] sim_vehicle.py: consolidate vehicle aliases into once place --- Tools/autotest/sim_vehicle.py | 43 ++++++++++++++++------------------- 1 file changed, 20 insertions(+), 23 deletions(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 43c4b2d4cd51f5..b6a358c3ee8785 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -957,6 +957,20 @@ def generate_frame_help(): return ret +# map from some vehicle aliases back to directory names. APMrover2 +# was the old name / directory name for Rover. +vehicle_map = { + "APMrover2": "Rover", + "Copter": "ArduCopter", + "Plane": "ArduPlane", + "Sub": "ArduSub", + "Blimp" : "Blimp", + "Rover": "Rover", +} +# add lower-case equivalents too +for k in list(vehicle_map.keys()): + vehicle_map[k.lower()] = vehicle_map[k] + # define and run parser parser = CompatOptionParser( "sim_vehicle.py", @@ -968,15 +982,10 @@ def generate_frame_help(): "simulate ArduPlane") vehicle_choices = list(vinfo.options.keys()) -# add an alias for people with too much m -vehicle_choices.append("APMrover2") -vehicle_choices.append("Copter") # should change to ArduCopter at some stage -vehicle_choices.append("Plane") # should change to ArduPlane at some stage -vehicle_choices.append("Sub") # should change to Sub at some stage -vehicle_choices.append("copter") # should change to ArduCopter at some stage -vehicle_choices.append("plane") # should change to ArduPlane at some stage -vehicle_choices.append("sub") # should change to Sub at some stage -vehicle_choices.append("blimp") # should change to Blimp at some stage + +# add vehicle aliases to argument parser options: +for c in vehicle_map.keys(): + vehicle_choices.append(c) parser.add_option("-v", "--vehicle", type='choice', @@ -1401,22 +1410,10 @@ def generate_frame_help(): break cwd = os.path.dirname(cwd) -# map from some vehicle aliases back to canonical names. APMrover2 -# was the old name / directory name for Rover. -vehicle_map = { - "APMrover2": "Rover", - "Copter": "ArduCopter", # will switch eventually - "Plane": "ArduPlane", # will switch eventually - "Sub": "ArduSub", # will switch eventually - "copter": "ArduCopter", # will switch eventually - "plane": "ArduPlane", # will switch eventually - "sub": "ArduSub", # will switch eventually - "blimp" : "Blimp", # will switch eventually -} if cmd_opts.vehicle in vehicle_map: - progress("%s is now known as %s" % - (cmd_opts.vehicle, vehicle_map[cmd_opts.vehicle])) cmd_opts.vehicle = vehicle_map[cmd_opts.vehicle] +elif cmd_opts.vehicle.lower() in vehicle_map: + cmd_opts.vehicle = vehicle_map[cmd_opts.vehicle.lower()] # try to validate vehicle if cmd_opts.vehicle not in vinfo.options: From 34411809d3a90cd1d37873c9f2f386c267083709 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 30 Mar 2023 12:43:02 +0100 Subject: [PATCH 097/287] AP_HAL_ChibiOS: revert to ChibiOS SPI driver model v1 --- libraries/AP_HAL_ChibiOS/SPIDevice.cpp | 22 ++++++++++------------ 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp index 2367f3de36f869..9b0dd2c3c3c194 100644 --- a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp @@ -205,7 +205,7 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len) // expect this timeout to trigger unless there is a severe MCU // error const uint32_t timeout_us = 20000U + len * 32U; - msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); + msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { ret = false; @@ -233,7 +233,7 @@ bool SPIDevice::clock_pulse(uint32_t n) acquire_bus(true, true); osalSysLock(); spiStartIgnoreI(spi_devices[device_desc.bus].driver, n); - msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); + msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[device_desc.bus].driver); @@ -246,7 +246,7 @@ bool SPIDevice::clock_pulse(uint32_t n) } osalSysLock(); spiStartIgnoreI(spi_devices[device_desc.bus].driver, n); - msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->sync_transfer, TIME_US2I(timeout_us)); + msg = osalThreadSuspendTimeoutS(&spi_devices[device_desc.bus].driver->thread, TIME_US2I(timeout_us)); osalSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[device_desc.bus].driver); @@ -365,18 +365,16 @@ bool SPIDevice::acquire_bus(bool set, bool skip_cs) spiAcquireBus(spi_devices[device_desc.bus].driver); /* Acquire ownership of the bus. */ bus.spicfg.ssport = PAL_PORT(device_desc.pal_line); bus.spicfg.sspad = PAL_PAD(device_desc.pal_line); - bus.spicfg.data_cb = nullptr; - bus.spicfg.error_cb = nullptr; - bus.spicfg.slave = false; + bus.spicfg.end_cb = nullptr; #if defined(STM32H7) bus.spicfg.cfg1 = freq_flag; bus.spicfg.cfg2 = device_desc.mode; - if (bus.spicfg.txsource == nullptr) { - bus.spicfg.txsource = (uint32_t *)malloc_dma(4); - memset(bus.spicfg.txsource, 0xFF, 4); + if (bus.spicfg.dummytx == nullptr) { + bus.spicfg.dummytx = (uint32_t *)malloc_dma(4); + memset(bus.spicfg.dummytx, 0xFF, 4); } - if (bus.spicfg.rxsink == nullptr) { - bus.spicfg.rxsink = (uint32_t *)malloc_dma(4); + if (bus.spicfg.dummyrx == nullptr) { + bus.spicfg.dummyrx = (uint32_t *)malloc_dma(4); } #else bus.spicfg.cr1 = (uint16_t)(freq_flag | device_desc.mode); @@ -502,7 +500,7 @@ void SPIDevice::test_clock_freq(void) uint32_t t0 = AP_HAL::micros(); spiStartExchange(spi_devices[i].driver, len, buf1, buf2); chSysLock(); - msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->sync_transfer, chTimeMS2I(100)); + msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->thread, chTimeMS2I(100)); chSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[i].driver); From 9752224ae1c0752a629acce01737d1760b2303a8 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 30 Mar 2023 13:19:00 +0100 Subject: [PATCH 098/287] ChibiOS: revert to SPI driver model v1 --- modules/ChibiOS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/ChibiOS b/modules/ChibiOS index 9e1f723e9f5047..ba4f0ad6af4bca 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit 9e1f723e9f5047442a7383499eb1182c4afefdbb +Subproject commit ba4f0ad6af4bca83e88d6949a85a70655c0a847a From 1e164c5221e619a42dfdf85bfd423b555c009a88 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 30 Mar 2023 20:16:59 +0100 Subject: [PATCH 099/287] ChibiOS: fix TIMv1 missing EICU ISRs --- modules/ChibiOS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/ChibiOS b/modules/ChibiOS index ba4f0ad6af4bca..7190726f62b6e6 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit ba4f0ad6af4bca83e88d6949a85a70655c0a847a +Subproject commit 7190726f62b6e6222063f7cc7947c7b654769cbb From 26b4b0e51a2ced0936e8199be3c5030812b54d60 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 31 Mar 2023 07:55:01 +0100 Subject: [PATCH 100/287] ChibiOS: point submodule at master rather than temporary branch --- modules/ChibiOS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/ChibiOS b/modules/ChibiOS index 7190726f62b6e6..4253f6db11790a 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit 7190726f62b6e6222063f7cc7947c7b654769cbb +Subproject commit 4253f6db11790a26361b6cc8b3663cd086709005 From bb74cb9be0f886ec09b9f487bad65db719e2bbad Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 3 Apr 2023 18:08:12 +0200 Subject: [PATCH 101/287] AP_Radio: build fix for skyviper --- libraries/AP_Radio/AP_Radio_cc2500.cpp | 2 +- libraries/AP_Radio/AP_Radio_cc2500.h | 2 +- libraries/AP_Radio/AP_Radio_cypress.cpp | 2 +- libraries/AP_Radio/AP_Radio_cypress.h | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Radio/AP_Radio_cc2500.cpp b/libraries/AP_Radio/AP_Radio_cc2500.cpp index e5e3b443af154b..fd6fc0a676e43e 100644 --- a/libraries/AP_Radio/AP_Radio_cc2500.cpp +++ b/libraries/AP_Radio/AP_Radio_cc2500.cpp @@ -414,7 +414,7 @@ void AP_Radio_cc2500::trigger_irq_radio_event() chSysUnlockFromISR(); } -void AP_Radio_cc2500::trigger_timeout_event(void *arg) +void AP_Radio_cc2500::trigger_timeout_event(virtual_timer_t* vt, void *arg) { (void)arg; //we are called from ISR context diff --git a/libraries/AP_Radio/AP_Radio_cc2500.h b/libraries/AP_Radio/AP_Radio_cc2500.h index ce5feb0c1fa944..1ddc608173ad32 100644 --- a/libraries/AP_Radio/AP_Radio_cc2500.h +++ b/libraries/AP_Radio/AP_Radio_cc2500.h @@ -87,7 +87,7 @@ class AP_Radio_cc2500 : public AP_Radio_backend static void irq_handler_thd(void* arg); static void trigger_irq_radio_event(void); - static void trigger_timeout_event(void *arg); + static void trigger_timeout_event(virtual_timer_t* vt, void *arg); void radio_init(void); diff --git a/libraries/AP_Radio/AP_Radio_cypress.cpp b/libraries/AP_Radio/AP_Radio_cypress.cpp index a66de153587e5c..ff6f99b4b65ef6 100644 --- a/libraries/AP_Radio/AP_Radio_cypress.cpp +++ b/libraries/AP_Radio/AP_Radio_cypress.cpp @@ -1199,7 +1199,7 @@ void AP_Radio_cypress::irq_handler_thd(void *arg) } } -void AP_Radio_cypress::trigger_timeout_event(void *arg) +void AP_Radio_cypress::trigger_timeout_event(virtual_timer_t* vt, void *arg) { (void)arg; //we are called from ISR context diff --git a/libraries/AP_Radio/AP_Radio_cypress.h b/libraries/AP_Radio/AP_Radio_cypress.h index 7aa49f615a67e5..15c63d528d7071 100644 --- a/libraries/AP_Radio/AP_Radio_cypress.h +++ b/libraries/AP_Radio/AP_Radio_cypress.h @@ -131,7 +131,7 @@ class AP_Radio_cypress : public AP_Radio_backend static void irq_handler_thd(void* arg); static void trigger_irq_radio_event(void); - static void trigger_timeout_event(void *arg); + static void trigger_timeout_event(virtual_timer_t* vt, void *arg); static const uint8_t max_channels = 16; From a25aa8d2acb816d57740ed0b76ed09f8f6a4da1a Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sun, 26 Jun 2022 08:47:08 +1000 Subject: [PATCH 102/287] AP_NavEKF3: Lock in wind state estimates when using srag to dead reckon --- libraries/AP_NavEKF3/AP_NavEKF3_core.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index d135c3099f808f..9fa9f5fd4f6a49 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -1116,12 +1116,18 @@ void NavEKF3_core::CovariancePrediction(Vector3F *rotVarVecPtr) lastInhibitMagStates = inhibitMagStates; if (!inhibitWindStates) { - ftype windVelVar = sq(dt * constrain_ftype(frontend->_windVelProcessNoise, 0.0f, 1.0f) * (1.0f + constrain_ftype(frontend->_wndVarHgtRateScale, 0.0f, 1.0f) * fabsF(hgtRate))); - if (!tasDataDelayed.allowFusion) { - // Allow wind states to recover faster when using sideslip fusion with a failed airspeed sesnor - windVelVar *= 10.0f; + const bool isDragFusionDeadReckoning = filterStatus.flags.dead_reckoning && !dragTimeout; + if (isDragFusionDeadReckoning) { + // when dead reckoning using drag fusion stop learning wind states to provide a more stable velocity estimate + P[23][23] = P[22][22] = 0.0f; + } else { + ftype windVelVar = sq(dt * constrain_ftype(frontend->_windVelProcessNoise, 0.0f, 1.0f) * (1.0f + constrain_ftype(frontend->_wndVarHgtRateScale, 0.0f, 1.0f) * fabsF(hgtRate))); + if (!tasDataDelayed.allowFusion) { + // Allow wind states to recover faster when using sideslip fusion with a failed airspeed sesnor + windVelVar *= 10.0f; + } + for (uint8_t i=12; i<=13; i++) processNoiseVariance[i] = windVelVar; } - for (uint8_t i=12; i<=13; i++) processNoiseVariance[i] = windVelVar; } // set variables used to calculate covariance growth From f7a8668c3040a4b3268c03371c774226c81bf1eb Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 18 Feb 2023 19:25:24 +0000 Subject: [PATCH 103/287] AP_Motors: Example: rework and update take optional arguments --- .../AP_Motors_test/AP_Motors_test.cpp | 140 ++++++++++++------ 1 file changed, 93 insertions(+), 47 deletions(-) diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index b68a58fda5043b..31b07ad3c127cc 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -3,6 +3,12 @@ * Code by Randy Mackay. DIYDrones.com */ +/* on Linux run with + ./waf configure --board linux + ./waf --targets examples/AP_Motors_test + ./build/linux/examples/AP_Motors_test +*/ + // Libraries #include #include @@ -11,6 +17,7 @@ #include #include #include +#include const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -41,14 +48,69 @@ void setup() hal.console->printf("AP_Motors library test ver 1.0\n"); // motor initialisation + motors.set_dt(1.0/400.0); motors.set_update_rate(490); + +#if NUM_OUTPUTS == 8 + motors.init(AP_Motors::MOTOR_FRAME_OCTA, AP_Motors::MOTOR_FRAME_TYPE_X); +#elif NUM_OUTPUTS == 6 + motors.init(AP_Motors::MOTOR_FRAME_HEXA, AP_Motors::MOTOR_FRAME_TYPE_X); +#else motors.init(AP_Motors::MOTOR_FRAME_QUAD, AP_Motors::MOTOR_FRAME_TYPE_X); +#endif + + char frame_and_type_string[30]; + motors.get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string)); + hal.console->printf("%s\n", frame_and_type_string); + #if HELI_TEST == 0 motors.update_throttle_range(); motors.set_throttle_avg_max(0.5f); #endif motors.output_min(); + // allow command line args for single run + uint8_t argc; + char * const *argv; + hal.util->commandline_arguments(argc, argv); + if (argc > 1) { + for (uint8_t i = 2; i < argc; i++) { + const char* arg = argv[i]; + + const char *eq = strchr(arg, '='); + if (eq == NULL) { + ::printf("Expected argument with \"=\"\n"); + exit(1); + } + char cmd[20] {}; + strncpy(cmd, arg, eq-arg); + const float value = atof(eq+1); + if (strcmp(cmd,"yaw_headroom") == 0) { + motors.set_yaw_headroom(value); + + } else if (strcmp(cmd,"throttle_avg_max") == 0) { + motors.set_throttle_avg_max(value); + + } else { + ::printf("Expected \"yaw_headroom\" or \"throttle_avg_max\"\n"); + exit(1); + } + + } + if (strcmp(argv[1],"t") == 0) { + motor_order_test(); + + } else if (strcmp(argv[1],"s") == 0) { + stability_test(); + + } else { + ::printf("Expected first argument, 't' or 's'\n"); + + } + hal.scheduler->delay(1000); + exit(0); + } + hal.scheduler->delay(1000); } @@ -71,9 +133,11 @@ void loop() // test motors if (value == 't' || value == 'T') { motor_order_test(); + hal.console->printf("finished test.\n"); } if (value == 's' || value == 'S') { stability_test(); + hal.console->printf("finished test.\n"); } } @@ -90,75 +154,58 @@ void motor_order_test() hal.scheduler->delay(2000); } motors.armed(false); - hal.console->printf("finished test.\n"); } // stability_test void stability_test() { - int16_t roll_in, pitch_in, yaw_in, avg_out; - float throttle_in; + hal.console->printf("Throttle average max: %0.4f\n", motors.get_throttle_avg_max()); + hal.console->printf("Yaw headroom: %i\n", motors.get_yaw_headroom()); - int16_t throttle_tests[] = {0, 100, 200, 300, 400, 500, 600, 700, 800, 900, 1000}; - uint8_t throttle_tests_num = sizeof(throttle_tests) / sizeof(int16_t); - int16_t rpy_tests[] = {0, 1000, 2000, 3000, 4500, -1000, -2000, -3000, -4500}; - uint8_t rpy_tests_num = sizeof(rpy_tests) / sizeof(int16_t); + const float throttle_tests[] = {0.0, 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9, 1.0}; + const uint8_t throttle_tests_num = ARRAY_SIZE(throttle_tests); + const float rpy_tests[] = {-1.0, -0.9, -0.8, -0.7, -0.6, -0.5, -0.4, -0.3, -0.2, -0.1, 0.0, 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9, 1.0}; + const uint8_t rpy_tests_num = ARRAY_SIZE(rpy_tests); // arm motors motors.armed(true); motors.set_interlock(true); SRV_Channels::enable_aux_servos(); -#if NUM_OUTPUTS <= 4 - hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,AvgOut,LimRP,LimY,LimThD,LimThU\n"); // quad -#elif NUM_OUTPUTS <= 6 - hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,Mot5,Mot6,AvgOut,LimRP,LimY,LimThD,LimThU\n"); // hexa -#else - hal.console->printf("Roll,Pitch,Yaw,Thr,Mot1,Mot2,Mot3,Mot4,Mot5,Mot6,Mot7,Mot8,AvgOut,LimRP,LimY,LimThD,LimThU\n"); // octa -#endif + hal.console->printf("Roll,Pitch,Yaw,Thr,"); + for (uint8_t i=0; iprintf("Mot%i,",i+1); + } + for (uint8_t i=0; iprintf("Mot%i_norm,",i+1); + } + hal.console->printf("LimR,LimP,LimY,LimThD,LimThU\n"); // run stability test for (uint8_t y=0; yread(0) + hal.rcout->read(1) + hal.rcout->read(2) + hal.rcout->read(3))/4); // display input and output -#if NUM_OUTPUTS <= 4 - hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d\n", // quad -#elif NUM_OUTPUTS <= 6 - hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d\n", // hexa -#else - hal.console->printf("%d,%d,%d,%3.1f,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d\n", // octa -#endif - (int)roll_in, - (int)pitch_in, - (int)yaw_in, - (double)throttle_in, - (int)hal.rcout->read(0), - (int)hal.rcout->read(1), - (int)hal.rcout->read(2), - (int)hal.rcout->read(3), -#if NUM_OUTPUTS >= 6 - (int)hal.rcout->read(4), - (int)hal.rcout->read(5), -#endif -#if NUM_OUTPUTS >= 8 - (int)hal.rcout->read(6), - (int)hal.rcout->read(7), -#endif - (int)avg_out, + hal.console->printf("%0.2f,%0.2f,%0.2f,%0.2f,", roll_in, pitch_in, yaw_in, throttle_in); + for (uint8_t i=0; iprintf("%d,",(int)hal.rcout->read(i)); + } + for (uint8_t i=0; iprintf("%0.4f,", motors.get_thrust_rpyt_out(i)); + } + hal.console->printf("%d,%d,%d,%d,%d\n", (int)motors.limit.roll, (int)motors.limit.pitch, (int)motors.limit.yaw, @@ -176,7 +223,6 @@ void stability_test() motors.set_throttle(0); motors.armed(false); - hal.console->printf("finished test.\n"); } void update_motors() From 7c92340b426e1ac9123a1058d735a74d8268f65a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 18 Feb 2023 19:25:53 +0000 Subject: [PATCH 104/287] AP_Motors: add getters for example --- libraries/AP_Motors/AP_MotorsMatrix.cpp | 28 ++++++++++++++++++-- libraries/AP_Motors/AP_MotorsMatrix.h | 4 +++ libraries/AP_Motors/AP_MotorsMulticopter.cpp | 13 +++++++++ libraries/AP_Motors/AP_MotorsMulticopter.h | 4 +++ 4 files changed, 47 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index e915526d75a933..790e9be77f519c 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -597,7 +597,7 @@ bool AP_MotorsMatrix::setup_quad_matrix(motor_frame_type frame_type) add_motors(motors, ARRAY_SIZE(motors)); break; } -#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN) case MOTOR_FRAME_TYPE_NYT_PLUS: { _frame_type_string = "NYT_PLUS"; static const AP_MotorsMatrix::MotorDef motors[] { @@ -620,7 +620,7 @@ bool AP_MotorsMatrix::setup_quad_matrix(motor_frame_type frame_type) add_motors(motors, ARRAY_SIZE(motors)); break; } -#endif //APM_BUILD_TYPE(APM_BUILD_ArduPlane) +#endif //APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN) case MOTOR_FRAME_TYPE_BF_X: { // betaflight quad X order // see: https://fpvfrenzy.com/betaflight-motor-order/ @@ -1365,5 +1365,29 @@ void AP_MotorsMatrix::disable_yaw_torque(void) } } +#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN) +// examples can pull values direct +float AP_MotorsMatrix::get_thrust_rpyt_out(uint8_t i) const +{ + if (i < AP_MOTORS_MAX_NUM_MOTORS) { + return _thrust_rpyt_out[i]; + } + return 0.0; +} + +bool AP_MotorsMatrix::get_factors(uint8_t i, float &roll, float &pitch, float &yaw, float &throttle, uint8_t &testing_order) const +{ + if ((i < AP_MOTORS_MAX_NUM_MOTORS) && motor_enabled[i]) { + roll = _roll_factor[i]; + pitch = _pitch_factor[i]; + yaw = _yaw_factor[i]; + throttle = _throttle_factor[i]; + testing_order = _test_order[i]; + return true; + } + return false; +} +#endif + // singleton instance AP_MotorsMatrix *AP_MotorsMatrix::_singleton; diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index 5b2061546fc2ea..fd5fe322b8faf9 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -101,6 +101,10 @@ class AP_MotorsMatrix : public AP_MotorsMulticopter { }; void add_motors_raw(const struct MotorDefRaw *motors, uint8_t num_motors); + // pull values direct, (examples only) + float get_thrust_rpyt_out(uint8_t i) const; + bool get_factors(uint8_t i, float &roll, float &pitch, float &yaw, float &throttle, uint8_t &testing_order) const; + protected: // output - sends commands to the motors void output_armed_stabilizing() override; diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 0a861ac6fbd386..1b07b8a36bb85a 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -873,3 +873,16 @@ bool AP_MotorsMulticopter::arming_checks(size_t buflen, char *buffer) const return true; } + +#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN) +// Getters for AP_Motors example, not used by vehicles +float AP_MotorsMulticopter::get_throttle_avg_max() const +{ + return _throttle_avg_max; +} + +int16_t AP_MotorsMulticopter::get_yaw_headroom() const +{ + return _yaw_headroom; +} +#endif diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 5971b6d144e0df..2e4fdcd615755d 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -105,6 +105,10 @@ class AP_MotorsMulticopter : public AP_Motors { // Run arming checks bool arming_checks(size_t buflen, char *buffer) const override; + // Getters for AP_Motors example, not used by vehicles + float get_throttle_avg_max() const; + int16_t get_yaw_headroom() const; + // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; From e9da278164b211d2b92ea041cc4f4308e068b060 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 18 Feb 2023 23:44:42 +0000 Subject: [PATCH 105/287] AP_Motors: example: add script to run motor example at a range of head rooms and throttle average max values --- .../examples/AP_Motors_test/MotorTestSweep.sh | 26 +++++++++++++++++++ 1 file changed, 26 insertions(+) create mode 100755 libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh diff --git a/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh new file mode 100755 index 00000000000000..fb972b77dcc472 --- /dev/null +++ b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh @@ -0,0 +1,26 @@ +# Build and run the motors example stability test at a range of yaw headroom and throttle average max values +# Output results to files for comparison + +cd "$(dirname "$0")" +cd ../../../.. + +mkdir -p MotorTestSweep + +./waf configure --board linux +./waf build --target examples/AP_Motors_test +echo + +YAW_HEADROOM="0 100 200 300 400 500 600 700 800 900 1000" +THR_AVERAGE_MAX="0 0.1 0.2 0.3 0.4 0.5 0.6 0.7 0.8 0.9 1.0" + +COUNTER=0 +for headroom in $YAW_HEADROOM; do + echo "Yaw Headroom: $headroom" + for Thr in $THR_AVERAGE_MAX; do + echo " Throttle average max: $Thr" + ./build/linux/examples/AP_Motors_test s yaw_headroom=$headroom throttle_avg_max=$Thr > MotorTestSweep/$COUNTER.csv + let COUNTER++ + done + echo +done + From 1a754904e90ad15393fed0ea9575b996182bd30b Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 7 Feb 2023 18:26:06 +0000 Subject: [PATCH 106/287] AP_Motors: Matrix: mixer simplification --- libraries/AP_Motors/AP_MotorsMatrix.cpp | 114 ++++++++++++------------ libraries/AP_Motors/AP_MotorsMatrix.h | 4 + 2 files changed, 62 insertions(+), 56 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index 790e9be77f519c..20aba55537138a 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -200,32 +200,38 @@ uint32_t AP_MotorsMatrix::get_motor_mask() return mask; } +// helper to return value scaled between boost and normal based on the value of _thrust_boost_ratio +// _thrust_boost_ratio of 1 -> return = boost_value +// _thrust_boost_ratio of 0 -> return = normal_value +float AP_MotorsMatrix::boost_ratio(float boost_value, float normal_value) const +{ + return _thrust_boost_ratio * boost_value + (1.0 - _thrust_boost_ratio) * normal_value; +} + // output_armed - sends commands to the motors // includes new scaling stability patch void AP_MotorsMatrix::output_armed_stabilizing() { - uint8_t i; // general purpose counter - float roll_thrust; // roll thrust input value, +/- 1.0 - float pitch_thrust; // pitch thrust input value, +/- 1.0 - float yaw_thrust; // yaw thrust input value, +/- 1.0 - float throttle_thrust; // throttle thrust input value, 0.0 - 1.0 - float throttle_avg_max; // throttle thrust average maximum value, 0.0 - 1.0 - float throttle_thrust_max; // throttle thrust maximum value, 0.0 - 1.0 - float throttle_thrust_best_rpy; // throttle providing maximum roll, pitch and yaw range without climbing - float rpy_scale = 1.0f; // this is used to scale the roll, pitch and yaw to fit within the motor limits - float yaw_allowed = 1.0f; // amount of yaw we can fit in - float thr_adj; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy - // apply voltage and air pressure compensation const float compensation_gain = get_compensation_gain(); // compensation for battery voltage and altitude - roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain; - pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain; - yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain; - throttle_thrust = get_throttle() * compensation_gain; - throttle_avg_max = _throttle_avg_max * compensation_gain; - // If thrust boost is active then do not limit maximum thrust - throttle_thrust_max = _thrust_boost_ratio + (1.0f - _thrust_boost_ratio) * _throttle_thrust_max * compensation_gain; + // pitch thrust input value, +/- 1.0 + const float roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain; + + // pitch thrust input value, +/- 1.0 + const float pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain; + + // yaw thrust input value, +/- 1.0 + float yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain; + + // throttle thrust input value, 0.0 - 1.0 + float throttle_thrust = get_throttle() * compensation_gain; + + // throttle thrust average maximum value, 0.0 - 1.0 + float throttle_avg_max = _throttle_avg_max * compensation_gain; + + // throttle thrust maximum value, 0.0 - 1.0, If thrust boost is active then do not limit maximum thrust + const float throttle_thrust_max = boost_ratio(1.0, _throttle_thrust_max * compensation_gain); // sanity check throttle is above zero and below current limited throttle if (throttle_thrust <= 0.0f) { @@ -240,8 +246,9 @@ void AP_MotorsMatrix::output_armed_stabilizing() // ensure that throttle_avg_max is between the input throttle and the maximum throttle throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, throttle_thrust_max); + // throttle providing maximum roll, pitch and yaw range // calculate the highest allowed average thrust that will provide maximum control range - throttle_thrust_best_rpy = MIN(0.5f, throttle_avg_max); + float throttle_thrust_best_rpy = MIN(0.5f, throttle_avg_max); // calculate throttle that gives most possible room for yaw which is the lower of: // 1. 0.5f - (rpy_low+rpy_high)/2.0 - this would give the maximum possible margin above the highest motor and below the lowest @@ -266,29 +273,26 @@ void AP_MotorsMatrix::output_armed_stabilizing() // calculate amount of yaw we can fit into the throttle range // this is always equal to or less than the requested yaw from the pilot or rate controller - float rp_low = 1.0f; // lowest thrust value - float rp_high = -1.0f; // highest thrust value - for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { + float yaw_allowed = 1.0f; // amount of yaw we can fit in + for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { // calculate the thrust outputs for roll and pitch _thrust_rpyt_out[i] = roll_thrust * _roll_factor[i] + pitch_thrust * _pitch_factor[i]; - // record lowest roll + pitch command - if (_thrust_rpyt_out[i] < rp_low) { - rp_low = _thrust_rpyt_out[i]; - } - // record highest roll + pitch command - if (_thrust_rpyt_out[i] > rp_high && (!_thrust_boost || i != _motor_lost_index)) { - rp_high = _thrust_rpyt_out[i]; - } // Check the maximum yaw control that can be used on this channel // Exclude any lost motors if thrust boost is enabled - if (!is_zero(_yaw_factor[i]) && (!_thrust_boost || i != _motor_lost_index)){ + if (!is_zero(_yaw_factor[i]) && (!_thrust_boost || i != _motor_lost_index)) { + const float thrust_rp_best_throttle = throttle_thrust_best_rpy + _thrust_rpyt_out[i]; + float motor_room; if (is_positive(yaw_thrust * _yaw_factor[i])) { - yaw_allowed = MIN(yaw_allowed, fabsf(MAX(1.0f - (throttle_thrust_best_rpy + _thrust_rpyt_out[i]), 0.0f)/_yaw_factor[i])); + // room to upper limit + motor_room = 1.0 - thrust_rp_best_throttle; } else { - yaw_allowed = MIN(yaw_allowed, fabsf(MAX(throttle_thrust_best_rpy + _thrust_rpyt_out[i], 0.0f)/_yaw_factor[i])); + // room to lower limit + motor_room = thrust_rp_best_throttle; } + const float motor_yaw_allowed = MAX(motor_room, 0.0)/fabsf(_yaw_factor[i]); + yaw_allowed = MIN(yaw_allowed, motor_yaw_allowed); } } } @@ -298,26 +302,25 @@ void AP_MotorsMatrix::output_armed_stabilizing() float yaw_allowed_min = (float)_yaw_headroom * 0.001f; // increase yaw headroom to 50% if thrust boost enabled - yaw_allowed_min = _thrust_boost_ratio * 0.5f + (1.0f - _thrust_boost_ratio) * yaw_allowed_min; + yaw_allowed_min = boost_ratio(0.5, yaw_allowed_min); // Let yaw access minimum amount of head room yaw_allowed = MAX(yaw_allowed, yaw_allowed_min); // Include the lost motor scaled by _thrust_boost_ratio to smoothly transition this motor in and out of the calculation if (_thrust_boost && motor_enabled[_motor_lost_index]) { - // record highest roll + pitch command - if (_thrust_rpyt_out[_motor_lost_index] > rp_high) { - rp_high = _thrust_boost_ratio * rp_high + (1.0f - _thrust_boost_ratio) * _thrust_rpyt_out[_motor_lost_index]; - } - // Check the maximum yaw control that can be used on this channel // Exclude any lost motors if thrust boost is enabled if (!is_zero(_yaw_factor[_motor_lost_index])){ + const float thrust_rp_best_throttle = throttle_thrust_best_rpy + _thrust_rpyt_out[_motor_lost_index]; + float motor_room; if (is_positive(yaw_thrust * _yaw_factor[_motor_lost_index])) { - yaw_allowed = _thrust_boost_ratio * yaw_allowed + (1.0f - _thrust_boost_ratio) * MIN(yaw_allowed, fabsf(MAX(1.0f - (throttle_thrust_best_rpy + _thrust_rpyt_out[_motor_lost_index]), 0.0f)/_yaw_factor[_motor_lost_index])); + motor_room = 1.0 - thrust_rp_best_throttle; } else { - yaw_allowed = _thrust_boost_ratio * yaw_allowed + (1.0f - _thrust_boost_ratio) * MIN(yaw_allowed, fabsf(MAX(throttle_thrust_best_rpy + _thrust_rpyt_out[_motor_lost_index], 0.0f)/_yaw_factor[_motor_lost_index])); + motor_room = thrust_rp_best_throttle; } + const float motor_yaw_allowed = MAX(motor_room, 0.0)/fabsf(_yaw_factor[_motor_lost_index]); + yaw_allowed = boost_ratio(yaw_allowed, MIN(yaw_allowed, motor_yaw_allowed)); } } @@ -330,7 +333,7 @@ void AP_MotorsMatrix::output_armed_stabilizing() // add yaw control to thrust outputs float rpy_low = 1.0f; // lowest thrust value float rpy_high = -1.0f; // highest thrust value - for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { + for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { _thrust_rpyt_out[i] = _thrust_rpyt_out[i] + yaw_thrust * _yaw_factor[i]; @@ -349,11 +352,12 @@ void AP_MotorsMatrix::output_armed_stabilizing() if (_thrust_boost) { // record highest roll + pitch + yaw command if (_thrust_rpyt_out[_motor_lost_index] > rpy_high && motor_enabled[_motor_lost_index]) { - rpy_high = _thrust_boost_ratio * rpy_high + (1.0f - _thrust_boost_ratio) * _thrust_rpyt_out[_motor_lost_index]; + rpy_high = boost_ratio(rpy_high, _thrust_rpyt_out[_motor_lost_index]); } } // calculate any scaling needed to make the combined thrust outputs fit within the output range + float rpy_scale = 1.0f; if (rpy_high - rpy_low > 1.0f) { rpy_scale = 1.0f / (rpy_high - rpy_low); } @@ -365,7 +369,7 @@ void AP_MotorsMatrix::output_armed_stabilizing() rpy_high *= rpy_scale; rpy_low *= rpy_scale; throttle_thrust_best_rpy = -rpy_low; - thr_adj = throttle_thrust - throttle_thrust_best_rpy; + float thr_adj = throttle_thrust - throttle_thrust_best_rpy; if (rpy_scale < 1.0f) { // Full range is being used by roll, pitch, and yaw. limit.roll = true; @@ -375,21 +379,19 @@ void AP_MotorsMatrix::output_armed_stabilizing() limit.throttle_upper = true; } thr_adj = 0.0f; - } else { - if (thr_adj < 0.0f) { - // Throttle can't be reduced to desired value - // todo: add lower limit flag and ensure it is handled correctly in altitude controller - thr_adj = 0.0f; - } else if (thr_adj > 1.0f - (throttle_thrust_best_rpy + rpy_high)) { - // Throttle can't be increased to desired value - thr_adj = 1.0f - (throttle_thrust_best_rpy + rpy_high); - limit.throttle_upper = true; - } + } else if (thr_adj < 0.0f) { + // Throttle can't be reduced to desired value + // todo: add lower limit flag and ensure it is handled correctly in altitude controller + thr_adj = 0.0f; + } else if (thr_adj > 1.0f - (throttle_thrust_best_rpy + rpy_high)) { + // Throttle can't be increased to desired value + thr_adj = 1.0f - (throttle_thrust_best_rpy + rpy_high); + limit.throttle_upper = true; } // add scaled roll, pitch, constrained yaw and throttle for each motor const float throttle_thrust_best_plus_adj = throttle_thrust_best_rpy + thr_adj; - for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { + for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { _thrust_rpyt_out[i] = (throttle_thrust_best_plus_adj * _throttle_factor[i]) + (rpy_scale * _thrust_rpyt_out[i]); } diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index fd5fe322b8faf9..ad36a0e0cc7bc9 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -156,6 +156,10 @@ class AP_MotorsMatrix : public AP_MotorsMulticopter { const char* _frame_type_string = ""; // string representation of frame type private: + + // helper to return value scaled between boost and normal based on the value of _thrust_boost_ratio + float boost_ratio(float boost_value, float normal_value) const; + // setup motors matrix bool setup_quad_matrix(motor_frame_type frame_type); bool setup_hexa_matrix(motor_frame_type frame_type); From 9e71c9953d59033dde419e252489e02f61e919d8 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 25 Feb 2023 17:33:21 +0000 Subject: [PATCH 107/287] AP_Motors: example: add thrust boost --- .../AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp | 7 +++++++ .../AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh | 5 ++++- 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index 31b07ad3c127cc..a782261a4d154e 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -42,6 +42,8 @@ AP_MotorsMatrix motors(400); AP_BattMonitor _battmonitor{0, nullptr, nullptr}; +bool thrust_boost = false; + // setup void setup() { @@ -91,6 +93,9 @@ void setup() } else if (strcmp(cmd,"throttle_avg_max") == 0) { motors.set_throttle_avg_max(value); + } else if (strcmp(cmd,"thrust_boost") == 0) { + thrust_boost = value > 0.0; + } else { ::printf("Expected \"yaw_headroom\" or \"throttle_avg_max\"\n"); exit(1); @@ -162,6 +167,7 @@ void stability_test() { hal.console->printf("Throttle average max: %0.4f\n", motors.get_throttle_avg_max()); hal.console->printf("Yaw headroom: %i\n", motors.get_yaw_headroom()); + hal.console->printf("Thrust boost: %s\n", thrust_boost?"True":"False"); const float throttle_tests[] = {0.0, 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9, 1.0}; const uint8_t throttle_tests_num = ARRAY_SIZE(throttle_tests); @@ -229,6 +235,7 @@ void update_motors() { // call update motors 1000 times to get any ramp limiting complete for (uint16_t i=0; i<1000; i++) { + motors.set_thrust_boost(thrust_boost); motors.output(); } } diff --git a/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh index fb972b77dcc472..767e018153bd04 100755 --- a/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh +++ b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh @@ -18,7 +18,10 @@ for headroom in $YAW_HEADROOM; do echo "Yaw Headroom: $headroom" for Thr in $THR_AVERAGE_MAX; do echo " Throttle average max: $Thr" - ./build/linux/examples/AP_Motors_test s yaw_headroom=$headroom throttle_avg_max=$Thr > MotorTestSweep/$COUNTER.csv + # Test with and without boost + ./build/linux/examples/AP_Motors_test s yaw_headroom=$headroom throttle_avg_max=$Thr thrust_boost=0 > MotorTestSweep/$COUNTER.csv + let COUNTER++ + ./build/linux/examples/AP_Motors_test s yaw_headroom=$headroom throttle_avg_max=$Thr thrust_boost=1 > MotorTestSweep/$COUNTER.csv let COUNTER++ done echo From c445bb5f9eda31241e6ca43f09757e0fc5f9f965 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Wed, 15 Feb 2023 15:49:40 +1100 Subject: [PATCH 108/287] AP_Common: Add same_alt_as function to Location --- libraries/AP_Common/Location.cpp | 14 ++++++++++++++ libraries/AP_Common/Location.h | 3 +++ 2 files changed, 17 insertions(+) diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index e7c31636f0da50..fb5225caaaa1c6 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -393,6 +393,20 @@ bool Location::same_latlon_as(const Location &loc2) const return (lat == loc2.lat) && (lng == loc2.lng); } +bool Location::same_alt_as(const Location &loc2) const +{ + // fast path if the altitude frame is the same + if (this->get_alt_frame() == loc2.get_alt_frame()) { + return this->alt == loc2.alt; + } + + ftype alt_diff; + bool have_diff = this->get_alt_distance(loc2, alt_diff); + + const ftype tolerance = FLT_EPSILON; + return have_diff && (fabsF(alt_diff) < tolerance); +} + // return true when lat and lng are within range bool Location::check_latlng() const { diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index e294cef2fbc9fe..ad1260fdac70a4 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -107,6 +107,9 @@ class Location // check if lat and lng match. Ignore altitude and options bool same_latlon_as(const Location &loc2) const; + // check if altitude matches. + bool same_alt_as(const Location &loc2) const; + /* * convert invalid waypoint with useful data. return true if location changed */ From 76e840729772c1a237b23ec208f19a4fba605fbf Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Wed, 15 Feb 2023 15:50:28 +1100 Subject: [PATCH 109/287] AP_Common: Add same_loc_as function to Location --- libraries/AP_Common/Location.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index ad1260fdac70a4..122bead689b6c5 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -110,6 +110,11 @@ class Location // check if altitude matches. bool same_alt_as(const Location &loc2) const; + // check if lat, lng, and alt match. + bool same_loc_as(const Location &loc2) const { + return same_latlon_as(loc2) && same_alt_as(loc2); + } + /* * convert invalid waypoint with useful data. return true if location changed */ From 6a2bfeb3ddba60a6cf3740484ea2ef4e49e8d32e Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Tue, 21 Mar 2023 21:18:36 +1100 Subject: [PATCH 110/287] Plane: Use new Location::same_loc_as() function --- ArduPlane/ArduPlane.cpp | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index a724c4af4a0f4c..d832d8fed3a342 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -821,12 +821,7 @@ bool Plane::get_target_location(Location& target_loc) */ bool Plane::update_target_location(const Location &old_loc, const Location &new_loc) { - if (!old_loc.same_latlon_as(next_WP_loc)) { - return false; - } - ftype alt_diff; - if (!old_loc.get_alt_distance(next_WP_loc, alt_diff) || - !is_zero(alt_diff)) { + if (!old_loc.same_loc_as(next_WP_loc)) { return false; } next_WP_loc = new_loc; From 674d7facdee82281fa384eceffb74490dae722b0 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Tue, 21 Mar 2023 21:20:11 +1100 Subject: [PATCH 111/287] Plane: Use Location::same_loc_as() in QuadPlane::waypoint_controller() --- ArduPlane/quadplane.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index c6c9a08d1f0b1b..5d308773ca172e 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3044,8 +3044,7 @@ void QuadPlane::waypoint_controller(void) const Location &loc = plane.next_WP_loc; const uint32_t now = AP_HAL::millis(); - if (!loc.same_latlon_as(last_auto_target) || - plane.next_WP_loc.alt != last_auto_target.alt || + if (!loc.same_loc_as(last_auto_target) || now - last_loiter_ms > 500) { wp_nav->set_wp_destination(poscontrol.target_cm.tofloat()); last_auto_target = loc; From 21d7a8102e106bccdf38807cb24c273befaf9a60 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Tue, 21 Mar 2023 13:13:17 -0500 Subject: [PATCH 112/287] Plane:allow airbrakes to be used --- ArduPlane/RC_Channel.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index e0435c8253af5f..1da0108f6ce95c 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -154,6 +154,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, case AUX_FUNC::RTL: case AUX_FUNC::TAKEOFF: case AUX_FUNC::FBWA: + case AUX_FUNC::AIRBRAKE: #if HAL_QUADPLANE_ENABLED case AUX_FUNC::QRTL: case AUX_FUNC::QSTABILIZE: From 91935fc40475973fe2b33afa2ece71a09a122e39 Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Fri, 24 Mar 2023 09:20:40 +0530 Subject: [PATCH 113/287] AP_Mount:Add GIMBAL_MANAGER_SET_ATTITUDE support --- libraries/AP_Mount/AP_Mount.cpp | 57 ++++++++++++++++++++++++++++ libraries/AP_Mount/AP_Mount.h | 1 + libraries/GCS_MAVLink/GCS_Common.cpp | 1 + 3 files changed, 59 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index c44014155ebb1a..f5249f1536f200 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -337,6 +337,60 @@ MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_pitchyaw(const mavlink_com return MAV_RESULT_FAILED; } +void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg){ + mavlink_gimbal_manager_set_attitude_t packet; + mavlink_msg_gimbal_manager_set_attitude_decode(&msg,&packet); + + AP_Mount_Backend *backend; + + // check gimbal device id. 0 is primary, 1 is 1st gimbal, 2 is + // 2nd gimbal, etc + const uint8_t instance = packet.gimbal_device_id; + if (instance == 0) { + backend = get_primary(); + } else { + backend = get_instance(instance - 1); + } + + if (backend == nullptr) { + return; + } + + // check flags for change to RETRACT + const uint32_t flags = packet.flags; + if ((flags & GIMBAL_MANAGER_FLAGS_RETRACT) > 0) { + backend->set_mode(MAV_MOUNT_MODE_RETRACT); + return; + } + + // check flags for change to NEUTRAL + if ((flags & GIMBAL_MANAGER_FLAGS_NEUTRAL) > 0) { + backend->set_mode(MAV_MOUNT_MODE_NEUTRAL); + return; + } + + const Quaternion att_quat{packet.q}; + if (!att_quat.is_nan()) { + // convert quaternion to euler angles + float roll_rad, pitch_rad, yaw_rad; + att_quat.to_euler(roll_rad, pitch_rad, yaw_rad); + + // radian to deg conversion + const float roll_deg = degrees(roll_rad); + const float pitch_deg = degrees(pitch_rad); + const float yaw_deg = degrees(yaw_rad); + backend->set_angle_target(roll_deg, pitch_deg, yaw_deg, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + return; + } + + if (!isnan(packet.angular_velocity_x) && !isnan(packet.angular_velocity_y) && !isnan(packet.angular_velocity_y)) { + const float roll_rate_degs = degrees(packet.angular_velocity_x); + const float pitch_rate_degs = degrees(packet.angular_velocity_y); + const float yaw_rate_degs = degrees(packet.angular_velocity_z); + backend->set_rate_target(roll_rate_degs, pitch_rate_degs, yaw_rate_degs, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + return; + } +} MAV_RESULT AP_Mount::handle_command_long(const mavlink_command_long_t &packet) { @@ -624,6 +678,9 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &m case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: handle_global_position_int(msg); break; + case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE: + handle_gimbal_manager_set_attitude(msg); + break; case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION: handle_gimbal_device_information(msg); break; diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index d2b5d62c6f2ae2..8788768c18294c 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -215,6 +215,7 @@ class AP_Mount MAV_RESULT handle_command_do_mount_configure(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_mount_control(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_long_t &packet); + void handle_gimbal_manager_set_attitude(const mavlink_message_t &msg); void handle_global_position_int(const mavlink_message_t &msg); void handle_gimbal_device_information(const mavlink_message_t &msg); void handle_gimbal_device_attitude_status(const mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index c0337a9d8b19a3..7f4c3b641acf45 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3868,6 +3868,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) case MAVLINK_MSG_ID_GIMBAL_REPORT: case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION: case MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS: + case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE: handle_mount_message(msg); break; #endif From c63ec307f13fbeaef57b1b296018dca0e5ecee45 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 25 Mar 2023 12:30:22 +1100 Subject: [PATCH 114/287] AP_Mount: do not allow both attitude and rate for GIMBAL_MANAGER_SET_ATTITUDE this will allow us to support both at the same time into the future without worrying about how it might break existing callers. --- libraries/AP_Mount/AP_Mount.cpp | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index f5249f1536f200..18e7303262b105 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -370,6 +370,19 @@ void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg){ } const Quaternion att_quat{packet.q}; + const Vector3f att_rate_degs { + packet.angular_velocity_x, + packet.angular_velocity_y, + packet.angular_velocity_y + }; + + // ensure that we are only demanded to a specific attitude or to + // achieve a specific rate. Do not allow both to be specified at + // the same time: + if (!att_quat.is_nan() && !att_rate_degs.is_nan()) { + return; + } + if (!att_quat.is_nan()) { // convert quaternion to euler angles float roll_rad, pitch_rad, yaw_rad; @@ -383,7 +396,7 @@ void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg){ return; } - if (!isnan(packet.angular_velocity_x) && !isnan(packet.angular_velocity_y) && !isnan(packet.angular_velocity_y)) { + { const float roll_rate_degs = degrees(packet.angular_velocity_x); const float pitch_rate_degs = degrees(packet.angular_velocity_y); const float yaw_rate_degs = degrees(packet.angular_velocity_z); From b24d74b35d4cf9126696875a6a67f9ecccc3c8a0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 3 Apr 2023 16:28:02 +1000 Subject: [PATCH 115/287] Copter: remove stale conversion functions past this PR upgrade from Copter-3.3 will not be seamless --- ArduCopter/Parameters.cpp | 68 --------------------------------------- 1 file changed, 68 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 1092475d55be45..1736d158b01436 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1370,46 +1370,7 @@ void Copter::load_parameters(void) // handle conversion of PID gains void Copter::convert_pid_parameters(void) { - // conversion info - const AP_Param::ConversionInfo pid_conversion_info[] = { - // PARAMETER_CONVERSION - Added: Apr-2016 - { Parameters::k_param_pid_rate_roll, 0, AP_PARAM_FLOAT, "ATC_RAT_RLL_P" }, - { Parameters::k_param_pid_rate_roll, 1, AP_PARAM_FLOAT, "ATC_RAT_RLL_I" }, - { Parameters::k_param_pid_rate_roll, 2, AP_PARAM_FLOAT, "ATC_RAT_RLL_D" }, - { Parameters::k_param_pid_rate_pitch, 0, AP_PARAM_FLOAT, "ATC_RAT_PIT_P" }, - { Parameters::k_param_pid_rate_pitch, 1, AP_PARAM_FLOAT, "ATC_RAT_PIT_I" }, - { Parameters::k_param_pid_rate_pitch, 2, AP_PARAM_FLOAT, "ATC_RAT_PIT_D" }, - { Parameters::k_param_pid_rate_yaw, 0, AP_PARAM_FLOAT, "ATC_RAT_YAW_P" }, - { Parameters::k_param_pid_rate_yaw, 1, AP_PARAM_FLOAT, "ATC_RAT_YAW_I" }, - { Parameters::k_param_pid_rate_yaw, 2, AP_PARAM_FLOAT, "ATC_RAT_YAW_D" }, -#if FRAME_CONFIG == HELI_FRAME - // PARAMETER_CONVERSION - Added: May-2016 - { Parameters::k_param_pid_rate_roll, 4, AP_PARAM_FLOAT, "ATC_RAT_RLL_VFF" }, - { Parameters::k_param_pid_rate_pitch, 4, AP_PARAM_FLOAT, "ATC_RAT_PIT_VFF" }, - { Parameters::k_param_pid_rate_yaw , 4, AP_PARAM_FLOAT, "ATC_RAT_YAW_VFF" }, -#endif - }; - const AP_Param::ConversionInfo imax_conversion_info[] = { - // PARAMETER_CONVERSION - Added: Apr-2016 - { Parameters::k_param_pid_rate_roll, 5, AP_PARAM_FLOAT, "ATC_RAT_RLL_IMAX" }, - { Parameters::k_param_pid_rate_pitch, 5, AP_PARAM_FLOAT, "ATC_RAT_PIT_IMAX" }, - { Parameters::k_param_pid_rate_yaw, 5, AP_PARAM_FLOAT, "ATC_RAT_YAW_IMAX" }, -#if FRAME_CONFIG == HELI_FRAME - // PARAMETER_CONVERSION - Added: May-2016 - { Parameters::k_param_pid_rate_roll, 7, AP_PARAM_FLOAT, "ATC_RAT_RLL_ILMI" }, - { Parameters::k_param_pid_rate_pitch, 7, AP_PARAM_FLOAT, "ATC_RAT_PIT_ILMI" }, - { Parameters::k_param_pid_rate_yaw, 7, AP_PARAM_FLOAT, "ATC_RAT_YAW_ILMI" }, -#endif - }; - // conversion from Copter-3.3 to Copter-3.4 const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = { - // PARAMETER_CONVERSION - Added: May-2016 - { Parameters::k_param_p_stabilize_roll, 0, AP_PARAM_FLOAT, "ATC_ANG_RLL_P" }, - { Parameters::k_param_p_stabilize_pitch, 0, AP_PARAM_FLOAT, "ATC_ANG_PIT_P" }, - { Parameters::k_param_p_stabilize_yaw, 0, AP_PARAM_FLOAT, "ATC_ANG_YAW_P" }, - // PARAMETER_CONVERSION - Added: Apr-2016 - { Parameters::k_param_pid_rate_roll, 6, AP_PARAM_FLOAT, "ATC_RAT_RLL_FILT" }, - { Parameters::k_param_pid_rate_pitch, 6, AP_PARAM_FLOAT, "ATC_RAT_PIT_FILT" }, // PARAMETER_CONVERSION - Added: Jan-2018 { Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" }, { Parameters::k_param_pi_vel_xy, 0, AP_PARAM_FLOAT, "PSC_VELXY_P" }, @@ -1429,11 +1390,6 @@ void Copter::convert_pid_parameters(void) { Parameters::k_param_p_alt_hold, 0, AP_PARAM_FLOAT, "PSC_POSZ_P" }, { Parameters::k_param_p_pos_xy, 0, AP_PARAM_FLOAT, "PSC_POSXY_P" }, }; - const AP_Param::ConversionInfo throttle_conversion_info[] = { - // PARAMETER_CONVERSION - Added: Jun-2016 - { Parameters::k_param_throttle_min, 0, AP_PARAM_FLOAT, "MOT_SPIN_MIN" }, - { Parameters::k_param_throttle_mid, 0, AP_PARAM_FLOAT, "MOT_THST_HOVER" } - }; const AP_Param::ConversionInfo loiter_conversion_info[] = { // PARAMETER_CONVERSION - Added: Apr-2018 { Parameters::k_param_wp_nav, 4, AP_PARAM_FLOAT, "LOIT_SPEED" }, @@ -1442,34 +1398,10 @@ void Copter::convert_pid_parameters(void) { Parameters::k_param_wp_nav, 9, AP_PARAM_FLOAT, "LOIT_BRK_ACCEL" } }; - // PARAMETER_CONVERSION - Added: Apr-2016 - // gains increase by 27% due to attitude controller's switch to use radians instead of centi-degrees - // and motor libraries switch to accept inputs in -1 to +1 range instead of -4500 ~ +4500 - float pid_scaler = 1.27f; - -#if FRAME_CONFIG != HELI_FRAME - // Multicopter x-frame gains are 40% lower because -1 or +1 input to motors now results in maximum rotation - if (g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_X || g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_V || g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_H) { - pid_scaler = 0.9f; - } -#endif - - // scale PID gains - for (const auto &info : pid_conversion_info) { - AP_Param::convert_old_parameter(&info, pid_scaler); - } - // reduce IMAX into -1 ~ +1 range - for (const auto &info : imax_conversion_info) { - AP_Param::convert_old_parameter(&info, 1.0f/4500.0f); - } // convert angle controller gain and filter without scaling for (const auto &info : angle_and_filt_conversion_info) { AP_Param::convert_old_parameter(&info, 1.0f); } - // convert throttle parameters (multicopter only) - for (const auto &info : throttle_conversion_info) { - AP_Param::convert_old_parameter(&info, 0.001f); - } // convert RC_FEEL_RP to ATC_INPUT_TC // PARAMETER_CONVERSION - Added: Mar-2018 const AP_Param::ConversionInfo rc_feel_rp_conversion_info = { Parameters::k_param_rc_feel_rp, 0, AP_PARAM_INT8, "ATC_INPUT_TC" }; From caa77ccba81ea48ba6f0e8dab4fabe56ea597d13 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 3 Apr 2023 16:56:36 +1000 Subject: [PATCH 116/287] Copter: remove very old parameter conversion information --- ArduCopter/Parameters.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 1736d158b01436..71ef92699fafb3 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1294,12 +1294,6 @@ ParametersG2::ParametersG2(void) old object. This should be zero for top level parameters. */ const AP_Param::ConversionInfo conversion_table[] = { - // PARAMETER_CONVERSION - Added: Oct-2014 - { Parameters::k_param_log_bitmask_old, 0, AP_PARAM_INT16, "LOG_BITMASK" }, - // PARAMETER_CONVERSION - Added: Jan-2015 - { Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" }, - { Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" }, - { Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" }, // PARAMETER_CONVERSION - Added: Jan-2017 { Parameters::k_param_arming_check_old, 0, AP_PARAM_INT8, "ARMING_CHECK" }, // battery From ffed6e0f26b27e8b17f4e1efc2fd17a85afed9d9 Mon Sep 17 00:00:00 2001 From: pedro-fuoco Date: Thu, 30 Mar 2023 23:30:27 -0300 Subject: [PATCH 117/287] AP_DDS: Switch NavSatFix topic to sensor data QOS * Change Reliability to BEST_EFFORT * Change Durability to VOLATILE * Change to smaller queue size on NavSatFix QOS --- libraries/AP_DDS/dds_xrce_profile.xml | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/libraries/AP_DDS/dds_xrce_profile.xml b/libraries/AP_DDS/dds_xrce_profile.xml index 6672867662ed4a..a8089b76af9df5 100644 --- a/libraries/AP_DDS/dds_xrce_profile.xml +++ b/libraries/AP_DDS/dds_xrce_profile.xml @@ -35,15 +35,18 @@ sensor_msgs::msg::dds_::NavSatFix_ KEEP_LAST - 20 + 5 PREALLOCATED_WITH_REALLOC - RELIABLE + BEST_EFFORT + + VOLATILE + NO_KEY @@ -51,7 +54,7 @@ sensor_msgs::msg::dds_::NavSatFix_ KEEP_LAST - 20 + 5 From 999eb5b03f80ac0ebfe256d834c8349861bd4b1f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 22 Mar 2023 17:10:22 +0000 Subject: [PATCH 118/287] SRV_Channel: move FUNCTION @Values to multi line format --- libraries/SRV_Channel/SRV_Channel.cpp | 96 +++++++++++++++++++++++++-- 1 file changed, 92 insertions(+), 4 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channel.cpp b/libraries/SRV_Channel/SRV_Channel.cpp index 105eb21c2f72a9..a3246a58a9038b 100644 --- a/libraries/SRV_Channel/SRV_Channel.cpp +++ b/libraries/SRV_Channel/SRV_Channel.cpp @@ -64,10 +64,98 @@ const AP_Param::GroupInfo SRV_Channel::var_info[] = { // @Param: FUNCTION // @DisplayName: Servo output function // @Description: Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function - // @Values: -1:GPIO,0:Disabled,1:RCPassThru,2:Flap,3:FlapAuto,4:Aileron,6:Mount1Yaw,7:Mount1Pitch,8:Mount1Roll,9:Mount1Retract,10:CameraTrigger,12:Mount2Yaw,13:Mount2Pitch,14:Mount2Roll,15:Mount2Retract,16:DifferentialSpoilerLeft1,17:DifferentialSpoilerRight1,19:Elevator,21:Rudder,22:SprayerPump,23:SprayerSpinner,24:FlaperonLeft,25:FlaperonRight,26:GroundSteering,27:Parachute,28:Gripper,29:LandingGear,30:EngineRunEnable,31:HeliRSC,32:HeliTailRSC,33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8,41:TiltMotorsFront,45:TiltMotorsRear,46:TiltMotorRearLeft,47:TiltMotorRearRight,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,67:Ignition,69:Starter,70:Throttle,71:TrackerYaw,72:TrackerPitch,73:ThrottleLeft,74:ThrottleRight,75:TiltMotorFrontLeft,76:TiltMotorFrontRight,77:ElevonLeft,78:ElevonRight,79:VTailLeft,80:VTailRight,81:BoostThrottle,82:Motor9,83:Motor10,84:Motor11,85:Motor12,86:DifferentialSpoilerLeft2,87:DifferentialSpoilerRight2,88:Winch,89:Main Sail,90:CameraISO,91:CameraAperture,92:CameraFocus,93:CameraShutterSpeed,94:Script1,95:Script2,96:Script3,97:Script4,98:Script5,99:Script6,100:Script7,101:Script8,102:Script9,103:Script10,104:Script11,105:Script12,106:Script13,107:Script14,108:Script15,109:Script16,120:NeoPixel1,121:NeoPixel2,122:NeoPixel3,123:NeoPixel4,124:RateRoll,125:RatePitch,126:RateThrust,127:RateYaw,128:WingSailElevator,129:ProfiLED1,130:ProfiLED2,131:ProfiLED3,132:ProfiLEDClock,133:Winch Clutch,134:SERVOn_MIN,135:SERVOn_TRIM,136:SERVOn_MAX,137:SailMastRotation,138:Alarm,139:Alarm Inverted,140:RCIN1Scaled,141:RCIN2Scaled,142:RCIN3Scaled,143:RCIN4Scaled,144:RCIN5Scaled,145:RCIN6Scaled,146:RCIN7Scaled,147:RCIN8Scaled,148:RCIN9Scaled,149:RCIN10Scaled,150:RCIN11Scaled,151:RCIN12Scaled,152:RCIN13Scaled,153:RCIN14Scaled,154:RCIN15Scaled,155:RCIN16Scaled - // @Values{Plane}: -1:GPIO,0:Disabled,1:RCPassThru,2:Flap,3:FlapAuto,4:Aileron,6:Mount1Yaw,7:Mount1Pitch,8:Mount1Roll,9:Mount1Retract,10:CameraTrigger,12:Mount2Yaw,13:Mount2Pitch,14:Mount2Roll,15:Mount2Retract,16:DifferentialSpoilerLeft1,17:DifferentialSpoilerRight1,19:Elevator,21:Rudder,22:SprayerPump,23:SprayerSpinner,24:FlaperonLeft,25:FlaperonRight,26:GroundSteering,27:Parachute,28:Gripper,29:LandingGear,30:EngineRunEnable,33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7/TailTiltServo,40:Motor8,41:TiltMotorsFront,45:TiltMotorsRear,46:TiltMotorRearLeft,47:TiltMotorRearRight,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,67:Ignition,69:Starter,70:Throttle,73:ThrottleLeft,74:ThrottleRight,75:TiltMotorFrontLeft,76:TiltMotorFrontRight,77:ElevonLeft,78:ElevonRight,79:VTailLeft,80:VTailRight,82:Motor9,83:Motor10,84:Motor11,85:Motor12,86:DifferentialSpoilerLeft2,87:DifferentialSpoilerRight2,90:CameraISO,91:CameraAperture,92:CameraFocus,93:CameraShutterSpeed,94:Script1,95:Script2,96:Script3,97:Script4,98:Script5,99:Script6,100:Script7,101:Script8,102:Script9,103:Script10,104:Script11,105:Script12,106:Script13,107:Script14,108:Script15,109:Script16,110:Airbrakes,120:NeoPixel1,121:NeoPixel2,122:NeoPixel3,123:NeoPixel4,124:RateRoll,125:RatePitch,126:RateThrust,127:RateYaw,129:ProfiLED1,130:ProfiLED2,131:ProfiLED3,132:ProfiLEDClock,134:SERVOn_MIN,135:SERVOn_TRIM,136:SERVOn_MAX,138:Alarm,139:Alarm Inverted,140:RCIN1Scaled,141:RCIN2Scaled,142:RCIN3Scaled,143:RCIN4Scaled,144:RCIN5Scaled,145:RCIN6Scaled,146:RCIN7Scaled,147:RCIN8Scaled,148:RCIN9Scaled,149:RCIN10Scaled,150:RCIN11Scaled,151:RCIN12Scaled,152:RCIN13Scaled,153:RCIN14Scaled,154:RCIN15Scaled,155:RCIN16Scaled - // @Values{Copter}: -1:GPIO,0:Disabled,1:RCPassThru,6:Mount1Yaw,7:Mount1Pitch,8:Mount1Roll,9:Mount1Retract,10:CameraTrigger,12:Mount2Yaw,13:Mount2Pitch,14:Mount2Roll,15:Mount2Retract,22:SprayerPump,23:SprayerSpinner,27:Parachute,28:Gripper,29:LandingGear,30:EngineRunEnable,31:HeliRSC,32:HeliTailRSC,33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,73:ThrottleLeft,74:ThrottleRight,75:TiltMotorFrontLeft,76:TiltMotorFrontRight,81:BoostThrottle,82:Motor9,83:Motor10,84:Motor11,85:Motor12,88:Winch,90:CameraISO,91:CameraAperture,92:CameraFocus,93:CameraShutterSpeed,94:Script1,95:Script2,96:Script3,97:Script4,98:Script5,99:Script6,100:Script7,101:Script8,102:Script9,103:Script10,104:Script11,105:Script12,106:Script13,107:Script14,108:Script15,109:Script16,120:NeoPixel1,121:NeoPixel2,122:NeoPixel3,123:NeoPixel4,124:RateRoll,125:RatePitch,126:RateThrust,127:RateYaw,129:ProfiLED1,130:ProfiLED2,131:ProfiLED3,132:ProfiLEDClock,133:Winch Clutch,134:SERVOn_MIN,135:SERVOn_TRIM,136:SERVOn_MAX,138:Alarm,139:Alarm Inverted,140:RCIN1Scaled,141:RCIN2Scaled,142:RCIN3Scaled,143:RCIN4Scaled,144:RCIN5Scaled,145:RCIN6Scaled,146:RCIN7Scaled,147:RCIN8Scaled,148:RCIN9Scaled,149:RCIN10Scaled,150:RCIN11Scaled,151:RCIN12Scaled,152:RCIN13Scaled,153:RCIN14Scaled,154:RCIN15Scaled,155:RCIN16Scaled - // @Values{Rover}: -1:GPIO,0:Disabled,1:RCPassThru,6:Mount1Yaw,7:Mount1Pitch,8:Mount1Roll,9:Mount1Retract,10:CameraTrigger,12:Mount2Yaw,13:Mount2Pitch,14:Mount2Roll,15:Mount2Retract,22:SprayerPump,23:SprayerSpinner,26:GroundSteering,28:Gripper,33:Motor1,34:Motor2,35:Motor3,36:Motor4,51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16,70:Throttle,73:ThrottleLeft,74:ThrottleRight,88:Winch,89:Main Sail,90:CameraISO,91:CameraAperture,92:CameraFocus,93:CameraShutterSpeed,94:Script1,95:Script2,96:Script3,97:Script4,98:Script5,99:Script6,100:Script7,101:Script8,102:Script9,103:Script10,104:Script11,105:Script12,106:Script13,107:Script14,108:Script15,109:Script16,120:NeoPixel1,121:NeoPixel2,122:NeoPixel3,123:NeoPixel4,128:WingSailElevator,129:ProfiLED1,130:ProfiLED2,131:ProfiLED3,132:ProfiLEDClock,133:Winch Clutch,134:SERVOn_MIN,135:SERVOn_TRIM,136:SERVOn_MAX,137:SailMastRotation,138:Alarm,139:Alarm Inverted,140:RCIN1Scaled,141:RCIN2Scaled,142:RCIN3Scaled,143:RCIN4Scaled,144:RCIN5Scaled,145:RCIN6Scaled,146:RCIN7Scaled,147:RCIN8Scaled,148:RCIN9Scaled,149:RCIN10Scaled,150:RCIN11Scaled,151:RCIN12Scaled,152:RCIN13Scaled,153:RCIN14Scaled,154:RCIN15Scaled,155:RCIN16Scaled + // @Values: -1:GPIO + // @Values{Plane, Copter, Rover}: -1:GPIO + // @Values: 0:Disabled + // @Values{Plane, Copter, Rover}: 0:Disabled + // @Values: 1:RCPassThru + // @Values{Plane, Copter, Rover}: 1:RCPassThru + // @Values: 2:Flap, 3:FlapAuto + // @Values{Plane}: 2:Flap,3:FlapAuto + // @Values: 4:Aileron + // @Values{Plane}: 4:Aileron + // @Values: 6:Mount1Yaw,7:Mount1Pitch,8:Mount1Roll,9:Mount1Retract + // @Values{Plane, Copter, Rover}: 6:Mount1Yaw,7:Mount1Pitch,8:Mount1Roll,9:Mount1Retract + // @Values: 10:CameraTrigger + // @Values{Plane, Copter, Rover}: 10:CameraTrigger + // @Values: 12:Mount2Yaw,13:Mount2Pitch,14:Mount2Roll,15:Mount2Retract + // @Values{Plane, Copter, Rover}: 12:Mount2Yaw,13:Mount2Pitch,14:Mount2Roll,15:Mount2Retract + // @Values: 16:DifferentialSpoilerLeft1,17:DifferentialSpoilerRight1 + // @Values{Plane}: 16:DifferentialSpoilerLeft1,17:DifferentialSpoilerRight1 + // @Values: 19:Elevator + // @Values{Plane}: 19:Elevator + // @Values: 21:Rudder + // @Values{Plane}: 21:Rudder + // @Values: 22:SprayerPump,23:SprayerSpinner + // @Values{Plane, Copter, Rover}: 22:SprayerPump,23:SprayerSpinner + // @Values: 24:FlaperonLeft,25:FlaperonRight + // @Values{Plane}: 24:FlaperonLeft,25:FlaperonRight + // @Values: 26:GroundSteering + // @Values{Plane, Rover}: 26:GroundSteering + // @Values: 27:Parachute + // @Values{Plane, Copter}: 27:Parachute + // @Values: 28:Gripper + // @Values{Plane, Copter, Rover}: 28:Gripper + // @Values: 29:LandingGear + // @Values{Plane, Copter}: 29:LandingGear + // @Values: 30:EngineRunEnable + // @Values{Plane, Copter}: 30:EngineRunEnable + // @Values: 31:HeliRSC,32:HeliTailRSC + // @Values{Copter}: 31:HeliRSC,32:HeliTailRSC + // @Values: 33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8 + // @Values{Plane}: 33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7/TailTiltServo,40:Motor8 + // @Values{Copter}: 33:Motor1,34:Motor2,35:Motor3,36:Motor4,37:Motor5,38:Motor6,39:Motor7,40:Motor8 + // @Values{Rover}: 33:Motor1,34:Motor2,35:Motor3,36:Motor4 + // @Values: 41:TiltMotorsFront,45:TiltMotorsRear,46:TiltMotorRearLeft,47:TiltMotorRearRight + // @Values{Plane}: 41:TiltMotorsFront,45:TiltMotorsRear,46:TiltMotorRearLeft,47:TiltMotorRearRight + // @Values: 51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16 + // @Values{Plane, Copter, Rover}: 51:RCIN1,52:RCIN2,53:RCIN3,54:RCIN4,55:RCIN5,56:RCIN6,57:RCIN7,58:RCIN8,59:RCIN9,60:RCIN10,61:RCIN11,62:RCIN12,63:RCIN13,64:RCIN14,65:RCIN15,66:RCIN16 + // @Values: 67:Ignition,69:Starter + // @Values{Plane}: 67:Ignition,69:Starter + // @Values: 70:Throttle + // @Values{Plane, Rover}: 70:Throttle + // @Values: 71:TrackerYaw,72:TrackerPitch + // @Values: 73:ThrottleLeft,74:ThrottleRight + // @Values{Plane, Copter, Rover}: 73:ThrottleLeft,74:ThrottleRight + // @Values: 75:TiltMotorFrontLeft,76:TiltMotorFrontRight + // @Values{Plane, Copter}: 75:TiltMotorFrontLeft,76:TiltMotorFrontRight + // @Values: 77:ElevonLeft,78:ElevonRight + // @Values{Plane}: 77:ElevonLeft,78:ElevonRight + // @Values: 79:VTailLeft,80:VTailRight + // @Values{Plane}: 79:VTailLeft,80:VTailRight + // @Values: 81:BoostThrottle + // @Values{Copter}: 81:BoostThrottle + // @Values: 82:Motor9,83:Motor10,84:Motor11,85:Motor12 + // @Values{Plane, Copter}: 82:Motor9,83:Motor10,84:Motor11,85:Motor12 + // @Values: 86:DifferentialSpoilerLeft2,87:DifferentialSpoilerRight2 + // @Values{Plane}: 86:DifferentialSpoilerLeft2,87:DifferentialSpoilerRight2 + // @Values: 88:Winch + // @Values{Copter, Rover}: 88:Winch + // @Values: 89:Main Sail + // @Values{Rover}: 89:Main Sail + // @Values: 90:CameraISO,91:CameraAperture,92:CameraFocus,93:CameraShutterSpeed + // @Values{Plane, Copter, Rover}: 90:CameraISO,91:CameraAperture,92:CameraFocus,93:CameraShutterSpeed + // @Values: 94:Script1,95:Script2,96:Script3,97:Script4,98:Script5,99:Script6,100:Script7,101:Script8,102:Script9,103:Script10,104:Script11,105:Script12,106:Script13,107:Script14,108:Script15,109:Script16 + // @Values{Plane, Copter, Rover}: 94:Script1,95:Script2,96:Script3,97:Script4,98:Script5,99:Script6,100:Script7,101:Script8,102:Script9,103:Script10,104:Script11,105:Script12,106:Script13,107:Script14,108:Script15,109:Script16 + // @Values{Plane}: 110:Airbrakes + // @Values: 120:NeoPixel1,121:NeoPixel2,122:NeoPixel3,123:NeoPixel4 + // @Values{Plane, Copter, Rover}: 120:NeoPixel1,121:NeoPixel2,122:NeoPixel3,123:NeoPixel4 + // @Values: 124:RateRoll,125:RatePitch,126:RateThrust,127:RateYaw + // @Values{Plane, Copter}: 124:RateRoll,125:RatePitch,126:RateThrust,127:RateYaw + // @Values: 128:WingSailElevator + // @Values{Rover}: 128:WingSailElevator + // @Values: 129:ProfiLED1,130:ProfiLED2,131:ProfiLED3,132:ProfiLEDClock + // @Values{Plane, Copter, Rover}: 129:ProfiLED1,130:ProfiLED2,131:ProfiLED3,132:ProfiLEDClock + // @Values: 133:Winch Clutch + // @Values{Copter, Rover}: 133:Winch Clutch + // @Values: 134:SERVOn_MIN,135:SERVOn_TRIM,136:SERVOn_MAX + // @Values{Plane, Copter, Rover}: 134:SERVOn_MIN,135:SERVOn_TRIM,136:SERVOn_MAX + // @Values: 137:SailMastRotation + // @Values{Rover}: 137:SailMastRotation + // @Values: 138:Alarm,139:Alarm Inverted + // @Values{Plane, Copter, Rover}: 138:Alarm,139:Alarm Inverted + // @Values: 140:RCIN1Scaled,141:RCIN2Scaled,142:RCIN3Scaled,143:RCIN4Scaled,144:RCIN5Scaled,145:RCIN6Scaled,146:RCIN7Scaled,147:RCIN8Scaled,148:RCIN9Scaled,149:RCIN10Scaled,150:RCIN11Scaled,151:RCIN12Scaled,152:RCIN13Scaled,153:RCIN14Scaled,154:RCIN15Scaled,155:RCIN16Scaled + // @Values{Plane, Copter, Rover}: 140:RCIN1Scaled,141:RCIN2Scaled,142:RCIN3Scaled,143:RCIN4Scaled,144:RCIN5Scaled,145:RCIN6Scaled,146:RCIN7Scaled,147:RCIN8Scaled,148:RCIN9Scaled,149:RCIN10Scaled,150:RCIN11Scaled,151:RCIN12Scaled,152:RCIN13Scaled,153:RCIN14Scaled,154:RCIN15Scaled,155:RCIN16Scaled // @User: Standard // @RebootRequired: True AP_GROUPINFO("FUNCTION", 5, SRV_Channel, function, 0), From aa863523a6467e551eb749c0b73129b4b454259f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 4 Apr 2023 21:19:27 +1000 Subject: [PATCH 119/287] Tools: remove dsdl_generated before building bootloader waf doesn't take care of this for us --- Tools/scripts/size_compare_branches.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index 55f57761dc5418..092e718c797dcc 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -298,6 +298,11 @@ def build_branch_into_dir(self, board, branch, vehicle, outdir, extra_hwdef=None # need special configuration directive bootloader_waf_configure_args = copy.copy(waf_configure_args) bootloader_waf_configure_args.append('--bootloader') + # hopefully temporary hack so you can build bootloader + # after building other vehicles without a clean: + dsdl_generated_path = os.path.join('build', board, "modules", "DroneCAN", "libcanard", "dsdlc_generated") + self.progress("HACK: Removing (%s)" % dsdl_generated_path) + shutil.rmtree(dsdl_generated_path, ignore_errors=True) self.run_waf(bootloader_waf_configure_args) self.run_waf([v]) self.run_program("rsync", ["rsync", "-aP", "build/", outdir]) From 00858dce7834105fe86414194e357cef02d3694d Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 3 Apr 2023 07:42:53 -0500 Subject: [PATCH 120/287] AP_InertialSensor: add buzzer noises --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index a69a0c4fd3d222..a3decab52787f5 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1675,6 +1675,7 @@ AP_InertialSensor::_init_gyro() // stop flashing leds AP_Notify::flags.initialising = false; + AP_Notify::flags.gyro_calibrated = true; } // save parameters to eeprom From ec1d29d8061dbc01414d594a9c406879d271ceda Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 3 Apr 2023 07:42:53 -0500 Subject: [PATCH 121/287] AP_Notify: add buzzer noises --- libraries/AP_Notify/AP_Notify.h | 1 + libraries/AP_Notify/Buzzer.cpp | 12 ++++++++++++ libraries/AP_Notify/Buzzer.h | 4 ++++ 3 files changed, 17 insertions(+) diff --git a/libraries/AP_Notify/AP_Notify.h b/libraries/AP_Notify/AP_Notify.h index 5649966f3722a5..55f296994beffc 100644 --- a/libraries/AP_Notify/AP_Notify.h +++ b/libraries/AP_Notify/AP_Notify.h @@ -123,6 +123,7 @@ class AP_Notify bool powering_off; // true when the vehicle is powering off bool video_recording; // true when the vehicle is recording video bool temp_cal_running; // true if a temperature calibration is running + bool gyro_calibrated; // true if calibrated gyro/acc }; /// notify_events_type - bitmask of active events. diff --git a/libraries/AP_Notify/Buzzer.cpp b/libraries/AP_Notify/Buzzer.cpp index acfde7ce5e1cb5..14d7b3299670ab 100644 --- a/libraries/AP_Notify/Buzzer.cpp +++ b/libraries/AP_Notify/Buzzer.cpp @@ -66,6 +66,18 @@ void Buzzer::update_pattern_to_play() return; } + // initializing? + if (_flags.gyro_calibrated != AP_Notify::flags.gyro_calibrated) { + _flags.gyro_calibrated = AP_Notify::flags.gyro_calibrated; + play_pattern(INIT_GYRO); + } + + // check if prearm check are good + if (AP_Notify::flags.pre_arm_check && !_flags.pre_arm_check) { + _flags.pre_arm_check = true; + play_pattern(PRE_ARM_GOOD); + } + // check if armed status has changed if (_flags.armed != AP_Notify::flags.armed) { _flags.armed = AP_Notify::flags.armed; diff --git a/libraries/AP_Notify/Buzzer.h b/libraries/AP_Notify/Buzzer.h index 4098148e76d37d..8bf81d18fc5ac3 100644 --- a/libraries/AP_Notify/Buzzer.h +++ b/libraries/AP_Notify/Buzzer.h @@ -43,6 +43,8 @@ class Buzzer: public NotifyDevice static const uint32_t ARMING_BUZZ = 0b11111111111111111111111111111100UL; // 3s static const uint32_t BARO_BUZZ = 0b10101010100000000000000000000000UL; static const uint32_t EKF_BAD = 0b11101101010000000000000000000000UL; + static const uint32_t INIT_GYRO = 0b10010010010010010010000000000000UL; + static const uint32_t PRE_ARM_GOOD = 0b10101011111111110000000000000000UL; /// play_pattern - plays the defined buzzer pattern void play_pattern(const uint32_t pattern); @@ -54,6 +56,8 @@ class Buzzer: public NotifyDevice uint8_t armed : 1; // 0 = disarmed, 1 = armed uint8_t failsafe_battery : 1; // 1 if battery failsafe has triggered uint8_t ekf_bad : 1; // 1 if ekf position has gone bad + uint8_t gyro_calibrated : 1; // 1 if calibrating gyro + uint8_t pre_arm_check : 1; // 1 if pre-arm check has passed } _flags; uint32_t _pattern; // current pattern From d8bc223fe45d3fefba9e0430afa845548d295eff Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 4 Apr 2023 23:52:52 +1000 Subject: [PATCH 122/287] autotest: param_parse.py: recurse, don't glob in lua script dirs many scripts are now categoriesed e.g. Aerobatics --- Tools/autotest/param_metadata/param_parse.py | 22 +++++++++++--------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/Tools/autotest/param_metadata/param_parse.py b/Tools/autotest/param_metadata/param_parse.py index b5585192bf6eb9..fce23c9c10a276 100755 --- a/Tools/autotest/param_metadata/param_parse.py +++ b/Tools/autotest/param_metadata/param_parse.py @@ -12,7 +12,6 @@ import os import re import sys -import glob from argparse import ArgumentParser from param import (Library, Parameter, Vehicle, known_group_fields, @@ -91,16 +90,19 @@ def debug(str_to_print): def lua_applets(): '''return list of Library objects for lua applets and drivers''' lua_lib = Library("", reference="Lua Script", not_rst=True, check_duplicates=True) - patterns = ["libraries/AP_Scripting/applets/*.lua", "libraries/AP_Scripting/drivers/*.lua"] + dirs = ["libraries/AP_Scripting/applets", "libraries/AP_Scripting/drivers"] paths = [] - for p in patterns: - debug("Adding lua paths %s" % p) - luafiles = glob.glob(os.path.join(apm_path, p)) - for f in luafiles: - # the library is expected to have the path as a relative path from within - # a vehicle directory - f = f.replace(apm_path, "../") - paths.append(f) + for d in dirs: + for root, dirs, files in os.walk(os.path.join(apm_path, d)): + for file in files: + if not file.endswith(".lua"): + continue + f = os.path.join(root, file) + debug("Adding lua path %s" % f) + # the library is expected to have the path as a relative path from within + # a vehicle directory + f = f.replace(apm_path, "../") + paths.append(f) setattr(lua_lib, "Path", ','.join(paths)) return lua_lib From 13cdc8bda895d8f6b1b6340ffe2272d14e0c55df Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Tue, 4 Apr 2023 18:09:18 +1000 Subject: [PATCH 123/287] AP_InertialSensor: fix hardfault in BatchSampler --- libraries/AP_InertialSensor/AP_InertialSensor.h | 1 + .../AP_InertialSensor_Logging.cpp | 2 +- libraries/AP_InertialSensor/BatchSampler.cpp | 14 ++++++++------ 3 files changed, 10 insertions(+), 7 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 4c4a839d8daf19..db108eb1991c3c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -329,6 +329,7 @@ class AP_InertialSensor : AP_AccelCal_Client // Parameters AP_Int16 _required_count; + uint16_t _real_required_count; AP_Int8 _sensor_mask; AP_Int8 _batch_options_mask; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp index 48f7c4105018dd..cbf5f8db6836cb 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp @@ -111,7 +111,7 @@ bool AP_InertialSensor::BatchSampler::Write_ISBH(const float sample_rate_hz) con sensor_type : (uint8_t)type, instance : instance_to_write, multiplier : multiplier, - sample_count : (uint16_t)_required_count, + sample_count : (uint16_t)_real_required_count, sample_us : measurement_started_us, sample_rate_hz : sample_rate_hz, }; diff --git a/libraries/AP_InertialSensor/BatchSampler.cpp b/libraries/AP_InertialSensor/BatchSampler.cpp index a125f1a2868396..e86a3f559c0e7a 100644 --- a/libraries/AP_InertialSensor/BatchSampler.cpp +++ b/libraries/AP_InertialSensor/BatchSampler.cpp @@ -58,12 +58,14 @@ void AP_InertialSensor::BatchSampler::init() _required_count.set(_required_count - (_required_count % 32)); // round down to nearest multiple of 32 - const uint32_t total_allocation = 3*_required_count*sizeof(uint16_t); + _real_required_count = _required_count; + + const uint32_t total_allocation = 3*_real_required_count*sizeof(uint16_t); GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "INS: alloc %u bytes for ISB (free=%u)", (unsigned int)total_allocation, (unsigned int)hal.util->available_memory()); - data_x = (int16_t*)calloc(_required_count, sizeof(int16_t)); - data_y = (int16_t*)calloc(_required_count, sizeof(int16_t)); - data_z = (int16_t*)calloc(_required_count, sizeof(int16_t)); + data_x = (int16_t*)calloc(_real_required_count, sizeof(int16_t)); + data_y = (int16_t*)calloc(_real_required_count, sizeof(int16_t)); + data_z = (int16_t*)calloc(_real_required_count, sizeof(int16_t)); if (data_x == nullptr || data_y == nullptr || data_z == nullptr) { free(data_x); free(data_y); @@ -226,7 +228,7 @@ void AP_InertialSensor::BatchSampler::push_data_to_log() data_read_offset += samples_per_msg; last_sent_ms = AP_HAL::millis(); - if (data_read_offset >= _required_count) { + if (data_read_offset >= _real_required_count) { // that was the last one. Clean up: data_read_offset = 0; isb_seqnum++; @@ -251,7 +253,7 @@ bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_T if (_type != type) { return false; } - if (data_write_offset >= _required_count) { + if (data_write_offset >= _real_required_count) { return false; } AP_Logger *logger = AP_Logger::get_singleton(); From 9643f44ecc2c834616698e5cc05dbd509a2e08b7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Mar 2023 09:21:14 +1100 Subject: [PATCH 124/287] hwdef: skyviper has only companion support for precision landing --- libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat index 12a1c79a3c46b0..99c17ffc6df97b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat @@ -173,4 +173,8 @@ define AP_CAMERA_MAVLINK_ENABLED 1 // remove RC Protocol support: define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0 +// few prelcnad backends are applicable +define AC_PRECLAND_BACKEND_DEFAULT_ENABLED 0 +define AC_PRECLAND_COMPANION_ENABLED 1 + AUTOBUILD_TARGETS Copter From 09dbf53454c638243178684336a1a7a3b971c780 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Mar 2023 09:24:41 +1100 Subject: [PATCH 125/287] AC_PrecLand: fixes for feature disablement --- libraries/AC_PrecLand/AC_PrecLand.cpp | 8 +++++++- libraries/AC_PrecLand/AC_PrecLand.h | 8 ++++++++ 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index b2e2212239cdae..398286b878aca5 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -241,17 +241,23 @@ void AC_PrecLand::init(uint16_t update_rate_hz) default: return; // companion computer +#if AC_PRECLAND_COMPANION_ENABLED case Type::COMPANION: _backend = new AC_PrecLand_Companion(*this, _backend_state); break; // IR Lock +#endif +#if AC_PRECLAND_IRLOCK_ENABLED case Type::IRLOCK: _backend = new AC_PrecLand_IRLock(*this, _backend_state); break; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif +#if AC_PRECLAND_SITL_GAZEBO_ENABLED case Type::SITL_GAZEBO: _backend = new AC_PrecLand_SITL_Gazebo(*this, _backend_state); break; +#endif +#if AC_PRECLAND_SITL_ENABLED case Type::SITL: _backend = new AC_PrecLand_SITL(*this, _backend_state); break; diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 397739c9f7a661..6826bded51fdaf 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -127,10 +127,18 @@ class AC_PrecLand // types of precision landing (used for PRECLAND_TYPE parameter) enum class Type : uint8_t { NONE = 0, +#if AC_PRECLAND_COMPANION_ENABLED COMPANION = 1, +#endif +#if AC_PRECLAND_IRLOCK_ENABLED IRLOCK = 2, +#endif +#if AC_PRECLAND_SITL_GAZEBO_ENABLED SITL_GAZEBO = 3, +#endif +#if AC_PRECLAND_SITL_ENABLED SITL = 4, +#endif }; enum PLndOptions { From 149b0e68f2c396541b1db153474a5de86395bd5c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Mar 2023 09:29:34 +1100 Subject: [PATCH 126/287] build_options.py: add options for companion and IRLock --- Tools/scripts/build_options.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 5e097ea0e9a019..0df5c2578d3e1f 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -285,6 +285,8 @@ def __init__(self, Feature('Actuators', 'FETTecOneWire', 'AP_FETTEC_ONEWIRE_ENABLED', 'Enable FETTec OneWire ESCs', 0, None), Feature('Precision Landing', 'PrecLand', 'AC_PRECLAND_ENABLED', 'Enable Precision Landing support', 0, None), + Feature('Precision Landing', 'PrecLand - Companion', 'AC_PRECLAND_COMPANION_ENABLED', 'Enable Companion-Supported Precision Landing support', 0, "PrecLand"), # noqa + Feature('Precision Landing', 'PrecLand - IRLock', 'AC_PRECLAND_IRLOCK_ENABLED', 'Enable IRLock-Supported Precision Landing support', 0, "PrecLand"), # noqa ] BUILD_OPTIONS.sort(key=lambda x: (x.category + x.label)) From 59c2197029ebb2a41e7db869c0fd6ecf24619ded Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Mar 2023 22:07:27 +1100 Subject: [PATCH 127/287] Tools: extract_features: extract precland backend features --- Tools/scripts/extract_features.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 394874ad2a5e26..90e22f16aeb505 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -40,6 +40,8 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_AIRSPEED_{type}_ENABLED', r'AP_Airspeed_(?P.*)::init',), ('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',), + ('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',), + ('AC_PRECLAND_{type}_ENABLED', 'AC_PrecLand_(?P.*)::update',), ('HAL_ADSB_ENABLED', 'AP_ADSB::AP_ADSB',), ('HAL_ADSB_{type}_ENABLED', r'AP_ADSB_(?P.*)::update',), From c6060dd047de64b6a6ca28ec49b331f1707d39e3 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 4 Apr 2023 22:43:11 -0600 Subject: [PATCH 128/287] AP_GPS: Fix spelling in receiver Signed-off-by: Ryan Friedman --- libraries/AP_GPS/MovingBase.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/MovingBase.h b/libraries/AP_GPS/MovingBase.h index 77de2a02fd4d8f..7df25fe0a2ae64 100644 --- a/libraries/AP_GPS/MovingBase.h +++ b/libraries/AP_GPS/MovingBase.h @@ -18,6 +18,6 @@ class MovingBase { }; AP_Int8 type; // an option from MovingBaseType - AP_Vector3f base_offset; // base position offset from the selected GPS reciever + AP_Vector3f base_offset; // base position offset from the selected GPS receiver }; From 1345e0615223bbafeb67e0815502adafe958808f Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 4 Apr 2023 22:43:28 -0600 Subject: [PATCH 129/287] AP_HAL_ESP32: Fix spelling receiver Signed-off-by: Ryan Friedman --- libraries/AP_HAL_ESP32/README.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_ESP32/README.md b/libraries/AP_HAL_ESP32/README.md index 1fbebf13f018d9..6c67ed0bc0241d 100644 --- a/libraries/AP_HAL_ESP32/README.md +++ b/libraries/AP_HAL_ESP32/README.md @@ -169,13 +169,13 @@ After flashing the esp32 , u can connect with a terminal app of your preference | GND | GND | | 5v | Pwr | -### RC reciever connection: +### RC receiver connection: -|ESP32| RCRECIEVER | -| --- | --- | -| D4 | CPPM-out | -| GND | GND | -| 5v | Pwr | +|ESP32| RC Receiver | +| --- | --- | +| D4 | CPPM-out | +| GND | GND | +| 5v | Pwr | ### I2C connection ( for gps with leds/compass-es/etc onboard, or digital airspeed sensorrs, etc): From 95354ac5726a000d94f28475601641fda5304df3 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 4 Apr 2023 22:43:50 -0600 Subject: [PATCH 130/287] RC_Channel: Fix spelling in receiver Signed-off-by: Ryan Friedman --- libraries/RC_Channel/RC_Channel.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index e8fedae4c71947..f19ab87a19abc1 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -582,7 +582,7 @@ class RC_Channels { // get mask of enabled protocols uint32_t enabled_protocols() const; - // returns true if we have had a direct detach RC reciever, does not include overrides + // returns true if we have had a direct detach RC receiver, does not include overrides bool has_had_rc_receiver() const { return _has_had_rc_receiver; } // returns true if we have had an override on any channel @@ -653,7 +653,7 @@ class RC_Channels { uint32_t last_update_ms; bool has_new_overrides; - bool _has_had_rc_receiver; // true if we have had a direct detach RC reciever, does not include overrides + bool _has_had_rc_receiver; // true if we have had a direct detach RC receiver, does not include overrides bool _has_had_override; // true if we have had an override on any channel AP_Float _override_timeout; From 4a29a57d8d1ba42c0996e05bd063d5efe96f8b77 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 6 Apr 2023 08:56:53 +1000 Subject: [PATCH 131/287] AP_Proximity: fix fallthrough in proximity switch in the case that cygbot was selected but not compiled in we would try to insantiate a DroneCAN backend --- libraries/AP_Proximity/AP_Proximity.cpp | 2 +- libraries/AP_Proximity/AP_Proximity.h | 2 ++ libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h | 4 ---- libraries/AP_Proximity/AP_Proximity_config.h | 4 ++++ 4 files changed, 7 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 2a1f9d95bd3867..866e5b3460ae39 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -173,8 +173,8 @@ void AP_Proximity::init() } break; - case Type::CYGBOT_D1: #if AP_PROXIMITY_CYGBOT_ENABLED + case Type::CYGBOT_D1: if (AP_Proximity_Cygbot_D1::detect(serial_instance)) { state[instance].instance = instance; drivers[instance] = new AP_Proximity_Cygbot_D1(*this, state[instance], params[instance], serial_instance); diff --git a/libraries/AP_Proximity/AP_Proximity.h b/libraries/AP_Proximity/AP_Proximity.h index d521d87359ce3b..e5ebb32a33a4e1 100644 --- a/libraries/AP_Proximity/AP_Proximity.h +++ b/libraries/AP_Proximity/AP_Proximity.h @@ -59,7 +59,9 @@ class AP_Proximity SITL = 10, AirSimSITL = 12, #endif +#if AP_PROXIMITY_CYGBOT_ENABLED CYGBOT_D1 = 13, +#endif DroneCAN = 14, }; diff --git a/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h b/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h index 3e844732f9127a..aaa1de91c8d69c 100644 --- a/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h +++ b/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.h @@ -2,10 +2,6 @@ #include "AP_Proximity.h" -#ifndef AP_PROXIMITY_CYGBOT_ENABLED -#define AP_PROXIMITY_CYGBOT_ENABLED HAL_PROXIMITY_ENABLED -#endif - #if (HAL_PROXIMITY_ENABLED && AP_PROXIMITY_CYGBOT_ENABLED) #include "AP_Proximity_Backend_Serial.h" diff --git a/libraries/AP_Proximity/AP_Proximity_config.h b/libraries/AP_Proximity/AP_Proximity_config.h index 92e87818bdc76d..c6ca9e029132a1 100644 --- a/libraries/AP_Proximity/AP_Proximity_config.h +++ b/libraries/AP_Proximity/AP_Proximity_config.h @@ -5,3 +5,7 @@ #ifndef HAL_PROXIMITY_ENABLED #define HAL_PROXIMITY_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) #endif + +#ifndef AP_PROXIMITY_CYGBOT_ENABLED +#define AP_PROXIMITY_CYGBOT_ENABLED HAL_PROXIMITY_ENABLED +#endif From ce1e0c37821cca819d8222633e5d20bf49e14774 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 5 Apr 2023 08:13:25 +0900 Subject: [PATCH 132/287] Copter: 4.3.6 release notes --- ArduCopter/ReleaseNotes.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index e6d1ae320a74a2..9ca8364d6cbc23 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,6 +1,6 @@ ArduPilot Copter Release Notes: ------------------------------------------------------------------ -Copter 4.3.6-beta1/beta2 27-Mar-2023 +Copter 4.3.6 05-Apr-2023 / 4.3.6-beta1, 4.3.6--beta2 27-Mar-2023 Changes from 4.3.5 1) Bi-directional DShot fix for possible motor stop approx 72min after startup ------------------------------------------------------------------ From ae4d1ae0afa49d553c6957572aa98670afdece82 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 6 Mar 2023 14:38:45 +0900 Subject: [PATCH 133/287] GCS_MAVLink: pass camera-information messages to AP_Camera --- libraries/GCS_MAVLink/GCS_Common.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 7f4c3b641acf45..a7a0f233542a62 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3812,6 +3812,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) #if AP_CAMERA_ENABLED case MAVLINK_MSG_ID_DIGICAM_CONTROL: case MAVLINK_MSG_ID_GOPRO_HEARTBEAT: // heartbeat from a GoPro in Solo gimbal + case MAVLINK_MSG_ID_CAMERA_INFORMATION: { AP_Camera *camera = AP::camera(); if (camera == nullptr) { From a9d271ff6a2d41630fa3d0b453b9104d12b4e331 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 3 Mar 2023 15:50:07 +0900 Subject: [PATCH 134/287] AP_Camera: MAVLinkCamV2 driver --- libraries/AP_Camera/AP_Camera.cpp | 8 +- libraries/AP_Camera/AP_Camera.h | 4 + libraries/AP_Camera/AP_Camera_MAVLink.h | 2 +- .../AP_Camera/AP_Camera_MAVLinkCamV2.cpp | 222 ++++++++++++++++++ libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h | 78 ++++++ libraries/AP_Camera/AP_Camera_Params.cpp | 2 +- 6 files changed, 313 insertions(+), 3 deletions(-) create mode 100644 libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp create mode 100644 libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index e9dad0de90608e..0b69871864f910 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -13,9 +13,10 @@ #include "AP_Camera_Backend.h" #include "AP_Camera_Servo.h" #include "AP_Camera_Relay.h" +#include "AP_Camera_SoloGimbal.h" #include "AP_Camera_Mount.h" #include "AP_Camera_MAVLink.h" -#include "AP_Camera_SoloGimbal.h" +#include "AP_Camera_MAVLinkCamV2.h" const AP_Param::GroupInfo AP_Camera::var_info[] = { @@ -163,6 +164,11 @@ void AP_Camera::init() case CameraType::MAVLINK: _backends[instance] = new AP_Camera_MAVLink(*this, _params[instance], instance); break; + + // check for MAVLink Camv2 driver + case CameraType::MAVLINK_CAMV2: + _backends[instance] = new AP_Camera_MAVLinkCamV2(*this, _params[instance], instance); + break; #endif case CameraType::NONE: break; diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 274e9f869600dc..014c729cc9810c 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -21,6 +21,8 @@ class AP_Camera_Servo; class AP_Camera_Relay; class AP_Camera_SoloGimbal; class AP_Camera_Mount; +class AP_Camera_MAVLink; +class AP_Camera_MAVLinkCamV2; /// @class Camera /// @brief Object managing a Photo or video camera @@ -33,6 +35,7 @@ class AP_Camera { friend class AP_Camera_SoloGimbal; friend class AP_Camera_Mount; friend class AP_Camera_MAVLink; + friend class AP_Camera_MAVLinkCamV2; public: @@ -62,6 +65,7 @@ class AP_Camera { #endif #if AP_CAMERA_MAVLINK_ENABLED MAVLINK = 5, // MAVLink enabled camera + MAVLINK_CAMV2 = 6, // MAVLink camera v2 #endif }; diff --git a/libraries/AP_Camera/AP_Camera_MAVLink.h b/libraries/AP_Camera/AP_Camera_MAVLink.h index 21a7308a6ce63c..0be92f09c0729c 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLink.h +++ b/libraries/AP_Camera/AP_Camera_MAVLink.h @@ -14,7 +14,7 @@ */ /* - Camera driver for cameras included in Mount + Camera driver for cameras that implement the older MAVLink camera protocol */ #pragma once diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp new file mode 100644 index 00000000000000..c7d671b7b598c5 --- /dev/null +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp @@ -0,0 +1,222 @@ +#include "AP_Camera_MAVLinkCamV2.h" + +#if AP_CAMERA_MAVLINK_ENABLED +#include + +extern const AP_HAL::HAL& hal; + +#define AP_CAMERA_MAVLINKCAMV2_SEARCH_MS 60000 // search for camera for 60 seconds after startup + +// update - should be called at 50hz +void AP_Camera_MAVLinkCamV2::update() +{ + // exit immediately if not initialised + if (!_initialised) { + find_camera(); + } + + // call parent update + AP_Camera_Backend::update(); +} + +// entry point to actually take a picture. returns true on success +bool AP_Camera_MAVLinkCamV2::trigger_pic() +{ + // exit immediately if have not found camera or does not support taking pictures + if (_link == nullptr || !(_cap_flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE)) { + return false; + } + + // prepare and send message + mavlink_command_long_t pkt {}; + pkt.command = MAV_CMD_IMAGE_START_CAPTURE; + pkt.param3 = 1; // number of images to take + pkt.param4 = image_index+1; // starting sequence number + + _link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt); + + return true; +} + +// start or stop video recording. returns true on success +// set start_recording = true to start record, false to stop recording +bool AP_Camera_MAVLinkCamV2::record_video(bool start_recording) +{ + // exit immediately if have not found camera or does not support recording video + if (_link == nullptr || !(_cap_flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO)) { + return false; + } + + // prepare and send message + mavlink_command_long_t pkt {}; + + if (start_recording) { + pkt.command = MAV_CMD_VIDEO_START_CAPTURE; + // param1 = 0, video stream id. 0 for all streams + // param2 = 0, status frequency. frequency that CAMERA_CAPTURE_STATUS messages should be sent while recording. 0 for no messages + } else { + pkt.command = MAV_CMD_VIDEO_STOP_CAPTURE; + // param1 = 0, video stream id. 0 for all streams + } + + _link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt); + + return true; +} + +// set camera zoom step. returns true on success +// zoom out = -1, hold = 0, zoom in = 1 +bool AP_Camera_MAVLinkCamV2::set_zoom_step(int8_t zoom_step) +{ + // exit immediately if have not found camera or does not support zoom + if (_link == nullptr || !(_cap_flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM)) { + return false; + } + + // prepare and send message + mavlink_command_long_t pkt {}; + pkt.command = MAV_CMD_SET_CAMERA_ZOOM; + pkt.param1 = ZOOM_TYPE_CONTINUOUS; // Zoom Type, 0:ZOOM_TYPE_STEP, 1:ZOOM_TYPE_CONTINUOUS, 2:ZOOM_TYPE_RANGE, 3:ZOOM_TYPE_FOCAL_LENGTH + pkt.param2 = zoom_step; // Zoom Value + + _link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt); + + return true; +} + +// set focus in, out or hold. returns true on success +// focus in = -1, focus hold = 0, focus out = 1 +bool AP_Camera_MAVLinkCamV2::set_manual_focus_step(int8_t focus_step) +{ + // exit immediately if have not found camera or does not support focus + if (_link == nullptr || !(_cap_flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS)) { + return false; + } + + // prepare and send message + mavlink_command_long_t pkt {}; + pkt.command = MAV_CMD_SET_CAMERA_FOCUS; + pkt.param1 = FOCUS_TYPE_CONTINUOUS; // Focus Type, 0:FOCUS_TYPE_STEP, 1:FOCUS_TYPE_CONTINUOUS, 2:FOCUS_TYPE_RANGE, 3:FOCUS_TYPE_METERS, 4:FOCUS_TYPE_AUTO, 5:FOCUS_TYPE_AUTO_SINGLE, 5:FOCUS_TYPE_AUTO_CONTINUOUS + pkt.param2 = focus_step; // Focus Value + + _link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt); + + return true; +} + +// auto focus. returns true on success +bool AP_Camera_MAVLinkCamV2::set_auto_focus() +{ + // exit immediately if have not found camera or does not support focus + if (_link == nullptr || !(_cap_flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS)) { + return false; + } + + // prepare and send message + mavlink_command_long_t pkt {}; + pkt.command = MAV_CMD_SET_CAMERA_FOCUS; + pkt.param1 = FOCUS_TYPE_AUTO; // Focus Type, 0:FOCUS_TYPE_STEP, 1:FOCUS_TYPE_CONTINUOUS, 2:FOCUS_TYPE_RANGE, 3:FOCUS_TYPE_METERS, 4:FOCUS_TYPE_AUTO, 5:FOCUS_TYPE_AUTO_SINGLE, 5:FOCUS_TYPE_AUTO_CONTINUOUS + pkt.param2 = 0; // Focus Value + + _link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt); + + return true; +} + +// handle incoming mavlink message including CAMERA_INFORMATION +void AP_Camera_MAVLinkCamV2::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) +{ + // exit immediately if this is not our message + if (msg.sysid != _sysid || msg.compid != _compid) { + return; + } + + // handle CAMERA_INFORMATION + if (msg.msgid == MAVLINK_MSG_ID_CAMERA_INFORMATION) { + mavlink_camera_information_t cam_info; + mavlink_msg_camera_information_decode(&msg, &cam_info); + + const uint8_t fw_ver_major = cam_info.firmware_version & 0x000000FF; + const uint8_t fw_ver_minor = (cam_info.firmware_version & 0x0000FF00) >> 8; + const uint8_t fw_ver_revision = (cam_info.firmware_version & 0x00FF0000) >> 16; + const uint8_t fw_ver_build = (cam_info.firmware_version & 0xFF000000) >> 24; + + // display camera info to user + gcs().send_text(MAV_SEVERITY_INFO, "Camera: %s %s fw:%u.%u.%u.%u", + cam_info.vendor_name, + cam_info.model_name, + (unsigned)fw_ver_major, + (unsigned)fw_ver_minor, + (unsigned)fw_ver_revision, + (unsigned)fw_ver_build); + + // capability flags + _cap_flags = cam_info.flags; + + _got_camera_info = true; + } +} + +// search for camera in GCS_MAVLink routing table +void AP_Camera_MAVLinkCamV2::find_camera() +{ + // do not look for camera for first 10 seconds so user may see banner + uint32_t now_ms = AP_HAL::millis(); + if (now_ms < 10000) { + return; + } + + // search for camera for 60 seconds or until armed + if ((now_ms > AP_CAMERA_MAVLINKCAMV2_SEARCH_MS) && hal.util->get_soft_armed()) { + return; + } + + // search for a mavlink enabled camera + if (_link == nullptr) { + // we expect that instance 0 has compid = MAV_COMP_ID_CAMERA, instance 1 has compid = MAV_COMP_ID_CAMERA2, etc + uint8_t compid = MIN(MAV_COMP_ID_CAMERA + _instance, MAV_COMP_ID_CAMERA6); + _link = GCS_MAVLINK::find_by_mavtype_and_compid(MAV_TYPE_CAMERA, compid, _sysid); + if (_link == nullptr) { + // have not yet found a camera so return + return; + } + _compid = compid; + } + + // request CAMERA_INFORMATION + if (!_got_camera_info) { + if (now_ms - _last_caminfo_req_ms > 1000) { + _last_caminfo_req_ms = now_ms; + request_camera_information(); + } + return; + } + + _initialised = true; +} + +// request CAMERA_INFORMATION (holds vendor and model name) +void AP_Camera_MAVLinkCamV2::request_camera_information() const +{ + if (_link == nullptr) { + return; + } + + const mavlink_command_long_t pkt { + MAVLINK_MSG_ID_CAMERA_INFORMATION, // param1 + 0, // param2 + 0, // param3 + 0, // param4 + 0, // param5 + 0, // param6 + 0, // param7 + MAV_CMD_REQUEST_MESSAGE, + _sysid, + _compid, + 0 // confirmation + }; + + _link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt); +} + +#endif // AP_CAMERA_MAVLINK_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h new file mode 100644 index 00000000000000..70bb86db3a42d1 --- /dev/null +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h @@ -0,0 +1,78 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + Camera driver for cameras that implement the newer MAVLink camera v2 protocol + see https://mavlink.io/en/services/camera.html + */ +#pragma once + +#include "AP_Camera_Backend.h" + +#if AP_CAMERA_MAVLINK_ENABLED + +class AP_Camera_MAVLinkCamV2 : public AP_Camera_Backend +{ +public: + + // Constructor + using AP_Camera_Backend::AP_Camera_Backend; + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Camera_MAVLinkCamV2); + + // update - should be called at 50hz + void update() override; + + // entry point to actually take a picture + bool trigger_pic() override; + + // start or stop video recording. returns true on success + // set start_recording = true to start record, false to stop recording + bool record_video(bool start_recording) override; + + // set camera zoom step. returns true on success + // zoom out = -1, hold = 0, zoom in = 1 + bool set_zoom_step(int8_t zoom_step) override; + + // set focus in, out or hold. returns true on success + // focus in = -1, focus hold = 0, focus out = 1 + bool set_manual_focus_step(int8_t focus_step) override; + + // auto focus. returns true on success + bool set_auto_focus() override; + + // handle incoming mavlink message + void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) override; + +private: + + // search for camera in GCS_MAVLink routing table + void find_camera(); + + // request CAMERA_INFORMATION (holds vendor and model name) + void request_camera_information() const; + + // internal members + bool _initialised; // true once the camera has provided a CAMERA_INFORMATION + bool _got_camera_info; // true once camera has provided CAMERA_INFORMATION + uint32_t _last_caminfo_req_ms; // system time that CAMERA_INFORMATION was last requested (used to throttle requests) + class GCS_MAVLINK *_link; // link we have found the camera on. nullptr if not seen yet + uint8_t _sysid; // sysid of camera + uint8_t _compid; // component id of gimbal + uint32_t _cap_flags; // capability flags from CAMERA_INFORMATION msg, see MAVLink CAMERA_CAP_FLAGS enum +}; + +#endif // AP_CAMERA_MAVLINK_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_Params.cpp b/libraries/AP_Camera/AP_Camera_Params.cpp index 623aac18ddc6a4..0ecec96b124ef7 100644 --- a/libraries/AP_Camera/AP_Camera_Params.cpp +++ b/libraries/AP_Camera/AP_Camera_Params.cpp @@ -8,7 +8,7 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = { // @Param: _TYPE // @DisplayName: Camera shutter (trigger) type // @Description: how to trigger the camera to take a picture - // @Values: 1:Servo,2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi), 5:MAVLink + // @Values: 1:Servo,2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi), 5:MAVLink, 6:MAVLinkCamV2 // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Camera_Params, type, 0, AP_PARAM_FLAG_ENABLE), From b328f8426045eab170a20b23051b7275c7d95cf1 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 4 Apr 2023 15:36:54 +0900 Subject: [PATCH 135/287] AP_Camera: add AP_CAMERA_MAVLINKCAMV2_ENABLED definition --- libraries/AP_Camera/AP_Camera.cpp | 3 ++- libraries/AP_Camera/AP_Camera.h | 2 ++ libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp | 4 ++-- libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h | 4 ++-- libraries/AP_Camera/AP_Camera_config.h | 4 ++++ 5 files changed, 12 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 0b69871864f910..d5db4eda2132e6 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -164,7 +164,8 @@ void AP_Camera::init() case CameraType::MAVLINK: _backends[instance] = new AP_Camera_MAVLink(*this, _params[instance], instance); break; - +#endif +#if AP_CAMERA_MAVLINKCAMV2_ENABLED // check for MAVLink Camv2 driver case CameraType::MAVLINK_CAMV2: _backends[instance] = new AP_Camera_MAVLinkCamV2(*this, _params[instance], instance); diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 014c729cc9810c..84df4681338c24 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -65,6 +65,8 @@ class AP_Camera { #endif #if AP_CAMERA_MAVLINK_ENABLED MAVLINK = 5, // MAVLink enabled camera +#endif +#if AP_CAMERA_MAVLINKCAMV2_ENABLED MAVLINK_CAMV2 = 6, // MAVLink camera v2 #endif }; diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp index c7d671b7b598c5..48a0b1473b31fc 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp @@ -1,6 +1,6 @@ #include "AP_Camera_MAVLinkCamV2.h" -#if AP_CAMERA_MAVLINK_ENABLED +#if AP_CAMERA_MAVLINKCAMV2_ENABLED #include extern const AP_HAL::HAL& hal; @@ -219,4 +219,4 @@ void AP_Camera_MAVLinkCamV2::request_camera_information() const _link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt); } -#endif // AP_CAMERA_MAVLINK_ENABLED +#endif // AP_CAMERA_MAVLINKCAMV2_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h index 70bb86db3a42d1..57c991ee8abe2b 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.h @@ -21,7 +21,7 @@ #include "AP_Camera_Backend.h" -#if AP_CAMERA_MAVLINK_ENABLED +#if AP_CAMERA_MAVLINKCAMV2_ENABLED class AP_Camera_MAVLinkCamV2 : public AP_Camera_Backend { @@ -75,4 +75,4 @@ class AP_Camera_MAVLinkCamV2 : public AP_Camera_Backend uint32_t _cap_flags; // capability flags from CAMERA_INFORMATION msg, see MAVLink CAMERA_CAP_FLAGS enum }; -#endif // AP_CAMERA_MAVLINK_ENABLED +#endif // AP_CAMERA_MAVLINKCAMV2_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_config.h b/libraries/AP_Camera/AP_Camera_config.h index 9dc0123a503a44..f814a1524c9984 100644 --- a/libraries/AP_Camera/AP_Camera_config.h +++ b/libraries/AP_Camera/AP_Camera_config.h @@ -15,6 +15,10 @@ #define AP_CAMERA_MAVLINK_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_CAMERA_MAVLINKCAMV2_ENABLED +#define AP_CAMERA_MAVLINKCAMV2_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024 +#endif + #ifndef AP_CAMERA_MOUNT_ENABLED #define AP_CAMERA_MOUNT_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_MOUNT_ENABLED #endif From 945b013e58da9e2959c2f5b453701e39b5db49ef Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 4 Apr 2023 15:37:28 +0900 Subject: [PATCH 136/287] Tools: build option for Camera_MAVLinkCamV2 --- Tools/scripts/build_options.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 0df5c2578d3e1f..a42eb2d2b3c65b 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -113,6 +113,7 @@ def __init__(self, Feature('Camera', 'Camera', 'AP_CAMERA_ENABLED', 'Enable Camera Trigger support', 0, None), Feature('Camera', 'Camera_MAVLink', 'AP_CAMERA_MAVLINK_ENABLED', 'Enable MAVLink Camera support', 0, 'Camera'), + Feature('Camera', 'Camera_MAVLinkCamV2', 'AP_CAMERA_MAVLINKCAMV2_ENABLED', 'Enable MAVLink CameraV2 support', 0, 'Camera'), Feature('Camera', 'Camera_Mount', 'AP_CAMERA_MOUNT_ENABLED', 'Enable Camera-in-Mount support', 0, 'Camera,MOUNT'), Feature('Camera', 'Camera_Relay', 'AP_CAMERA_RELAY_ENABLED', 'Enable Camera Trigger via Relay support', 0, 'Camera'), Feature('Camera', 'Camera_Servo', 'AP_CAMERA_SERVO_ENABLED', 'Enable Camera Trigger via Servo support', 0, 'Camera'), From 335de9cb8848b9240d78f69e1855f7bf040759db Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 4 Apr 2023 15:41:23 +0900 Subject: [PATCH 137/287] AP_Camera: MAVLinkCamV2 limits vendor name to 32 chars model name is also limited --- libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp index 48a0b1473b31fc..3eb6eb67bef43e 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp @@ -142,7 +142,7 @@ void AP_Camera_MAVLinkCamV2::handle_message(mavlink_channel_t chan, const mavlin const uint8_t fw_ver_build = (cam_info.firmware_version & 0xFF000000) >> 24; // display camera info to user - gcs().send_text(MAV_SEVERITY_INFO, "Camera: %s %s fw:%u.%u.%u.%u", + gcs().send_text(MAV_SEVERITY_INFO, "Camera: %s.32 %s.32 fw:%u.%u.%u.%u", cam_info.vendor_name, cam_info.model_name, (unsigned)fw_ver_major, From 67895ef2c55eddaa13e1b51c2be896231f76be74 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 5 Apr 2023 18:32:19 +0200 Subject: [PATCH 138/287] ChibiOS: enable timers when using EICU --- modules/ChibiOS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/ChibiOS b/modules/ChibiOS index 4253f6db11790a..75de0f2e5db9e2 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit 4253f6db11790a26361b6cc8b3663cd086709005 +Subproject commit 75de0f2e5db9e2078e4a5612e6838c4dbcdea867 From cdb4012886b5e904904a8531306aa40de0042122 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 5 Apr 2023 12:59:12 +1000 Subject: [PATCH 139/287] Tools: enforce astyle formatting in AP_DDS --- .github/workflows/test_scripts.yml | 3 ++ Tools/scripts/build_ci.sh | 6 +++ Tools/scripts/run_astyle.py | 64 ++++++++++++++++++++++++++++++ 3 files changed, 73 insertions(+) create mode 100755 Tools/scripts/run_astyle.py diff --git a/.github/workflows/test_scripts.yml b/.github/workflows/test_scripts.yml index b26699e8b77bcc..1f73fa05677367 100644 --- a/.github/workflows/test_scripts.yml +++ b/.github/workflows/test_scripts.yml @@ -17,6 +17,7 @@ jobs: check_autotest_options, param_parse, python-cleanliness, + astyle-cleanliness, validate_board_list, ] steps: @@ -29,4 +30,6 @@ jobs: CI_BUILD_TARGET: ${{matrix.config}} shell: bash run: | + sudo apt update + sudo apt-get install -y astyle Tools/scripts/build_ci.sh diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 357df28cb32684..bc48d06d8610e0 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -401,6 +401,12 @@ for t in $CI_BUILD_TARGET; do continue fi + if [ "$t" == "astyle-cleanliness" ]; then + echo "Checking AStyle code cleanliness" + ./Tools/scripts/run_astyle.py + continue + fi + if [ "$t" == "configure-all" ]; then echo "Checking configure of all boards" ./Tools/scripts/configure_all.py diff --git a/Tools/scripts/run_astyle.py b/Tools/scripts/run_astyle.py new file mode 100755 index 00000000000000..2a9ac336b74c1a --- /dev/null +++ b/Tools/scripts/run_astyle.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python3 + +""" +Runs astyle over directory sub-trees known to be "astyle-clean" + + AP_FLAKE8_CLEAN +""" + +import os +import pathlib +import subprocess +import sys + +import argparse + +os.environ['PYTHONUNBUFFERED'] = '1' + + +class AStyleChecker(object): + def __init__(self): + self.retcode = 0 + self.directories_to_check = [ + 'libraries/AP_DDS', + ] + self.files_to_check = [] + + def progress(self, string): + print("****** %s" % (string,)) + + def check(self): + '''run astyle on all files in self.files_to_check''' + # for path in self.files_to_check: + # self.progress("Checking (%s)" % path) + astyle_command = ["astyle", "--dry-run"] + astyle_command.extend(self.files_to_check) + ret = subprocess.run( + astyle_command, + stdout=subprocess.PIPE, + stderr=subprocess.STDOUT, + text=True + ) + if ret.returncode != 0: + self.progress("astyle check failed: (%s)" % (ret.stdout)) + self.retcode = 1 + if "Formatted" in ret.stdout: + self.progress("Files needing formatting found") + print(ret.stdout) + self.retcode = 1 + + def run(self): + for d in self.directories_to_check: + self.files_to_check.extend(list(pathlib.Path(d).glob("*"))) + self.files_to_check = list(filter(lambda x : x.suffix in [".c", ".h", ".cpp"], self.files_to_check)) + self.check() + return self.retcode + + +if __name__ == '__main__': + parser = argparse.ArgumentParser(description='Check all Python files for astyle cleanliness') + # parser.add_argument('--build', action='store_true', default=False, help='build as well as configure') + args = parser.parse_args() + + checker = AStyleChecker() + sys.exit(checker.run()) From e2bceab1f1d0dda5e5c73369d04c0c75d68fb745 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:04:09 +1000 Subject: [PATCH 140/287] modules: remove uavcan submodule --- .gitmodules | 3 --- modules/uavcan | 1 - 2 files changed, 4 deletions(-) delete mode 160000 modules/uavcan diff --git a/.gitmodules b/.gitmodules index 8c7cc94fcd8e3b..ff6918a69b89bd 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,6 +1,3 @@ -[submodule "modules/uavcan"] - path = modules/uavcan - url = https://github.com/DroneCAN/libuavcan.git [submodule "modules/waf"] path = modules/waf url = https://github.com/ArduPilot/waf.git diff --git a/modules/uavcan b/modules/uavcan deleted file mode 160000 index f845e02dcd2e97..00000000000000 --- a/modules/uavcan +++ /dev/null @@ -1 +0,0 @@ -Subproject commit f845e02dcd2e97f6c4743c96f3b2380c4b03ab5f From 0c3c379f696ef7895d472ebe8940b33d4792006f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:05:06 +1000 Subject: [PATCH 141/287] Tools: remove references to modules/uavcan --- Tools/ardupilotwaf/uavcangen.py | 76 --------------------------------- Tools/scripts/run_coverage.py | 2 - 2 files changed, 78 deletions(-) delete mode 100644 Tools/ardupilotwaf/uavcangen.py diff --git a/Tools/ardupilotwaf/uavcangen.py b/Tools/ardupilotwaf/uavcangen.py deleted file mode 100644 index 7ee2d7e01f5edb..00000000000000 --- a/Tools/ardupilotwaf/uavcangen.py +++ /dev/null @@ -1,76 +0,0 @@ -# encoding: utf-8 - -""" -generate DSDLC headers for uavcan -""" - -from waflib import Logs, Task, Utils, Node -from waflib.TaskGen import feature, before_method, extension -import os -import os.path -from xml.etree import ElementTree as et - -class uavcangen(Task.Task): - """generate uavcan header files""" - color = 'BLUE' - before = 'cxx c' - - def run(self): - python = self.env.get_flat('PYTHON') - out = self.env.get_flat('OUTPUT_DIR') - src = self.env.get_flat('SRC') - dsdlc = self.env.get_flat("UC_DSDL_COMPILER") - - ret = self.exec_command(['{}'.format(python), - '{}'.format(dsdlc), - '-O{}'.format(out)] + [x.abspath() for x in self.inputs]) - - if ret != 0: - # ignore if there was a signal to the interpreter rather - # than a real error in the script. Some environments use a - # signed and some an unsigned return for this - if ret > 128 or ret < 0: - Logs.warn('uavcangen crashed with code: {}'.format(ret)) - ret = 0 - else: - Logs.error('uavcangen returned {} error code'.format(ret)) - return ret - - def post_run(self): - super(uavcangen, self).post_run() - for header in self.generator.output_dir.ant_glob("*.hpp **/*.hpp", remove=False): - header.sig = header.cache_sig = self.cache_sig - -def options(opt): - opt.load('python') - -@feature('uavcangen') -@before_method('process_source') -def process_uavcangen(self): - if not hasattr(self, 'output_dir'): - self.bld.fatal('uavcangen: missing option output_dir') - - inputs = self.to_nodes(self.source) - outputs = [] - - self.source = [] - - if not isinstance(self.output_dir, Node.Node): - self.output_dir = self.bld.bldnode.find_or_declare(self.output_dir) - - task = self.create_task('uavcangen', inputs, outputs) - task.env['OUTPUT_DIR'] = self.output_dir.abspath() - - task.env.env = dict(os.environ) - -def configure(cfg): - """ - setup environment for uavcan header generator - """ - cfg.load('python') - cfg.check_python_version(minver=(2,7,0)) - - env = cfg.env - env.UC_DSDL_COMPILER_DIR = cfg.srcnode.make_node('modules/uavcan/libuavcan/dsdl_compiler').abspath() - env.UC_DSDL_COMPILER = env.UC_DSDL_COMPILER_DIR + '/libuavcan_dsdlc' - cfg.msg('UC_DSDL compiler', env.UC_DSDL_COMPILER) diff --git a/Tools/scripts/run_coverage.py b/Tools/scripts/run_coverage.py index d21a0dec63531e..3c254e205eec59 100755 --- a/Tools/scripts/run_coverage.py +++ b/Tools/scripts/run_coverage.py @@ -82,7 +82,6 @@ def init_coverage(self, use_example=False): "--no-external", "--initial", "--capture", - "--exclude", root_dir + "/modules/uavcan/*", "--exclude", root_dir + "/build/sitl/modules/*", "--directory", root_dir, "-o", self.INFO_FILE_BASE, @@ -227,7 +226,6 @@ def update_stats(self): "--remove", self.INFO_FILE, ".waf*", root_dir + "/modules/gtest/*", - root_dir + "/modules/uavcan/*", root_dir + "/modules/DroneCAN/libcanard/*", root_dir + "/build/linux/libraries/*", root_dir + "/build/sitl/libraries/*", From e9e3b943b3141c04e271244063048f8daf71e106 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:05:21 +1000 Subject: [PATCH 142/287] waf: removed reference to uavcan --- wscript | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/wscript b/wscript index 58ec32bbc74a29..2a542055556cfe 100644 --- a/wscript +++ b/wscript @@ -481,7 +481,6 @@ def configure(cfg): if cfg.options.board in cfg.ap_periph_boards(): cfg.load('dronecangen') else: - cfg.load('uavcangen') if cfg.options.force_32bit or (cfg.options.board != 'sitl' and cfg.options.board != 'linux'): cfg.load('dronecangen') @@ -670,16 +669,6 @@ def _build_dynamic_sources(bld): ) if (bld.get_board().with_can or bld.env.HAL_NUM_CAN_IFACES) and not bld.env.AP_PERIPH: - bld( - features='uavcangen', - source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/* libraries/AP_UAVCAN/dsdl/*', dir=True, src=False), - output_dir='modules/uavcan/libuavcan/include/dsdlc_generated', - name='uavcan', - export_includes=[ - bld.bldnode.make_node('modules/uavcan/libuavcan/include/dsdlc_generated').abspath(), - bld.srcnode.find_dir('modules/uavcan/libuavcan/include').abspath() - ] - ) if (not bld.env.FORCE32BIT) and (bld.env.BOARD == 'sitl' or bld.env.BOARD == 'linux'): # remove generated files dronecan_dir = bld.bldnode.make_node('modules/DroneCAN/libcanard/dsdlc_generated/').abspath() From 53390f3a6f7b1f8b50a82c2a63d7175a00c614c7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:06:51 +1000 Subject: [PATCH 143/287] AP_DroneCAN: rename from AP_UAVCAN --- libraries/{AP_UAVCAN => AP_DroneCAN}/AP_Canard_iface.cpp | 0 libraries/{AP_UAVCAN => AP_DroneCAN}/AP_Canard_iface.h | 0 libraries/{AP_UAVCAN => AP_DroneCAN}/AP_UAVCAN.cpp | 0 libraries/{AP_UAVCAN => AP_DroneCAN}/AP_UAVCAN.h | 0 libraries/{AP_UAVCAN => AP_DroneCAN}/AP_UAVCAN_DNA_Server.cpp | 0 libraries/{AP_UAVCAN => AP_DroneCAN}/AP_UAVCAN_DNA_Server.h | 0 libraries/{AP_UAVCAN => AP_DroneCAN}/canard/canard_helpers_user.h | 0 libraries/{AP_UAVCAN => AP_DroneCAN}/dsdl/README.md | 0 .../{AP_UAVCAN => AP_DroneCAN}/examples/UAVCAN_sniffer/README.md | 0 .../examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp | 0 .../examples/UAVCAN_sniffer/nobuild.txt | 0 .../{AP_UAVCAN => AP_DroneCAN}/examples/UAVCAN_sniffer/wscript | 0 12 files changed, 0 insertions(+), 0 deletions(-) rename libraries/{AP_UAVCAN => AP_DroneCAN}/AP_Canard_iface.cpp (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/AP_Canard_iface.h (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/AP_UAVCAN.cpp (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/AP_UAVCAN.h (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/AP_UAVCAN_DNA_Server.cpp (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/AP_UAVCAN_DNA_Server.h (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/canard/canard_helpers_user.h (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/dsdl/README.md (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/examples/UAVCAN_sniffer/README.md (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/examples/UAVCAN_sniffer/nobuild.txt (100%) rename libraries/{AP_UAVCAN => AP_DroneCAN}/examples/UAVCAN_sniffer/wscript (100%) diff --git a/libraries/AP_UAVCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp similarity index 100% rename from libraries/AP_UAVCAN/AP_Canard_iface.cpp rename to libraries/AP_DroneCAN/AP_Canard_iface.cpp diff --git a/libraries/AP_UAVCAN/AP_Canard_iface.h b/libraries/AP_DroneCAN/AP_Canard_iface.h similarity index 100% rename from libraries/AP_UAVCAN/AP_Canard_iface.h rename to libraries/AP_DroneCAN/AP_Canard_iface.h diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.cpp b/libraries/AP_DroneCAN/AP_UAVCAN.cpp similarity index 100% rename from libraries/AP_UAVCAN/AP_UAVCAN.cpp rename to libraries/AP_DroneCAN/AP_UAVCAN.cpp diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.h b/libraries/AP_DroneCAN/AP_UAVCAN.h similarity index 100% rename from libraries/AP_UAVCAN/AP_UAVCAN.h rename to libraries/AP_DroneCAN/AP_UAVCAN.h diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_UAVCAN_DNA_Server.cpp similarity index 100% rename from libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp rename to libraries/AP_DroneCAN/AP_UAVCAN_DNA_Server.cpp diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h b/libraries/AP_DroneCAN/AP_UAVCAN_DNA_Server.h similarity index 100% rename from libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h rename to libraries/AP_DroneCAN/AP_UAVCAN_DNA_Server.h diff --git a/libraries/AP_UAVCAN/canard/canard_helpers_user.h b/libraries/AP_DroneCAN/canard/canard_helpers_user.h similarity index 100% rename from libraries/AP_UAVCAN/canard/canard_helpers_user.h rename to libraries/AP_DroneCAN/canard/canard_helpers_user.h diff --git a/libraries/AP_UAVCAN/dsdl/README.md b/libraries/AP_DroneCAN/dsdl/README.md similarity index 100% rename from libraries/AP_UAVCAN/dsdl/README.md rename to libraries/AP_DroneCAN/dsdl/README.md diff --git a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/README.md b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/README.md similarity index 100% rename from libraries/AP_UAVCAN/examples/UAVCAN_sniffer/README.md rename to libraries/AP_DroneCAN/examples/UAVCAN_sniffer/README.md diff --git a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp similarity index 100% rename from libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp rename to libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp diff --git a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/nobuild.txt b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/nobuild.txt similarity index 100% rename from libraries/AP_UAVCAN/examples/UAVCAN_sniffer/nobuild.txt rename to libraries/AP_DroneCAN/examples/UAVCAN_sniffer/nobuild.txt diff --git a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/wscript b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/wscript similarity index 100% rename from libraries/AP_UAVCAN/examples/UAVCAN_sniffer/wscript rename to libraries/AP_DroneCAN/examples/UAVCAN_sniffer/wscript From 1efd6406245824a3b7677f789db61587ede1a3c8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:08:18 +1000 Subject: [PATCH 144/287] AP_DroneCAN: rename source files for AP_DroneCAN --- libraries/AP_DroneCAN/{AP_UAVCAN.cpp => AP_DroneCAN.cpp} | 0 libraries/AP_DroneCAN/{AP_UAVCAN.h => AP_DroneCAN.h} | 0 .../{AP_UAVCAN_DNA_Server.cpp => AP_DroneCAN_DNA_Server.cpp} | 0 .../{AP_UAVCAN_DNA_Server.h => AP_DroneCAN_DNA_Server.h} | 0 4 files changed, 0 insertions(+), 0 deletions(-) rename libraries/AP_DroneCAN/{AP_UAVCAN.cpp => AP_DroneCAN.cpp} (100%) rename libraries/AP_DroneCAN/{AP_UAVCAN.h => AP_DroneCAN.h} (100%) rename libraries/AP_DroneCAN/{AP_UAVCAN_DNA_Server.cpp => AP_DroneCAN_DNA_Server.cpp} (100%) rename libraries/AP_DroneCAN/{AP_UAVCAN_DNA_Server.h => AP_DroneCAN_DNA_Server.h} (100%) diff --git a/libraries/AP_DroneCAN/AP_UAVCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp similarity index 100% rename from libraries/AP_DroneCAN/AP_UAVCAN.cpp rename to libraries/AP_DroneCAN/AP_DroneCAN.cpp diff --git a/libraries/AP_DroneCAN/AP_UAVCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h similarity index 100% rename from libraries/AP_DroneCAN/AP_UAVCAN.h rename to libraries/AP_DroneCAN/AP_DroneCAN.h diff --git a/libraries/AP_DroneCAN/AP_UAVCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp similarity index 100% rename from libraries/AP_DroneCAN/AP_UAVCAN_DNA_Server.cpp rename to libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp diff --git a/libraries/AP_DroneCAN/AP_UAVCAN_DNA_Server.h b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h similarity index 100% rename from libraries/AP_DroneCAN/AP_UAVCAN_DNA_Server.h rename to libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h From 75ed340efabc4501be31018699eaf899a62c4a0d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:17:10 +1000 Subject: [PATCH 145/287] waf: rename UAVCAN to DroneCAN --- Tools/ardupilotwaf/boards.py | 2 +- Tools/ardupilotwaf/chibios.py | 2 +- wscript | 6 +++--- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 1b3484301549dc..c1b8c6cd9c2e5a 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -435,7 +435,7 @@ def configure_env(self, cfg, env): ) else: env.AP_LIBRARIES += [ - 'AP_UAVCAN', + 'AP_DroneCAN', 'modules/DroneCAN/libcanard/*.c', ] if cfg.options.enable_dronecan_tests: diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 68c30fa6833c93..63eeb0a42bdc3e 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -442,7 +442,7 @@ def setup_canmgr_build(cfg): the build based on the presence of CAN pins in hwdef.dat except for AP_Periph builds''' env = cfg.env env.AP_LIBRARIES += [ - 'AP_UAVCAN', + 'AP_DroneCAN', 'modules/DroneCAN/libcanard/*.c', ] env.INCLUDES += [ diff --git a/wscript b/wscript index 2a542055556cfe..0a36e56b576201 100644 --- a/wscript +++ b/wscript @@ -678,19 +678,19 @@ def _build_dynamic_sources(bld): else: bld( features='dronecangen', - source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/* libraries/AP_UAVCAN/dsdl/*', dir=True, src=False), + source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/* libraries/AP_DroneCAN/dsdl/*', dir=True, src=False), output_dir='modules/DroneCAN/libcanard/dsdlc_generated/', name='dronecan', export_includes=[ bld.bldnode.make_node('modules/DroneCAN/libcanard/dsdlc_generated/include').abspath(), bld.srcnode.find_dir('modules/DroneCAN/libcanard/').abspath(), - bld.srcnode.find_dir('libraries/AP_UAVCAN/canard/').abspath(), + bld.srcnode.find_dir('libraries/AP_DroneCAN/canard/').abspath(), ] ) elif bld.env.AP_PERIPH: bld( features='dronecangen', - source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/* libraries/AP_UAVCAN/dsdl/*', dir=True, src=False), + source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/* libraries/AP_DroneCAN/dsdl/*', dir=True, src=False), output_dir='modules/DroneCAN/libcanard/dsdlc_generated/', name='dronecan', export_includes=[ From c179ea32328479bbf8e164f713733312bceebc25 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 146/287] AP_Airspeed: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp | 38 ++++++++++---------- libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h | 12 +++---- 2 files changed, 25 insertions(+), 25 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp index d905dc132b96df..93fd090cfc5961 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp @@ -3,7 +3,7 @@ #if AP_AIRSPEED_UAVCAN_ENABLED #include -#include +#include #include extern const AP_HAL::HAL& hal; @@ -18,18 +18,18 @@ AP_Airspeed_UAVCAN::AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance AP_Airspeed_Backend(_frontend, _instance) {} -void AP_Airspeed_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) +void AP_Airspeed_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_airspeed, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("airspeed_sub"); } #if AP_AIRSPEED_HYGROMETER_ENABLE - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_hygrometer, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("hygrometer_sub"); } #endif @@ -42,9 +42,9 @@ AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _ AP_Airspeed_UAVCAN* backend = nullptr; for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { - if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) { + if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { const auto bus_id = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, - _detected_modules[i].ap_uavcan->get_driver_index(), + _detected_modules[i].ap_dronecan->get_driver_index(), _detected_modules[i].node_id, 0); if (previous_devid != 0 && previous_devid != bus_id) { // match with previous ID only @@ -56,14 +56,14 @@ AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _ LOG_TAG, "Failed register UAVCAN Airspeed Node %d on Bus %d\n", _detected_modules[i].node_id, - _detected_modules[i].ap_uavcan->get_driver_index()); + _detected_modules[i].ap_dronecan->get_driver_index()); } else { _detected_modules[i].driver = backend; AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Registered UAVCAN Airspeed Node %d on Bus %d\n", _detected_modules[i].node_id, - _detected_modules[i].ap_uavcan->get_driver_index()); + _detected_modules[i].ap_dronecan->get_driver_index()); backend->set_bus_id(bus_id); } break; @@ -73,15 +73,15 @@ AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _ return backend; } -AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id) +AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return nullptr; } for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { if (_detected_modules[i].driver != nullptr && - _detected_modules[i].ap_uavcan == ap_uavcan && + _detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id ) { return _detected_modules[i].driver; } @@ -89,7 +89,7 @@ AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, bool detected = false; for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { - if (_detected_modules[i].ap_uavcan == ap_uavcan && _detected_modules[i].node_id == node_id) { + if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { // detected detected = true; break; @@ -98,8 +98,8 @@ AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, if (!detected) { for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { - if (_detected_modules[i].ap_uavcan == nullptr) { - _detected_modules[i].ap_uavcan = ap_uavcan; + if (_detected_modules[i].ap_dronecan == nullptr) { + _detected_modules[i].ap_dronecan = ap_dronecan; _detected_modules[i].node_id = node_id; break; } @@ -109,11 +109,11 @@ AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, return nullptr; } -void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg) +void AP_Airspeed_UAVCAN::handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg) { WITH_SEMAPHORE(_sem_registry); - AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); + AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { WITH_SEMAPHORE(driver->_sem_airspeed); @@ -128,11 +128,11 @@ void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN *ap_uavcan, const CanardRxTra } #if AP_AIRSPEED_HYGROMETER_ENABLE -void AP_Airspeed_UAVCAN::handle_hygrometer(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg) +void AP_Airspeed_UAVCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg) { WITH_SEMAPHORE(_sem_registry); - AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); + AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { WITH_SEMAPHORE(driver->_sem_airspeed); diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h index 83d99568b7d0e4..3ccbdd7127ca5a 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h @@ -10,7 +10,7 @@ #include "AP_Airspeed_Backend.h" -#include +#include class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { public: @@ -29,16 +29,16 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) override; #endif - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_Airspeed_Backend* probe(AP_Airspeed &_fronted, uint8_t _instance, uint32_t previous_devid); private: - static void handle_airspeed(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg); - static void handle_hygrometer(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg); + static void handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg); + static void handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg); - static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id); + static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); float _pressure; // Pascal float _temperature; // Celcius @@ -55,7 +55,7 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { // Module Detection Registry static struct DetectedModules { - AP_UAVCAN* ap_uavcan; + AP_DroneCAN* ap_dronecan; uint8_t node_id; AP_Airspeed_UAVCAN *driver; } _detected_modules[AIRSPEED_MAX_SENSORS]; From 85ce16deb672d4ca51c9099dd02b848ca0f5b63b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 147/287] AP_Arming: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_Arming/AP_Arming.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index d2434bbfb79f2a..c39a9f7fdd2d8b 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -65,7 +65,7 @@ #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub) #include #endif - #include + #include #endif #include @@ -1176,8 +1176,8 @@ bool AP_Arming::can_checks(bool report) case AP_CANManager::Driver_Type_UAVCAN: { #if HAL_ENABLE_LIBUAVCAN_DRIVERS - AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i); - if (ap_uavcan != nullptr && !ap_uavcan->prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) { + AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_uavcan(i); + if (ap_dronecan != nullptr && !ap_dronecan->prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) { check_failed(ARMING_CHECK_SYSTEM, report, "UAVCAN: %s", fail_msg); return false; } From 305a8275f830e4660c583f86b679403226e1fb7c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 148/287] AP_Baro: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_Baro/AP_Baro_UAVCAN.cpp | 38 ++++++++++++++-------------- libraries/AP_Baro/AP_Baro_UAVCAN.h | 14 +++++----- 2 files changed, 26 insertions(+), 26 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp index 0a2a41ca802ffe..b4c3db984596d0 100644 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp @@ -21,16 +21,16 @@ AP_Baro_UAVCAN::AP_Baro_UAVCAN(AP_Baro &baro) : AP_Baro_Backend(baro) {} -void AP_Baro_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) +void AP_Baro_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_pressure, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("pressure_sub"); } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_temperature, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("temperature_sub"); } } @@ -41,31 +41,31 @@ AP_Baro_Backend* AP_Baro_UAVCAN::probe(AP_Baro &baro) AP_Baro_UAVCAN* backend = nullptr; for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { - if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) { + if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { backend = new AP_Baro_UAVCAN(baro); if (backend == nullptr) { AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "Failed register UAVCAN Baro Node %d on Bus %d\n", _detected_modules[i].node_id, - _detected_modules[i].ap_uavcan->get_driver_index()); + _detected_modules[i].ap_dronecan->get_driver_index()); } else { _detected_modules[i].driver = backend; backend->_pressure = 0; backend->_pressure_count = 0; - backend->_ap_uavcan = _detected_modules[i].ap_uavcan; + backend->_ap_dronecan = _detected_modules[i].ap_dronecan; backend->_node_id = _detected_modules[i].node_id; backend->_instance = backend->_frontend.register_sensor(); backend->set_bus_id(backend->_instance, AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, - _detected_modules[i].ap_uavcan->get_driver_index(), + _detected_modules[i].ap_dronecan->get_driver_index(), backend->_node_id, 0)); AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Registered UAVCAN Baro Node %d on Bus %d\n", _detected_modules[i].node_id, - _detected_modules[i].ap_uavcan->get_driver_index()); + _detected_modules[i].ap_dronecan->get_driver_index()); } break; } @@ -73,14 +73,14 @@ AP_Baro_Backend* AP_Baro_UAVCAN::probe(AP_Baro &baro) return backend; } -AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, bool create_new) +AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return nullptr; } for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { if (_detected_modules[i].driver != nullptr && - _detected_modules[i].ap_uavcan == ap_uavcan && + _detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { return _detected_modules[i].driver; } @@ -90,7 +90,7 @@ AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t bool already_detected = false; //Check if there's an empty spot for possible registeration for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { - if (_detected_modules[i].ap_uavcan == ap_uavcan && _detected_modules[i].node_id == node_id) { + if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { //Already Detected already_detected = true; break; @@ -98,8 +98,8 @@ AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t } if (!already_detected) { for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { - if (_detected_modules[i].ap_uavcan == nullptr) { - _detected_modules[i].ap_uavcan = ap_uavcan; + if (_detected_modules[i].ap_dronecan == nullptr) { + _detected_modules[i].ap_dronecan = ap_dronecan; _detected_modules[i].node_id = node_id; break; } @@ -121,12 +121,12 @@ void AP_Baro_UAVCAN::_update_and_wrap_accumulator(float *accum, float val, uint8 } } -void AP_Baro_UAVCAN::handle_pressure(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg) +void AP_Baro_UAVCAN::handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg) { AP_Baro_UAVCAN* driver; { WITH_SEMAPHORE(_sem_registry); - driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, true); + driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, true); if (driver == nullptr) { return; } @@ -138,12 +138,12 @@ void AP_Baro_UAVCAN::handle_pressure(AP_UAVCAN *ap_uavcan, const CanardRxTransfe } } -void AP_Baro_UAVCAN::handle_temperature(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg) +void AP_Baro_UAVCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg) { AP_Baro_UAVCAN* driver; { WITH_SEMAPHORE(_sem_registry); - driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, false); + driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, false); if (driver == nullptr) { return; } diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.h b/libraries/AP_Baro/AP_Baro_UAVCAN.h index 38c73eb2d8f39e..c3fb700d252ba6 100644 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.h +++ b/libraries/AP_Baro/AP_Baro_UAVCAN.h @@ -4,7 +4,7 @@ #if AP_BARO_UAVCAN_ENABLED -#include +#include #if AP_TEST_DRONECAN_DRIVERS #include #endif @@ -15,12 +15,12 @@ class AP_Baro_UAVCAN : public AP_Baro_Backend { void update() override; - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); - static AP_Baro_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, bool create_new); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static AP_Baro_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new); static AP_Baro_Backend* probe(AP_Baro &baro); - static void handle_pressure(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg); - static void handle_temperature(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg); + static void handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg); + static void handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg); #if AP_TEST_DRONECAN_DRIVERS void update_healthy_flag(uint8_t instance) override { _frontend.sensors[instance].healthy = !AP::sitl()->baro[instance].disable; }; #endif @@ -36,12 +36,12 @@ class AP_Baro_UAVCAN : public AP_Baro_Backend { uint8_t _pressure_count; HAL_Semaphore _sem_baro; - AP_UAVCAN* _ap_uavcan; + AP_DroneCAN* _ap_dronecan; uint8_t _node_id; // Module Detection Registry static struct DetectedModules { - AP_UAVCAN* ap_uavcan; + AP_DroneCAN* ap_dronecan; uint8_t node_id; AP_Baro_UAVCAN* driver; } _detected_modules[BARO_MAX_DRIVERS]; From a03c395cce66746bb5f2ee73e748ad80c1eddece Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 149/287] AP_BattMonitor: rename AP_UAVCAN to AP_DroneCAN --- .../AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp | 40 +++++++++---------- .../AP_BattMonitor/AP_BattMonitor_UAVCAN.h | 14 +++---- 2 files changed, 27 insertions(+), 27 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp index ce1d66ccf90f9a..434292f870dd0a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include #define LOG_TAG "BattMon" @@ -43,28 +43,28 @@ AP_BattMonitor_UAVCAN::AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor _state.healthy = false; } -void AP_BattMonitor_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) +void AP_BattMonitor_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_battery_info_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("battinfo_sub"); } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_battery_info_aux_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("battinfo_aux_sub"); } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_mppt_stream_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("mppt_stream_sub"); } } -AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t battery_id) +AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return nullptr; } for (uint8_t i = 0; i < AP::battery()._num_instances; i++) { @@ -73,7 +73,7 @@ AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u continue; } AP_BattMonitor_UAVCAN* driver = (AP_BattMonitor_UAVCAN*)AP::battery().drivers[i]; - if (driver->_ap_uavcan == ap_uavcan && driver->_node_id == node_id && match_battery_id(i, battery_id)) { + if (driver->_ap_dronecan == ap_dronecan && driver->_node_id == node_id && match_battery_id(i, battery_id)) { return driver; } } @@ -84,10 +84,10 @@ AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u match_battery_id(i, battery_id)) { AP_BattMonitor_UAVCAN* batmon = (AP_BattMonitor_UAVCAN*)AP::battery().drivers[i]; - if(batmon->_ap_uavcan != nullptr || batmon->_node_id != 0) { + if(batmon->_ap_dronecan != nullptr || batmon->_node_id != 0) { continue; } - batmon->_ap_uavcan = ap_uavcan; + batmon->_ap_dronecan = ap_dronecan; batmon->_node_id = node_id; batmon->_instance = i; batmon->init(); @@ -95,7 +95,7 @@ AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u LOG_TAG, "Registered BattMonitor Node %d on Bus %d\n", node_id, - ap_uavcan->get_driver_index()); + ap_dronecan->get_driver_index()); return batmon; } } @@ -197,27 +197,27 @@ void AP_BattMonitor_UAVCAN::handle_mppt_stream(const mppt_Stream &msg) _mppt.fault_flags = msg.fault_flags; } -void AP_BattMonitor_UAVCAN::handle_battery_info_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg) +void AP_BattMonitor_UAVCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.battery_id); + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); if (driver == nullptr) { return; } driver->handle_battery_info(msg); } -void AP_BattMonitor_UAVCAN::handle_battery_info_aux_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) +void AP_BattMonitor_UAVCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.battery_id); + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); if (driver == nullptr) { return; } driver->handle_battery_info_aux(msg); } -void AP_BattMonitor_UAVCAN::handle_mppt_stream_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const mppt_Stream &msg) +void AP_BattMonitor_UAVCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, transfer.source_node_id); + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id); if (driver == nullptr) { return; } @@ -312,7 +312,7 @@ void AP_BattMonitor_UAVCAN::mppt_check_powered_state() // force should be true to force sending the state change request to the MPPT void AP_BattMonitor_UAVCAN::mppt_set_powered_state(bool power_on) { - if (_ap_uavcan == nullptr || !_mppt.is_detected) { + if (_ap_dronecan == nullptr || !_mppt.is_detected) { return; } @@ -326,7 +326,7 @@ void AP_BattMonitor_UAVCAN::mppt_set_powered_state(bool power_on) request.disable = !request.enable; if (mppt_outputenable_client == nullptr) { - mppt_outputenable_client = new Canard::Client{_ap_uavcan->get_canard_iface(), mppt_outputenable_res_cb}; + mppt_outputenable_client = new Canard::Client{_ap_dronecan->get_canard_iface(), mppt_outputenable_res_cb}; if (mppt_outputenable_client == nullptr) { return; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h index 475d7210bb1119..22e4cfd170b6b6 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h @@ -3,7 +3,7 @@ #include "AP_BattMonitor.h" #include "AP_BattMonitor_Backend.h" #if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include +#include #define AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS 5000000 // sensor becomes unhealthy if no successful readings for 5 seconds @@ -46,11 +46,11 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend // return mavlink fault bitmask (see MAV_BATTERY_FAULT enum) uint32_t get_mavlink_fault_bitmask() const override; - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); - static AP_BattMonitor_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t battery_id); - static void handle_battery_info_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg); - static void handle_battery_info_aux_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg); - static void handle_mppt_stream_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const mppt_Stream &msg); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static AP_BattMonitor_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id); + static void handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg); + static void handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg); + static void handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg); void mppt_set_powered_state(bool power_on) override; @@ -84,7 +84,7 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend HAL_Semaphore _sem_battmon; - AP_UAVCAN* _ap_uavcan; + AP_DroneCAN* _ap_dronecan; uint8_t _soc; uint8_t _node_id; uint16_t _cycle_count; From dbe91670a9e99939956f19d2d0140a58e69fa11d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 150/287] AP_CANManager: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_CANManager/AP_CANDriver.cpp | 6 +++--- libraries/AP_CANManager/AP_CANManager.cpp | 10 +++++----- libraries/AP_CANManager/AP_CANTester.cpp | 2 +- libraries/AP_CANManager/AP_CANTester.h | 2 +- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_CANManager/AP_CANDriver.cpp b/libraries/AP_CANManager/AP_CANDriver.cpp index ed5ee7f66665da..0a2b9a197cbcab 100644 --- a/libraries/AP_CANManager/AP_CANDriver.cpp +++ b/libraries/AP_CANManager/AP_CANDriver.cpp @@ -19,7 +19,7 @@ #include "AP_CANManager.h" #include -#include +#include #include #include "AP_CANTester.h" #include @@ -38,8 +38,8 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = { #if HAL_ENABLE_LIBUAVCAN_DRIVERS // @Group: UC_ - // @Path: ../AP_UAVCAN/AP_UAVCAN.cpp - AP_SUBGROUPPTR(_uavcan, "UC_", 2, AP_CANManager::CANDriver_Params, AP_UAVCAN), + // @Path: ../AP_DroneCAN/AP_DroneCAN.cpp + AP_SUBGROUPPTR(_uavcan, "UC_", 2, AP_CANManager::CANDriver_Params, AP_DroneCAN), #endif #if (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)) diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index 72b45648c65c5d..f597eaff3e5961 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -24,7 +24,7 @@ #include #include -#include +#include #include #include #include @@ -205,14 +205,14 @@ void AP_CANManager::init() // Allocate the set type of Driver #if HAL_ENABLE_LIBUAVCAN_DRIVERS if (drv_type[drv_num] == Driver_Type_UAVCAN) { - _drivers[drv_num] = _drv_param[drv_num]._uavcan = new AP_UAVCAN(drv_num); + _drivers[drv_num] = _drv_param[drv_num]._uavcan = new AP_DroneCAN(drv_num); if (_drivers[drv_num] == nullptr) { AP_BoardConfig::allocation_error("uavcan %d", i + 1); continue; } - AP_Param::load_object_from_eeprom((AP_UAVCAN*)_drivers[drv_num], AP_UAVCAN::var_info); + AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info); } else #endif if (drv_type[drv_num] == Driver_Type_KDECAN) { @@ -289,14 +289,14 @@ void AP_CANManager::init() WITH_SEMAPHORE(_sem); for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) { if ((Driver_Type) _drv_param[i]._driver_type.get() == Driver_Type_UAVCAN) { - _drivers[i] = _drv_param[i]._uavcan = new AP_UAVCAN(i); + _drivers[i] = _drv_param[i]._uavcan = new AP_DroneCAN(i); if (_drivers[i] == nullptr) { AP_BoardConfig::allocation_error("uavcan %d", i + 1); continue; } - AP_Param::load_object_from_eeprom((AP_UAVCAN*)_drivers[i], AP_UAVCAN::var_info); + AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[i], AP_DroneCAN::var_info); _drivers[i]->init(i, true); _driver_type_cache[i] = (Driver_Type) _drv_param[i]._driver_type.get(); } diff --git a/libraries/AP_CANManager/AP_CANTester.cpp b/libraries/AP_CANManager/AP_CANTester.cpp index 806713f8939a9a..05617dcfa7e69e 100644 --- a/libraries/AP_CANManager/AP_CANTester.cpp +++ b/libraries/AP_CANManager/AP_CANTester.cpp @@ -25,7 +25,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/libraries/AP_CANManager/AP_CANTester.h b/libraries/AP_CANManager/AP_CANTester.h index 45fffa26b4950e..c93ba0649fe375 100644 --- a/libraries/AP_CANManager/AP_CANTester.h +++ b/libraries/AP_CANManager/AP_CANTester.h @@ -17,7 +17,7 @@ #include "AP_CANDriver.h" #include -#include +#include #ifndef HAL_ENABLE_CANTESTER #define HAL_ENABLE_CANTESTER 0 #endif From 34f70b98b34bb2a9cc9da4aa33b6b13305c3f077 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 151/287] AP_Compass: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_Compass/AP_Compass_UAVCAN.cpp | 42 +++++++++++----------- libraries/AP_Compass/AP_Compass_UAVCAN.h | 16 ++++----- 2 files changed, 29 insertions(+), 29 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_UAVCAN.cpp b/libraries/AP_Compass/AP_Compass_UAVCAN.cpp index 75cefff4dd6851..7b0dcf0818e3b0 100644 --- a/libraries/AP_Compass/AP_Compass_UAVCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_UAVCAN.cpp @@ -20,7 +20,7 @@ #include #include -#include +#include #include #include @@ -31,24 +31,24 @@ extern const AP_HAL::HAL& hal; AP_Compass_UAVCAN::DetectedModules AP_Compass_UAVCAN::_detected_modules[]; HAL_Semaphore AP_Compass_UAVCAN::_sem_registry; -AP_Compass_UAVCAN::AP_Compass_UAVCAN(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id, uint32_t devid) - : _ap_uavcan(ap_uavcan) +AP_Compass_UAVCAN::AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid) + : _ap_dronecan(ap_dronecan) , _node_id(node_id) , _sensor_id(sensor_id) , _devid(devid) { } -void AP_Compass_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) +void AP_Compass_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_magnetic_field, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("mag_sub"); } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_magnetic_field_2, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("mag2_sub"); } } @@ -56,10 +56,10 @@ void AP_Compass_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) AP_Compass_Backend* AP_Compass_UAVCAN::probe(uint8_t index) { AP_Compass_UAVCAN* driver = nullptr; - if (!_detected_modules[index].driver && _detected_modules[index].ap_uavcan) { + if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) { WITH_SEMAPHORE(_sem_registry); // Register new Compass mode to a backend - driver = new AP_Compass_UAVCAN(_detected_modules[index].ap_uavcan, _detected_modules[index].node_id, _detected_modules[index].sensor_id, _detected_modules[index].devid); + driver = new AP_Compass_UAVCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].node_id, _detected_modules[index].sensor_id, _detected_modules[index].devid); if (driver) { if (!driver->init()) { delete driver; @@ -70,7 +70,7 @@ AP_Compass_Backend* AP_Compass_UAVCAN::probe(uint8_t index) LOG_TAG, "Found Mag Node %d on Bus %d Sensor ID %d\n", _detected_modules[index].node_id, - _detected_modules[index].ap_uavcan->get_driver_index(), + _detected_modules[index].ap_dronecan->get_driver_index(), _detected_modules[index].sensor_id); #if AP_TEST_DRONECAN_DRIVERS // Scroll through the registered compasses, and set the offsets @@ -108,14 +108,14 @@ bool AP_Compass_UAVCAN::init() return true; } -AP_Compass_UAVCAN* AP_Compass_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id) +AP_Compass_UAVCAN* AP_Compass_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return nullptr; } for (uint8_t i=0; iget_driver_index(), + ap_dronecan->get_driver_index(), node_id, sensor_id + 1); // we use sensor_id as devtype break; @@ -172,12 +172,12 @@ void AP_Compass_UAVCAN::handle_mag_msg(const Vector3f &mag) accumulate_sample(raw_field, _instance); } -void AP_Compass_UAVCAN::handle_magnetic_field(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg) +void AP_Compass_UAVCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg) { WITH_SEMAPHORE(_sem_registry); Vector3f mag_vector; - AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, 0); + AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, 0); if (driver != nullptr) { mag_vector[0] = msg.magnetic_field_ga[0]; mag_vector[1] = msg.magnetic_field_ga[1]; @@ -186,13 +186,13 @@ void AP_Compass_UAVCAN::handle_magnetic_field(AP_UAVCAN *ap_uavcan, const Canard } } -void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg) +void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg) { WITH_SEMAPHORE(_sem_registry); Vector3f mag_vector; uint8_t sensor_id = msg.sensor_id; - AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, sensor_id); + AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, sensor_id); if (driver != nullptr) { mag_vector[0] = msg.magnetic_field_ga[0]; mag_vector[1] = msg.magnetic_field_ga[1]; diff --git a/libraries/AP_Compass/AP_Compass_UAVCAN.h b/libraries/AP_Compass/AP_Compass_UAVCAN.h index b68860c4e2e1e3..32f66768baa117 100644 --- a/libraries/AP_Compass/AP_Compass_UAVCAN.h +++ b/libraries/AP_Compass/AP_Compass_UAVCAN.h @@ -6,19 +6,19 @@ #include "AP_Compass_Backend.h" -#include +#include class AP_Compass_UAVCAN : public AP_Compass_Backend { public: - AP_Compass_UAVCAN(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id, uint32_t devid); + AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid); void read(void) override; - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_Compass_Backend* probe(uint8_t index); static uint32_t get_detected_devid(uint8_t index) { return _detected_modules[index].devid; } - static void handle_magnetic_field(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg); - static void handle_magnetic_field_2(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg); + static void handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg); + static void handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg); private: bool init(); @@ -26,18 +26,18 @@ class AP_Compass_UAVCAN : public AP_Compass_Backend { // callback for DroneCAN messages void handle_mag_msg(const Vector3f &mag); - static AP_Compass_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id); + static AP_Compass_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id); uint8_t _instance; - AP_UAVCAN* _ap_uavcan; + AP_DroneCAN* _ap_dronecan; uint8_t _node_id; uint8_t _sensor_id; uint32_t _devid; // Module Detection Registry static struct DetectedModules { - AP_UAVCAN* ap_uavcan; + AP_DroneCAN* ap_dronecan; uint8_t node_id; uint8_t sensor_id; AP_Compass_UAVCAN *driver; From 8b096c2987af9061659d6ff4ff9d354bbb852f7f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 152/287] AP_DroneCAN: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_DroneCAN/AP_Canard_iface.h | 4 +- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 124 +++++++++--------- libraries/AP_DroneCAN/AP_DroneCAN.h | 52 ++++---- .../AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp | 68 +++++----- .../AP_DroneCAN/AP_DroneCAN_DNA_Server.h | 18 +-- .../UAVCAN_sniffer/UAVCAN_sniffer.cpp | 10 +- 6 files changed, 138 insertions(+), 138 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.h b/libraries/AP_DroneCAN/AP_Canard_iface.h index 9c88df8826e481..37638dffd98077 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.h +++ b/libraries/AP_DroneCAN/AP_Canard_iface.h @@ -3,9 +3,9 @@ #if HAL_ENABLE_LIBUAVCAN_DRIVERS #include -class AP_UAVCAN; +class AP_DroneCAN; class CanardInterface : public Canard::Interface { - friend class AP_UAVCAN; + friend class AP_DroneCAN; public: /// @brief delete copy constructor and assignment operator diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 44a599e3910af1..be43ab7ac08d37 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -19,7 +19,7 @@ #include #if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "AP_UAVCAN.h" +#include "AP_DroneCAN.h" #include #include @@ -42,7 +42,7 @@ #include #include #include -#include "AP_UAVCAN_DNA_Server.h" +#include "AP_DroneCAN_DNA_Server.h" #include #include #include @@ -78,18 +78,18 @@ extern const AP_HAL::HAL& hal; #define debug_uavcan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "UAVCAN", fmt, ##args); } while (0) // Translation of all messages from UAVCAN structures into AP structures is done -// in AP_UAVCAN and not in corresponding drivers. +// in AP_DroneCAN and not in corresponding drivers. // The overhead of including definitions of DSDL is very high and it is best to // concentrate in one place. // table of user settable CAN bus parameters -const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { +const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Param: NODE // @DisplayName: UAVCAN node that is used for this network // @Description: UAVCAN node should be set implicitly // @Range: 1 250 // @User: Advanced - AP_GROUPINFO("NODE", 1, AP_UAVCAN, _dronecan_node, 10), + AP_GROUPINFO("NODE", 1, AP_DroneCAN, _dronecan_node, 10), // @Param: SRV_BM // @DisplayName: Output channels to be transmitted as servo over UAVCAN @@ -97,14 +97,14 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15, 15: Servo 16, 16: Servo 17, 17: Servo 18, 18: Servo 19, 19: Servo 20, 20: Servo 21, 21: Servo 22, 22: Servo 23, 23: Servo 24, 24: Servo 25, 25: Servo 26, 26: Servo 27, 27: Servo 28, 28: Servo 29, 29: Servo 30, 30: Servo 31, 31: Servo 32 // @User: Advanced - AP_GROUPINFO("SRV_BM", 2, AP_UAVCAN, _servo_bm, 0), + AP_GROUPINFO("SRV_BM", 2, AP_DroneCAN, _servo_bm, 0), // @Param: ESC_BM // @DisplayName: Output channels to be transmitted as ESC over UAVCAN // @Description: Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32 // @User: Advanced - AP_GROUPINFO("ESC_BM", 3, AP_UAVCAN, _esc_bm, 0), + AP_GROUPINFO("ESC_BM", 3, AP_DroneCAN, _esc_bm, 0), // @Param: SRV_RT // @DisplayName: Servo output rate @@ -112,14 +112,14 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { // @Range: 1 200 // @Units: Hz // @User: Advanced - AP_GROUPINFO("SRV_RT", 4, AP_UAVCAN, _servo_rate_hz, 50), + AP_GROUPINFO("SRV_RT", 4, AP_DroneCAN, _servo_rate_hz, 50), // @Param: OPTION // @DisplayName: UAVCAN options // @Description: Option flags // @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy,4:SendServoAsPWM,5:SendGNSS // @User: Advanced - AP_GROUPINFO("OPTION", 5, AP_UAVCAN, _options, 0), + AP_GROUPINFO("OPTION", 5, AP_DroneCAN, _options, 0), // @Param: NTF_RT // @DisplayName: Notify State rate @@ -127,21 +127,21 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { // @Range: 1 200 // @Units: Hz // @User: Advanced - AP_GROUPINFO("NTF_RT", 6, AP_UAVCAN, _notify_state_hz, 20), + AP_GROUPINFO("NTF_RT", 6, AP_DroneCAN, _notify_state_hz, 20), // @Param: ESC_OF // @DisplayName: ESC Output channels offset // @Description: Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficint usage of CAN bandwidth // @Range: 0 18 // @User: Advanced - AP_GROUPINFO("ESC_OF", 7, AP_UAVCAN, _esc_offset, 0), + AP_GROUPINFO("ESC_OF", 7, AP_DroneCAN, _esc_offset, 0), // @Param: POOL // @DisplayName: CAN pool size // @Description: Amount of memory in bytes to allocate for the DroneCAN memory pool. More memory is needed for higher CAN bus loads // @Range: 1024 16384 // @User: Advanced - AP_GROUPINFO("POOL", 8, AP_UAVCAN, _pool_size, UAVCAN_NODE_POOL_SIZE), + AP_GROUPINFO("POOL", 8, AP_DroneCAN, _pool_size, UAVCAN_NODE_POOL_SIZE), AP_GROUPEND }; @@ -150,7 +150,7 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { // set this to 1 to minimise resend of stale msgs #define CAN_PERIODIC_TX_TIMEOUT_MS 2 -AP_UAVCAN::AP_UAVCAN(const int driver_index) : +AP_DroneCAN::AP_DroneCAN(const int driver_index) : _driver_index(driver_index), canard_iface(driver_index), _dna_server(*this) @@ -162,23 +162,23 @@ _dna_server(*this) _SRV_conf[i].servo_pending = false; } - debug_uavcan(AP_CANManager::LOG_INFO, "AP_UAVCAN constructed\n\r"); + debug_uavcan(AP_CANManager::LOG_INFO, "AP_DroneCAN constructed\n\r"); } -AP_UAVCAN::~AP_UAVCAN() +AP_DroneCAN::~AP_DroneCAN() { } -AP_UAVCAN *AP_UAVCAN::get_uavcan(uint8_t driver_index) +AP_DroneCAN *AP_DroneCAN::get_uavcan(uint8_t driver_index) { if (driver_index >= AP::can().get_num_drivers() || AP::can().get_driver_type(driver_index) != AP_CANManager::Driver_Type_UAVCAN) { return nullptr; } - return static_cast(AP::can().get_driver(driver_index)); + return static_cast(AP::can().get_driver(driver_index)); } -bool AP_UAVCAN::add_interface(AP_HAL::CANIface* can_iface) +bool AP_DroneCAN::add_interface(AP_HAL::CANIface* can_iface) { if (!canard_iface.add_interface(can_iface)) { debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: can't add UAVCAN interface\n\r"); @@ -187,7 +187,7 @@ bool AP_UAVCAN::add_interface(AP_HAL::CANIface* can_iface) return true; } -void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) +void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) { if (driver_index != _driver_index) { debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: init called with wrong driver_index"); @@ -200,10 +200,10 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) node_info_rsp.name.len = snprintf((char*)node_info_rsp.name.data, sizeof(node_info_rsp.name.data), "org.ardupilot:%u", driver_index); - node_info_rsp.software_version.major = AP_UAVCAN_SW_VERS_MAJOR; - node_info_rsp.software_version.minor = AP_UAVCAN_SW_VERS_MINOR; - node_info_rsp.hardware_version.major = AP_UAVCAN_HW_VERS_MAJOR; - node_info_rsp.hardware_version.minor = AP_UAVCAN_HW_VERS_MINOR; + node_info_rsp.software_version.major = AP_DRONECAN_SW_VERS_MAJOR; + node_info_rsp.software_version.minor = AP_DRONECAN_SW_VERS_MINOR; + node_info_rsp.hardware_version.major = AP_DRONECAN_HW_VERS_MAJOR; + node_info_rsp.hardware_version.minor = AP_DRONECAN_HW_VERS_MINOR; #if HAL_CANFD_SUPPORTED if (option_is_set(Options::CANFD_ENABLED)) { @@ -323,7 +323,7 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) snprintf(_thread_name, sizeof(_thread_name), "uavcan_%u", driver_index); - if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_UAVCAN::loop, void), _thread_name, UAVCAN_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_CAN, 0)) { + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_DroneCAN::loop, void), _thread_name, UAVCAN_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_CAN, 0)) { debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't create thread\n\r"); return; } @@ -332,7 +332,7 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) debug_uavcan(AP_CANManager::LOG_INFO, "UAVCAN: init done\n\r"); } -void AP_UAVCAN::loop(void) +void AP_DroneCAN::loop(void) { while (true) { if (!_initialized) { @@ -383,7 +383,7 @@ void AP_UAVCAN::loop(void) #endif #if AP_DRONECAN_SEND_GPS - if (option_is_set(AP_UAVCAN::Options::SEND_GNSS) && !AP_GPS_UAVCAN::instance_exists(this)) { + if (option_is_set(AP_DroneCAN::Options::SEND_GNSS) && !AP_GPS_UAVCAN::instance_exists(this)) { // send if enabled and this interface/driver is not used by the AP_GPS driver gnss_send_fix(); gnss_send_yaw(); @@ -395,7 +395,7 @@ void AP_UAVCAN::loop(void) } -void AP_UAVCAN::send_node_status(void) +void AP_DroneCAN::send_node_status(void) { const uint32_t now = AP_HAL::native_millis(); if (now - _node_status_last_send_ms < 1000) { @@ -406,7 +406,7 @@ void AP_UAVCAN::send_node_status(void) node_status.broadcast(node_status_msg); } -void AP_UAVCAN::handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req) +void AP_DroneCAN::handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req) { node_info_rsp.status = node_status_msg; node_info_rsp.status.uptime_sec = AP_HAL::native_millis() / 1000; @@ -417,7 +417,7 @@ void AP_UAVCAN::handle_node_info_request(const CanardRxTransfer& transfer, const ///// SRV output ///// -void AP_UAVCAN::SRV_send_actuator(void) +void AP_DroneCAN::SRV_send_actuator(void) { uint8_t starting_servo = 0; bool repeat_send; @@ -473,7 +473,7 @@ void AP_UAVCAN::SRV_send_actuator(void) } while (repeat_send); } -void AP_UAVCAN::SRV_send_esc(void) +void AP_DroneCAN::SRV_send_esc(void) { static const int cmd_max = ((1<<13)-1); uavcan_equipment_esc_RawCommand esc_msg; @@ -524,7 +524,7 @@ void AP_UAVCAN::SRV_send_esc(void) } } -void AP_UAVCAN::SRV_push_servos() +void AP_DroneCAN::SRV_push_servos() { WITH_SEMAPHORE(SRV_sem); @@ -543,7 +543,7 @@ void AP_UAVCAN::SRV_push_servos() ///// LED ///// -void AP_UAVCAN::led_out_send() +void AP_DroneCAN::led_out_send() { uint64_t now = AP_HAL::native_micros64(); @@ -572,9 +572,9 @@ void AP_UAVCAN::led_out_send() _led_conf.last_update = now; } -bool AP_UAVCAN::led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue) +bool AP_DroneCAN::led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t blue) { - if (_led_conf.devices_count >= AP_UAVCAN_MAX_LED_DEVICES) { + if (_led_conf.devices_count >= AP_DRONECAN_MAX_LED_DEVICES) { return false; } @@ -606,7 +606,7 @@ bool AP_UAVCAN::led_write(uint8_t led_index, uint8_t red, uint8_t green, uint8_t } // buzzer send -void AP_UAVCAN::buzzer_send() +void AP_DroneCAN::buzzer_send() { uavcan_equipment_indication_BeepCommand msg; WITH_SEMAPHORE(_buzzer.sem); @@ -621,7 +621,7 @@ void AP_UAVCAN::buzzer_send() } // buzzer support -void AP_UAVCAN::set_buzzer_tone(float frequency, float duration_s) +void AP_DroneCAN::set_buzzer_tone(float frequency, float duration_s) { WITH_SEMAPHORE(_buzzer.sem); _buzzer.frequency = frequency; @@ -630,7 +630,7 @@ void AP_UAVCAN::set_buzzer_tone(float frequency, float duration_s) } // notify state send -void AP_UAVCAN::notify_state_send() +void AP_DroneCAN::notify_state_send() { uint32_t now = AP_HAL::native_millis(); @@ -719,7 +719,7 @@ void AP_UAVCAN::notify_state_send() } #if AP_DRONECAN_SEND_GPS -void AP_UAVCAN::gnss_send_fix() +void AP_DroneCAN::gnss_send_fix() { const AP_GPS &gps = AP::gps(); @@ -841,7 +841,7 @@ void AP_UAVCAN::gnss_send_fix() } } -void AP_UAVCAN::gnss_send_yaw() +void AP_DroneCAN::gnss_send_yaw() { const AP_GPS &gps = AP::gps(); @@ -868,7 +868,7 @@ void AP_UAVCAN::gnss_send_yaw() #endif // AP_DRONECAN_SEND_GPS -void AP_UAVCAN::rtcm_stream_send() +void AP_DroneCAN::rtcm_stream_send() { WITH_SEMAPHORE(_rtcm_stream.sem); if (_rtcm_stream.buf == nullptr || @@ -900,7 +900,7 @@ void AP_UAVCAN::rtcm_stream_send() } // SafetyState send -void AP_UAVCAN::safety_state_send() +void AP_DroneCAN::safety_state_send() { uint32_t now = AP_HAL::native_millis(); if (now - _last_safety_state_ms < 500) { @@ -936,7 +936,7 @@ void AP_UAVCAN::safety_state_send() /* send RTCMStream packet on all active UAVCAN drivers */ -void AP_UAVCAN::send_RTCMStream(const uint8_t *data, uint32_t len) +void AP_DroneCAN::send_RTCMStream(const uint8_t *data, uint32_t len) { WITH_SEMAPHORE(_rtcm_stream.sem); if (_rtcm_stream.buf == nullptr) { @@ -953,7 +953,7 @@ void AP_UAVCAN::send_RTCMStream(const uint8_t *data, uint32_t len) /* handle Button message */ -void AP_UAVCAN::handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg) +void AP_DroneCAN::handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg) { switch (msg.button) { case ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY: { @@ -974,7 +974,7 @@ void AP_UAVCAN::handle_button(const CanardRxTransfer& transfer, const ardupilot_ /* handle traffic report */ -void AP_UAVCAN::handle_traffic_report(const CanardRxTransfer& transfer, const ardupilot_equipment_trafficmonitor_TrafficReport& msg) +void AP_DroneCAN::handle_traffic_report(const CanardRxTransfer& transfer, const ardupilot_equipment_trafficmonitor_TrafficReport& msg) { #if HAL_ADSB_ENABLED AP_ADSB *adsb = AP::ADSB(); @@ -1041,7 +1041,7 @@ void AP_UAVCAN::handle_traffic_report(const CanardRxTransfer& transfer, const ar /* handle actuator status message */ -void AP_UAVCAN::handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg) +void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg) { // log as CSRV message AP::logger().Write_ServoStatus(AP_HAL::native_micros64(), @@ -1053,7 +1053,7 @@ void AP_UAVCAN::handle_actuator_status(const CanardRxTransfer& transfer, const u } #if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED -void AP_UAVCAN::handle_actuator_status_Volz(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ActuatorStatusVolzCb &cb) +void AP_DroneCAN::handle_actuator_status_Volz(AP_DroneCAN* ap_dronecan, uint8_t node_id, const ActuatorStatusVolzCb &cb) { AP::logger().WriteStreaming( "CVOL", @@ -1074,7 +1074,7 @@ void AP_UAVCAN::handle_actuator_status_Volz(AP_UAVCAN* ap_uavcan, uint8_t node_i /* handle ESC status message */ -void AP_UAVCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg) +void AP_DroneCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg) { #if HAL_WITH_ESC_TELEM const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, UAVCAN_SRV_NUMBER); @@ -1098,7 +1098,7 @@ void AP_UAVCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavcan #endif } -bool AP_UAVCAN::is_esc_data_index_valid(const uint8_t index) { +bool AP_DroneCAN::is_esc_data_index_valid(const uint8_t index) { if (index > UAVCAN_SRV_NUMBER) { // printf("UAVCAN: invalid esc index: %d. max index allowed: %d\n\r", index, UAVCAN_SRV_NUMBER); return false; @@ -1109,7 +1109,7 @@ bool AP_UAVCAN::is_esc_data_index_valid(const uint8_t index) { /* handle LogMessage debug */ -void AP_UAVCAN::handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg) +void AP_DroneCAN::handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg) { #if HAL_LOGGING_ENABLED if (AP::can().get_log_level() != AP_CANManager::LOG_NONE) { @@ -1122,7 +1122,7 @@ void AP_UAVCAN::handle_debug(const CanardRxTransfer& transfer, const uavcan_prot #endif } -void AP_UAVCAN::send_parameter_request() +void AP_DroneCAN::send_parameter_request() { WITH_SEMAPHORE(_param_sem); if (param_request_sent) { @@ -1132,7 +1132,7 @@ void AP_UAVCAN::send_parameter_request() param_request_sent = true; } -bool AP_UAVCAN::set_parameter_on_node(uint8_t node_id, const char *name, float value, ParamGetSetFloatCb *cb) +bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, float value, ParamGetSetFloatCb *cb) { WITH_SEMAPHORE(_param_sem); if (param_int_cb != nullptr || @@ -1150,7 +1150,7 @@ bool AP_UAVCAN::set_parameter_on_node(uint8_t node_id, const char *name, float v return true; } -bool AP_UAVCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32_t value, ParamGetSetIntCb *cb) +bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32_t value, ParamGetSetIntCb *cb) { WITH_SEMAPHORE(_param_sem); if (param_int_cb != nullptr || @@ -1168,7 +1168,7 @@ bool AP_UAVCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32_t return true; } -bool AP_UAVCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetFloatCb *cb) +bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetFloatCb *cb) { WITH_SEMAPHORE(_param_sem); if (param_int_cb != nullptr || @@ -1185,7 +1185,7 @@ bool AP_UAVCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGe return true; } -bool AP_UAVCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetIntCb *cb) +bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetIntCb *cb) { WITH_SEMAPHORE(_param_sem); if (param_int_cb != nullptr || @@ -1202,7 +1202,7 @@ bool AP_UAVCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGe return true; } -void AP_UAVCAN::handle_param_get_set_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_GetSetResponse& rsp) +void AP_DroneCAN::handle_param_get_set_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_GetSetResponse& rsp) { WITH_SEMAPHORE(_param_sem); if (!param_int_cb && @@ -1239,7 +1239,7 @@ void AP_UAVCAN::handle_param_get_set_response(const CanardRxTransfer& transfer, } -void AP_UAVCAN::send_parameter_save_request() +void AP_DroneCAN::send_parameter_save_request() { WITH_SEMAPHORE(_param_save_sem); if (param_save_request_sent) { @@ -1249,7 +1249,7 @@ void AP_UAVCAN::send_parameter_save_request() param_save_request_sent = true; } -bool AP_UAVCAN::save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb) +bool AP_DroneCAN::save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb) { WITH_SEMAPHORE(_param_save_sem); if (save_param_cb != nullptr) { @@ -1265,7 +1265,7 @@ bool AP_UAVCAN::save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb) } // handle parameter save request response -void AP_UAVCAN::handle_param_save_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_ExecuteOpcodeResponse& rsp) +void AP_DroneCAN::handle_param_save_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_ExecuteOpcodeResponse& rsp) { WITH_SEMAPHORE(_param_save_sem); if (!save_param_cb) { @@ -1278,7 +1278,7 @@ void AP_UAVCAN::handle_param_save_response(const CanardRxTransfer& transfer, con // Send Reboot command // Note: Do not call this from outside UAVCAN thread context, // THIS IS NOT A THREAD SAFE API! -void AP_UAVCAN::send_reboot_request(uint8_t node_id) +void AP_DroneCAN::send_reboot_request(uint8_t node_id) { uavcan_protocol_RestartNodeRequest request; request.magic_number = UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAGIC_NUMBER; @@ -1287,7 +1287,7 @@ void AP_UAVCAN::send_reboot_request(uint8_t node_id) // check if a option is set and if it is then reset it to 0. // return true if it was set -bool AP_UAVCAN::check_and_reset_option(Options option) +bool AP_DroneCAN::check_and_reset_option(Options option) { bool ret = option_is_set(option); if (ret) { @@ -1297,7 +1297,7 @@ bool AP_UAVCAN::check_and_reset_option(Options option) } // handle prearm check -bool AP_UAVCAN::prearm_check(char* fail_msg, uint8_t fail_msg_len) const +bool AP_DroneCAN::prearm_check(char* fail_msg, uint8_t fail_msg_len) const { // forward this to DNA_Server return _dna_server.prearm_check(fail_msg, fail_msg_len); @@ -1306,7 +1306,7 @@ bool AP_UAVCAN::prearm_check(char* fail_msg, uint8_t fail_msg_len) const /* periodic logging */ -void AP_UAVCAN::logging(void) +void AP_DroneCAN::logging(void) { #if HAL_LOGGING_ENABLED const uint32_t now_ms = AP_HAL::millis(); diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index ad2d2680605320..f736cf10cce227 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -31,7 +31,7 @@ #include #include #include -#include "AP_UAVCAN_DNA_Server.h" +#include "AP_DroneCAN_DNA_Server.h" #include #include @@ -43,27 +43,27 @@ #define AP_DRONECAN_SEND_GPS (BOARD_FLASH_SIZE > 1024) #endif -#define AP_UAVCAN_SW_VERS_MAJOR 1 -#define AP_UAVCAN_SW_VERS_MINOR 0 +#define AP_DRONECAN_SW_VERS_MAJOR 1 +#define AP_DRONECAN_SW_VERS_MINOR 0 -#define AP_UAVCAN_HW_VERS_MAJOR 1 -#define AP_UAVCAN_HW_VERS_MINOR 0 +#define AP_DRONECAN_HW_VERS_MAJOR 1 +#define AP_DRONECAN_HW_VERS_MINOR 0 -#define AP_UAVCAN_MAX_LED_DEVICES 4 +#define AP_DRONECAN_MAX_LED_DEVICES 4 // fwd-declare callback classes -class AP_UAVCAN_DNA_Server; +class AP_DroneCAN_DNA_Server; -class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { - friend class AP_UAVCAN_DNA_Server; +class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { + friend class AP_DroneCAN_DNA_Server; public: - AP_UAVCAN(const int driver_index); - ~AP_UAVCAN(); + AP_DroneCAN(const int driver_index); + ~AP_DroneCAN(); static const struct AP_Param::GroupInfo var_info[]; // Return uavcan from @driver_index or nullptr if it's not ready or doesn't exist - static AP_UAVCAN *get_uavcan(uint8_t driver_index); + static AP_DroneCAN *get_uavcan(uint8_t driver_index); bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const; void init(uint8_t driver_index, bool enable_filters) override; @@ -71,9 +71,9 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { uint8_t get_driver_index() const { return _driver_index; } - FUNCTOR_TYPEDEF(ParamGetSetIntCb, bool, AP_UAVCAN*, const uint8_t, const char*, int32_t &); - FUNCTOR_TYPEDEF(ParamGetSetFloatCb, bool, AP_UAVCAN*, const uint8_t, const char*, float &); - FUNCTOR_TYPEDEF(ParamSaveCb, void, AP_UAVCAN*, const uint8_t, bool); + FUNCTOR_TYPEDEF(ParamGetSetIntCb, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); + FUNCTOR_TYPEDEF(ParamGetSetFloatCb, bool, AP_DroneCAN*, const uint8_t, const char*, float &); + FUNCTOR_TYPEDEF(ParamSaveCb, void, AP_DroneCAN*, const uint8_t, bool); void send_node_status(); @@ -181,7 +181,7 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { uint32_t *mem_pool; - AP_UAVCAN_DNA_Server _dna_server; + AP_DroneCAN_DNA_Server _dna_server; uint8_t _driver_index; @@ -214,7 +214,7 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { }; struct { - led_device devices[AP_UAVCAN_MAX_LED_DEVICES]; + led_device devices[AP_DRONECAN_MAX_LED_DEVICES]; uint8_t devices_count; uint64_t last_update; } _led_conf; @@ -281,38 +281,38 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { Canard::Publisher gnss_status{canard_iface}; #endif // incoming messages - Canard::ObjCallback safety_button_cb{this, &AP_UAVCAN::handle_button}; + Canard::ObjCallback safety_button_cb{this, &AP_DroneCAN::handle_button}; Canard::Subscriber safety_button_listener{safety_button_cb, _driver_index}; - Canard::ObjCallback traffic_report_cb{this, &AP_UAVCAN::handle_traffic_report}; + Canard::ObjCallback traffic_report_cb{this, &AP_DroneCAN::handle_traffic_report}; Canard::Subscriber traffic_report_listener{traffic_report_cb, _driver_index}; - Canard::ObjCallback actuator_status_cb{this, &AP_UAVCAN::handle_actuator_status}; + Canard::ObjCallback actuator_status_cb{this, &AP_DroneCAN::handle_actuator_status}; Canard::Subscriber actuator_status_listener{actuator_status_cb, _driver_index}; - Canard::ObjCallback esc_status_cb{this, &AP_UAVCAN::handle_ESC_status}; + Canard::ObjCallback esc_status_cb{this, &AP_DroneCAN::handle_ESC_status}; Canard::Subscriber esc_status_listener{esc_status_cb, _driver_index}; - Canard::ObjCallback debug_cb{this, &AP_UAVCAN::handle_debug}; + Canard::ObjCallback debug_cb{this, &AP_DroneCAN::handle_debug}; Canard::Subscriber debug_listener{debug_cb, _driver_index}; // param client - Canard::ObjCallback param_get_set_res_cb{this, &AP_UAVCAN::handle_param_get_set_response}; + Canard::ObjCallback param_get_set_res_cb{this, &AP_DroneCAN::handle_param_get_set_response}; Canard::Client param_get_set_client{canard_iface, param_get_set_res_cb}; - Canard::ObjCallback param_save_res_cb{this, &AP_UAVCAN::handle_param_save_response}; + Canard::ObjCallback param_save_res_cb{this, &AP_DroneCAN::handle_param_save_response}; Canard::Client param_save_client{canard_iface, param_save_res_cb}; // reboot client void handle_restart_node_response(const CanardRxTransfer& transfer, const uavcan_protocol_RestartNodeResponse& msg) {} - Canard::ObjCallback restart_node_res_cb{this, &AP_UAVCAN::handle_restart_node_response}; + Canard::ObjCallback restart_node_res_cb{this, &AP_DroneCAN::handle_restart_node_response}; Canard::Client restart_node_client{canard_iface, restart_node_res_cb}; uavcan_protocol_param_ExecuteOpcodeRequest param_save_req; uavcan_protocol_param_GetSetRequest param_getset_req; // Node Info Server - Canard::ObjCallback node_info_req_cb{this, &AP_UAVCAN::handle_node_info_request}; + Canard::ObjCallback node_info_req_cb{this, &AP_DroneCAN::handle_node_info_request}; Canard::Server node_info_server{canard_iface, node_info_req_cb}; uavcan_protocol_GetNodeInfoResponse node_info_rsp; diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index 72c6019f833f3a..073265d9b500dd 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -20,8 +20,8 @@ #if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "AP_UAVCAN_DNA_Server.h" -#include "AP_UAVCAN.h" +#include "AP_DroneCAN_DNA_Server.h" +#include "AP_DroneCAN.h" #include #include #include @@ -36,18 +36,18 @@ extern const AP_HAL::HAL& hal; #define debug_uavcan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "UAVCAN", fmt, ##args); } while (0) -AP_UAVCAN_DNA_Server::AP_UAVCAN_DNA_Server(AP_UAVCAN &ap_uavcan) : - _ap_uavcan(ap_uavcan), - _canard_iface(ap_uavcan.canard_iface), +AP_DroneCAN_DNA_Server::AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan) : + _ap_dronecan(ap_dronecan), + _canard_iface(ap_dronecan.canard_iface), storage(StorageManager::StorageCANDNA), - allocation_sub(allocation_cb, _ap_uavcan.get_driver_index()), - node_status_sub(node_status_cb, _ap_uavcan.get_driver_index()), + allocation_sub(allocation_cb, _ap_dronecan.get_driver_index()), + node_status_sub(node_status_cb, _ap_dronecan.get_driver_index()), node_info_client(_canard_iface, node_info_cb) {} /* Method to generate 6byte hash from the Unique ID. We return it packed inside the referenced NodeData structure */ -void AP_UAVCAN_DNA_Server::getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const +void AP_DroneCAN_DNA_Server::getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const { uint64_t hash = FNV_1_OFFSET_BASIS_64; hash_fnv_1a(size, unique_id, &hash); @@ -62,7 +62,7 @@ void AP_UAVCAN_DNA_Server::getHash(NodeData &node_data, const uint8_t unique_id[ } //Read Node Data from Storage Region -bool AP_UAVCAN_DNA_Server::readNodeData(NodeData &data, uint8_t node_id) +bool AP_DroneCAN_DNA_Server::readNodeData(NodeData &data, uint8_t node_id) { if (node_id > MAX_NODE_ID) { return false; @@ -77,7 +77,7 @@ bool AP_UAVCAN_DNA_Server::readNodeData(NodeData &data, uint8_t node_id) } //Write Node Data to Storage Region -bool AP_UAVCAN_DNA_Server::writeNodeData(const NodeData &data, uint8_t node_id) +bool AP_DroneCAN_DNA_Server::writeNodeData(const NodeData &data, uint8_t node_id) { if (node_id > MAX_NODE_ID) { return false; @@ -93,7 +93,7 @@ bool AP_UAVCAN_DNA_Server::writeNodeData(const NodeData &data, uint8_t node_id) /* Set Occupation Mask, handy for keeping track of all node ids that are allocated and all that are available. */ -bool AP_UAVCAN_DNA_Server::setOccupationMask(uint8_t node_id) +bool AP_DroneCAN_DNA_Server::setOccupationMask(uint8_t node_id) { if (node_id > MAX_NODE_ID) { return false; @@ -104,7 +104,7 @@ bool AP_UAVCAN_DNA_Server::setOccupationMask(uint8_t node_id) /* Remove Node Data from Server Record in Storage, and also clear Occupation Mask */ -bool AP_UAVCAN_DNA_Server::freeNodeID(uint8_t node_id) +bool AP_DroneCAN_DNA_Server::freeNodeID(uint8_t node_id) { if (node_id > MAX_NODE_ID) { return false; @@ -125,7 +125,7 @@ bool AP_UAVCAN_DNA_Server::freeNodeID(uint8_t node_id) /* Sets the verification mask. This is to be called, once The Seen Node has been both registered and verified against the Server Records. */ -void AP_UAVCAN_DNA_Server::setVerificationMask(uint8_t node_id) +void AP_DroneCAN_DNA_Server::setVerificationMask(uint8_t node_id) { if (node_id > MAX_NODE_ID) { return; @@ -135,7 +135,7 @@ void AP_UAVCAN_DNA_Server::setVerificationMask(uint8_t node_id) /* Checks if the NodeID is occupied, i.e. its recorded in the Server Records against a unique ID */ -bool AP_UAVCAN_DNA_Server::isNodeIDOccupied(uint8_t node_id) const +bool AP_DroneCAN_DNA_Server::isNodeIDOccupied(uint8_t node_id) const { if (node_id > MAX_NODE_ID) { return false; @@ -145,7 +145,7 @@ bool AP_UAVCAN_DNA_Server::isNodeIDOccupied(uint8_t node_id) const /* Checks if NodeID is verified, i.e. the unique id in Storage Records matches the one provided by Device with this node id. */ -bool AP_UAVCAN_DNA_Server::isNodeIDVerified(uint8_t node_id) const +bool AP_DroneCAN_DNA_Server::isNodeIDVerified(uint8_t node_id) const { if (node_id > MAX_NODE_ID) { return false; @@ -156,7 +156,7 @@ bool AP_UAVCAN_DNA_Server::isNodeIDVerified(uint8_t node_id) const /* Go through Server Records, and fetch node id that matches the provided Unique IDs hash. Returns 255 if no Node ID was detected */ -uint8_t AP_UAVCAN_DNA_Server::getNodeIDForUniqueID(const uint8_t unique_id[], uint8_t size) +uint8_t AP_DroneCAN_DNA_Server::getNodeIDForUniqueID(const uint8_t unique_id[], uint8_t size) { uint8_t node_id = 255; NodeData node_data, cmp_node_data; @@ -179,7 +179,7 @@ uint8_t AP_UAVCAN_DNA_Server::getNodeIDForUniqueID(const uint8_t unique_id[], ui /* Hash the Unique ID and add it to the Server Record for specified Node ID. */ -bool AP_UAVCAN_DNA_Server::addNodeIDForUniqueID(uint8_t node_id, const uint8_t unique_id[], uint8_t size) +bool AP_DroneCAN_DNA_Server::addNodeIDForUniqueID(uint8_t node_id, const uint8_t unique_id[], uint8_t size) { NodeData node_data; getHash(node_data, unique_id, size); @@ -198,7 +198,7 @@ bool AP_UAVCAN_DNA_Server::addNodeIDForUniqueID(uint8_t node_id, const uint8_t u } //Checks if a valid Server Record is present for specified Node ID -bool AP_UAVCAN_DNA_Server::isValidNodeDataAvailable(uint8_t node_id) +bool AP_DroneCAN_DNA_Server::isValidNodeDataAvailable(uint8_t node_id) { NodeData node_data; readNodeData(node_data, node_id); @@ -213,9 +213,9 @@ bool AP_UAVCAN_DNA_Server::isValidNodeDataAvailable(uint8_t node_id) Also resets the Server Record in case there is a mismatch between specified node id and unique id against the existing Server Record. */ -bool AP_UAVCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id) +bool AP_DroneCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id) { - //Read the details from AP_UAVCAN + //Read the details from AP_DroneCAN server_state = HEALTHY; /* Go through our records and look for valid NodeData, to initialise occupation mask */ @@ -235,7 +235,7 @@ bool AP_UAVCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id_l //Its not there a reset should write it in the Storage reset(); } - if (_ap_uavcan.check_and_reset_option(AP_UAVCAN::Options::DNA_CLEAR_DATABASE)) { + if (_ap_dronecan.check_and_reset_option(AP_DroneCAN::Options::DNA_CLEAR_DATABASE)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UC DNA database reset"); reset(); } @@ -281,7 +281,7 @@ bool AP_UAVCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id_l //Reset the Server Records -void AP_UAVCAN_DNA_Server::reset() +void AP_DroneCAN_DNA_Server::reset() { NodeData node_data; memset(&node_data, 0, sizeof(node_data)); @@ -300,7 +300,7 @@ void AP_UAVCAN_DNA_Server::reset() /* Go through the Occupation mask for available Node ID based on pseudo code provided in uavcan/protocol/dynamic_node_id/1.Allocation.uavcan */ -uint8_t AP_UAVCAN_DNA_Server::findFreeNodeID(uint8_t preferred) +uint8_t AP_DroneCAN_DNA_Server::findFreeNodeID(uint8_t preferred) { // Search up uint8_t candidate = (preferred > 0) ? preferred : 125; @@ -323,7 +323,7 @@ uint8_t AP_UAVCAN_DNA_Server::findFreeNodeID(uint8_t preferred) } //Check if we have received Node Status from this node_id -bool AP_UAVCAN_DNA_Server::isNodeSeen(uint8_t node_id) +bool AP_DroneCAN_DNA_Server::isNodeSeen(uint8_t node_id) { if (node_id > MAX_NODE_ID) { return false; @@ -333,7 +333,7 @@ bool AP_UAVCAN_DNA_Server::isNodeSeen(uint8_t node_id) /* Set the Seen Node Mask, to be called when received Node Status from the node id */ -void AP_UAVCAN_DNA_Server::addToSeenNodeMask(uint8_t node_id) +void AP_DroneCAN_DNA_Server::addToSeenNodeMask(uint8_t node_id) { if (node_id > MAX_NODE_ID) { return; @@ -345,7 +345,7 @@ void AP_UAVCAN_DNA_Server::addToSeenNodeMask(uint8_t node_id) than once per 5 second. We continually verify the nodes in our seen list, So that we can raise issue if there are duplicates on the bus. */ -void AP_UAVCAN_DNA_Server::verify_nodes() +void AP_DroneCAN_DNA_Server::verify_nodes() { uint32_t now = AP_HAL::millis(); if ((now - last_verification_request) < 5000) { @@ -398,14 +398,14 @@ void AP_UAVCAN_DNA_Server::verify_nodes() /* Handles Node Status Message, adds to the Seen Node list Also starts the Service call for Node Info to complete the Verification process. */ -void AP_UAVCAN_DNA_Server::handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg) +void AP_DroneCAN_DNA_Server::handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg) { if (transfer.source_node_id > MAX_NODE_ID || transfer.source_node_id == 0) { return; } if ((msg.health != UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK || msg.mode != UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL) && - !_ap_uavcan.option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { + !_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { //if node is not healthy or operational, clear resp health mask, and set fault_node_id fault_node_id = transfer.source_node_id; server_state = NODE_STATUS_UNHEALTHY; @@ -430,7 +430,7 @@ Handle responses from GetNodeInfo Request. We verify the node info against our records. Marks Verification mask if already recorded, Or register if the node id is available and not recorded for the received Unique ID */ -void AP_UAVCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp) +void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp) { if (transfer.source_node_id > MAX_NODE_ID) { return; @@ -470,7 +470,7 @@ void AP_UAVCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, cons nodeInfo_resp_rcvd = true; } setVerificationMask(transfer.source_node_id); - } else if (!_ap_uavcan.option_is_set(AP_UAVCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { + } else if (!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { /* This is a device with node_id already registered for another device */ server_state = DUPLICATE_NODES; @@ -497,7 +497,7 @@ void AP_UAVCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, cons /* Handle the allocation message from the devices supporting dynamic node allocation. */ -void AP_UAVCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg) +void AP_DroneCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg) { if (transfer.source_node_id != 0) { //Ignore Allocation messages that are not DNA requests @@ -575,7 +575,7 @@ void AP_UAVCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer, co } //report the server state, along with failure message if any -bool AP_UAVCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) const +bool AP_DroneCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) const { switch (server_state) { case HEALTHY: @@ -585,7 +585,7 @@ bool AP_UAVCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) co return false; } case DUPLICATE_NODES: { - if (_ap_uavcan.option_is_set(AP_UAVCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { + if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) { // ignore error return true; } @@ -597,7 +597,7 @@ bool AP_UAVCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) co return false; } case NODE_STATUS_UNHEALTHY: { - if (_ap_uavcan.option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { + if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { // ignore error return true; } diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h index 0ba7a193f927b6..8ceab48d1a9259 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h @@ -12,9 +12,9 @@ #include "AP_Canard_iface.h" #include -class AP_UAVCAN; +class AP_DroneCAN; //Forward declaring classes -class AP_UAVCAN_DNA_Server +class AP_DroneCAN_DNA_Server { StorageAccess storage; @@ -89,26 +89,26 @@ class AP_UAVCAN_DNA_Server bool isValidNodeDataAvailable(uint8_t node_id); HAL_Semaphore storage_sem; - AP_UAVCAN &_ap_uavcan; + AP_DroneCAN &_ap_dronecan; CanardInterface &_canard_iface; Canard::Publisher allocation_pub{_canard_iface}; - Canard::ObjCallback allocation_cb{this, &AP_UAVCAN_DNA_Server::handleAllocation}; + Canard::ObjCallback allocation_cb{this, &AP_DroneCAN_DNA_Server::handleAllocation}; Canard::Subscriber allocation_sub; - Canard::ObjCallback node_status_cb{this, &AP_UAVCAN_DNA_Server::handleNodeStatus}; + Canard::ObjCallback node_status_cb{this, &AP_DroneCAN_DNA_Server::handleNodeStatus}; Canard::Subscriber node_status_sub; - Canard::ObjCallback node_info_cb{this, &AP_UAVCAN_DNA_Server::handleNodeInfo}; + Canard::ObjCallback node_info_cb{this, &AP_DroneCAN_DNA_Server::handleNodeInfo}; Canard::Client node_info_client; public: - AP_UAVCAN_DNA_Server(AP_UAVCAN &ap_uavcan); + AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan); // Do not allow copies - CLASS_NO_COPY(AP_UAVCAN_DNA_Server); + CLASS_NO_COPY(AP_DroneCAN_DNA_Server); //Initialises publisher and Server Record for specified uavcan driver bool init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id); @@ -124,7 +124,7 @@ class AP_UAVCAN_DNA_Server /* Subscribe to the messages to be handled for maintaining and allocating Node ID list */ - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); //report the server state, along with failure message if any bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const; diff --git a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp index 0c5d625f0156df..942404349b29c6 100644 --- a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp +++ b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp @@ -8,7 +8,7 @@ #include -#include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include @@ -135,11 +135,11 @@ void UAVCAN_sniffer::init(void) node_info.name.len = snprintf((char*)node_info.name.data, sizeof(node_info.name.data), "org.ardupilot:%u", driver_index); - node_info.software_version.major = AP_UAVCAN_SW_VERS_MAJOR; - node_info.software_version.minor = AP_UAVCAN_SW_VERS_MINOR; + node_info.software_version.major = AP_DRONECAN_SW_VERS_MAJOR; + node_info.software_version.minor = AP_DRONECAN_SW_VERS_MINOR; - node_info.hardware_version.major = AP_UAVCAN_HW_VERS_MAJOR; - node_info.hardware_version.minor = AP_UAVCAN_HW_VERS_MINOR; + node_info.hardware_version.major = AP_DRONECAN_HW_VERS_MAJOR; + node_info.hardware_version.minor = AP_DRONECAN_HW_VERS_MINOR; #define START_CB(mtype, cbname) Canard::allocate_sub_static_callback(cb_ ## cbname,driver_index) From 7e74fde24c8c7c3acc8bae5b29ca7fe34b702102 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 153/287] AP_EFI: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_EFI/AP_EFI_DroneCAN.cpp | 10 +++++----- libraries/AP_EFI/AP_EFI_DroneCAN.h | 6 +++--- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp index 18332295e0d293..c242598cf092a9 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp @@ -5,7 +5,7 @@ #if AP_EFI_DRONECAN_ENABLED #include -#include +#include #include extern const AP_HAL::HAL& hal; @@ -20,13 +20,13 @@ AP_EFI_DroneCAN::AP_EFI_DroneCAN(AP_EFI &_frontend) : } // links the DroneCAN message to this backend -void AP_EFI_DroneCAN::subscribe_msgs(AP_UAVCAN *ap_uavcan) +void AP_EFI_DroneCAN::subscribe_msgs(AP_DroneCAN *ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &trampoline_status, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &trampoline_status, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("status_sub"); } } @@ -37,7 +37,7 @@ void AP_EFI_DroneCAN::update() } // EFI message handler -void AP_EFI_DroneCAN::trampoline_status(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg) +void AP_EFI_DroneCAN::trampoline_status(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg) { if (driver == nullptr) { return; diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.h b/libraries/AP_EFI/AP_EFI_DroneCAN.h index fc695962be2139..c4f9dde22c4724 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.h +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.h @@ -4,7 +4,7 @@ #include "AP_EFI_Backend.h" #if AP_EFI_DRONECAN_ENABLED -#include +#include class AP_EFI_DroneCAN : public AP_EFI_Backend { public: @@ -12,8 +12,8 @@ class AP_EFI_DroneCAN : public AP_EFI_Backend { void update() override; - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); - static void trampoline_status(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static void trampoline_status(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ice_reciprocating_Status &msg); private: void handle_status(const uavcan_equipment_ice_reciprocating_Status &pkt); From 8829f54d89cef4d1cb63c53198e93552b8fcc4fb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 154/287] AP_GPS: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_GPS/AP_GPS.cpp | 2 +- libraries/AP_GPS/AP_GPS_UAVCAN.cpp | 96 +++++++++++++++--------------- libraries/AP_GPS/AP_GPS_UAVCAN.h | 34 +++++------ 3 files changed, 66 insertions(+), 66 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index e3adaf8059a551..d54ab189105945 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -43,7 +43,7 @@ #if HAL_ENABLE_LIBUAVCAN_DRIVERS #include -#include +#include #include "AP_GPS_UAVCAN.h" #endif diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp index 21ae0987d61f0e..8ac0ca6d6571ba 100644 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp @@ -22,7 +22,7 @@ #include "AP_GPS_UAVCAN.h" #include -#include +#include #include #include @@ -65,9 +65,9 @@ AP_GPS_UAVCAN::AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GP interim_state(_state), role(_role) { - param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_int, bool, AP_UAVCAN*, const uint8_t, const char*, int32_t &); - param_float_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_float, bool, AP_UAVCAN*, const uint8_t, const char*, float &); - param_save_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_save_response, void, AP_UAVCAN*, const uint8_t, bool); + param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_int, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); + param_float_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_float, bool, AP_DroneCAN*, const uint8_t, const char*, float &); + param_save_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_save_response, void, AP_DroneCAN*, const uint8_t, bool); } AP_GPS_UAVCAN::~AP_GPS_UAVCAN() @@ -83,33 +83,33 @@ AP_GPS_UAVCAN::~AP_GPS_UAVCAN() #endif } -void AP_GPS_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) +void AP_GPS_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_fix2_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_fix2_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("status_sub"); } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_aux_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_aux_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("status_sub"); } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_heading_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_heading_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("status_sub"); } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_status_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_status_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("status_sub"); } #if GPS_MOVING_BASELINE - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_moving_baseline_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_moving_baseline_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("moving_baseline_sub"); } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_relposheading_msg_trampoline, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_relposheading_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("relposheading_sub"); } #endif @@ -122,7 +122,7 @@ AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) AP_GPS_UAVCAN* backend = nullptr; bool bad_override_config = false; for (int8_t i = GPS_MAX_RECEIVERS - 1; i >= 0; i--) { - if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) { + if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { if (_gps._override_node_id[_state.instance] != 0 && _gps._override_node_id[_state.instance] != _detected_modules[i].node_id) { continue; // This device doesn't match the correct node @@ -182,7 +182,7 @@ AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) LOG_TAG, "Failed to register UAVCAN GPS Node %d on Bus %d\n", _detected_modules[found_match].node_id, - _detected_modules[found_match].ap_uavcan->get_driver_index()); + _detected_modules[found_match].ap_dronecan->get_driver_index()); } else { _detected_modules[found_match].driver = backend; backend->_detected_module = found_match; @@ -190,9 +190,9 @@ AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) LOG_TAG, "Registered UAVCAN GPS Node %d on Bus %d as instance %d\n", _detected_modules[found_match].node_id, - _detected_modules[found_match].ap_uavcan->get_driver_index(), + _detected_modules[found_match].ap_dronecan->get_driver_index(), _state.instance); - snprintf(backend->_name, ARRAY_SIZE(backend->_name), "UAVCAN%u-%u", _detected_modules[found_match].ap_uavcan->get_driver_index()+1, _detected_modules[found_match].node_id); + snprintf(backend->_name, ARRAY_SIZE(backend->_name), "UAVCAN%u-%u", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); _detected_modules[found_match].instance = _state.instance; for (uint8_t i=0; i < GPS_MAX_RECEIVERS; i++) { if (_detected_modules[found_match].node_id == AP::gps()._node_id[i]) { @@ -210,7 +210,7 @@ AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) if (backend->role == AP_GPS::GPS_ROLE_MB_BASE) { backend->rtcm3_parser = new RTCM3_Parser; if (backend->rtcm3_parser == nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UAVCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_uavcan->get_driver_index()+1, _detected_modules[found_match].node_id); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UAVCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); } } #endif // GPS_MOVING_BASELINE @@ -254,15 +254,15 @@ bool AP_GPS_UAVCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_le return true; } -AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id) +AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return nullptr; } for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { if (_detected_modules[i].driver != nullptr && - _detected_modules[i].ap_uavcan == ap_uavcan && + _detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { return _detected_modules[i].driver; } @@ -271,7 +271,7 @@ AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t n bool already_detected = false; // Check if there's an empty spot for possible registeration for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { - if (_detected_modules[i].ap_uavcan == ap_uavcan && _detected_modules[i].node_id == node_id) { + if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { // Already Detected already_detected = true; break; @@ -279,8 +279,8 @@ AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t n } if (!already_detected) { for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { - if (_detected_modules[i].ap_uavcan == nullptr) { - _detected_modules[i].ap_uavcan = ap_uavcan; + if (_detected_modules[i].ap_dronecan == nullptr) { + _detected_modules[i].ap_dronecan = ap_dronecan; _detected_modules[i].node_id = node_id; // Just set the Node ID in order of appearance // This will be used to set select ids @@ -593,41 +593,41 @@ void AP_GPS_UAVCAN::clear_RTCMV3(void) #endif // GPS_MOVING_BASELINE -void AP_GPS_UAVCAN::handle_fix2_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg) +void AP_GPS_UAVCAN::handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_fix2_msg(msg, transfer.timestamp_usec); } } -void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg) +void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_aux_msg(msg); } } -void AP_GPS_UAVCAN::handle_heading_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg) +void AP_GPS_UAVCAN::handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_heading_msg(msg); } } -void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg) +void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_status_msg(msg); } @@ -635,20 +635,20 @@ void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_UAVCAN *ap_uavcan, const Can #if GPS_MOVING_BASELINE // Moving Baseline msg trampoline -void AP_GPS_UAVCAN::handle_moving_baseline_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg) +void AP_GPS_UAVCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_moving_baseline_msg(msg, transfer.source_node_id); } } // RelPosHeading msg trampoline -void AP_GPS_UAVCAN::handle_relposheading_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg) +void AP_GPS_UAVCAN::handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_relposheading_msg(msg, transfer.source_node_id); } @@ -657,26 +657,26 @@ void AP_GPS_UAVCAN::handle_relposheading_msg_trampoline(AP_UAVCAN *ap_uavcan, co bool AP_GPS_UAVCAN::do_config() { - AP_UAVCAN *ap_uavcan = _detected_modules[_detected_module].ap_uavcan; - if (ap_uavcan == nullptr) { + AP_DroneCAN *ap_dronecan = _detected_modules[_detected_module].ap_dronecan; + if (ap_dronecan == nullptr) { return false; } uint8_t node_id = _detected_modules[_detected_module].node_id; switch(cfg_step) { case STEP_SET_TYPE: - ap_uavcan->get_parameter_on_node(node_id, "GPS_TYPE", ¶m_int_cb); + ap_dronecan->get_parameter_on_node(node_id, "GPS_TYPE", ¶m_int_cb); break; case STEP_SET_MB_CAN_TX: if (role != AP_GPS::GPS_Role::GPS_ROLE_NORMAL) { - ap_uavcan->get_parameter_on_node(node_id, "GPS_MB_ONLY_PORT", ¶m_int_cb); + ap_dronecan->get_parameter_on_node(node_id, "GPS_MB_ONLY_PORT", ¶m_int_cb); } else { cfg_step++; } break; case STEP_SAVE_AND_REBOOT: if (requires_save_and_reboot) { - ap_uavcan->save_parameters_on_node(node_id, ¶m_save_cb); + ap_dronecan->save_parameters_on_node(node_id, ¶m_save_cb); } else { cfg_step++; } @@ -765,15 +765,15 @@ void AP_GPS_UAVCAN::inject_data(const uint8_t *data, uint16_t len) // send the data as broadcast on all UAVCAN devive ports and we // don't want to send duplicates if (_detected_module == 0 || - _detected_modules[_detected_module].ap_uavcan != _detected_modules[0].ap_uavcan) { - _detected_modules[_detected_module].ap_uavcan->send_RTCMStream(data, len); + _detected_modules[_detected_module].ap_dronecan != _detected_modules[0].ap_dronecan) { + _detected_modules[_detected_module].ap_dronecan->send_RTCMStream(data, len); } } /* handle param get/set response */ -bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_UAVCAN* ap_uavcan, uint8_t node_id, const char* name, int32_t &value) +bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, int32_t &value) { Debug("AP_GPS_UAVCAN: param set/get response from %d %s %ld\n", node_id, name, value); if (strcmp(name, "GPS_TYPE") == 0 && cfg_step == STEP_SET_TYPE) { @@ -810,13 +810,13 @@ bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_UAVCAN* ap_uavcan, uint return false; } -bool AP_GPS_UAVCAN::handle_param_get_set_response_float(AP_UAVCAN* ap_uavcan, uint8_t node_id, const char* name, float &value) +bool AP_GPS_UAVCAN::handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, float &value) { Debug("AP_GPS_UAVCAN: param set/get response from %d %s %f\n", node_id, name, value); return false; } -void AP_GPS_UAVCAN::handle_param_save_response(AP_UAVCAN* ap_uavcan, const uint8_t node_id, bool success) +void AP_GPS_UAVCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success) { Debug("AP_GPS_UAVCAN: param save response from %d %s\n", node_id, success ? "success" : "failure"); @@ -830,14 +830,14 @@ void AP_GPS_UAVCAN::handle_param_save_response(AP_UAVCAN* ap_uavcan, const uint8 // Also send reboot command // this is ok as we are sending from UAVCAN thread context Debug("AP_GPS_UAVCAN: sending reboot command %d\n", node_id); - ap_uavcan->send_reboot_request(node_id); + ap_dronecan->send_reboot_request(node_id); } #if AP_DRONECAN_SEND_GPS -bool AP_GPS_UAVCAN::instance_exists(const AP_UAVCAN* ap_uavcan) +bool AP_GPS_UAVCAN::instance_exists(const AP_DroneCAN* ap_dronecan) { for (uint8_t i=0; i +#include class AP_GPS_UAVCAN : public AP_GPS_Backend { public: @@ -41,17 +41,17 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { const char *name() const override { return _name; } - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); static AP_GPS_Backend* probe(AP_GPS &_gps, AP_GPS::GPS_State &_state); - static void handle_fix2_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg); + static void handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg); - static void handle_aux_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg); - static void handle_heading_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg); - static void handle_status_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg); + static void handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg); + static void handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg); + static void handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg); #if GPS_MOVING_BASELINE - static void handle_moving_baseline_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg); - static void handle_relposheading_msg_trampoline(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg); + static void handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg); + static void handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg); #endif static bool backends_healthy(char failure_msg[], uint16_t failure_msg_len); void inject_data(const uint8_t *data, uint16_t len) override; @@ -64,7 +64,7 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { #endif #if AP_DRONECAN_SEND_GPS - static bool instance_exists(const AP_UAVCAN* ap_uavcan); + static bool instance_exists(const AP_DroneCAN* ap_dronecan); #endif private: @@ -95,7 +95,7 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { static bool take_registry(); static void give_registry(); - static AP_GPS_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id); + static AP_GPS_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); bool _new_data; AP_GPS::GPS_State interim_state; @@ -116,7 +116,7 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { // Module Detection Registry static struct DetectedModules { - AP_UAVCAN* ap_uavcan; + AP_DroneCAN* ap_dronecan; uint8_t node_id; uint8_t instance; AP_GPS_UAVCAN* driver; @@ -131,12 +131,12 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { // the role set from GPS_TYPE AP_GPS::GPS_Role role; - FUNCTOR_DECLARE(param_int_cb, bool, AP_UAVCAN*, const uint8_t, const char*, int32_t &); - FUNCTOR_DECLARE(param_float_cb, bool, AP_UAVCAN*, const uint8_t, const char*, float &); - FUNCTOR_DECLARE(param_save_cb, void, AP_UAVCAN*, const uint8_t, bool); + FUNCTOR_DECLARE(param_int_cb, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); + FUNCTOR_DECLARE(param_float_cb, bool, AP_DroneCAN*, const uint8_t, const char*, float &); + FUNCTOR_DECLARE(param_save_cb, void, AP_DroneCAN*, const uint8_t, bool); - bool handle_param_get_set_response_int(AP_UAVCAN* ap_uavcan, const uint8_t node_id, const char* name, int32_t &value); - bool handle_param_get_set_response_float(AP_UAVCAN* ap_uavcan, const uint8_t node_id, const char* name, float &value); - void handle_param_save_response(AP_UAVCAN* ap_uavcan, const uint8_t node_id, bool success); + bool handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, int32_t &value); + bool handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, float &value); + void handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success); }; #endif From e0f2f060c6b568ff151bc3fcf533a16f0faa48ed Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 155/287] AP_HAL_ChibiOS: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat index c122822bd8ec14..e99f50662bd33f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat @@ -145,7 +145,7 @@ define HAL_OS_FATFS_IO 1 define HAL_WITH_UAVCAN 1 env HAL_WITH_UAVCAN 1 define HAL_PICCOLO_CAN_ENABLE 0 -define AP_UAVCAN_SLCAN_ENABLED 1 +define AP_CAN_SLCAN_ENABLED 1 PA1 ANALOG_CAN_VOLTAGE1 ADC1 SCALE(21.404) PA2 ANALOG_CAN_VOLTAGE2 ADC1 SCALE(21.404) From 420ceec553ca73c0b36f7495ff628b3901d0aebc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 156/287] AP_HAL: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_HAL/AP_HAL_Boards.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index e62c415f74fc7d..d369d2ce5ff979 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -246,9 +246,9 @@ #endif #if HAL_NUM_CAN_IFACES && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -#define AP_UAVCAN_SLCAN_ENABLED 1 +#define AP_CAN_SLCAN_ENABLED 1 #else -#define AP_UAVCAN_SLCAN_ENABLED 0 +#define AP_CAN_SLCAN_ENABLED 0 #endif #ifndef USE_LIBC_REALLOC From 9c6d84ddb1f00b8ae64470c551fb05cf592b61e2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 157/287] AP_Notify: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_Notify/MMLPlayer.cpp | 4 ++-- libraries/AP_Notify/UAVCAN_RGB_LED.cpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Notify/MMLPlayer.cpp b/libraries/AP_Notify/MMLPlayer.cpp index 68bf2e8164a368..7cb2aac3e34d66 100644 --- a/libraries/AP_Notify/MMLPlayer.cpp +++ b/libraries/AP_Notify/MMLPlayer.cpp @@ -7,7 +7,7 @@ #include #if HAL_CANMANAGER_ENABLED -#include +#include #include #endif @@ -69,7 +69,7 @@ void MMLPlayer::start_note(float duration, float frequency, float volume) uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i); + AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); if (uavcan != nullptr && (AP::notify().get_buzzer_types() & AP_Notify::Notify_Buzz_UAVCAN)) { uavcan->set_buzzer_tone(frequency, _note_duration_us*1.0e-6); diff --git a/libraries/AP_Notify/UAVCAN_RGB_LED.cpp b/libraries/AP_Notify/UAVCAN_RGB_LED.cpp index 5b705235a79127..f07a230f672c71 100644 --- a/libraries/AP_Notify/UAVCAN_RGB_LED.cpp +++ b/libraries/AP_Notify/UAVCAN_RGB_LED.cpp @@ -20,7 +20,7 @@ #if HAL_ENABLE_LIBUAVCAN_DRIVERS #include "UAVCAN_RGB_LED.h" -#include +#include #include @@ -47,7 +47,7 @@ bool UAVCAN_RGB_LED::init() { const uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i); + AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); if (uavcan != nullptr) { return true; } @@ -63,7 +63,7 @@ bool UAVCAN_RGB_LED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_UAVCAN *uavcan = AP_UAVCAN::get_uavcan(i); + AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); if (uavcan != nullptr) { success = uavcan->led_write(_led_index, red, green, blue) || success; } From aa4789547f3001b7da37f3e5c4abebe0937aa746 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:01 +1000 Subject: [PATCH 158/287] AP_OpenDroneID: rename AP_UAVCAN to AP_DroneCAN --- libraries/AP_OpenDroneID/AP_OpenDroneID.h | 16 +++++++-------- .../AP_OpenDroneID_DroneCAN.cpp | 20 +++++++++---------- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID.h b/libraries/AP_OpenDroneID/AP_OpenDroneID.h index e3d8eaa21a997e..217ada58b7422c 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID.h +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID.h @@ -63,7 +63,7 @@ #define ODID_AREA_COUNT_MIN 1 #define ODID_AREA_COUNT_MAX 65000 -class AP_UAVCAN; +class AP_DroneCAN; class AP_OpenDroneID { @@ -81,7 +81,7 @@ class AP_OpenDroneID void update(); // send pending dronecan messages - void dronecan_send(AP_UAVCAN *); + void dronecan_send(AP_DroneCAN *); // handle a message from the GCS void handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg); @@ -193,12 +193,12 @@ class AP_OpenDroneID uint8_t dronecan_done_init; uint8_t dronecan_init_failed; - void dronecan_init(AP_UAVCAN *uavcan); - void dronecan_send_location(AP_UAVCAN *uavcan); - void dronecan_send_basic_id(AP_UAVCAN *uavcan); - void dronecan_send_system(AP_UAVCAN *uavcan); - void dronecan_send_self_id(AP_UAVCAN *uavcan); - void dronecan_send_operator_id(AP_UAVCAN *uavcan); + void dronecan_init(AP_DroneCAN *uavcan); + void dronecan_send_location(AP_DroneCAN *uavcan); + void dronecan_send_basic_id(AP_DroneCAN *uavcan); + void dronecan_send_system(AP_DroneCAN *uavcan); + void dronecan_send_self_id(AP_DroneCAN *uavcan); + void dronecan_send_operator_id(AP_DroneCAN *uavcan); }; namespace AP diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp b/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp index 8d374ac108e26a..30887b9da53943 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp @@ -20,7 +20,7 @@ #if AP_OPENDRONEID_ENABLED -#include +#include #if HAL_ENABLE_LIBUAVCAN_DRIVERS #include @@ -31,9 +31,9 @@ static Canard::Publisher* dc_self_id[HAL_MAX_CAN_PROTO static Canard::Publisher* dc_system[HAL_MAX_CAN_PROTOCOL_DRIVERS]; static Canard::Publisher* dc_operator_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; -static void handle_arm_status(AP_UAVCAN* ap_uavcan, const CanardRxTransfer &transfer, const dronecan_remoteid_ArmStatus &msg); +static void handle_arm_status(AP_DroneCAN* ap_dronecan, const CanardRxTransfer &transfer, const dronecan_remoteid_ArmStatus &msg); -void AP_OpenDroneID::dronecan_init(AP_UAVCAN *uavcan) +void AP_OpenDroneID::dronecan_init(AP_DroneCAN *uavcan) { const uint8_t driver_index = uavcan->get_driver_index(); const uint8_t driver_mask = 1U<get_driver_index(); const uint8_t driver_mask = 1U<get_driver_index()]->broadcast(msg); } -void AP_OpenDroneID::dronecan_send_basic_id(AP_UAVCAN *uavcan) +void AP_OpenDroneID::dronecan_send_basic_id(AP_DroneCAN *uavcan) { dronecan_remoteid_BasicID msg {}; const auto &pkt = pkt_basic_id; @@ -175,7 +175,7 @@ void AP_OpenDroneID::dronecan_send_basic_id(AP_UAVCAN *uavcan) dc_basic_id[uavcan->get_driver_index()]->broadcast(msg); } -void AP_OpenDroneID::dronecan_send_system(AP_UAVCAN *uavcan) +void AP_OpenDroneID::dronecan_send_system(AP_DroneCAN *uavcan) { dronecan_remoteid_System msg {}; const auto &pkt = pkt_system; @@ -195,7 +195,7 @@ void AP_OpenDroneID::dronecan_send_system(AP_UAVCAN *uavcan) dc_system[uavcan->get_driver_index()]->broadcast(msg); } -void AP_OpenDroneID::dronecan_send_self_id(AP_UAVCAN *uavcan) +void AP_OpenDroneID::dronecan_send_self_id(AP_DroneCAN *uavcan) { dronecan_remoteid_SelfID msg {}; const auto &pkt = pkt_self_id; @@ -205,7 +205,7 @@ void AP_OpenDroneID::dronecan_send_self_id(AP_UAVCAN *uavcan) dc_self_id[uavcan->get_driver_index()]->broadcast(msg); } -void AP_OpenDroneID::dronecan_send_operator_id(AP_UAVCAN *uavcan) +void AP_OpenDroneID::dronecan_send_operator_id(AP_DroneCAN *uavcan) { dronecan_remoteid_OperatorID msg {}; const auto &pkt = pkt_operator_id; @@ -218,7 +218,7 @@ void AP_OpenDroneID::dronecan_send_operator_id(AP_UAVCAN *uavcan) /* handle ArmStatus message from DroneCAN */ -static void handle_arm_status(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const dronecan_remoteid_ArmStatus &msg) +static void handle_arm_status(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_remoteid_ArmStatus &msg) { mavlink_open_drone_id_arm_status_t status {}; From 6bc060d8abb6894319d2899563de5fe255b15a71 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:02 +1000 Subject: [PATCH 159/287] AP_OpticalFlow: rename AP_UAVCAN to AP_DroneCAN --- .../AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp | 18 +++++++++--------- .../AP_OpticalFlow/AP_OpticalFlow_HereFlow.h | 8 ++++---- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp index d3c506992da03d..e7a94704420d00 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp @@ -5,14 +5,14 @@ #include #include -#include +#include #include extern const AP_HAL::HAL& hal; uint8_t AP_OpticalFlow_HereFlow::_node_id = 0; AP_OpticalFlow_HereFlow* AP_OpticalFlow_HereFlow::_driver = nullptr; -AP_UAVCAN* AP_OpticalFlow_HereFlow::_ap_uavcan = nullptr; +AP_DroneCAN* AP_OpticalFlow_HereFlow::_ap_dronecan = nullptr; /* constructor - registers instance at top Flow driver */ @@ -26,31 +26,31 @@ AP_OpticalFlow_HereFlow::AP_OpticalFlow_HereFlow(AP_OpticalFlow &flow) : } //links the HereFlow messages to the backend -void AP_OpticalFlow_HereFlow::subscribe_msgs(AP_UAVCAN* ap_uavcan) +void AP_OpticalFlow_HereFlow::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_measurement, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("measurement_sub"); } } //updates driver states based on received HereFlow messages -void AP_OpticalFlow_HereFlow::handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const com_hex_equipment_flow_Measurement &msg) +void AP_OpticalFlow_HereFlow::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const com_hex_equipment_flow_Measurement &msg) { if (_driver == nullptr) { return; } //protect from data coming from duplicate sensors, //as we only handle one Here Flow at a time as of now - if (_ap_uavcan == nullptr) { - _ap_uavcan = ap_uavcan; + if (_ap_dronecan == nullptr) { + _ap_dronecan = ap_dronecan; _node_id = transfer.source_node_id; } - if (_ap_uavcan == ap_uavcan && _node_id == transfer.source_node_id) { + if (_ap_dronecan == ap_dronecan && _node_id == transfer.source_node_id) { WITH_SEMAPHORE(_driver->_sem); _driver->new_data = true; _driver->flowRate = Vector2f(msg.flow_integral[0], msg.flow_integral[1]); diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h index 941fe26681b928..145d8754481f3d 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h @@ -8,7 +8,7 @@ #if AP_OPTICALFLOW_HEREFLOW_ENABLED -#include +#include class AP_OpticalFlow_HereFlow : public OpticalFlow_backend { public: @@ -18,9 +18,9 @@ class AP_OpticalFlow_HereFlow : public OpticalFlow_backend { void update() override; - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static void handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const com_hex_equipment_flow_Measurement &msg); + static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const com_hex_equipment_flow_Measurement &msg); private: @@ -31,7 +31,7 @@ class AP_OpticalFlow_HereFlow : public OpticalFlow_backend { static uint8_t _node_id; static AP_OpticalFlow_HereFlow* _driver; - static AP_UAVCAN* _ap_uavcan; + static AP_DroneCAN* _ap_dronecan; void _push_state(void); }; From 739fb91439b4f3c3b3dd74d5c73af2eb6dd5cdf8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:02 +1000 Subject: [PATCH 160/287] AP_Proximity: rename AP_UAVCAN to AP_DroneCAN --- .../AP_Proximity/AP_Proximity_DroneCAN.cpp | 22 +++++++++---------- .../AP_Proximity/AP_Proximity_DroneCAN.h | 10 ++++----- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp index 80456962bd3c8f..a12a075c5c59b3 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp @@ -19,7 +19,7 @@ #include #include -#include +#include #include #include @@ -32,21 +32,21 @@ ObjectBuffer_TS AP_Proximity_DroneCAN::item //links the Proximity DroneCAN message to this backend -void AP_Proximity_DroneCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) +void AP_Proximity_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_measurement, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("measurement_sub"); } } //Method to find the backend relating to the node id -AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t address, bool create_new) +AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return nullptr; } @@ -64,7 +64,7 @@ AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_UAVCAN* ap_u } //Double check if the driver was initialised as DroneCAN Type if (driver != nullptr && (driver->_backend_type == AP_Proximity::Type::DroneCAN)) { - if (driver->_ap_uavcan == ap_uavcan && + if (driver->_ap_dronecan == ap_dronecan && driver->_node_id == node_id) { return driver; } else { @@ -99,8 +99,8 @@ AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_UAVCAN* ap_u unsigned(i), unsigned(i)); } //Assign node id and respective dronecan driver, for identification - if (driver->_ap_uavcan == nullptr) { - driver->_ap_uavcan = ap_uavcan; + if (driver->_ap_dronecan == nullptr) { + driver->_ap_dronecan = ap_dronecan; driver->_node_id = node_id; break; } @@ -154,10 +154,10 @@ float AP_Proximity_DroneCAN::distance_min() const } //Proximity message handler -void AP_Proximity_DroneCAN::handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg) +void AP_Proximity_DroneCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg) { //fetch the matching DroneCAN driver, node id and sensor id backend instance - AP_Proximity_DroneCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.sensor_id, true); + AP_Proximity_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); if (driver == nullptr) { return; } diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h index 00844c18a6a39e..aa85f7169b5d93 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h @@ -2,7 +2,7 @@ #include "AP_Proximity_Backend.h" -#include +#include #ifndef AP_PROXIMITY_DRONECAN_ENABLED #define AP_PROXIMITY_DRONECAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && HAL_PROXIMITY_ENABLED) @@ -24,18 +24,18 @@ class AP_Proximity_DroneCAN : public AP_Proximity_Backend float distance_min() const override; - static AP_Proximity_DroneCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t address, bool create_new); + static AP_Proximity_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static void handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg); + static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg); private: uint32_t _last_update_ms; // system time of last message received - AP_UAVCAN* _ap_uavcan; + AP_DroneCAN* _ap_dronecan; uint8_t _node_id; struct ObstacleItem { From ac809c84f21726a38511259cefb978c11d8d58c9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:02 +1000 Subject: [PATCH 161/287] AP_RangeFinder: rename AP_UAVCAN to AP_DroneCAN --- .../AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp | 22 +++++++++---------- .../AP_RangeFinder/AP_RangeFinder_UAVCAN.h | 10 ++++----- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp index 4a5b89ffb028e5..b9abe57194a38f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp @@ -4,7 +4,7 @@ #include #include -#include +#include #include #include @@ -13,20 +13,20 @@ extern const AP_HAL::HAL& hal; #define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0) //links the rangefinder uavcan message to this backend -void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) +void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return; } - if (Canard::allocate_sub_arg_callback(ap_uavcan, &handle_measurement, ap_uavcan->get_driver_index()) == nullptr) { + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { AP_BoardConfig::allocation_error("measurement_sub"); } } //Method to find the backend relating to the node id -AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t address, bool create_new) +AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) { - if (ap_uavcan == nullptr) { + if (ap_dronecan == nullptr) { return nullptr; } AP_RangeFinder_UAVCAN* driver = nullptr; @@ -39,7 +39,7 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u } //Double check if the driver was initialised as UAVCAN Type if (driver != nullptr && (driver->_backend_type == RangeFinder::Type::UAVCAN)) { - if (driver->_ap_uavcan == ap_uavcan && + if (driver->_ap_dronecan == ap_dronecan && driver->_node_id == node_id) { return driver; } else { @@ -68,8 +68,8 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u gcs().send_text(MAV_SEVERITY_INFO, "RangeFinder[%u]: added UAVCAN node %u addr %u", unsigned(i), unsigned(node_id), unsigned(address)); //Assign node id and respective uavcan driver, for identification - if (driver->_ap_uavcan == nullptr) { - driver->_ap_uavcan = ap_uavcan; + if (driver->_ap_dronecan == nullptr) { + driver->_ap_dronecan = ap_dronecan; driver->_node_id = node_id; break; } @@ -100,10 +100,10 @@ void AP_RangeFinder_UAVCAN::update() } //RangeFinder message handler -void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg) +void AP_RangeFinder_UAVCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg) { //fetch the matching uavcan driver, node id and sensor id backend instance - AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_uavcan, transfer.source_node_id, msg.sensor_id, true); + AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); if (driver == nullptr) { return; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h index 18f320583610b3..47cdca2284b4ed 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h @@ -8,7 +8,7 @@ #if AP_RANGEFINDER_UAVCAN_ENABLED -#include +#include class MeasurementCb; @@ -19,11 +19,11 @@ class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { void update() override; - static void subscribe_msgs(AP_UAVCAN* ap_uavcan); - static AP_RangeFinder_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t address, bool create_new); + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static AP_RangeFinder_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); - static void handle_measurement(AP_UAVCAN *ap_uavcan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg); + static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg); protected: virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { @@ -34,7 +34,7 @@ class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { RangeFinder::Status _status; uint16_t _distance_cm; uint32_t _last_reading_ms; - AP_UAVCAN* _ap_uavcan; + AP_DroneCAN* _ap_dronecan; uint8_t _node_id; bool new_data; MAV_DISTANCE_SENSOR _sensor_type; From ee9b6bad7b0e062c0e941d8d0a5e89cddd5452c4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:02 +1000 Subject: [PATCH 162/287] GCS_MAVLink: rename AP_UAVCAN to AP_DroneCAN --- libraries/GCS_MAVLink/GCS_Common.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a7a0f233542a62..eaa41364aacd4f 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -82,7 +82,7 @@ #include #endif #include - #include + #include #endif #if !defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY) From 4c4af3330ac67e9ac723d377e8aa6ba19520ccfa Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:02 +1000 Subject: [PATCH 163/287] SITL: rename AP_UAVCAN to AP_DroneCAN --- libraries/SITL/SIM_DroneCANDevice.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/SITL/SIM_DroneCANDevice.cpp b/libraries/SITL/SIM_DroneCANDevice.cpp index f550095f01a5d9..51d1c9ac3d7340 100644 --- a/libraries/SITL/SIM_DroneCANDevice.cpp +++ b/libraries/SITL/SIM_DroneCANDevice.cpp @@ -24,7 +24,7 @@ #include #include #include -#include +#include using namespace SITL; @@ -235,4 +235,4 @@ void DroneCANDevice::update() update_rangefinder(); } -#endif // AP_TEST_DRONECAN_DRIVERS \ No newline at end of file +#endif // AP_TEST_DRONECAN_DRIVERS From 61259970935c661e20003de44a942f442642ccac Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:02 +1000 Subject: [PATCH 164/287] SRV_Channel: rename AP_UAVCAN to AP_DroneCAN --- libraries/SRV_Channel/SRV_Channels.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channels.cpp b/libraries/SRV_Channel/SRV_Channels.cpp index 798b0830a51d85..b6489e1b9393b2 100644 --- a/libraries/SRV_Channel/SRV_Channels.cpp +++ b/libraries/SRV_Channel/SRV_Channels.cpp @@ -27,7 +27,7 @@ #if HAL_MAX_CAN_PROTOCOL_DRIVERS #include - #include + #include // To be replaced with macro saying if KDECAN library is included #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub) @@ -540,11 +540,11 @@ void SRV_Channels::push() for (uint8_t i = 0; i < can_num_drivers; i++) { switch (AP::can().get_driver_type(i)) { case AP_CANManager::Driver_Type_UAVCAN: { - AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i); - if (ap_uavcan == nullptr) { + AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_uavcan(i); + if (ap_dronecan == nullptr) { continue; } - ap_uavcan->SRV_push_servos(); + ap_dronecan->SRV_push_servos(); break; } case AP_CANManager::Driver_Type_KDECAN: { From 70fb79c349e1470a58d4c8bc51d92fdb0c526491 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:18:02 +1000 Subject: [PATCH 165/287] Tools: rename AP_UAVCAN to AP_DroneCAN --- Tools/scripts/extract_features.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 90e22f16aeb505..a841b9f63b1dc2 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -152,7 +152,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P.*)::_process_pulse\b',), ('AP_VOLZ_ENABLED', r'AP_Volz_Protocol::init\b',), - ('AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', r'AP_UAVCAN::handle_actuator_status_Volz\b',), + ('AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', r'AP_DroneCAN::handle_actuator_status_Volz\b',), ('AP_ROBOTISSERVO_ENABLED', r'AP_RobotisServo::init\b',), ('AP_FETTEC_ONEWIRE_ENABLED', r'AP_FETtecOneWire::init\b',), From bdbcdfce603887434f68097a3e3d6a7e8620ca73 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 10:28:22 +1000 Subject: [PATCH 166/287] AP_HAL: fixed SLCAN duplicate define --- libraries/AP_HAL/AP_HAL_Boards.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index d369d2ce5ff979..3107ec5743f3ac 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -245,7 +245,7 @@ #define HAL_HAVE_DUAL_USB_CDC 0 #endif -#if HAL_NUM_CAN_IFACES && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if HAL_NUM_CAN_IFACES && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && !defined(AP_CAN_SLCAN_ENABLED) #define AP_CAN_SLCAN_ENABLED 1 #else #define AP_CAN_SLCAN_ENABLED 0 From dec4dff1d855c189f8239232cc408e85004c8e4a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 17:43:08 +1000 Subject: [PATCH 167/287] AP_DroneCAN: fixed valgrind errors --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 3 ++- libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index be43ab7ac08d37..7a3651ce142fef 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -914,15 +914,16 @@ void AP_DroneCAN::safety_state_send() switch (hal.util->safety_switch_state()) { case AP_HAL::Util::SAFETY_ARMED: safety_msg.status = ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_OFF; + safety_state.broadcast(safety_msg); break; case AP_HAL::Util::SAFETY_DISARMED: safety_msg.status = ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON; + safety_state.broadcast(safety_msg); break; default: // nothing to send break; } - safety_state.broadcast(safety_msg); } { // handle ArmingStatus diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index 073265d9b500dd..0a703b7d2029bb 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -544,7 +544,7 @@ void AP_DroneCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer, rcvd_unique_id_offset += msg.unique_id.len; //send follow up message - uavcan_protocol_dynamic_node_id_Allocation rsp; + uavcan_protocol_dynamic_node_id_Allocation rsp {}; /* Respond with the message containing the received unique ID so far or with node id if we successfully allocated one. */ From baa7301977b7295f1390cedce014ba27b420abe8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 16:39:30 +1000 Subject: [PATCH 168/287] HAL_SITL: fixed valgrind error --- libraries/AP_HAL_SITL/CANSocketIface.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index 84c6147509a549..6e443e1425e55a 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -57,7 +57,8 @@ uint8_t CANIface::next_interface; static can_frame makeSocketCanFrame(const AP_HAL::CANFrame& uavcan_frame) { - can_frame sockcan_frame { uavcan_frame.id& AP_HAL::CANFrame::MaskExtID, uavcan_frame.dlc, { } }; + can_frame sockcan_frame { uavcan_frame.id& AP_HAL::CANFrame::MaskExtID, uavcan_frame.dlc, { }, }; + memset(sockcan_frame.data, 0, sizeof(sockcan_frame.data)); std::copy(uavcan_frame.data, uavcan_frame.data + uavcan_frame.dlc, sockcan_frame.data); if (uavcan_frame.isExtended()) { sockcan_frame.can_id |= CAN_EFF_FLAG; @@ -73,7 +74,8 @@ static can_frame makeSocketCanFrame(const AP_HAL::CANFrame& uavcan_frame) static canfd_frame makeSocketCanFDFrame(const AP_HAL::CANFrame& uavcan_frame) { - canfd_frame sockcan_frame { uavcan_frame.id& AP_HAL::CANFrame::MaskExtID, AP_HAL::CANFrame::dlcToDataLength(uavcan_frame.dlc), CANFD_BRS, 0, 0, { } }; + canfd_frame sockcan_frame { uavcan_frame.id& AP_HAL::CANFrame::MaskExtID, AP_HAL::CANFrame::dlcToDataLength(uavcan_frame.dlc), CANFD_BRS, 0, 0, { }, }; + memset(sockcan_frame.data, 0, sizeof(sockcan_frame.data)); std::copy(uavcan_frame.data, uavcan_frame.data + AP_HAL::CANFrame::dlcToDataLength(uavcan_frame.dlc), sockcan_frame.data); if (uavcan_frame.isExtended()) { sockcan_frame.can_id |= CAN_EFF_FLAG; From d8416eb38f872e179b9de83ad829536bf2b78791 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 21:09:55 +1000 Subject: [PATCH 169/287] AP_HAL: fixed build for HerePro --- libraries/AP_HAL/AP_HAL_Boards.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 3107ec5743f3ac..2a3706ad034d72 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -245,11 +245,13 @@ #define HAL_HAVE_DUAL_USB_CDC 0 #endif -#if HAL_NUM_CAN_IFACES && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && !defined(AP_CAN_SLCAN_ENABLED) +#ifndef AP_CAN_SLCAN_ENABLED +#if HAL_NUM_CAN_IFACES && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #define AP_CAN_SLCAN_ENABLED 1 #else #define AP_CAN_SLCAN_ENABLED 0 #endif +#endif #ifndef USE_LIBC_REALLOC #define USE_LIBC_REALLOC 1 From 08b3609fa91ea30687c10d740d7594a4af3a199f Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 27 Mar 2023 10:23:25 -0500 Subject: [PATCH 170/287] AP_OSD:add option to convert home,wind,waypoint and gndspd arrows for BF font set --- libraries/AP_OSD/AP_OSD.cpp | 2 +- libraries/AP_OSD/AP_OSD.h | 2 ++ libraries/AP_OSD/AP_OSD_Screen.cpp | 39 ++++++++++++++++++------------ 3 files changed, 26 insertions(+), 17 deletions(-) diff --git a/libraries/AP_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp index 3088cd96c6fe7e..e883c8c1defbc3 100644 --- a/libraries/AP_OSD/AP_OSD.cpp +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -85,7 +85,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = { // @Param: _OPTIONS // @DisplayName: OSD Options // @Description: This sets options that change the display - // @Bitmask: 0:UseDecimalPack, 1:InvertedWindPointer, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair + // @Bitmask: 0:UseDecimalPack, 1:InvertedWindArrow, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 5:TranslateArrows // @User: Standard AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK), diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index eaadd0e0d1150e..9dcc8b1fc8d9fd 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -271,6 +271,7 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen //helper functions void draw_speed(uint8_t x, uint8_t y, float angle_rad, float magnitude); void draw_distance(uint8_t x, uint8_t y, float distance); + char get_arrow_font_index (int32_t angle_cd); #if HAL_WITH_ESC_TELEM void draw_esc_temp(uint8_t x, uint8_t y); void draw_esc_rpm(uint8_t x, uint8_t y); @@ -537,6 +538,7 @@ class AP_OSD OPTION_INVERTED_AH_ROLL = 1U<<2, OPTION_IMPERIAL_MILES = 1U<<3, OPTION_DISABLE_CROSSHAIR = 1U<<4, + OPTION_BF_ARROWS = 1U<<5, }; enum { diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index ca931576a99026..86ca4647dbb462 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -1291,6 +1291,17 @@ float AP_OSD_AbstractScreen::u_scale(enum unit_type unit, float value) return value * scale[units][unit] + (offsets[units]?offsets[units][unit]:0); } +char AP_OSD_Screen::get_arrow_font_index(int32_t angle_cd) +{ + uint32_t interval = 36000 / SYMBOL(SYM_ARROW_COUNT); + angle_cd = wrap_360_cd(angle_cd); + // if using BF font table must translate arrows + if (check_option(AP_OSD::OPTION_BF_ARROWS)) { + angle_cd = angle_cd > 18000? 54000 - angle_cd : 18000- angle_cd; + } + return SYMBOL(SYM_ARROW_START) + ((angle_cd + interval / 2) / interval) % SYMBOL(SYM_ARROW_COUNT); +} + void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y) { float alt; @@ -1510,8 +1521,8 @@ void AP_OSD_Screen::draw_message(uint8_t x, uint8_t y) // draw a arrow at the given angle, and print the given magnitude void AP_OSD_Screen::draw_speed(uint8_t x, uint8_t y, float angle_rad, float magnitude) { - static const int32_t interval = 36000 / SYMBOL(SYM_ARROW_COUNT); - char arrow = SYMBOL(SYM_ARROW_START) + ((int32_t(angle_rad*DEGX100) + interval / 2) / interval) % SYMBOL(SYM_ARROW_COUNT); + int32_t angle_cd = angle_rad * DEGX100; + char arrow = get_arrow_font_index(angle_cd); if (u_scale(SPEED, magnitude) < 9.95) { backend->write(x, y, false, "%c %1.1f%c", arrow, u_scale(SPEED, magnitude), u_icon(SPEED)); } else { @@ -1525,13 +1536,11 @@ void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y) WITH_SEMAPHORE(ahrs.get_semaphore()); Vector2f v = ahrs.groundspeed_vector(); backend->write(x, y, false, "%c", SYMBOL(SYM_GSPD)); - float angle = 0; const float length = v.length(); if (length > 1.0f) { - angle = wrap_2PI(atan2f(v.y, v.x) - ahrs.yaw); + angle = atan2f(v.y, v.x) - ahrs.yaw; } - draw_speed(x + 1, y, angle, length); } @@ -1617,13 +1626,12 @@ void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y) if (ahrs.get_location(loc) && ahrs.home_is_set()) { const Location &home_loc = ahrs.get_home(); float distance = home_loc.get_distance(loc); - int32_t angle = wrap_360_cd(loc.get_bearing_to(home_loc) - ahrs.yaw_sensor); - int32_t interval = 36000 / SYMBOL(SYM_ARROW_COUNT); + int32_t angle_cd = loc.get_bearing_to(home_loc) - ahrs.yaw_sensor; if (distance < 2.0f) { //avoid fast rotating arrow at small distances - angle = 0; + angle_cd = 0; } - char arrow = SYMBOL(SYM_ARROW_START) + ((angle + interval / 2) / interval) % SYMBOL(SYM_ARROW_COUNT); + char arrow = get_arrow_font_index(angle_cd); backend->write(x, y, false, "%c%c", SYMBOL(SYM_HOME), arrow); draw_distance(x+2, y, distance); } else { @@ -1755,14 +1763,14 @@ void AP_OSD_Screen::draw_wind(uint8_t x, uint8_t y) if (check_option(AP_OSD::OPTION_INVERTED_WIND)) { angle = M_PI; } - angle = wrap_2PI(angle + atan2f(v.y, v.x) - ahrs.yaw); - } + angle = angle + atan2f(v.y, v.x) - ahrs.yaw; + } draw_speed(x + 1, y, angle, length); #else const AP_WindVane* windvane = AP_WindVane::get_singleton(); if (windvane != nullptr) { - draw_speed(x + 1, y, wrap_2PI(windvane->get_apparent_wind_direction_rad() + M_PI), windvane->get_apparent_wind_speed()); + draw_speed(x + 1, y, windvane->get_apparent_wind_direction_rad() + M_PI, windvane->get_apparent_wind_speed()); } #endif @@ -1924,13 +1932,12 @@ void AP_OSD_Screen::draw_hdop(uint8_t x, uint8_t y) void AP_OSD_Screen::draw_waypoint(uint8_t x, uint8_t y) { AP_AHRS &ahrs = AP::ahrs(); - int32_t angle = wrap_360_cd(osd->nav_info.wp_bearing - ahrs.yaw_sensor); - int32_t interval = 36000 / SYMBOL(SYM_ARROW_COUNT); + int32_t angle_cd = osd->nav_info.wp_bearing - ahrs.yaw_sensor; if (osd->nav_info.wp_distance < 2.0f) { //avoid fast rotating arrow at small distances - angle = 0; + angle_cd = 0; } - char arrow = SYMBOL(SYM_ARROW_START) + ((angle + interval / 2) / interval) % SYMBOL(SYM_ARROW_COUNT); + char arrow = get_arrow_font_index(angle_cd); backend->write(x,y, false, "%c%2u%c",SYMBOL(SYM_WPNO), osd->nav_info.wp_number, arrow); draw_distance(x+4, y, osd->nav_info.wp_distance); } From def0fec958cb124cfeebaefa601a0dbe1932f074 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 7 Apr 2023 18:26:24 +1000 Subject: [PATCH 171/287] AP_BattMonitor: correct compilation when AP_BattMonitor_Analog disabled --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 89dea3872ecd6e..f03ce3f6e0c289 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -266,10 +266,12 @@ AP_BattMonitor::init() state[instance].instance = instance; switch (get_type(instance)) { +#if AP_BATTERY_ANALOG_ENABLED case Type::ANALOG_VOLTAGE_ONLY: case Type::ANALOG_VOLTAGE_AND_CURRENT: drivers[instance] = new AP_BattMonitor_Analog(*this, state[instance], _params[instance]); break; +#endif #if AP_BATTERY_SMBUS_SOLO_ENABLED case Type::SOLO: drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance]); From ba6d467c9dfea921351826e817e54789fdf6a731 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sat, 8 Apr 2023 12:34:08 -0500 Subject: [PATCH 172/287] AP_SerialManager: allow SERIAL1 protocol to be hwdef defined --- libraries/AP_SerialManager/AP_SerialManager.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 64d34730f0d8ad..2f70f96eb72f2d 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -28,6 +28,12 @@ extern const AP_HAL::HAL& hal; +#ifdef HAL_SERIAL1_PROTOCOL +#define SERIAL1_PROTOCOL HAL_SERIAL1_PROTOCOL +#else +#define SERIAL1_PROTOCOL SerialProtocol_MAVLink2 +#endif + #ifdef HAL_SERIAL2_PROTOCOL #define SERIAL2_PROTOCOL HAL_SERIAL2_PROTOCOL #else @@ -139,7 +145,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp // @User: Standard // @RebootRequired: True - AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2), + AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SERIAL1_PROTOCOL), // @Param: 1_BAUD // @DisplayName: Telem1 Baud Rate From ae37d76f2d985e35e342051828ee3d82e4b5db7e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 7 Apr 2023 10:58:57 +1000 Subject: [PATCH 173/287] autotest: allow other prearm failures while waiting for estop prearm accels inconsistent was popping up in here. We can ignore that - we only care we won't arm because of the estop being active. This will also save a bit of time with the removal of the raw delay-for-10-seconds --- Tools/autotest/common.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 02ec61791fa55b..92564e452b1c81 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -11665,10 +11665,12 @@ def Button(self): 0, want_result=mavutil.mavlink.MAV_RESULT_FAILED ) - self.wait_statustext("PreArm: Motors Emergency Stopped", check_context=True) + self.assert_prearm_failure("Motors Emergency Stopped", + other_prearm_failures_fatal=False) self.reboot_sitl() - self.delay_sim_time(10) - self.assert_prearm_failure("Motors Emergency Stopped") + self.assert_prearm_failure( + "Motors Emergency Stopped", + other_prearm_failures_fatal=False) self.context_pop() self.reboot_sitl() From 9f2aef4c97c666e68ed375340047b5e747e57d63 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 7 Apr 2023 10:58:57 +1000 Subject: [PATCH 174/287] autotest: allow other prearm failures while waiting for estop prearm accels inconsistent was popping up in here. We can ignore that - we only care we won't arm because of the estop being active. This will also save a bit of time with the removal of the raw delay-for-10-seconds --- Tools/autotest/rover.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 78789d4ff8e788..86bd82c5469fe3 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6071,8 +6071,9 @@ def EStopAtBoot(self): }) self.set_rc(9, 2000) self.reboot_sitl() - self.delay_sim_time(10) - self.assert_prearm_failure("Motors Emergency Stopped") + self.assert_prearm_failure( + "Motors Emergency Stopped", + other_prearm_failures_fatal=False) self.context_pop() self.reboot_sitl() From 6941193cf0a3a2eec66e4c97447ab2ca2d3cd2db Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 00:06:42 +1000 Subject: [PATCH 175/287] RC_Channel: correct use of transitive include we use this library in this file --- libraries/RC_Channel/RC_Channel.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index bd5d65e261d71d..9d94b6655276e5 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -46,6 +46,7 @@ extern const AP_HAL::HAL& hal; #include #include #include +#include #include #include #include From 465e8839c878da8257be1b76ecb02b57cbd7fea9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 8 Apr 2023 12:48:40 +1000 Subject: [PATCH 176/287] Tools: validate features are removed when we compile them out --- Tools/autotest/test_build_options.py | 59 ++++++++++++++++++++++++++-- Tools/scripts/extract_features.py | 15 +++++-- 2 files changed, 66 insertions(+), 8 deletions(-) diff --git a/Tools/autotest/test_build_options.py b/Tools/autotest/test_build_options.py index 50e9626d0e664f..bb665a20135f7f 100755 --- a/Tools/autotest/test_build_options.py +++ b/Tools/autotest/test_build_options.py @@ -23,9 +23,13 @@ import fnmatch import optparse import os +import sys from pysim import util +sys.path.insert(1, os.path.join(os.path.dirname(__file__), '..', 'scripts')) +import extract_features # noqa + class TestBuildOptionsResult(object): '''object to return results from a comparison''' @@ -160,6 +164,29 @@ def test_disable_feature(self, feature, options): self.test_compile_with_defines(defines) + # if the feature is truly disabled then extract_features.py + # should say so: + for target in self.build_targets: + path = self.target_to_elf_path(target) + extracter = extract_features.ExtractFeatures(path) + (compiled_in_feature_defines, not_compiled_in_feature_defines) = extracter.extract() + for define in defines: + # the following defines are known not to work on some + # or all vehicles: + feature_define_whitelist = set([ + 'AP_RANGEFINDER_ENABLED', # only at vehicle level ATM + 'AC_AVOID_ENABLED', # Rover doesn't obey this + 'AC_OAPATHPLANNER_ENABLED', # Rover doesn't obey this + 'BEACON_ENABLED', # Rover doesn't obey this (should also be AP_BEACON_ENABLED) + 'WINCH_ENABLED', # Copter doesn't use this; should use AP_WINCH_ENABLED + ]) + if define in compiled_in_feature_defines: + error = f"feature gated by {define} still compiled into ({target}); extract_features.py bug?" + if define in feature_define_whitelist: + print("warn: " + error) + else: + raise ValueError(error) + def test_enable_feature(self, feature, options): defines = self.get_enable_defines(feature, options) @@ -195,9 +222,9 @@ def test_compile_with_defines(self, defines): (t,)) raise - def find_build_sizes(self): - '''returns a hash with size of all build targets''' - ret = {} + def target_to_path(self, target, extension=None): + '''given a build target (e.g. copter), return expected path to .bin + file for that target''' target_to_binpath = { "copter": "arducopter", "plane": "arduplane", @@ -206,8 +233,26 @@ def find_build_sizes(self): "sub": "ardusub", "blimp": "blimp", } + filename = target_to_binpath[target] + if extension is not None: + filename += "." + extension + return os.path.join("build", self.board(), "bin", filename) + + def target_to_bin_path(self, target): + '''given a build target (e.g. copter), return expected path to .bin + file for that target''' + return self.target_to_path(target, 'bin') + + def target_to_elf_path(self, target): + '''given a build target (e.g. copter), return expected path to .elf + file for that target''' + return self.target_to_path(target) + + def find_build_sizes(self): + '''returns a hash with size of all build targets''' + ret = {} for target in self.build_targets: - path = os.path.join("build", self.board(), "bin", "%s.bin" % target_to_binpath[target]) + path = self.target_to_bin_path(target) ret[target] = os.path.getsize(path) return ret @@ -253,9 +298,15 @@ def run_disable_in_turn(self): options = list(filter(lambda x : fnmatch.fnmatch(x.define, self.match_glob), options)) count = 1 for feature in sorted(options, key=lambda x : x.define): + with open("/tmp/run-disable-in-turn-progress", "w") as f: + print(f.write(f"{count}/{len(options)} {feature.define}\n")) + # if feature.define < "WINCH_ENABLED": + # count += 1 + # continue if feature.define in self.must_have_defines_for_board(self._board): self.progress("Feature %s(%s) (%u/%u) is a MUST-HAVE" % (feature.label, feature.define, count, len(options))) + count += 1 continue self.progress("Disabling feature %s(%s) (%u/%u)" % (feature.label, feature.define, count, len(options))) diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index a841b9f63b1dc2..bab804c31f22b9 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -319,9 +319,8 @@ def extract_symbols_from_elf(self, filename): return ret - def create_string(self): - - ret = "" + def extract(self): + '''returns two sets - compiled_in and not_compiled_in''' build_options_defines = set([x.define for x in build_options.BUILD_OPTIONS]) @@ -350,10 +349,18 @@ def create_string(self): continue compiled_in_feature_defines.append(some_define) remaining_build_options_defines.discard(some_define) + return (compiled_in_feature_defines, remaining_build_options_defines) + + def create_string(self): + '''returns a string with compiled in and not compiled-in features''' + + (compiled_in_feature_defines, not_compiled_in_feature_defines) = self.extract() + + ret = "" for compiled_in_feature_define in sorted(compiled_in_feature_defines): ret += compiled_in_feature_define + "\n" - for remaining in sorted(remaining_build_options_defines): + for remaining in sorted(not_compiled_in_feature_defines): ret += "!" + remaining + "\n" return ret From d958ce384ffba030425a3e1ae8490b64520d0ada Mon Sep 17 00:00:00 2001 From: Mirko Denecke Date: Sat, 8 Apr 2023 21:09:44 +0200 Subject: [PATCH 177/287] AC_AttitudeControl: fix get_vel_target_z_cms description --- libraries/AC_AttitudeControl/AC_PosControl.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index a9b4d0926e487c..5284f3f36fabc7 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -293,7 +293,7 @@ class AC_PosControl /// set_vel_desired_z_cms - sets desired velocity in cm/s in z axis void set_vel_desired_z_cms(float vel_z_cms) {_vel_desired.z = vel_z_cms;} - /// get_vel_target_z_cms - returns current vertical speed in cm/s + /// get_vel_target_z_cms - returns target vertical speed in cm/s float get_vel_target_z_cms() const { return _vel_target.z; } From 9c32c963344866e8f169fa42e6ae16248038e430 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 16:45:04 +1000 Subject: [PATCH 178/287] Tools: build_options.py correct winch enablement this was renamed throughout - except in here --- Tools/scripts/build_options.py | 2 +- Tools/scripts/extract_features.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index a42eb2d2b3c65b..6d7dd9f022d624 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -167,7 +167,7 @@ def __init__(self, Feature('Payload', 'GRIPPER', 'AP_GRIPPER_ENABLED', 'Enable Gripper', 0, None), Feature('Payload', 'SPRAYER', 'HAL_SPRAYER_ENABLED', 'Enable Sprayer', 0, None), Feature('Payload', 'LANDING_GEAR', 'AP_LANDINGGEAR_ENABLED', 'Enable Landing Gear', 0, None), - Feature('Payload', 'WINCH', 'WINCH_ENABLED', 'Enable Winch', 0, None), + Feature('Payload', 'WINCH', 'AP_WINCH_ENABLED', 'Enable Winch', 0, None), Feature('Plane', 'QUADPLANE', 'HAL_QUADPLANE_ENABLED', 'Enable QuadPlane support', 0, None), Feature('Plane', 'SOARING', 'HAL_SOARING_ENABLED', 'Enable Soaring', 0, None), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index bab804c31f22b9..8bb56d31dc9485 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -146,7 +146,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_GRIPPER_ENABLED', r'AP_Gripper::init\b',), ('HAL_SPRAYER_ENABLED', 'AC_Sprayer::AC_Sprayer',), ('AP_LANDINGGEAR_ENABLED', r'AP_LandingGear::init\b',), - ('WINCH_ENABLED', 'AP_Winch::AP_Winch',), + ('AP_WINCH_ENABLED', 'AP_Winch::AP_Winch',), ('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P.*)::_process_byte\b',), ('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P.*)::_process_pulse\b',), From 80ca43ad37b89e8ec093bef111b083b4f5c0a25e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 21:28:24 +1000 Subject: [PATCH 179/287] AP_Scripting: correct depends for AP_Winch --- libraries/AP_Scripting/generator/description/bindings.desc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index c9584d8e0b6f64..254a5417e70629 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -604,8 +604,8 @@ singleton AP_Mount method get_location_target boolean uint8_t'skip_check Locatio singleton AP_Mount method set_attitude_euler void uint8_t'skip_check float'skip_check float'skip_check float'skip_check singleton AP_Mount method get_camera_state boolean uint8_t'skip_check uint16_t'Null boolean'Null int8_t'Null int8_t'Null boolean'Null -include AP_Winch/AP_Winch.h depends APM_BUILD_COPTER_OR_HELI -singleton AP_Winch depends APM_BUILD_COPTER_OR_HELI +include AP_Winch/AP_Winch.h +singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI singleton AP_Winch rename winch singleton AP_Winch method healthy boolean singleton AP_Winch method relax void From 1b88f4e185e82c1790af19369f0c5781a1dbba24 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 16:37:39 +1000 Subject: [PATCH 180/287] DroneCAN: update for 64 bit libcanard --- modules/DroneCAN/libcanard | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/DroneCAN/libcanard b/modules/DroneCAN/libcanard index 149aa59bd04a00..603f62ecf5ea39 160000 --- a/modules/DroneCAN/libcanard +++ b/modules/DroneCAN/libcanard @@ -1 +1 @@ -Subproject commit 149aa59bd04a005803756e2fc3c20d8a3e9266f0 +Subproject commit 603f62ecf5ea39d1fc4278df7746e7f802162acb From 85d4024e64104424c4ccd9c1d8d04434eb5245c0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 16:38:18 +1000 Subject: [PATCH 181/287] waf: allow for 64 bit CAN builds --- Tools/ardupilotwaf/boards.py | 17 ++++++----------- wscript | 31 ++++++++++--------------------- 2 files changed, 16 insertions(+), 32 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index c1b8c6cd9c2e5a..b407cf937392ae 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -429,15 +429,10 @@ def configure_env(self, cfg, env): ] if self.with_can and not cfg.env.AP_PERIPH: - if not cfg.env.FORCE32BIT and (cfg.env.BOARD == 'sitl' or cfg.env.BOARD == 'linux'): - env.DEFINES.update( - HAL_ENABLE_LIBUAVCAN_DRIVERS = 0 - ) - else: - env.AP_LIBRARIES += [ - 'AP_DroneCAN', - 'modules/DroneCAN/libcanard/*.c', - ] + env.AP_LIBRARIES += [ + 'AP_DroneCAN', + 'modules/DroneCAN/libcanard/*.c', + ] if cfg.options.enable_dronecan_tests: env.DEFINES.update( AP_TEST_DRONECAN_DRIVERS = 1 @@ -1142,7 +1137,7 @@ def __init__(self): self.with_can = False def configure_env(self, cfg, env): - if cfg.options.board == 'linux' and cfg.options.force_32bit: + if cfg.options.board == 'linux': self.with_can = True super(linux, self).configure_env(cfg, env) @@ -1189,7 +1184,7 @@ def configure_env(self, cfg, env): env.DEFINES.update( HAL_FORCE_32BIT = 0, ) - if self.with_can and cfg.options.board == 'linux' and cfg.options.force_32bit: + if self.with_can and cfg.options.board == 'linux': cfg.env.HAL_NUM_CAN_IFACES = 2 cfg.define('HAL_NUM_CAN_IFACES', 2) cfg.define('UAVCAN_EXCEPTIONS', 0) diff --git a/wscript b/wscript index 0a36e56b576201..a9101b821ecacf 100644 --- a/wscript +++ b/wscript @@ -478,11 +478,7 @@ def configure(cfg): cfg.load('clang_compilation_database') cfg.load('waf_unit_test') cfg.load('mavgen') - if cfg.options.board in cfg.ap_periph_boards(): - cfg.load('dronecangen') - else: - if cfg.options.force_32bit or (cfg.options.board != 'sitl' and cfg.options.board != 'linux'): - cfg.load('dronecangen') + cfg.load('dronecangen') cfg.env.SUBMODULE_UPDATE = cfg.options.submodule_update @@ -669,22 +665,15 @@ def _build_dynamic_sources(bld): ) if (bld.get_board().with_can or bld.env.HAL_NUM_CAN_IFACES) and not bld.env.AP_PERIPH: - if (not bld.env.FORCE32BIT) and (bld.env.BOARD == 'sitl' or bld.env.BOARD == 'linux'): - # remove generated files - dronecan_dir = bld.bldnode.make_node('modules/DroneCAN/libcanard/dsdlc_generated/').abspath() - if os.path.exists(dronecan_dir): - print("Removing DroneCAN generated files") - shutil.rmtree(dronecan_dir) - else: - bld( - features='dronecangen', - source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/* libraries/AP_DroneCAN/dsdl/*', dir=True, src=False), - output_dir='modules/DroneCAN/libcanard/dsdlc_generated/', - name='dronecan', - export_includes=[ - bld.bldnode.make_node('modules/DroneCAN/libcanard/dsdlc_generated/include').abspath(), - bld.srcnode.find_dir('modules/DroneCAN/libcanard/').abspath(), - bld.srcnode.find_dir('libraries/AP_DroneCAN/canard/').abspath(), + bld( + features='dronecangen', + source=bld.srcnode.ant_glob('modules/DroneCAN/DSDL/* libraries/AP_DroneCAN/dsdl/*', dir=True, src=False), + output_dir='modules/DroneCAN/libcanard/dsdlc_generated/', + name='dronecan', + export_includes=[ + bld.bldnode.make_node('modules/DroneCAN/libcanard/dsdlc_generated/include').abspath(), + bld.srcnode.find_dir('modules/DroneCAN/libcanard/').abspath(), + bld.srcnode.find_dir('libraries/AP_DroneCAN/canard/').abspath(), ] ) elif bld.env.AP_PERIPH: From 57f63430585df220952f831bfd3ed752e5c48bab Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 16:39:06 +1000 Subject: [PATCH 182/287] AP_HAL: fixed valgrind error --- libraries/AP_HAL/CANIface.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL/CANIface.cpp b/libraries/AP_HAL/CANIface.cpp index 9f31fc6fd7e848..1bc85bc969f740 100644 --- a/libraries/AP_HAL/CANIface.cpp +++ b/libraries/AP_HAL/CANIface.cpp @@ -105,6 +105,7 @@ AP_HAL::CANFrame::CANFrame(uint32_t can_id, const uint8_t* can_data, uint8_t dat return; } memcpy(this->data, can_data, data_len); + memset(&this->data[data_len], 0, MaxDataLen-data_len); if (data_len <= NonFDCANMaxDataLen) { dlc = data_len; } else { From 12ecb4354bb9b36a4d1882b7dcec1baf8435b8c0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 16:39:17 +1000 Subject: [PATCH 183/287] AP_HAL: allow for 64 bit CAN on Linux --- libraries/AP_HAL/board/linux.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL/board/linux.h b/libraries/AP_HAL/board/linux.h index 989b768c539411..58e714b1f73c76 100644 --- a/libraries/AP_HAL/board/linux.h +++ b/libraries/AP_HAL/board/linux.h @@ -397,7 +397,7 @@ #define HAL_GYROFFT_ENABLED 0 #endif -#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NONE) && HAL_FORCE_32BIT +#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NONE // we can use virtual CAN on native builds #define HAL_LINUX_USE_VIRTUAL_CAN 1 #else From b6ae79c7004ffe7c77019bc8e175fc6a9f2b121e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 17:50:02 +1000 Subject: [PATCH 184/287] HAL_SITL: fixed 64 bit periph build --- libraries/AP_HAL_SITL/SITL_Periph_State.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index ce0a51809b2b46..db09856c7afd1a 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -67,8 +67,8 @@ void SITL_State::wait_clock(uint64_t wait_time_usec) { // when Periph can use SITL simulated devices we should remove these // stubs: -ssize_t SITL::SerialDevice::read_from_device(char*, unsigned int) const { return -1; } +ssize_t SITL::SerialDevice::read_from_device(char*, size_t) const { return -1; } -ssize_t SITL::SerialDevice::write_to_device(char const*, unsigned int) const { return -1; } +ssize_t SITL::SerialDevice::write_to_device(char const*, size_t) const { return -1; } #endif //CONFIG_HAL_BOARD == HAL_BOARD_SITL && defined(HAL_BUILD_AP_PERIPH) From cb4b27042c1912224a033ca507b0624da6727608 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 17:50:14 +1000 Subject: [PATCH 185/287] waf: build sitl periph GPS as 64 bit --- Tools/ardupilotwaf/boards.py | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index b407cf937392ae..a744dcc0f2c11b 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -804,17 +804,6 @@ def configure_env(self, cfg, env): HAL_SUPPORT_RCOUT_SERIAL = 0, AP_CAN_SLCAN_ENABLED = 0, ) - # libcanard is written for 32bit platforms - env.CXXFLAGS += [ - '-m32', - ] - env.CFLAGS += [ - '-m32', - ] - env.LDFLAGS += [ - '-m32', - ] - class esp32(Board): From b24adf04f233839181c535c30699d2031285f433 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Apr 2023 17:55:17 +1000 Subject: [PATCH 186/287] autotest: allow sitl periph GPS to run under valgrind and gdb --- Tools/autotest/sim_vehicle.py | 24 ++++++++++++++++++++++-- 1 file changed, 22 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index b6a358c3ee8785..6a788cb5bfb76f 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -670,8 +670,28 @@ def start_CAN_GPS(opts): options = vinfo.options["sitl_periph_gps"]['frames']['gps'] do_build(opts, options) exe = os.path.join(root_dir, 'build/sitl_periph_gps', 'bin/AP_Periph') - run_in_terminal_window("sitl_periph_gps", - ["nice", exe]) + cmd = ["nice"] + cmd_name = "sitl_periph_gps" + if opts.valgrind: + cmd_name += " (valgrind)" + cmd.append("valgrind") + # adding this option allows valgrind to cope with the overload + # of operator new + cmd.append("--soname-synonyms=somalloc=nouserintercepts") + cmd.append("--track-origins=yes") + if opts.gdb or opts.gdb_stopped: + cmd_name += " (gdb)" + cmd.append("gdb") + gdb_commands_file = tempfile.NamedTemporaryFile(mode='w', delete=False) + atexit.register(os.unlink, gdb_commands_file.name) + gdb_commands_file.write("set pagination off\n") + if not opts.gdb_stopped: + gdb_commands_file.write("r\n") + gdb_commands_file.close() + cmd.extend(["-x", gdb_commands_file.name]) + cmd.append("--args") + cmd.append(exe) + run_in_terminal_window(cmd_name, cmd) def start_vehicle(binary, opts, stuff, spawns=None): From a960e647b5443075e8bcacc7c957f13ac0a80202 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Apr 2023 07:32:11 +1000 Subject: [PATCH 187/287] HAL_SITL: fixed sitl periph storage this allows persistent parameters for sitl_periph_gps target --- libraries/AP_HAL_SITL/HAL_SITL_Class.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.h b/libraries/AP_HAL_SITL/HAL_SITL_Class.h index 2f3a890b6449bc..4ddc20b2cb6663 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.h +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.h @@ -47,7 +47,7 @@ class HAL_SITL : public AP_HAL::HAL { void setup_signal_handlers() const; static void exit_signal_handler(int); - bool storage_posix_enabled; + bool storage_posix_enabled = true; bool storage_flash_enabled; bool storage_fram_enabled; From 81b1b69cd59412dc990db9b05c62e2bf315fedcf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Apr 2023 07:33:39 +1000 Subject: [PATCH 188/287] HAL_SITL: fixed receive of CANFD in SITL socketcan we need to use read() and look at the size to work out if each frame is bxCAN of CANFD See https://www.kernel.org/doc/Documentation/networking/can.txt --- libraries/AP_HAL_SITL/CANSocketIface.cpp | 81 +++--------------------- libraries/AP_HAL_SITL/CANSocketIface.h | 2 - 2 files changed, 10 insertions(+), 73 deletions(-) diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index 6e443e1425e55a..536ec62db27ac0 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -106,7 +106,7 @@ static AP_HAL::CANFrame makeCanFrame(const can_frame& sockcan_frame) static AP_HAL::CANFrame makeCanFDFrame(const canfd_frame& sockcan_frame) { - AP_HAL::CANFrame can_frame(sockcan_frame.can_id & CAN_EFF_MASK, sockcan_frame.data, sockcan_frame.len); + AP_HAL::CANFrame can_frame(sockcan_frame.can_id & CAN_EFF_MASK, sockcan_frame.data, sockcan_frame.len, true); if (sockcan_frame.can_id & CAN_EFF_FLAG) { can_frame.id |= AP_HAL::CANFrame::FlagEFF; } @@ -341,16 +341,11 @@ bool CANIface::_pollRead() uint8_t iterations_count = 0; while (iterations_count < CAN_MAX_POLL_ITERATIONS_COUNT) { - iterations_count++; CanRxItem rx; rx.timestamp_us = AP_HAL::native_micros64(); // Monotonic timestamp is not required to be precise (unlike UTC) bool loopback = false; int res; - if (iterations_count % 2 == 0) { - res = _read(rx.frame, rx.timestamp_us, loopback); - } else { - res = _readfd(rx.frame, rx.timestamp_us, loopback); - } + res = _read(rx.frame, rx.timestamp_us, loopback); if (res == 1) { bool accept = true; if (loopback) { // We receive loopback for all CAN frames @@ -411,76 +406,20 @@ int CANIface::_read(AP_HAL::CANFrame& frame, uint64_t& timestamp_us, bool& loopb if (_fd < 0) { return -1; } - auto iov = iovec(); - auto sockcan_frame = can_frame(); - iov.iov_base = &sockcan_frame; - iov.iov_len = sizeof(sockcan_frame); - union { - uint8_t data[CMSG_SPACE(sizeof(::timeval))]; - struct cmsghdr align; - } control; - - auto msg = msghdr(); - msg.msg_iov = &iov; - msg.msg_iovlen = 1; - msg.msg_control = control.data; - msg.msg_controllen = sizeof(control.data); - - const int res = recvmsg(_fd, &msg, MSG_DONTWAIT); - if (res <= 0) { - return (res < 0 && errno == EWOULDBLOCK) ? 0 : res; - } - /* - * Flags - */ - loopback = (msg.msg_flags & static_cast(MSG_CONFIRM)) != 0; - - if (!loopback && !_checkHWFilters(sockcan_frame)) { - return 0; - } - - frame = makeCanFrame(sockcan_frame); - /* - * Timestamp - */ - timestamp_us = AP_HAL::native_micros64(); - return 1; -} - -int CANIface::_readfd(AP_HAL::CANFrame& frame, uint64_t& timestamp_us, bool& loopback) const -{ - if (_fd < 0) { - return -1; - } - auto iov = iovec(); - auto sockcan_frame = canfd_frame(); - iov.iov_base = &sockcan_frame; - iov.iov_len = sizeof(sockcan_frame); union { - uint8_t data[CMSG_SPACE(sizeof(::timeval))]; - struct cmsghdr align; - } control; - - auto msg = msghdr(); - msg.msg_iov = &iov; - msg.msg_iovlen = 1; - msg.msg_control = control.data; - msg.msg_controllen = sizeof(control.data); + can_frame frame; + canfd_frame frame_fd; + } frames; - const int res = recvmsg(_fd, &msg, MSG_DONTWAIT); + const int res = read(_fd, &frames, sizeof(frames)); if (res <= 0) { return (res < 0 && errno == EWOULDBLOCK) ? 0 : res; } - /* - * Flags - */ - loopback = (msg.msg_flags & static_cast(MSG_CONFIRM)) != 0; - - if (!loopback && !_checkHWFilters(sockcan_frame)) { - return 0; + if (res == sizeof(can_frame)) { + frame = makeCanFrame(frames.frame); + } else { + frame = makeCanFDFrame(frames.frame_fd); } - - frame = makeCanFDFrame(sockcan_frame); /* * Timestamp */ diff --git a/libraries/AP_HAL_SITL/CANSocketIface.h b/libraries/AP_HAL_SITL/CANSocketIface.h index 37dd3fd5847def..7d1e8831e37465 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.h +++ b/libraries/AP_HAL_SITL/CANSocketIface.h @@ -144,8 +144,6 @@ class CANIface: public AP_HAL::CANIface { int _read(AP_HAL::CANFrame& frame, uint64_t& ts_usec, bool& loopback) const; - int _readfd(AP_HAL::CANFrame& frame, uint64_t& ts_usec, bool& loopback) const; - void _incrementNumFramesInSocketTxQueue(); void _confirmSentFrame(); From 47a73d2c8fca3fc6e8e61cec263d11963dd4a64f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Apr 2023 07:34:04 +1000 Subject: [PATCH 189/287] waf: fixed build with CANFD and TAO for sitl_periph_gps --- Tools/ardupilotwaf/boards.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index a744dcc0f2c11b..5c56156a9a844e 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -791,6 +791,7 @@ def configure_env(self, cfg, env): AP_MISSION_ENABLED = 0, HAL_RALLY_ENABLED = 0, AP_SCHEDULER_ENABLED = 0, + CANARD_ENABLE_TAO_OPTION = 1, CANARD_ENABLE_CANFD = 1, CANARD_MULTI_IFACE = 1, HAL_CANMANAGER_ENABLED = 0, From 119b0b15f11201eeed324d6f89af8372bd484c25 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Apr 2023 07:34:59 +1000 Subject: [PATCH 190/287] AP_Periph: cope with mixed bxCAN and CANFD packets this allows for runtime switching of CANFD enable, while supporting incoming bxCAN packets in CANFD mode --- Tools/AP_Periph/can.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 85a9519a8797eb..3921b830a9738e 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -925,6 +925,11 @@ static void onTransferReceived(CanardInstance* ins, palToggleLine(HAL_GPIO_PIN_LED_CAN1); #endif +#if HAL_CANFD_SUPPORTED + // enable tao for decoding when not on CANFD + transfer->tao = !transfer->canfd; +#endif + /* * Dynamic node ID allocation protocol. * Taking this branch only if we don't have a node ID, ignoring otherwise. @@ -1477,6 +1482,7 @@ static bool can_do_dna() ,(1U << dronecan.dna_interface) #endif #if HAL_CANFD_SUPPORTED + // always send allocation request as non-FD ,false #endif ); @@ -1767,6 +1773,12 @@ void AP_Periph_FW::can_update() const uint32_t now_us = AP_HAL::micros(); while ((AP_HAL::micros() - now_us) < 1000) { hal.scheduler->delay_microseconds(HAL_PERIPH_LOOP_DELAY_US); + +#if HAL_CANFD_SUPPORTED + // allow for user enabling/disabling CANFD at runtime + dronecan.canard.tao_disabled = periph.g.can_fdmode == 1; +#endif + processTx(); processRx(); } From 526ebcf8c818a48bd5bd2304bbc525e06b14e378 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Apr 2023 08:12:57 +1000 Subject: [PATCH 191/287] DroneCAN: updated dronecan_dsdlc submodule --- modules/DroneCAN/dronecan_dsdlc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/DroneCAN/dronecan_dsdlc b/modules/DroneCAN/dronecan_dsdlc index e3068c595a755d..ebaf96860a11a4 160000 --- a/modules/DroneCAN/dronecan_dsdlc +++ b/modules/DroneCAN/dronecan_dsdlc @@ -1 +1 @@ -Subproject commit e3068c595a755d827bd3350bd8192a0f0393e026 +Subproject commit ebaf96860a11a4cc43c01df6b651df143c6cde2d From d59e8813012ba4fa5752c11995c09fd5b63182f7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Apr 2023 11:31:59 +1000 Subject: [PATCH 192/287] AP_CANManager: fixed MAVCAN fwding flag this caused corruption due to multiple frames --- libraries/AP_CANManager/AP_CANManager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index f597eaff3e5961..a43e8b50fa3fcb 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -521,7 +521,7 @@ void AP_CANManager::process_frame_buffer(void) } const int16_t retcode = hal.can[frame.bus]->send(frame.frame, AP_HAL::native_micros64() + timeout_us, - frame.frame.isCanFDFrame()?AP_HAL::CANIface::IsMAVCAN:0); + AP_HAL::CANIface::IsMAVCAN); if (retcode == 0) { // no space in the CAN output slots, try again later break; From 7b4e4889c730311f9a246f9c35301987756e2cbe Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Apr 2023 11:32:27 +1000 Subject: [PATCH 193/287] AP_Periph: use generated decoder for FW update and actuators --- Tools/AP_Periph/can.cpp | 51 ++++++++++------------------------------- 1 file changed, 12 insertions(+), 39 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 3921b830a9738e..b8a206b46ce914 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -440,20 +440,16 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* memset(comms, 0, sizeof(struct app_bootloader_comms)); comms->magic = APP_BOOTLOADER_COMMS_MAGIC; - // manual decoding due to TAO bug in libcanard generated code - if (transfer->payload_len < 1 || transfer->payload_len > sizeof(comms->path)+1) { + uavcan_protocol_file_BeginFirmwareUpdateRequest req; + if (uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &req)) { return; } - uint32_t offset = 0; - canardDecodeScalar(transfer, 0, 8, false, (void*)&comms->server_node_id); - offset += 8; - for (uint8_t i=0; ipayload_len-1; i++) { - canardDecodeScalar(transfer, offset, 8, false, (void*)&comms->path[i]); - offset += 8; - } + + comms->server_node_id = req.source_node_id; if (comms->server_node_id == 0) { comms->server_node_id = transfer->source_node_id; } + memcpy(comms->path, req.image_file_remote_path.path.data, req.image_file_remote_path.path.len); comms->my_node_id = canardGetLocalNodeID(ins); uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE] {}; @@ -786,42 +782,19 @@ static void handle_esc_rawcommand(CanardInstance* ins, CanardRxTransfer* transfe static void handle_act_command(CanardInstance* ins, CanardRxTransfer* transfer) { - // manual decoding due to TAO bug in libcanard generated code - if (transfer->payload_len < 1 || transfer->payload_len > UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_MAX_SIZE+1) { + uavcan_equipment_actuator_ArrayCommand cmd; + if (uavcan_equipment_actuator_ArrayCommand_decode(transfer, &cmd)) { return; } - const uint8_t data_count = (transfer->payload_len / UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_MAX_SIZE); - uavcan_equipment_actuator_Command data[data_count] {}; - - uint32_t offset = 0; - for (uint8_t i=0; i Date: Mon, 10 Apr 2023 14:45:07 +1000 Subject: [PATCH 194/287] Tools: fixed build of CPUInfo and other tools --- Tools/CPUInfo/CPUInfo.cpp | 2 +- Tools/ardupilotwaf/chibios.py | 4 ++-- Tools/scripts/build_ci.sh | 2 ++ Tools/scripts/make_abin.sh | 2 +- 4 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Tools/CPUInfo/CPUInfo.cpp b/Tools/CPUInfo/CPUInfo.cpp index 73d1c6a45a9cfc..9802c9f93a418c 100644 --- a/Tools/CPUInfo/CPUInfo.cpp +++ b/Tools/CPUInfo/CPUInfo.cpp @@ -25,7 +25,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #if CONFIG_HAL_BOARD != HAL_BOARD_LINUX // On H750 we want to measure external flash to ram performance -#if defined(EXT_FLASH_SIZE_MB) && defined(STM32H7) +#if defined(EXT_FLASH_SIZE_MB) && EXT_FLASH_SIZE_MB>0 && defined(STM32H7) #define DISABLE_CACHES #endif diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 63eeb0a42bdc3e..67920c4c3f5c6f 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -348,7 +348,7 @@ def run(self): class build_abin(Task.Task): '''build an abin file for skyviper firmware upload via web UI''' color='CYAN' - run_str='${TOOLS_SCRIPTS}/make_abin.sh ${SRC}.bin ${SRC}.abin' + run_str='${TOOLS_SCRIPTS}/make_abin.sh ${SRC} ${TGT}' always_run = True def keyword(self): return "Generating" @@ -400,7 +400,7 @@ def chibios_firmware(self): if self.env.BUILD_ABIN: abin_target = self.bld.bldnode.find_or_declare('bin/' + link_output.change_ext('.abin').name) - abin_task = self.create_task('build_abin', src=link_output, tgt=abin_target) + abin_task = self.create_task('build_abin', src=bin_target, tgt=abin_target) abin_task.set_run_after(generate_apj_task) cleanup_task = self.create_task('build_normalized_bins', src=bin_target) diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index bc48d06d8610e0..c4fa17d6c934d4 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -285,6 +285,8 @@ for t in $CI_BUILD_TARGET; do $waf configure --board Durandal $waf clean $waf copter + echo "Building CPUInfo" + $waf --target=tool/CPUInfo # test external flash build echo "Building SPRacingH7" diff --git a/Tools/scripts/make_abin.sh b/Tools/scripts/make_abin.sh index 96d6756281b904..8e903558bba00d 100755 --- a/Tools/scripts/make_abin.sh +++ b/Tools/scripts/make_abin.sh @@ -12,7 +12,7 @@ BINFILE="$1" ABINFILE="$2" [ -f "$BINFILE" ] || { - echo "Can't find bin file" + echo "Can't find bin file $BINFILE for abin" exit 1 } From 386318399628fa5a5b9c964d4b6a7d3e41000e38 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 10 Apr 2023 12:28:05 +1000 Subject: [PATCH 195/287] autotest: give Rover longer to arrive home vagaries of interaction with Python script means we need to give this more time when running balancebot --- Tools/autotest/rover.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 86bd82c5469fe3..64e83424f12705 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -1295,17 +1295,21 @@ def Rally(self): self.wait_ready_to_arm() self.arm_vehicle() + # calculate early to avoid round-trips while vehicle is moving: + accuracy = self.get_parameter("WP_RADIUS") + self.reach_heading_manual(10) self.reach_distance_manual(50) self.change_mode("RTL") + # location copied in from rover-test-rally.txt: loc = mavutil.location(40.071553, -105.229401, 0, 0) - accuracy = self.get_parameter("WP_RADIUS") - self.wait_location(loc, accuracy=accuracy, minimum_duration=10) + + self.wait_location(loc, accuracy=accuracy, minimum_duration=10, timeout=45) self.disarm_vehicle() def fence_with_bad_frame(self, target_system=1, target_component=1): From b620ba23a909bc4f14adf449fa87e78163660bef Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 7 Apr 2023 11:31:05 +1000 Subject: [PATCH 196/287] autotest: correct implicit reboot after a failed test correct problem where we only rebooted if the vehicle was armed after a failed test. Should correct cascading failures after some tests --- Tools/autotest/common.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 92564e452b1c81..0b75a17b37eca0 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -7858,6 +7858,9 @@ def run_one_test_attempt(self, test, interact=False, attempt=1): passed = False reset_needed = True + # if we haven't already reset ArduPilot because it's dead, + # then ensure the vehicle was disarmed at the end of the test. + # If it wasn't then the test is considered failed: if ardupilot_alive and self.armed() and not self.is_tracker(): if ex is None: ex = ArmedAtEndOfTestException("Still armed at end of test") @@ -7874,6 +7877,10 @@ def run_one_test_attempt(self, test, interact=False, attempt=1): self.progress("Force-rebooting SITL") self.reboot_sitl() # that'll learn it passed = False + elif not passed: # implicit reboot after a failed test: + self.progress("Test failed but ArduPilot process alive; rebooting") + self.progress("Force-rebooting SITL") + self.reboot_sitl() # that'll learn it if self._mavproxy is not None: self.progress("Stopping auto-started mavproxy") From 5dc7bfc71874b2160cb728810474afca8e6fe34e Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 9 Apr 2023 14:41:58 -0500 Subject: [PATCH 197/287] AP_TECS: correct metadata for FLARE_HGT --- libraries/AP_TECS/AP_TECS.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 5ea9eba7bbb777..1f6d2a4ee1e3a6 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -268,10 +268,9 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = { // @Param: FLARE_HGT // @DisplayName: Flare holdoff height - // @Description: When height above ground is below this, the sink rate will be held at TECS_LAND_SINK. Use this to perform a hold-of manoeuvre when combined with small values for TECS_LAND_SINK. - // @Range: -10 15 - // @Units: deg - // @Increment: 1 + // @Description: When height above ground is below this, the sink rate will be held at TECS_LAND_SINK. Use this to perform a hold-off manoeuvre when combined with small values for TECS_LAND_SINK. + // @Range: 0 15 + // @Units: m // @User: Advanced AP_GROUPINFO("FLARE_HGT", 32, AP_TECS, _flare_holdoff_hgt, 1.0f), From 395c1e1815689340e3930eb8d1935ea0306020ee Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 6 Apr 2023 23:34:40 +1000 Subject: [PATCH 198/287] Tools: correct OSD feature extraction ... setting OSD_ENABLED false doesn't actually get rid of AP_OSD::AP_OSD ATM! --- Tools/scripts/extract_features.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 8bb56d31dc9485..e507152511a1af 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -129,7 +129,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('HAL_GENERATOR_ENABLED', 'AP_Generator::AP_Generator',), ('AP_GENERATOR_{type}_ENABLED', r'AP_Generator_(?P.*)::update',), - ('OSD_ENABLED', 'AP_OSD::AP_OSD',), + ('OSD_ENABLED', 'AP_OSD::update_osd',), ('HAL_PLUSCODE_ENABLE', 'AP_OSD_Screen::draw_pluscode',), ('OSD_PARAM_ENABLED', 'AP_OSD_ParamScreen::AP_OSD_ParamScreen',), ('HAL_OSD_SIDEBAR_ENABLE', 'AP_OSD_Screen::draw_sidebars',), From ece07601d7771500d254f27b18b7d5788b72403f Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 23 Mar 2023 11:29:17 -0500 Subject: [PATCH 199/287] AP_Scripting:make trikid -1 not valid --- .../applets/Aerobatics/FixedWing/plane_aerobatics.lua | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua index 5ce9690daf0d94..c919888b6533ff 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua @@ -2481,6 +2481,11 @@ function check_trick() end if action == 1 and selection ~= last_trick_selection then local id = TRICKS[selection].id:get() + if id == -1 then + gcs:send_text(0,string.format("Trick %u not setup",selection)) + last_trick_selection = selection + return + end load_trick(id) if command_table[id] ~= nil then local cmd = command_table[id] @@ -2501,6 +2506,11 @@ function check_trick() return end local id = TRICKS[selection].id:get() + if id == -1 then + gcs:send_text(0,string.format("Trick %u not setup",selection)) + last_trick_selection = selection + return + end load_trick(id) if command_table[id] == nil then gcs:send_text(0, string.format("Invalid trick ID %u", id)) From 0a84d38f434a2073b06436a1d4bed067ed552bfa Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 23 Mar 2023 11:35:50 -0500 Subject: [PATCH 200/287] AP_Scritping:change TRIKx_ID defaults to -1 (not setup) --- .../applets/Aerobatics/FixedWing/plane_aerobatics.lua | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua index c919888b6533ff..e6bcf819423ec9 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua @@ -117,7 +117,7 @@ if TRIK_ENABLE:get() > 0 then for i = 1, count do local k = 5*i local prefix = string.format("%u", i) - TRICKS[i] = TrickDef(bind_add_param2(prefix .. "_ID", k+0, i), + TRICKS[i] = TrickDef(bind_add_param2(prefix .. "_ID", k+0, -1), bind_add_param2(prefix .. "_ARG1", k+1, 30), bind_add_param2(prefix .. "_ARG2", k+2, 0), bind_add_param2(prefix .. "_ARG3", k+3, 0), From e12d9e38c787b02f7156be0d33da869fa3858eb4 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 23 Mar 2023 17:41:16 -0500 Subject: [PATCH 201/287] AP_Scripting:add plane aerobatics metadata --- .../Aerobatics/FixedWing/plane_aerobatics.lua | 55 ++++++++++++++++++- 1 file changed, 54 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua index e6bcf819423ec9..0ea2a38faef4ca 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua @@ -31,17 +31,48 @@ ERR_CORR_D = bind_add_param('ERR_COR_D', 13, 2.8) AEROM_ENTRY_RATE = bind_add_param('ENTRY_RATE', 14, 60) AEROM_THR_LKAHD = bind_add_param('THR_LKAHD', 15, 1) AEROM_DEBUG = bind_add_param('DEBUG', 16, 0) +--[[ + // @Param: AEROM_THR_MIN + // @DisplayName: Minimum Throttle + // @Description: Lowest throttle used during maneuvers + // @Units: % +--]] AEROM_THR_MIN = bind_add_param('THR_MIN', 17, 0) AEROM_THR_BOOST = bind_add_param('THR_BOOST', 18, 50) AEROM_YAW_ACCEL = bind_add_param('YAW_ACCEL', 19, 1500) AEROM_LKAHD = bind_add_param('LKAHD', 20, 0.5) +--[[ + // @Param: AEROM_PATH_SCALE + // @DisplayName: Path Scale + // @Description: Scale factor for Path/Box size. 0.5 would half the distances in maneuvers. Radii are unaffected. + // @Range: 0.1 100 +--]] AEROM_PATH_SCALE = bind_add_param('PATH_SCALE', 21, 1.0) +--[[ + // @Param: AEROM_BOX_WIDTH + // @DisplayName: Box Width + // @Description: Length of aerobatic "box" + // @Units: m +--]] AEROM_BOX_WIDTH = bind_add_param('BOX_WIDTH', 22, 400) AEROM_STALL_THR = bind_add_param('STALL_THR', 23, 40) AEROM_STALL_PIT = bind_add_param('STALL_PIT', 24, -20) -- 25 was AEROM_KE_TC + +--[[ + // @Param: AEROM_KE_RUDD + // @DisplayName: KnifeEdge Rudder + // @Description: Percent of rudder normally uses to sustain knife-edge at trick speed + // @Units: % +--]] AEROM_KE_RUDD = bind_add_param('KE_RUDD', 26, 25) AEROM_KE_RUDD_LK = bind_add_param('KE_RUDD_LK', 27, 0.25) +--[[ + // @Param: AEROM_ALT_ABORT + // @DisplayName: Altitude Abort + // @Description: Maximum allowable loss in altitude during a trick or sequence from its starting altitude. + // @Units: m +--]] AEROM_ALT_ABORT = bind_add_param('ALT_ABORT',28,15) -- cope with old param values @@ -77,7 +108,11 @@ function bind_add_param2(name, idx, default_value) assert(param:add_param(PARAM_TABLE_KEY2, idx, name, default_value), string.format('could not add param %s', name)) return Parameter(PARAM_TABLE_PREFIX2 .. name) end - +--[[ + // @Param: TRIK_ENABLE + // @DisplayName: Tricks on Switch Enable + // @Description: Enables Tricks on Switch. TRIK params hidden until enabled +--]] local TRIK_ENABLE = bind_add_param2("_ENABLE", 1, 0) local TRICKS = nil local TRIK_SEL_FN = nil @@ -107,8 +142,26 @@ local function sq(x) end if TRIK_ENABLE:get() > 0 then +--[[ + // @Param: TRIK_SEL_FN + // @DisplayName: Trik Selection Scripting Function + // @Description: Setting an RC channel's _OPTION to this value will use it for trick selection + // @Range: 301 307 +--]] TRIK_SEL_FN = bind_add_param2("_SEL_FN", 2, 301) +--[[ + // @Param: TRIK_ACT_FN + // @DisplayName: Trik Action Scripting Function + // @Description: Setting an RC channel's _OPTION to this value will use it for trick action (abort,announce,execute) + // @Range: 301 307 +--]] TRIK_ACT_FN = bind_add_param2("_ACT_FN", 3, 300) +--[[ + // @Param: TRIK_COUNT + // @DisplayName: Trik Count + // @Description: Number of tricks which can be selected over the range of the trik selection RC channel + // @Range: 1 11 +--]] TRIK_COUNT = bind_add_param2("_COUNT", 4, 3) TRICKS = {} From 5d39dd45bea4439cfc53427e17e12c7e40df9d31 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Wed, 15 Feb 2023 15:52:56 +1100 Subject: [PATCH 202/287] AP_Mount: Add clear_roi_target() function --- libraries/AP_Mount/AP_Mount.cpp | 10 ++++++++++ libraries/AP_Mount/AP_Mount.h | 4 ++++ libraries/AP_Mount/AP_Mount_Backend.cpp | 13 +++++++++++++ libraries/AP_Mount/AP_Mount_Backend.h | 2 ++ 4 files changed, 29 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 18e7303262b105..c52ecf96a9b007 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -595,6 +595,16 @@ void AP_Mount::set_roi_target(uint8_t instance, const Location &target_loc) backend->set_roi_target(target_loc); } +// clear_roi_target - clears target location that mount should attempt to point towards +void AP_Mount::clear_roi_target(uint8_t instance) +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; + } + backend->clear_roi_target(); +} + // // camera controls for gimbals that include a camera // diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 8788768c18294c..1b97c29f14f375 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -139,6 +139,10 @@ class AP_Mount void set_roi_target(const Location &target_loc) { set_roi_target(_primary,target_loc); } void set_roi_target(uint8_t instance, const Location &target_loc); + // clear_roi_target - clears target location that mount should attempt to point towards + void clear_roi_target() { clear_roi_target(_primary); } + void clear_roi_target(uint8_t instance); + // point at system ID sysid void set_target_sysid(uint8_t sysid) { set_target_sysid(_primary, sysid); } void set_target_sysid(uint8_t instance, uint8_t sysid); diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 9033a91f05f76f..c161315c777b04 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -48,6 +48,19 @@ void AP_Mount_Backend::set_roi_target(const Location &target_loc) set_mode(MAV_MOUNT_MODE_GPS_POINT); } +// clear_roi_target - clears target location that mount should attempt to point towards +void AP_Mount_Backend::clear_roi_target() +{ + // clear the target GPS location + _roi_target_set = false; + + // reset the mode if in GPS tracking mode + if (_mode == MAV_MOUNT_MODE_GPS_POINT) { + MAV_MOUNT_MODE default_mode = (MAV_MOUNT_MODE)_params.default_mode.get(); + set_mode(default_mode); + } +} + // set_sys_target - sets system that mount should attempt to point towards void AP_Mount_Backend::set_target_sysid(uint8_t sysid) { diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 72acbdab802b36..e62c0d8df3e4bd 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -74,6 +74,8 @@ class AP_Mount_Backend // set_roi_target - sets target location that mount should attempt to point towards void set_roi_target(const Location &target_loc); + // clear_roi_target - clears target location that mount should attempt to point towards + void clear_roi_target(); // set_sys_target - sets system that mount should attempt to point towards void set_target_sysid(uint8_t sysid); From 8bd127d63093d996a5c974a64080507f035be333 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Wed, 15 Feb 2023 15:53:39 +1100 Subject: [PATCH 203/287] GCS_MAVLink: Use new Mount clear_roi_target() --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index eaa41364aacd4f..f282c54c0687b5 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4971,12 +4971,8 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const Location &roi_loc) } if (roi_loc.lat == 0 && roi_loc.lng == 0 && roi_loc.alt == 0) { - // switch off the camera tracking if enabled - if (mount->get_mode() == MAV_MOUNT_MODE_GPS_POINT) { - mount->set_mode_to_default(); - } + mount->clear_roi_target(); } else { - // send the command to the camera mount mount->set_roi_target(roi_loc); } return MAV_RESULT_ACCEPTED; From 9077f60e87f2833942c8f280f01ae293c229eb44 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 28 Mar 2023 15:12:49 +1100 Subject: [PATCH 204/287] AP_Motors: Tricopter: rework and move yaw servo to arming check, allow no yaw on plane --- libraries/AP_Motors/AP_MotorsTri.cpp | 42 ++++++++++++++++++---------- libraries/AP_Motors/AP_MotorsTri.h | 4 +++ 2 files changed, 32 insertions(+), 14 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index 418a7b88fbc95c..f55f462e99da4c 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -39,18 +39,12 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty motor_enabled[AP_MOTORS_MOT_2] = true; motor_enabled[AP_MOTORS_MOT_4] = true; -#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane) // Tilt Rotors do not need a yaw servo - // find the yaw servo - if (!SRV_Channels::get_channel_for(SRV_Channel::k_motor7, AP_MOTORS_CH_TRI_YAW)) { - gcs().send_text(MAV_SEVERITY_ERROR, "MotorsTri: unable to setup yaw channel"); - // don't set initialised_ok - return; - } -#endif - // allow mapping of motor7 add_motor_num(AP_MOTORS_CH_TRI_YAW); + // Check for tail servo + _have_tail_servo = SRV_Channels::function_assigned(SRV_Channel::k_motor7); + SRV_Channels::set_angle(SRV_Channels::get_motor_function(AP_MOTORS_CH_TRI_YAW), _yaw_servo_angle_max_deg*100); // check for reverse tricopter @@ -175,11 +169,16 @@ void AP_MotorsTri::output_armed_stabilizing() pitch_thrust *= -1.0f; } - // calculate angle of yaw pivot - _pivot_angle = safe_asin(yaw_thrust); - if (fabsf(_pivot_angle) > radians(_yaw_servo_angle_max_deg)) { - limit.yaw = true; - _pivot_angle = constrain_float(_pivot_angle, -radians(_yaw_servo_angle_max_deg), radians(_yaw_servo_angle_max_deg)); + // VTOL plane may not have tail servo + if (!_have_tail_servo) { + _pivot_angle = 0.0; + } else { + // calculate angle of yaw pivot + _pivot_angle = safe_asin(yaw_thrust); + if (fabsf(_pivot_angle) > radians(_yaw_servo_angle_max_deg)) { + limit.yaw = true; + _pivot_angle = constrain_float(_pivot_angle, -radians(_yaw_servo_angle_max_deg), radians(_yaw_servo_angle_max_deg)); + } } float pivot_thrust_max = cosf(_pivot_angle); @@ -360,3 +359,18 @@ float AP_MotorsTri::get_roll_factor(uint8_t i) return ret; } + +// Run arming checks +bool AP_MotorsTri::arming_checks(size_t buflen, char *buffer) const +{ +#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane) // Tilt Rotors do not need a yaw servo + // Check for yaw servo + if (!_have_tail_servo) { + hal.util->snprintf(buffer, buflen, "no SERVOx_FUNCTION set to Motor7 for tail servo"); + return false; + } +#endif + + // run base class checks + return AP_MotorsMulticopter::arming_checks(buflen, buffer); +} diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 03a1fe6284459a..430e5c9b706a22 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -48,6 +48,9 @@ class AP_MotorsTri : public AP_MotorsMulticopter { // using copter motors for forward flight float get_roll_factor(uint8_t i) override; + // Run arming checks + bool arming_checks(size_t buflen, char *buffer) const override; + protected: // output - sends commands to the motors void output_armed_stabilizing() override; @@ -71,4 +74,5 @@ class AP_MotorsTri : public AP_MotorsMulticopter { // reverse pitch bool _pitch_reversed; + bool _have_tail_servo; }; From 4785c248c551588e42890b0e4e7d75e477a4a633 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 28 Mar 2023 15:13:42 +1100 Subject: [PATCH 205/287] SRV_Channel: remove unused defualt in get channel for function --- libraries/SRV_Channel/SRV_Channel.h | 2 +- libraries/SRV_Channel/SRV_Channel_aux.cpp | 5 +---- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index 230a379ce4a24d..a930a37c8dfab9 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -481,7 +481,7 @@ class SRV_Channels { static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan); // find first channel that a function is assigned to, returning SRV_Channel object - static SRV_Channel *get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1); + static SRV_Channel *get_channel_for(SRV_Channel::Aux_servo_function_t function); // call set_angle() on matching channels static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle); diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index 1416e3a190542f..bed75a2363988c 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -559,12 +559,9 @@ bool SRV_Channels::find_channel(SRV_Channel::Aux_servo_function_t function, uint /* get a pointer to first auxiliary channel for a channel function */ -SRV_Channel *SRV_Channels::get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan) +SRV_Channel *SRV_Channels::get_channel_for(SRV_Channel::Aux_servo_function_t function) { uint8_t chan; - if (default_chan >= 0) { - set_aux_channel_default(function, default_chan); - } if (!find_channel(function, chan)) { return nullptr; } From c36c042e7165ad02d5d01338621aed35ba12385a Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 10 Apr 2023 07:08:01 -0500 Subject: [PATCH 206/287] AP_Arming: move estop pre-arm to AP_Arming and add exception --- libraries/AP_Arming/AP_Arming.cpp | 23 ++++++++++++++++++++++- libraries/AP_Arming/AP_Arming.h | 2 ++ 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index c39a9f7fdd2d8b..a74d50b2badc0d 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -1466,6 +1466,26 @@ bool AP_Arming::serial_protocol_checks(bool display_failure) return true; } +//Check for estop +bool AP_Arming::estop_checks(bool display_failure) +{ + if (!SRV_Channels::get_emergency_stop()) { + // not emergency-stopped, so no prearm failure: + return true; + } + // vehicle is emergency-stopped; if this *appears* to have been done via switch then we do not fail prearms: + const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP); + if (chan != nullptr) { + // an RC channel is configured for arm_emergency_stop option, so estop maybe activated via this switch + if (chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::LOW) { + // switch is configured and is in estop position, so likely the reason we are estopped, so no prearm failure + return true; // no prearm failure + } + } + check_failed(display_failure,"Motors Emergency Stopped"); + return false; +} + bool AP_Arming::pre_arm_checks(bool report) { #if !APM_BUILD_COPTER_OR_HELI @@ -1507,7 +1527,8 @@ bool AP_Arming::pre_arm_checks(bool report) & disarm_switch_checks(report) & fence_checks(report) & opendroneid_checks(report) - & serial_protocol_checks(report); + & serial_protocol_checks(report) + & estop_checks(report); } bool AP_Arming::arm_checks(AP_Arming::Method method) diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 98e531e127ce21..8cb1c5f060d3ab 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -213,6 +213,8 @@ class AP_Arming { bool opendroneid_checks(bool display_failure); bool serial_protocol_checks(bool display_failure); + + bool estop_checks(bool display_failure); virtual bool system_checks(bool report); From 1f94fd69f9dfaffe71a005b936b8c38fa3126e55 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 10 Apr 2023 07:08:01 -0500 Subject: [PATCH 207/287] ArduCopter: move estop pre-arm to AP_Arming and add exception --- ArduCopter/AP_Arming.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 91c2db7fd67b27..8f7ae7186612ea 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -33,12 +33,6 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) return false; } - // if we are using motor Estop switch, it must not be in Estop position - if (SRV_Channels::get_emergency_stop()){ - check_failed(display_failure, "Motor Emergency Stopped"); - return false; - } - if (!disarm_switch_checks(display_failure)) { return false; } From c86c89f05c13fdf8288c9e7a99271c8be490eef6 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 10 Apr 2023 07:08:01 -0500 Subject: [PATCH 208/287] ArduPlane: move estop pre-arm to AP_Arming and add exception --- ArduPlane/AP_Arming.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 46e52620876dc3..54fdc5592f961c 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -106,11 +106,6 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure) ret = false; } - if (SRV_Channels::get_emergency_stop()) { - check_failed(display_failure,"Motors Emergency Stopped"); - ret = false; - } - if (plane.g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM){ int16_t trim = plane.channel_throttle->get_radio_trim(); if (trim < 1250 || trim > 1750) { From 02932275caf3809d0e9562baabc173f06817146c Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 10 Apr 2023 07:08:01 -0500 Subject: [PATCH 209/287] Rover: move estop pre-arm to AP_Arming and add exception --- Rover/AP_Arming.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Rover/AP_Arming.cpp b/Rover/AP_Arming.cpp index d043360700baa2..c952f7d9652b55 100644 --- a/Rover/AP_Arming.cpp +++ b/Rover/AP_Arming.cpp @@ -80,10 +80,6 @@ bool AP_Arming_Rover::pre_arm_checks(bool report) if (checks_to_perform == 0) { return true; } - if (SRV_Channels::get_emergency_stop()) { - check_failed(report, "Motors Emergency Stopped"); - return false; - } if (rover.g2.sailboat.sail_enabled() && !rover.g2.windvane.enabled()) { check_failed(report, "Sailing enabled with no WindVane"); From 98e27828518e50d018a3bb64ad3fad2574224c70 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 7 Apr 2023 18:25:34 +1000 Subject: [PATCH 210/287] Plane: correct compilation when AP_Rally disabled --- ArduPlane/Parameters.cpp | 2 ++ ArduPlane/Plane.h | 6 ++++++ ArduPlane/commands_logic.cpp | 13 ++++++++++++- ArduPlane/fence.cpp | 2 +- ArduPlane/mode_qrtl.cpp | 5 ++--- 5 files changed, 23 insertions(+), 5 deletions(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 83188fe94552b6..83c1924e4287b2 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -943,9 +943,11 @@ const AP_Param::Info Plane::var_info[] = { // @Path: ../libraries/AP_Mission/AP_Mission.cpp GOBJECT(mission, "MIS_", AP_Mission), +#if HAL_RALLY_ENABLED // @Group: RALLY_ // @Path: ../libraries/AP_Rally/AP_Rally.cpp GOBJECT(rally, "RALLY_", AP_Rally), +#endif #if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 8d5a08a1892986..087e86cd414ab2 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -244,8 +244,14 @@ class Plane : public AP_Vehicle { AP_OpticalFlow optflow; #endif +#if HAL_RALLY_ENABLED // Rally Ponints AP_Rally rally; +#endif + + // returns a Location for a rally point or home; if + // HAL_RALLY_ENABLED is false, just home. + Location calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt_amsl_cm) const; #if OSD_ENABLED || OSD_PARAM_ENABLED AP_OSD osd; diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 299f5e004ccf1c..b6d017a53a7295 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -344,7 +344,7 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm) auto_state.next_wp_crosstrack = false; auto_state.crosstrack = false; prev_WP_loc = current_loc; - next_WP_loc = rally.calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm); + next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm); setup_terrain_target_alt(next_WP_loc); set_target_altitude_location(next_WP_loc); @@ -360,6 +360,17 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm) logger.Write_Mode(control_mode->mode_number(), control_mode_reason); } +Location Plane::calc_best_rally_or_home_location(const Location &_current_loc, float rtl_home_alt_amsl_cm) const +{ +#if HAL_RALLY_ENABLED + return plane.rally.calc_best_rally_or_home_location(_current_loc, rtl_home_alt_amsl_cm); +#else + Location destination = plane.home; + destination.set_alt_cm(rtl_home_alt_amsl_cm, Location::AltFrame::ABSOLUTE); + return destination; +#endif +} + /* start a NAV_TAKEOFF command */ diff --git a/ArduPlane/fence.cpp b/ArduPlane/fence.cpp index 28f4abdca677e9..640ad65869926d 100644 --- a/ArduPlane/fence.cpp +++ b/ArduPlane/fence.cpp @@ -75,7 +75,7 @@ void Plane::fence_check() Location loc; if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) { - loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm()); + loc = calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm()); } else { //return to fence return point, not a rally point if (fence.get_return_altitude() > 0) { diff --git a/ArduPlane/mode_qrtl.cpp b/ArduPlane/mode_qrtl.cpp index 98bfe3a28342b0..75d82b48225fab 100644 --- a/ArduPlane/mode_qrtl.cpp +++ b/ArduPlane/mode_qrtl.cpp @@ -17,8 +17,7 @@ bool ModeQRTL::_enter() int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL; if (quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) { // VTOL motors are active, either in VTOL flight or assisted flight - Location destination = plane.rally.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm); - + Location destination = plane.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm); const float dist = plane.current_loc.get_distance(destination); const float radius = get_VTOL_return_radius(); @@ -122,7 +121,7 @@ void ModeQRTL::run() plane.prev_WP_loc = plane.current_loc; int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL; - Location destination = plane.rally.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm); + Location destination = plane.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm); const float dist = plane.current_loc.get_distance(destination); const float radius = get_VTOL_return_radius(); if (dist < radius) { From 9371e604316d5b18ed38f428e7165a6405f715ab Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 2 Apr 2023 08:00:19 -0500 Subject: [PATCH 211/287] AP_HAL_ChibiOS: Add SpeedyBeeF405Wing --- Tools/AP_Bootloader/board_types.txt | 1 + Tools/bootloaders/SpeedyBeeF405WING_bl.bin | Bin 0 -> 14440 bytes .../hwdef/SpeedyBeeF405WING/Readme.md | 102 ++++++++ .../SpeedyBeeF405WING/SpeedyBeeF405WING.png | Bin 0 -> 650911 bytes .../SpeedyBeeF405WING_wiring.png | Bin 0 -> 87178 bytes .../hwdef/SpeedyBeeF405WING/defaults.parm | 9 + .../hwdef/SpeedyBeeF405WING/hwdef-bl.dat | 37 +++ .../hwdef/SpeedyBeeF405WING/hwdef.dat | 224 ++++++++++++++++++ 8 files changed, 373 insertions(+) create mode 100755 Tools/bootloaders/SpeedyBeeF405WING_bl.bin create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING_wiring.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index e98d4f3af1e1de..af66dca9c15b9f 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -216,6 +216,7 @@ AP_HW_rFCU 1102 AP_HW_rGNSS 1103 AP_HW_AEROFOX_AIRSPEED_DLVR 1104 AP_HW_KakuteH7-Wing 1105 +AP_HW_SpeedyBeeF405WING 1106 AP_HW_PixSurveyA-IND 1107 diff --git a/Tools/bootloaders/SpeedyBeeF405WING_bl.bin b/Tools/bootloaders/SpeedyBeeF405WING_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..a52f96f9c8212243ef9d8d5f1d8327c7d3e6d0be GIT binary patch literal 14440 zcmch84R}<=)&Ja&&ECxhvdKnBHW7BSpn*kPNRViJWwRS@LKX}VeG5U`n*{W3FtDPw z*pHXx!-~+>XlNS~ZIRd(wFMI0)~In2u-_lMVA=rsiuGd+sc&ycU~e|C_y3#Sg<{+H z|L^-e@AJ>|%+B1IGiT16b7tn8GZT_QtnV{K_~2hi2Is#9M{)JcC&Ec2rj!V?kX9i5 zD`Q*@^YB0Ev#jiYhUeXXg5&Bj{x{40*Z-suL+C_I~U^D zfZv5n1j%)dkl!NRexdCC-=8ClAcaQj9uJLfe4Mr%KBu5%=Zep^)G36#|6iue+b`Uj z?vr5+jOOj6y%^XbX3)0Y(1KH?{%YRue0u?2jj+jFJ;4?2>yOxp8TiL4%?d{HGz?j@o;H&G%IAFMo=%ds|Q|4&rjNt7>5aEI52 z2s{roOXdBPXMG$IBs;OLLRs+U`?->=!S_BPilAc!ioy6g{Z(IMy`;E7@>f$h3O~a; zv(^+W5({Kzo-53kw!6n8O|lJAzxkxq+a+@&q?tP(DD8C5I}S-Hr4y`Gi~U}+crEvl zV$0fs4VHTfHmts{VeRS-4fix`Xz;m}0Nc>m;44n&7SxcHmPQL|XkO^s^wT=!jNNHF zstU{A9wPI%LVC}L+oAcUYEwT65vaKpNz+m~LCRSdm3{l67rdm+TCCYJ_dg>OWoY6@ zwdT#;eLt*WY@C$iPjNfN>-*#TYWH5@wG>bBnsk|ap7D}Si}Z9YdD;wqP74vc+22u% zHItbis+UfP|1L&E1~c6>F{9^6Z=p;aM9JAk=iVCU+PE&_ICq-1ubkkzY!y=+pA0hl zR;qS|gmf81xB=-+qz80=OI|$@3JpY9AQ0iZNFk(;kSI(no%_)KgLJ>2pqzv9}hTS*sddv%0l3!x%Ww;#G!`V%z|dRGzO7llsviIN}JPa8f>`#g_6ABUMm zx*N&4Q(NErM6Ym}lT7BDbaq`kZ`183iZwp<%pEnnZ9KXPzZa6fqtQC0NN_>_|1B*$S5F#_Q*n^2RQ4tt_ z7bSCl5Kgr`8=*9PA)yyZNmrP1(HN&SKTMG8z7YSqN=M9%^I}^MvC(o-oVkgVj6_}) z=~~S-v!IyH^)|E}8+Sw*^xc`5Db9eVzUbDUq$~EramMLV?%m2S7>(M!WahPgtM^s$ zZs|7h$Dm}yVm|2DGJa@;2-<}e2lEw9zh!LM!R*>6WnoyywYwKx z5D&g`KCop`%zZG|%e23;*#2&c&uhn_5uIeVc45Imri<(3RK~$9{4@$3#`?Mo>+A2= zCQsKVQWkAT`Xwm%(#xvSvu$Y;u%Q{t)N0Tyj{02N@w=sC5rWv1K7*PY3YLlITyO`3+;p-KS%YDIIRj*oa)wR1szF7A>QC^Mn3j<;_S`PfTjO*IY zMSrK}1yXvDF`f}6_O&*CKi^K2^C~IXGWPNTI_CY!F%KNzJBYFZy*|DQ?)@a(-Xz@J zNx04=+_LerNqXy(b#0*cuJQMiHMPl_M-S+p&x4FUH_qGiBHzYCYu{3D7W<-9a{E;M zH0{De2VR5JHXSI3)bzuKq}0|YM=D9;Sa$%k)Ynz@EnYPC{DB(GDXd~HZFB{EUp0*I zhLPmj(PE|~{4!8s0N1L*lt;#}P@MTZ-2;Axx?94jJ%}j#$F&%_R8&Kh2Q>4c zzV=auxbkDVx^y4ED*ngE3&pQ~Om&9p*50o(#2?J|7H(!rPxms8EHP&=YuPNBo(Yp% z_Dyi}8L?O_5f4@GaPtv8c72PVvHJV##^Tr?iZo(XqbA@Ht|Qhx&{KVo*jbUWO&ZaY zZ>oBy77J_Eo@Z1&Nu6bNisr;ANHRqs$lJ8on_56&$l+d>Tj+Pbtiu`hu8;R-ia!<^ z(JDG$m#RsK;!e@YC|uldyJ49#KxUN4r8~E~g_DdjI_{A9DyH=1^MOSU>D&oF_WtjH z78!|Ae*7vKArd(sa1z;HP0LRb`o$=YR|(O1EwavAxUEEarP3rQ4fNsSOb;e?|!wd08=E zF7zHAHR|{oBx~Bv1Mb4eU2^-luzadlcir@zkGh3W`#8Itxs4m)xeF2Imdq;VR-@SN zo_suSoY}al=$;;;GWT)f`6zQMH!>%J&LfdbowVkD z0-pNI7?R(l{z4ju3A)qn=EA?d>)0Jk>39@pI57p8a??1osG{eIapHQ~%|$Fd%sl3n zv8aXCSUW7Hev^1H%89HPw&ad8g=AJd;;&|_ILw_5V<#<)NBz||45^;!%kso;t23;6 zai_TQwf9ti+tV-M+v(_|>##<=u}O=4prM8w9ue4m?vhZk_{ZK#@kyc^4iGJNkhVFW zE1Xt!p;wqYwW_V^!`?^K8Pe&97MrS(l0QX+GmaK+cpJCf{fDp?n}oXGM2NNj6LmXd zorqGovR=z(BtMlcT`zR)n1b0$v$6Jrs!g1P{9Sd1oK@4*dR*npJqpVmK~9u=E(uGl zSkZ5fr&{dk7E^!LO|XHnMqKV}l7}+YFK5uOEVJqf_oQ%+%2cd!33k^g;hBm#F0-O> zJI*dA7b1U+I{U5LU-^`kJ#vnRk+`1xYTDNvtXluJx~I${=WOO@T@$f=m7SFvDR?;d zF~+{zWp-ypnCJPCrG!z+G{99cUABi=(JEsv9A^)i`tz{1e)a|-SnH*<+=KE`m>3TE;!&fNc#i@@JvIc^E&dO3;MJ<{PJwv?I4UYG6FJ;;k} z8`DlkcCfQV@*RqUV*S-6gO}a&yCKrdpSN$KwX?+3{M!=zA%DMwHNs@W_nk}xqwFl+ z20JwKVdw$d)>!+nVZKK#Cc7Ta?V*~{(a72lt9$ae2MK(soSl@G@*uZ`7tK9w>K)D( z`>fZ38tjZ^8b6XpW`1d-!Z1X6{NfJvj^%Vz`b~EtqCE0?c|X>NjTd?Bv)GI6_Add- zN#|M~tqirPRZdQkI4it@Hg&PpHoHzC z95*<9cE%v(eevvx$l;;MrQ8{=c3ZQ)_((IimhMzJ(A|Zfk&7iMm#J6jN=}4~EY+33 zZ#te>)x$hbO9hF~YE4k(4mm-y5+uW0xknCt&&P|C#6(ZZ4(Ep-(L1jdK=X@<33-jL zP|m=73VWC~Mqv|72lqUqD3_?*xvp6_Gl=p{HD#si4k`T;a)U2dCbQ3n3wJRUX4goB zAE{!`Mh)}IgUeN$>z(u{plF6!UP-0KotC?Ncgu@=c$<{3#rz2>?L27v=tZlj#a>OM zu$T8!*)ht>R~S3zC-%cbOzF|a?M+2`#gMG@&z{6KR_Myzoe9rex*S~odZ?!|m_esr?@;akD-Ul8hVf0Cu zwMiJ=XJ8CC6a7KfPG<5V=f~Or)%=}rt$n01pq4F%4yny@p=|G=oTk)Z$LQxa>l`M` zH8UJgmpgUfh6gZ4@UH`BU$;c{k=d-9l>zNqZuQ8lzfius*Z6~NYMGO2Ke1y3CzXyB zI&$N9v)m=W)VBw^X;viNf-tes`aevh@;4_a9p;`4)OJ*7*mt0>zn_*#$%o;W)mrDD z*LS*ihCXQCGhXHVXgzV%DNZhMj@wFZAj-Lbp%^`^)ZZtzw}&R%sbufR3ZgZqqI<9k zIAsgxIm_Bz=h*q}Zdi%|+u%#E-fO~>1{ueqFbjXKJwP12(5R*CzGk-g&&~F=Z$@7_ zzjX^yx&kkqcWrqtvPTu2jAL))Wp$~O?&b5(ymX#yTo#@RTzfap3wNJC+{`%I2AgF- zT0f89YSYVVjngU~!c2CAJ#u$5Cx6gvK|j;Ro5HROth?R4Wo+}oyS&}ato?&#Vm}Ic z=_p&qS`X53=*e(wX!4!Up*(Z#=IG1dAsuaUlA0ar?Z6JdM@w;#Npg^bMiM)El|CKi zN9wrlW(Iien|X&RlG0(yp<@ZEwVbV4-l5hlw?U4^9?Ek%K5_hK7`09wm?&oA_+yw& z;yw=gYMj?*a7s2~6*C7IWxmRk@L?8KY~DeKw=?SSb|BVLppGVILNF8IAnjvDkC(!h z46DeZ*GKW60BSJ)!WF3V2QEYH4Hu@N-iUVsswe*4Xxi^bjZQ=viC~es1cOrcQsXVQ>#Bp0VqvBL=_Uy93Y{z`WN;qZV zym> z4Hc|oVldUup6-9m-}NszbB$vtVoa{htEtgqr!HMyEl06mu7SJ!%qmQmkp?|jz9*9J( zi0zFuenjl&q7lS?%u<6iin&5ZLptwCS$HU4W@U?1FEPdJLxWNx#=p@4d&?Qj^1ds3 ziyl41i`ij^XsDI379Jd@y77TV<2v;Fi{tx!dYnmG?4&jxrTw0tLIfVZ!fCk;`%;H{ z4=iMQ2GTaci^!KeC>N*4D}Lx5NsE0;qaF;kKN7K@_fxo3|0mJE)6Ja3c%fAP@}PdH zeu+@SVAr+#*WrYCaN_a_LH!E?+pYsTM{yA4^L>9E%?ViXtJ|KkHRw5H3OZ@cj$@+& zpVvbz3lpgSxwZo(>ThwiE9824jitjqF$nk&F_AO7CDtx9?%pQAN7*iS!|L&y!=v6br+dUoC@vdfhDkmIVP9$ep9ruj zDqv@^-qUhNW42X`-4vqjDgDu6qi7R?Oj^bQ+RM^Auh5@?J~#Kc<$TD~EO{gztusT^ zYfSNq1Mf4!7MYcnOHVcCLuwh|V#?l`1RHdRn?%a{IoU4VB|QQSi6zFOrXVLjE$?$@ z4c;a1l8n+)$tJCqo|1Q2I#Zg26RJ?oE&L1klsT(Blxg$hG@B%5UMCgMI54B^iSva& zaC3tX70pEiX*8NSmp_?2i>-|EpRf9HzNx`H?ltN3+*8=?&JZ(Be6^?q_&3L|7Z-@R86ocJ{liXi(D_rTp{iV2J@;0Km{yN!!J=wX?aT}ZGd#X z1+HA{b4>hV!ay7K~4xmk^CXkI^@fKT1NBhskw_ zwNLK_sP3h-6Z$?YE6mN}!^|vwO+NMqe>FE-H>j&2!$$ze*8moEB;<#WW`*rMgZgU0 z&OWk9--SOe*G3<4pAW^!@gIUY6mQGqS z8#cH=wAj6xZsgZ2KVl+=C0b0YlxGH;aAO`Khj?EM%pcQC@m&=G?gveQ_o9 zFA@8W=I<-;7K?PJs88RA?Z$0M;bya6zaXdV-KbE!Bni1y>%cwJzM_K71_L|)S9h~2 zUqodNt!C;M({HXwiR70F3ywyi1M8Uup=cX)iq7{1L9t5bqPTO;(ibGX)#69do4aPI~2;OZIIZJo%0(ci(EVwXtGE`|J)mJ?f~A-+`Cu^ z8qud6eg3E!&MVb78!QEMq0nau!ySv4naZ%t`EO zIO~3|WuSeAGr#JH#n{JK$D+A1Rz-xbpz$Tz$5=u=vJzmSV@g4Py%z8AO$ot^BS0f)ArF>OYKB`0Qh@ z2PzsXe4eucSJ8-@*7b9fcf4AR(H!#k+@FL20~{5=Q3MkJlcoWbkg zF4|Z%MjkA>H3{)$yR0$Y(X*aI~d z(b&VIF3gYCQ+T@fXL^k_#@aTw@r2QPswmg;=CopkV|TmD>8*_|5$o^A`Yv=K{Us{n zUYg!TUrrQAg`H%x}{d^KF@1)%3e?N zI@a604t{w^rt(=x_eX9s<3J1|GTU3#+JWfuEN{d5ei>DZSX=4^>c{N_@JFQRA^)kw| zja>IbiLR?JYU|}=stH#1F*OgVNcQ$+db=B`z2Dr}EqkE9-I5T8QRAZ&2*;S*e6_ek7DAw8x5GX zsT@?7XL^TWGadHeyF#EGsX)nx{N~|S?D;Ho*?e|gcaz%x7wi?T05Q2++tk}l$J3ZS zXBji7DNn_$X=G?|>nVAPoS|?T4@_eny5UN5mKYGT<6Fn;&Q_W*Bj%`TD#RQaoQqsX z=%+jr=SH9KeJfOYd&WrM-!sk=k<7X!{JCBH$SP(Dv(U3~`G8uKZ}hwcjdA1?+@PBZ z>V3@hjnjVQ>Uzn%>&e|+0yBGOsNOTE-ev8`cc0}v%!rHCA*T6D^)6x)>yz^ObwU_^ zj8L!Eb9P64P1#yznrH3`;4Ys|ac`!PZ{6^csee*Qp>2#*{sK82*>;xW4kOO6h{G)- zmx(i{M6^L#`x1aQ;ojtC`xx;YMow|r&+7H?V?zYIB0OQYwdTr4*5Upa@#0nUJgrNZ zHLJ{H#Knj4J3T7|yDzy$YyK~7;4AYRxuC@;n2X=yIYHJpYrm==vcFdE4AachaIjodCng5cp&S;khMeRP|G+By^|xyRiT`= zo5uoMFq?|JkVgsBdlXWSIaQz~7t*fqD7*)fu5e<_((_`*vJI^n!!9!~o=}CaU|oNu zT%S4cN9a_6K4U;Pyo0ler{xlHjoeWk*H2HjoYog6TTaTq?c43E+0`KTPAC`1#FXM) zefjb!xy?Q4c&_E>5Sfv(v5Ym8&%2U-Aw5A5yNvVa)<0%H%W~_t{svzBXxJvQ@EerM z{Oa@?17G~$i>LKI-*xiGQZ4iEuUQabC)OjX$uJv{NDg*oCgu&g1#Z}#XTrR(QVe+^ z>{rWO3Rw>QH=u>i8~YmX!o0Dsl?m|9ZyLJ>%j$asa zojvBFI4o5^kJ5XbimUnb82I#9zQSbJopnvMg#U-zCX^`j&k}b1mh-nAr0_k7o1@LG@2MZ|#T^ozrJ=jEOa4Oq z(TT3bi!OYPzU&zGnsJ&JFk>!T4``i^6+;Thtin??uTLyOF7Nu4#mVeRq zm?3T)rF*6w9NA6pC%}=_;&O0=S@_%N6M7+p9X6n!-4Vil=Wcd{VLL)~XY)&TMA=es zfu-|bDIZt!q0NHzogq^6>~K~VvF&tcQZDg`wfj0{79M{CejB8gXpX|+T@c0kjm0}d zEU;pgGCPx4X)KiLq^Fe|uFQ$hootMl-$d@OzEXE{y6)zy>MF3S{{vjQ4sc{d@^I%H zJqG4iz1vk{W{Qb2o$GXY3|)jvw;fdjHfoKEnAC9^w(*XCg=B%)b0 z&Q~BEf$wlcI^r`|ZS!%B?d};NPYc&bt-3efpkBlz@dLS{r^#o&HdpR$GFN@j1b_I9 z{mZ3&)bC5gy6|4=(^KXB7>VHaA7|tdA5(Eu@+2{O(ilCB@QIta^{LwsKm2zd@7Hp6 ze!b;3*wnw#bhr!pI=)Nbr*^mexdq+!dTGIM`4tTV2(v@b3RwTrKfxUvgR zmWuSOr*AbqNKe2w?QU_Ex^C)jaxFj)duMw5Z)>}Nsoy<#oR0RZs8ejf%!}0SmNiwM zuj+2PyDEy<8=I69H^JK=Co_#XWR`M}7TNvTnpUF)ZEWAGlbyNN&XzRxQ1H`6yUsoURA z>3IgZO%mJ0r>NXADM!h5FNr^Dsq0&kl-OQK>`~Mv<9$?O`dcjfhcoow#aS{{blq5Z zQa9q_;72>)X*ixqOAE5PDJ84FjrwhkN?u%i@;DvkchOnmE#jqEmDb%-QT1<-*KJiF zMN@p98bM6IXM4-;9=@W>GC6FPj^Z`xQR%49QnlU3Hg;ZK58wp@8Bj?;%N1uIUWj;B zwfL)PPKsAGTN>HoQ;<~Zo0e$23^2GKO~%iHgMaF(c%Bvm@o{@~=_8BVC3cI^s{4-$3~r>GCTm?@yO|Q9hO~ z{}^SwXinn%VKU-Ql>d4q>6a7MRf4(Ex5caDiCAO;HjYX?@z356 zr&QNA%ca}#N<0;tL+fA38E5ikLeo#Pypw8A%C@mHjRxM3mFYPpolq}Y4NKq+ZaRum zrtAiWOvze&>Py@4#)0yX(6`uJTn9`24DKY7_oHZ-3?1eqyrXr!kG@Xx5~UbzNs5u*W7%M=HOa2AfZrtLZzN+b|Dp3_%d}A4 zSiqToZ^6Cwu)oLyh_fqq^d;#YfruV5_)A1VN4ws(n*;!6ylCw4yXQVn* zc_h11Un>ObeH^UT`bK+?4x<@+mc#c+-7tmUAh$BEGq6K0!?9_&cEE+Nz`gztaQtO_ zKH&3R#<%|;;DpQg02jUjx91<=OqcPs0AI^xe1R))Q*b|cmyaLYys4qFJA)rE*R}&P z3`hxIrdsoQ^jqIiZNpbqZ9Bfg`1-SsA28IK??c;tuzc~Qt8K?u7+>^OMT^xTzIK@h z1?e%q>TYOk0_>Dpb1Qnbc2wK(g%R-;#@891AHYr02DEMHsD2h-7!hA#d^O=qs5Ngy z+eY-m7e>Ta7+r#NJ+woeI>(2Z*8^MwG$aOJ#66uQp|=&Gtl{km#k)9x_uT5G*owrZ*sM!h><5=plEdPio{HCgBt-Rq6YKY7*hk`Osk3BG!MN9p>H2)e=|?W#dNs<d4n5| zx9S(KTvEAoCg9m*FG8L*5n)me;zz_q_Ts+d5Ypu~E)BB+?X+k@I*fK&zC13q-x-D_ zD~gEFSV)9RNbe(g05b=1DFf>vEJF^@H(-Jci=u7@F)_Ls3}N^gEUTN5K^VPm8;467 z1J4jP6CL$BhIP?wE6qqQ(q`bwWlR`}xD2_Kp94~s0}(uD;L|fC_5OA1);{cBw@xf` zF8JJ%+pCFl-u%+C1vf1$zq!)wsah-o5k+`)O3sAN_`gepd^?v2%dR29IFbvUe~CHM zM0qfXJb>JV56Z9BM&AbFTYKL+lnE1dzwBhDk?+u4xSY}EZ$Pfe#((nje*kWz Bc5?s# literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md new file mode 100644 index 00000000000000..7f53b54bd9932d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md @@ -0,0 +1,102 @@ +# SpeedyBeeF405WING Flight Controller + +The SpeedyBeeF405WING is a flight controller produced by [SpeedyBee](http://www.speedybee.com/). + +## Features + Processor + STM32F405 168Mhz, 1MB 32-bit processor + AT7456E OSD + Sensors + ICM42688P Acc/Gyro + SPL006 barometer + Power + 2S - 6S Lipo input voltage with voltage monitoring + 90A Cont., 215A peak current monitor + 9V/12/5V, 1.8A BEC for powering Video Transmitter + 4.9V/6V/7.2V, 4.5A BEC for servos + 5V, 2.4A BEC for internal and peripherals + Interfaces + 12x PWM outputs DShot capable (Serail LED output is PWM12) + 1x RC input + 5x UARTs/serial for GPS and other peripherals, 6th UART internally tied to Wireless board) + I2C port for external compass, airspeed, etc. + microSDCard for logging, etc. + USB-C port + + +## Pinout + +![SpeedyBeeF405WING](SpeedyBeeF405WING.png) + +## Wiring Diagram + +![SpeedyBeeF405WING Wiring](SpeedyBeeF405WING_wiring.png) + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> USART1 (Serial RC input) (DMA capable) + - SERIAL2 -> USART2 (RX tied to inverted SBUS RC input, but can be used as normal UART if :ref:`BRD_ALT_CONFIG<>` =1) + - SERIAL3 -> UART3 (GPS) (TX DMA capable) + - SERIAL4 -> UART4 (User) (TX DMA capable) + - SERIAL5 -> UART5 (User, available on DJI air unit connector) (TX DMA capable) + - SERIAL6 -> UART6 (tied to internal wireless module, MAVLink2 telem) + + +## RC Input + +RC input is configured on the SBUS pin (inverted and sent to UART2_RX). It supports all RC +protocols except serial protocols such as CRSF, ELRS, etc. Those devices can be connected to USART1 TX and RX, instead. +Fport can be connected to USART1 TX also, but will require an external bi-directional inverter and the ref:`SERIAL1_OPTION' = 4 (HalfDuplex) set. + +## OSD Support + +The SpeedyBeeF405Wing supports using its internal OSD using OSD_TYPE 1 (MAX7456 driver). External OSD support such as DJI or DisplayPort is supported using UART5 or any other free UART5. See :ref:`common-msp-osd-overview-4.2` for more info. + +## PWM Output + +The SpeedyBeeF405Wing supports up to 12 PWM outputs (PWM12 is the serial LED output, by default). All outputs support DShot. + +The PWM is in 5 groups: + + - PWM 1,2 in group1 + - PWM 2,4 in group2 + - PWM 5-7 in group3 + - PWM 8-10 in group4 + - PWM 11,12 in group5 Note: PWM12 is setup for LED use by default, if PWM11 is used, you must re-assign PMW12 to a normal PWM output or nothing + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in that group would need +to use DShot. + +## Battery Monitoring + +The board has a builting voltage and current sensor. The current +sensor can read up to 90A continuosly, 215 Amps peak. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are set by default and are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.5 + - BATT_AMP_PERVLT 50 + +## Compass + +The SpeedyBeeF405Wing does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware +Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled “SpeedyBeeF405Wing”. + +Initial firmware load can be done with DFU by plugging in USB with the +boot button pressed. Then you should load the "SpeedyBeeF405Wing_bl.hex" +firmware, using your favourite DFU loading tool. + +Subsequently, you can update firmware with Mission Planner. + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING.png b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/SpeedyBeeF405WING.png new file mode 100644 index 0000000000000000000000000000000000000000..ac32c47e9d7b0c2ff6a9674c7b796ae5fa19fff0 GIT binary patch literal 650911 zcmaI;WmuHm`!;|MDcwj4Lw8DdcXxL;2uOE#cMc`pNOy}!x6%j*($cVRp5Oo7$NscG zI36#Rkzijp)c5+M=@1VWXSkx&DHpqD@(7%>EB;FIr{#4f;pP@mMK#Xxn_ z#7DpzSZh&5Q4pvx5&6j!4tS5~BBT2W1VS5n`v*1V{KWzUdM%Tc5Y_N9I{EpoNNcf? z`{@&pdlEAk91`@! zyxa7x@4wduf9PXHH}y^DAGuw>bepXd_3gh;3B7A*EGsK34nd;-QuOw+WsK~o_xk$( z-WG)fl4&r>z~O4BhypL?&OudhmH+)9@bZGH(hB~+Z&U{QpsL=N{=ehgaf>X5{O@;w zUwnoCqL=jl4!N}n(nMB!JKEbJpNNX=ME~#Hz{z0#|DEia+l>D1tEl%aArVpNll|6a z+1LM_&*$y%FGuIg8;uW6TgKir)y)50$<`*^B8%Do@6murK+LHe&TlJij`}6# zQ2p^o0^rsNh>eg?wJHKSr300O6(a3E!f}~@#@_$#_2uU6`8>@Je3%#9D=#z567=;{ zS66RbLBfw)!*sZb51|`BHmH^Ax05n4H({0=SeZnWll$L;d6oL_p2~`{X99tL9wnVKc(U;10cPtp5$?mhgYW7szMB?~a%QV>mvQ{V~2X z`13FCcOSAm4`;}P=f;&KFcihvIIRe~sa?@!1K9C3pHFv1aK+S^Z`ZcP+oI>?L$$sYS)yt zfv}}dh6;xS^8fD%82xWllSngp;@vu8jmtra zdZEDaRaM~kJXz`Z^!p^-8kQ1PbRfwP3=vrj{NFT-e4CHw%8@PL`&5D)koMoQOe4O# ztxy`}f{haC#O#mOy)O@cfa{(0wozB$#E=pU(}FPz`#nZ;&lV8?%?3iRIDmnlb}UOsV4}8^%F98Of#^7PGS-!~XJWi?pGm^zC=5E#jdrJ@2354P5Y5{ZYJJuxQ+V z2A1d)y$Fh6TFRJc(F}sZZ@t>n*ONlr?_D{zNh%^85BDm4Wntd884iIxD}5==z_h-* z6??m47HDo%T3^z@r;AW@A+Njb$ZG5(`GZ{NUUytQjB48ZU9jhoKoc^wn%;r~(Kjcs zx=AKx;0hQsR|(?41A;Fxf_0}CK{k^J+l!=yB2py4AiJqW6j2ToFJcRF(nF7fI;klP zpl?{!xwJq!{(LbjGi%^bI2mV?qqB+?(^&A%A_lcVc=$(%vgUPQ*vcy3edM6<&>Aq+ zwn(9YWjxRajl*@rB8=w!e6w8N`*4iR(yh|?dRUSeflAc29YI8Y^|R}1Pb0-zqoDM_~HJ(~BygBf~MqqdyGE-5IJ0T9X^Ynon+>?~=%0|t5JAzBDuW`@ zR&@!9e@@w4hFu=EQ5SkT7e_@ht97+;iU3txehxuJN80d=K~Sg<5{5RXj*x zk@1BZz=+3Chlb)0jr{oioyc-*sWB7=j=Lg?&+Ll37-Eq+9zRSef$En~@dIejr7PCT zm0P^t1!ojx7l-{{K7sP^CTlU@gL8g+cJloNA;BYj)R<%L?ONOMGh1~4x1rVZenhyyhYpj@*|kJ*wX&cG}Ny+ zY8g{0O5hpIJ!>*8m~1OtF^7O&2y!q;KsSU!sZi+W7ez!ktn6f|4+k@UGBMOcbq5Ou zf9YL(JQlvj$lhr|QnAaI|5@+0Q$9_h9|uN}a@TjKx&K5@Al|spYOhT}-mfgw`GtJ& z=$X+(Iq8SluIl#<-emOtY@EDgICIoN6hvjgG>1=2;liwEbtza}yWIl89T{@nzq;Qh zoiM?Fg_y71yvn1tv(2_7%-DTalBU3G=jrOl>oosa9KlDc>e@C!A-}tCEPVpDbEVwB zyh=X(p0=wpL@IDYmWHZ4lpLtlG+-CCpzkq-$4Ez%xG_jF40gvAk%ziePrW8sOMX(J zg#7Y76BK;M2M-#EfP||BQN+98bV1YFx`HUz=9?@yMp93`20=TREO8lLIR_Ze-ajNfKl>*K}(Z*yEn92{6 zF&gqAv~aWG!t+hWrc6L0$C1=4y)sI~DNaxRw3n*96kf`gK*(wLc>2}Y=cvqsgeK2r zuv9j6LC+AH>&dB{9g(Fv^U?}WB74}jijpC~6rTR8Th>F)q_ue)ZT8*l#k>=pegj=z z6fIrLk+56?gM-&3JMr|w!8u5Vv697OKTQ*(|MH9c=Ww*aQC2T0oIK)%`a^jy(QrD* z;*K-2qCEE1ig}`9HhZ`xP^rflc_^{TaV*x%_z}!vPrb~rLbs_{8O<5TKy0WV!k`-) zH{@fJy-hQJinc2nt;dk&9~-FA533X zV>bO=13s-9CzONu@KUHhFWE)jYXQp)*TfRNqA3zeEN4-}*u*aGNu?$Qo9WJW3M-}( zI=cm*OY@^+q@5kofC);1uq7_~7tQ6JTks(!noKN)z5-j)RKZGgEiBhL^FNRvED~j) zfMn6HfX7oJr}ph7eP`TY4WGZe1RORqhqEQ`&`BI(r1wra*UTs)T0S4i&;2Q~MjWBv z7^e@)Vk*XIYl&c%fyVtTXTs$h7aTS{J7YO%UmcxpYi5rpC#XX&orj4GMg$A|OY0xZ z(=IwMx?v8#^}Ay%+fvUIitGbm z`Pu(qCz-B-sqfRpn6kiygz;(bGHznM-#!CFZ41_3=bt(NNbOESLRK>%{fqQ@lTaAA zk}{JGAz{#JcNMIyFa-nWY@Z8_359_C5stE-SLX}?9z;V{(T}_g!WpoCo~JJ#m6(enDL7A+jhbD^ z(n(jxh@XXfm!uNsP$K9>Y>Fr_zm*hMoTfgN7a}dG^^GYz!z+3UxfO(KC7}@&NVQN6 zDyIrDV$QaTt|*>@+jh>M3Rb3iDFOd`y4uq|FGPPsJi;ILY;-lD_kc z@_BIYX22ur2fpig?q58QC(Uo2c0mJguBryMQ8iy43zj~H4y>Qs@(4mc*)|*<%+uRDY7I*%s|gwWqI@hEbcL*98f#wl4rhP^ zDTfH|G8ddCp_Ue;0wdw3U>jM4F|DT#pUIWU1(Fei{ehJ#S6bj`G(L)T$AkB&d5CoZ^OAu>;FYL(koKZpatrC@215oU{}uNf(M>FA#Zr(##)kxlT-B5k_7` zSu0_Kcm+XZ@fUoFV~&EXYhba9Y7A7WSLh8=Q`49A%Hdgd_1INxQG(mLAC9Znow{nN z&1Z^43EQ7@$fOYb2UaNz ztanKXWHgp>vfyf{>mW@jH{M$shr@pd4a42ii6r+!ZMFst1o=64p|IaQeH_24ikyf= z`>7l{gu_-8@UZ;oR_U{3HkQkhkHR28UaiG=`0ZS8%tW{U3k%~9uP84Q`c8eA+itg> zNKeKO>$`#J`y}@cZiQ|A2;b{SoJD@@hQ)L>s z0d3e^OJ40YjlfL(*O#J97aW8L@FBh#E)2#%cOundEU|pq01_^5?~7w8o`}p4%=sa1 zL-8<{(U;Y>=IoZwoBrB=L=LtFLgA1?jU>#We&eavzIBIRUc2#%XFa#S&H`T_ZOzCH zLNCi${B41rOLGn|N}lKIc~y53*ZKDdso+WLohf9Ac^nPM%r-_!bBq$tfeU1)k?ehP z7Ll0(G51Ke74!$TQ#cVu7zUd|sUGB+BK#rvxg`tdX|}=H?I6+L{|5xc_< zB?oafH>3r$n!D|o0$Es*6|u;fkgR4ftTiMjNzbi16h@yscrT1?&cQxiy({yq#&F7c_D-0JZ=rLNLkEag#ckG+k( z&9A?F?6WO1Ry~#tr4xv~r+I%La-~5u%Hi+~RH&p1Ic(?Z1E1}u($>D1VVV(wxhNom zCKMAGIBqry-(?)-|Aww(k!66>GO9hHIMpTy*ewu9kG?b44y7s!Rc_CCZ>buqH>&XT z&dD*eY@G329J&2YYkyaY>>k>MY)j7`BI1l z1JsF-p=y)hsoH6?&42-{44|YmKe2YHVdoqrA;Wq%cewAiYKQO0#`ILjYlI}KK+K*Y zqxBKBtiZ`v#Oo7Za2Ae?$sZW}7}q-R@=*7aiP4J>*(W;s&(HqnmGEh-nN&9@SA@C) zfh_+a8h4j5qrhhm|A<7l!nVocX%j##QI{k2+6unw(CeHgxTdH1AdrOooBm#JY3e^NcvUCN3Zb2%+2~4l{S1G~FNM_WfJ42Nq_c zjEc65c_I~sff9{0>cI|r#k}UC#zk5!Bt@Rl)9#O0i4-$kYoSl{S^-h z9u^WV2Um#&XBnRGJF=*Za~_0b(MVR%v{iq1Sfc^Er7R(iRy0hIKKXYk4?=XAeCBFK zM0dDEqcqw{dXXP$Nh#3y*`K1H4d$bwBF>>@a?rQhKjrW!o=(ECnu!OSv!=*$_JQw0 zi`EAlY)W$|T#oVKqc~Avzp`P3PQ>kUL2qNBO5pIwDXDK@jfTk+Gg2J{pODW>QAD+t zkqZ<@LSymC@WP9|yBQ8DbJ&xiEf02EHb!h~G4mi46?|^qa^A1s>VtbZum@y=D>3ib zJvwjJG|I|7WYSyUf!qP3!!&z)G;e*{y8O$wBHv=Px~@|W`Ert>evgLqlHW?-LSIuo zMp-i1f=mR7THQ%gb;11m*w@}0ru9U=<1fH`_f3|3KaokRH2lGH#k3@z%jf0(ci>I6 zFRb-((CDv+Zy^BhOV!#O3hAQKNwS{a*h^H`pd%fjTyS=hA!k42#cd(y!fn zna;VSvkP4Cf`yA6pzZ|jB})ff72#UG!2II9NeE_!n5S)=5p3$({z7>MZ{=?J3v(cDa zf%>IgnR+qE4;1ZUT#PPqiuxbpg7GWHeNz^N2sy<0!_li!2YL-h?Zz2rrORd$)v$k zAxv3#AzZSt9K-%H_Nx{xRa%f5dB%ZZe(dGzCmVlsKu8Y^-hf=%rXNwO^ZqID{X0Q= z=LK{>TytC>pdVsoBnB8FC}n?(?5Yv~lzD=J$Oxf-L zg3;=J69;2idRL@y!rwzEx0bIN8~UN|;Q$m8ijZ9Cdvh!~y*H8CxP7!-zX_DjwPtH& z=n2(9OXbA`={u^6Up>A=nuOJHq+Aa8s-A4(&c(qd^vJ&p0|T;e0W_O*v8?ah1C)S^ zZ0myJ2cS5aW08{q+R779%Bv)RFI>4d{hD*gRP@RKaqPo$G)=+GN7wCYsc9`mTOCmv!NQzYly9rJXN9A?+E!2+`{AH}9)&JB&CJs;8?sd-E`x!s-=3#L zWqj4o;Yo~AD40+sTnmoDQJ`UFGhTdB#LpLl z1dGv3d3_S5T#!%la@hQ76(>z|_dsx?a&LuCP-~b;QjNmtSMzIGxdExHg?Iw=3P10A#5pgSNlTlQo z20qLeUW-o(7|s#cV%$iDy3H$cyPBSF4Xhz6f%G% z75ScPz^4`c!*H5%XKv>M?-KFZ#AtEaU=^wE<}!O*2H=Sr=BvgJWmf)ucMiA$U_Jp* zl7s+Wb+e>j=sqWFo#zVwfY*07;vD$6je+W8V#waG4Xmm*sM96_tsbI$KXkHKU~s0wxi-q!g>5B6u^MLj?;d~Ohm<+1Xg0Xjvb=~`H{m< zkL91PV;^SyhZ*jb1#i+kB?64iqN!TIgg6sQpDzKRzXFN;vVX9%DXD0e`f1|!1o5^* z*yq}YYU%wEx?uWHnxCw}rpu~j=6?NlQp3CwKi%(~P(XdosYAr3KBRe*^Z=#L`|f;u za*A`=poBqfdJ%s;9WsP2Y=9|v(lA8gb69*9aNEUD*ACH$HOAEidKGR3AbHNz0WE7y z60ULce)@9@&jU(NCP~P*<2Qfk{OQN*(~l5j=C{fFDNhzDBCY4A=lWY`gGhwGkL0%o z&I`~-UY9MA_jLeCN1DTwCME-Cw1DNnXMRQYaxLlr2I~`|cx|g8u?IMVRohHuzSbh5 zb+B=mu2{(o*+Ha;OIOx+lzG^tFDqck)>k~20S-}5;<&Gvf&!3YgJ_+As+I*c`DiRe zPsC)W%Zo8m?$&(2E(mj^O;`z!F1xvSlvIX@!vH~#ivWf^)hEO#q>p@UGB6j(k90lf z2+_z<88e2g@PM>C$R{>1=JF4iOkO+DQJtx8z?niiVIjq-WmbxE@15=6-1s133iZU$^@h^B~)1)+GH!Z!4^6(?61 znE=`7LP|$N&r(xXr@2>H)au~A-)<{{&g8m8SgEV)64jQ3=ok!oXrshr)PAWObJ}Ro z7RXHRV-H#rEM4ZoK4KWtQxIeZhIaG>b;v;7tDI_zlc_ks8Sejt5|CSLoLgA86-WBo z<+!Gertym!HPyw%?pS^6lHOq-fFr3Db0{O}vzxk4o6?;hfNrBhpxyu|A?bjD_yV*= zZvZ}7=&vgNRZn!4^W@4=la5`BgG44_XoAz8_MQM-Ih{x=qvLlmg8Nu39vN_IZ=B2L zQ57IIP{88~@f5{_xSchQk=!>|$0({DXR(=k{__5<@6@r+-FJ@~%v0vud-z4c1JU9Q z2K7BG*0&c;sPy3X0m6cvLHp>!xN7dE*Dk8k^JQk=-uN4NNRv@hzVqB2jM5A*i9*i%_ic^{8|M=XqJSWTF^oJ~9^bgi8r64=7A2U& zv0t`wdK5;^)S~YJv694$2$1ZL1h^70{sDPjapM=C(>*=&*xk}S-uAmO>JM4=K)hRV*k6g|Y9LjF&E z108P`WU?R^fud?|$An*071L{|T#fGmjB-OB%Si5FCraYA1@*+9%xGRuT;V_ziB8&k z()5k_>xLULQ%e%ziM*cVtz}_Nm?+Y`3kng}ROXlN%4verMg5sCB##b~X$_P-beBLM zUAM3AS#ah&09eZhPP+xZKQ$$`cSp*BRfzpX9(NasfhfXc(MS=`xb>s;pIQY zHn!nDuh^zS_FaS4~h8GyaRxPpq|DQZu*G|q~>1mQ4vYf^lhSU?K^SPN&*pSrF90QDg!1YH?&FrESoC#Gz?OOpIZA$wSCmLio|MvfX0 zs!xuboNjRn?T7eCWz6aD!nSXNnE=4|E)7DFDYbKsL6z?-%^- ztk)HT+$^Jog3AoXv%`Us=qKBg3pM6AK1IN7{Ih4Wv;5&o7GY{!&=)X1Xc&t&8#7)M zIzb^S42P{4W+zn4{I8mrw%cGR2!ZT+jl{zp3c;uNNj(UUli|-4vYHymY-J16lHTSp zigP~peK&Pk*85!gJDmTF94M7nxhwWmDAl)a*8D^05r8TeM72*>X9sdS7np zSvvMo+8&GI@&R#r8lasKX0qbvfQp~<&`T=dt~X+o-VoZdp32&B>NvCSY5$E!0-gjmWQ;V>pq&`$fGR^r?23kc@*Y6tA|cq@ z&O4#Oxh`^uY;(D}L;G8z4O9`s5S93yaxyVB(AFKIC?XA|r&JT22?$AqjErIkDCm~f zzhh!PLZl|sKS_qqZXYuOE7Mm?W`27wO zoG!MU8_L4Z9Mx{L35lMYh|E|+QDUz98yF@mhGaXDMHYF;X0o={4hQB(&a~&`O0C9+ zMPc}SdAp`u@B_9u?;$IBe_<)*qMH|47b2N`C*m|ggW+P<@mXh{9D=wNDgpP_d~M?so9{4%y!7(4pLiPFU*_Mli*p zfJKX+!N0#heF5SQv`6|EdjRI;m6dQB^np;)W6gWF0NDX=g)N#oP z=TCLL4|dP6FlpY7F+Du{EcBqBJTO7oRa?Fk!J4UH`$i@47dv@uS;Kh%hFri0i7geD@ccm$81m? zC(i&psc}tAg_P$Pg}sOKvccTQt~VI{jtz7E%Ql(8#Zclv%Is`vzxweOk0R8;0vQfx zib78%np$Baz?Tq4SOPAPtsOPnIUE^k8V1q$PZ|KbfWP+*?CR)1;K*qHWu=gs1Yv$K z0aGH7%ZCuniYm0GO*+!I5m!1g^I>Jg!tjX%>nmnk=#vM9p!SPuHK%3bA_c)95UoVN z6Ze#q>{mmK8@3VvayG3;zo6k0cziM`10|z4ltnNYMH$%^nM+b7f9LSQ&Zz(wMejwHp99y zeXNa4!6G@H{KW0pYNfQUDy)U^e|7K|q?>sHI_2aOU^p_&HMNaZru_vhzL@MIfTHPB zVW`?Axh!gvsy%=NBP;%1q|%)|7Tr2laowR%ap`qCq8lZT*W)9o-Z^S;29qB%JWbFP z<^d2+j^Lw(-Rk%EPm>W=Bht0R71C_2$j{r6q)Xv6$rK((3;YEI9>rqU&EZbPTSU9hERFku4kqHh}qCYjskQvw-W;r@UOX$ z&3DuP)&t`$d?HJeZ_(A%3D`fYkX=j{_R4R@oOAV29jsU*N|*<5x42}_F^k(0}$sONPxShGb=3QfWu+W0)4} zZK!2PC~Sa1AyFY8X<|ufSS5etmqx*2QXtK;72~t19}`aunD9&BdxQbLZV8OXK8Get z&vlA;<8s9-iSJ2qG9kM~RP)`h+umD%xw+&$#}y~*P{dQhtijOo+Hyu+%u^gOUzn))d6EKuWPL+h)&h76A&4TNS!|)&}=y@_@HQ z2s|Mg*=7nF(cfWozC&;i-q`6PM;F=OQus_yNLG%ai#ZAdX7vW9U-4E+7BaN)mxeGK zI+V3cRvmWghAhnJCMpQKRr(pm6Q<0EC<{ymrr?sS3{UtFY-lW;^;nOd`(?0)cU7@=u(G?_BFsscn)*ZFaF|0sE+l#CzWIP{Wgn zQpQs}sm+X-JXTZqi_29_Z;H4*W6e$)yBT_fB%a|lFlx8)%&x-%*-DM3Sya4|i=xT7 z8q#TiZW=0USCyi^m%OH|RmPf8^e0=TAn?UI8&k5r#LBs2KO>g02_g7WV-4>{)6kj~ zQRw-seHX37faOyo20AkDIAuyST-zVvHh{X~Y8zav+1CpK4jaBmf|O~lV;g3j#9P-L znu0gMZN8*?o=tal&+}7d`UiAlpmg4SDM{eF-T1`2pPQ~G3Cvv5=Rv&QqNZc?-q+_d zVW709@E9){2l}sN7f;6g%CWDT5cs|%jxK1S$^8iseDeJNt)dIvfu$G7m~hrPxZj9T zi)C8*luaK``xN^(8y}m6eVfY_3TTJUn5mKN#Z6|(5b}1 z&AUyx2Re$Fu430nv`R@XtyMC&sAl&3&5hAmyLpE_!l$Jp=dbT#?)UcR(e?GF0@l0t&j!u z^NRjhAhny9;>{w=)tD5mMGYXdXJ>?)hT(6oI^{GpB$12wB9?Qxk?DpwZqsbGxX)Bk z0pY(Iox$VAKXrnpVyDuUj)dO9#=o~a-`gR%nC9l_y|Sev_0!z80c*p&m1%pXX8>xcu4#&yf{45TEaO&_EPdR+_axmfS_h_h+WSY=Eb?lr1*NLb zX$nPSMo_nj?e*a-;IbB+x^!}o=Ad+p;#3&QDohQP3nx+60g*9vCEjqs?Kdr@6%B}$ zl_p5*`UBD#6-&nB%8mC|z&%R!o|VM=>3h}_MPIj9y_CWQ*oe5#qeRXN^+n$z_=m=M!sTiZI&zfq{3VHCOzA5aoeFe*Vq)#qDx$0zfDyKrL<= z#sY!>seFL13j{F;HPu_R^=!)k*+~a0rqp9Um6kI)G)_Yr=mch3w$NLX_kgrmLg2F% z{0>dCEF`slqW3Bzf)+F)(?RFoV~0$7td@=-d7{JM}$#zN^Litej=-i^k{LkZ%uy zW`rUtVWv!&9IErQh4@`sZp}oV9Pxuv$zfEgE@g1L6N+&y-2#`sFsmvYh1uWhN{ZJW2y|(1%BpPdA=hiSL9-`(PGGhaIUfRi>7#sxBv>_9 zK$Nt_(fE8cS~W%0g~^bZ)K4j?3a_#3|B_P`;(ouRy#V;ex`fVMr(D#S%pciFLVLVg z2-V`Q!+HVZ(M@#!pGTc$Cmxh-3+b~5D#yQTF%HH{3U&T_z zwZ!JqWB9TzsM(rRNKW>-_-`W{pEKQD&nvIr088OZelO>~4@ykx&iApVXiV6tZt-q_ znHTsR(}|Wy?(s4^*}5+vA{aV+BGz|k47c+Kaw?U#v)F+t@B^?yZVlZ z$35FD|7u|k_^neJxEe8%{V~s{$;rUWY$nRMbF?U#-(R&!RkgisMo z7jK2=*5lrbG}^Q|C3)tG$b+4ZQRsjPs>~=>c!xpz1>R^BCC^T>dw%-_eTu^r(9?Z! zx%Baz4`%_0YaGbAXU$$uL+8nW`dE;b7Y})D#u40GX+65~VrM#t$opCFqMx5a&SNPI zUY=q)4544Ns0RxhOORd$I9RpkN? z`@>wO#~!yuO-&Je&*%3z`qg|D6x_4^*~WIc_jINhnY*>p606Z&MKAf_{ian&rg(J` zZdDaU~Ry<|ToMSF$zsiVb_{-tQbq3d^~2svou zmy#78rF1>X;534D_4Se|E@N@e^qo3^~U-GobuiFY5|lMI~GcL$x2Q(#rjw5Ugj1lYqxh>z}H zQl8Od_M6`<&;=@hu*z<`4!hHlVCYMb%*bbA*q-3XYbWGir*xn7J^~@kh_)`Q&4;D0 zI+7H-M{94meZx(DZuq!D__?y#3O_X}d~fR#iM1;bw zL#1~W#S6!#cR*MArU&hvc0RZ&j?e=NNx;Gl36)`yv&DsgApQAiv5E-hE_})37Jw*D zFu`W_$>L3qv&wZW4;uh&rNJ^NA}-8zkkbGl_KpfdHR8l`n0`2Z$uz!+QNNVB zIR;pwpft23Q=OPwZy&8w!)5HlSH*w}k7cX=q5^qlLHDH-^q!+W>XS>8A-b+ z=B$6QR3jrhmtC)H5^Is{XByikGMVwhn9SHgn<_N2Wcb<8Kf0cPy%pLHpNNu&oeDEr zykihBDv%$s)H22|(metCXAFc3n)-%IW#k#4QqpOGn&urFr%V{nBBojWwWy{4ojaq~v_A+6nXw@#Wr8cl z&%>6^FWb;#QImVaCG=o|*^scan~_n7`)HrAPp0HEU>5v~XU4la1oj{Oro*#Y7VzI^ zFfN9E2Jo{bO@V|sEipFN`YJ{6!=9vdDFwFp_Tt297RxN)M#wi>kW@4GJ-KO(_>Uq} zKQ6*lSap3=Thmm3SL*?@#%~#IM{({y@foUk&}dt2MM>~R!+7X~E|8((O!Y`tz9~6> zuM0k5H0@c$5a-IVZFTg5EpAkUkP6!s05TqS3Y~yR#(4Dc%UkMJiT{*?kl+WUBBHI| zvTr=8@Gr~;IYUgT%hT55jdWAgvb*-qHI{c|FCFI!W?XVE!%anmFi~DSW)^)tEvz^4 z#t$jql=F|@>Z#562E#nCl;!abiGKb9szBTw6JcFwdaW0YnWXu7K*S zaJZBiHkcKLs?y{*5`M>)4`#S^_Mgif-HEl0yvwjL+4985+WO&&-ZoPFkSv?6vMH4p z2?iB&p=LFaF@v7SDF~ynPV16VJ(vU;mVfAbqWfF%NMurGBGo0jH<@`zL#0wHvge4o z#|%ad%(tm3AL&QYa;t|Sz6(>|);g!MrB4u-7{WIpS>KV&(Noq`VwKZU@ISc_7JPjw z#M3e9kCKG{{Abq5^IIfo_bWi`rihznqLlLOUQ+~ZJBxXl6i=xFa4C|O`Foin6bU@qlCQ6aBCY{APMxpCTme{fbM1pY!#so z7WlG;i6HB9bGIn4s(2NgRRfh=K3g{Z<_ZD(M@qE~Ri{{G2z34e?K3GF~$Y6&C&XT4XhS{$V^QL7On8) za#JxZ4Lbnv5%HQs#!>*ENLN!FB_Gxjaqx50U#4^;84vl*yHRcqaiQdBO;HaNIv`K| zdcfT`p^g5N}Ffg}6ptFqL(2PnLjpllnK_0)Ww>Y3pK{#&GEHpSGk1tw8)B z)dT=qu95p_Iv55x^I`+LQHE#>f~wSHJL0`I4U^19GlQV7`$^(xs)oez>=SOcF_nOE zQ4x^Frfuwh1L!jjvFJX}e}SB#7qAuMqk@afd#dA_wH+*aR>Ja+(>&tla;-rs6_Jmt zKLQR?1b`TF;L|SY2h_aPJY3SKQzm6$ z<@Ua&DO~MlE*r_A0G>o1hb^lW1DZ@}1FOfgxJZ0vRfOLsW6mz=2L;c1&^QQ10iqh_ zZ8wRjk8jH<42L6CEVLblZNQZBfq|@Zj`Za`5=cFJtV=oon$5^=$Lb#yo!p=-!czzw zT!?R4eYEV`bUvHFrM4Rcr>lK#CG&<)M~gB9s(vgbv86gX)zCuD@;hg z15PB74~Wfuc9)+C-^($YgA_kd;HtEXMz94?OIcc{&Y6E&c^)28xqIE_uLAb-qgiYM zL{eI=q@BI8%+ymocS#stAL>g05|AfHxjg9cJR15P-U<2Q)tK=f0E`|>x?>c#t|#(v zKh6K0;3{qA_g*OpKfCMxxV-?Z04ElBbfYqjFMb0>rL>bmbA?=DQeb1{B0e>mp<|*2 z-a?^X-L zIT&!psgYNk_fq812-w5&`CvwO(;iPQ!@mNyMuP#tP`OHFILg&`iP*64V5HulKLjA z;~IyX&1YHs?%f1_JMytOf@UCEa_Bp!0#I0E_nMkcK;PrYFLfnux9Y~G4LCw>ZF}R+ zBud)?fZlRRK|FdMqEUkv?P~}1i&)MbHZ$S=cTChY zkk!@9?t$CFI1ogi!RkkfhF%irn#_t#hFzWYbdv-NuW&`gdJ%Tek0`fm0z{oDJ8 z>CO7PU2yB)szycm3vSCQ;|ah2c8R{?PPRZ>z_zRY(;n^C)D`haliqWs6A{v+7JQ*} z-OP+>`FbSytpljRWjJ)-9%s@R7Xs7&X@BGSww|x85fVU1*MXb6?$*Y+n>0VUi&z zGMKyR`mHmO$$XBJG86fGKsHAckLnwCHM})4lR>IN**6&#|8xbMpIMr?dSu*+wxVRx z+7j(f6De4<25Q}V_6CihqulVz62F*_-kVjIBK0;~s-NRKX{&%NuBYWMT^Cg0R1ls{ zHU4@vM$=^WrS>CjM2S>Q>^UttX_n&6+E#$xp7=sy9-8C?!O(#)xZ=d>A8ry_2RnY~t0T-gckN zL98-_!MY~ZV_UEEtaKR-z$}OEqjm+kv>KRx zn^{mc2wJgD;V7}ok5g{kupaO2gsk5HWwP(_mwsTtMYbd!QR7?;!|mV2-+(+S^!wzB zc+Br7-}lY>Z!@OPj@cKk;_A8onscoca{ska5V85OX$ReII664|v1n0F`#+1LKFQia zA>wjD(6($J5CAxCd^C|sIqVYg{yrM@4%O3dWu90dMT-+^);6oI-3*Ww%4Hh$Dq|0p z(LgK+NGGuv$m|L_FI(&V759~j=eU#T%F6GP_$^2$V*NII*9i5;)0||~8?xzFCmIrk zU)r%~sTz|6)v|>8Gl2Zl;8#reY)Pu5u`({)5We&jVtAO)jz?bk#Xc*g zC_ZR4j#9dEhNjUVm8<~RYuagJgNa~@6>osShl%Z?N|m%fMJ-|64%Ept<`2j?V@KbA zc!1kx$XywRlvHM$GAnuBB7#sj+)_=!77@H?b6KLT%^1u~QNP0Z;7yi3V*Z(45o5m( z`%~@m0FMhrut{5>q>|R6BBb_{fm6H&R{a`Oro~DAK=fM-&z4QC1=pO0!KT|JdYtxm zr}F8VBKOZy)$*TM((Z_Fj{4uFi=!_aKf>fUY%q;fvDhrJ(3#pW4!0UGvHGIe!<#4R zdnkEaGvh0&YO24ndT1mv1kpN0rSbvEK|?E13>U*K0DSM+x)={N0v+Km5T{{|7~+Ih zDno9R!}N%A)$AsG&n`OyJ8!flLRkgLLD@P2Jv<5;0%$Q5r+BMeTMBsp}< z$XQDuKX$qR_LzqX{Dezfg6+Bki5GU=;ujD_P@)dSK5fAZX#oBTf-{gkyUV8zMRYaY z5b5RdH$nh6BqIq%23P`LU~~KWAA@FffMlIps-V==-z=+<4-K(8>;(OKCUzDyL97Mj z#jJy$mdf+_5EBwA)}@Hz^}Y8st*0Gav}u&OA8Nl=T>qUnKO7A0^f;@E-~RvbbQb<} zzyJT&UB`5cqnYmRuIU=4n`t&?+R@$J-7#h}-3()LZ`~8ajH%ysKHuBz_XoJC*Lhvf z>k;?oPf&oi9lSmf12f%01R7V}(}vxg&BBMt{~5>YI4V^2sYo&CKXNRggoUb@7u1c& zTBf^N3je?zDIME}s?j7ey=8$Csa$-apS1O*mkS}H_BZj%I26)m&+@n?;BX~Zgcbx| zjD_#4?`!#iT4odc{-K?z0n_JTz$4cP`K!St^|*=up{NS9JJeJD+R~U{jIfrD{hYLe zPHbXrf~po{?*5Ay-yxN~e)deBg_`lG1Q{Lc%0oEe09==NB1v!4!|U>;NJa!+ALVVu zdR9^DMt%f>W?_oX=eRDQRE(w{73Q6Gr{-fpvY4K2jOb@3Pf$dX zj%#7lx!FGhwk+2(5N0Rl6>$A!*dQFVpl`UVL|@WJZ*M~y@_B>e?|Xy2Tpi{2ajI8X z3nCyl@q38Wt55|C`8FDjvP~wzE_RCsf0w-@mh%(KmkPqzDafUST`gnH*->p{gGJL! zjdSmYx8{*N7Cu#e>rJ|SWvMHn)5WC{q*;VL@(^dKP)x2z+i$MckPEu-+ks2Z10Cx9 znFK4Z+NR5-mr*-iV`%1g7a84va~|6=7@%r|9c%Kc%Z-#FXv5uxaOJ-Sh)5>0rx!`X z^a&d>I|;Asv7$O16B2Rp6z<9QBEyZ`v}*`)pv`W4C;h?wJAM^kBwUteKmf#HsefQS;BOdk{^OPsCEtD6 zC_;@)BwLvguI;jA^5syrmeXCoMQ86>B7C?z>~O|xy)je&^CGM3e=vst+U2t6;(GFD zKT7qPiPWmKIONl4(+Jd@Qt0YYRA~rPN4VBiO6TI=IIsKOs)T(mLKyvgJ&v(drbaJ< zRU_0$w3+6RrgC@(@+rC&3~mux9q$i{qpA$Z82aJ`S4KaY1ljbX@B z9!n{!;68To{pn+9)(<{b^|DJ7^o8$JdfvsA{94X^DQ!$y$@|UIp!pt-#8@=X*3-1f zJ)wf&Vy1071v4(3g2?>h^IL;d0^%@n#q6I|;jK|vD#m>TF-p(hhO?m2&rREv$Oo&m z)C_B$5UD3reOL(v@8<-%DO}CP@~@?&oik%rKjvD+cCC-lN!&m~XV zzQY}kw={eTF-a6*@hIyR!tZ09jj49w3F<+J5({NQ3JX%~n-R^7JjuKaJ%gTFA*$D2 zQv%dUC7c&XwKuaEH_n;kP_1cM6wek0qb+)+pql}jnsFA;BdgWIXoNx3GViWIyH3Th z>LUQ&~^ zBZGpLSN}}K|At?KdoT_&l*9?@Il-U|a zMG61}DV>UFw z**z&S$e!|#`<0QKw~e>9D|YZaUWJ1&Hv$g3O@|iu7=Nv=My}w3&w>Ydaa*jk{mq+y z(bzNJBbO_K&B<+Hv7X&3N%VDi>)UkD{p?67$!n*b(V@NEMnlQv7?QRhKF!6Ugzy&N zS8}JbLoVo>)q~`>)~cc6c$uQRf8kSZGf#T`y!MdM zqF8Ml@SL5h>pl|4II$X;VoOTJU!9){Dnnbmz28jK*5->W48p@ntpY;7eXcBc$MznI zqP=LlI8!V~zFk%pq)37K0XRt>p;iTj0f?XKKCx{v8Ql9UqhuJ#R77k86_1|M=v1=m zB^7l14=qjWf3YZjaae{C)#C+06TXHKt@4QW3|bjv!>IA0xpt*Dx<|Aw_K|GLcOZyh zpWlYzrRAb9XWoEVJa8C^01GR12A5{Tq2}FhqQZVM1S)fbGh>89zwWc*eO;UV()L{L zZ+^Q`bHS^s;*+mHTVq}U4Z%)#Cob4)4OCnIF5A;Q$h#F8Zr2eXf&^V&^=XGv@<&?X zP0O;@XNpYP%#n-c0riXl5o$Jy@f7W2Ot~9Z1VsLZL*&2psLoq6SOj72w=G)ieZa<{ zE1Eti=tKrtGWRHfmIidJ=O!>h^S^<=w`l(Ok;4@1qvN**=t))be!lz|N**c~Y6kRy zI(?y3T;X^@LbYl+enJddn87mDbMz@?U2lZO<&`y19wAZVX!jmT$Y=g~bCGSIUwnA- zvvMB^`QM*|*)EOmzgD=cOjZCD%JOL5?`zXa78Dyd^P7#*>5(RF2~h|!3jFDQdf}f{ zZ}dAd9^Cr!KXb__V|fr;x> zfMRAp;f*B{V-i}3+f#K#{)r{;B9lY4=#8$+4M%kXkO%P0NX@*HpNHDun4)Es>-B6K zUcy5jufo+vwsTW#UI}+D+vVZ{Ed?uKCREpP7KT9@lcOPPRZcc~hsChEvC;#kDGdc^ zs_r;L*l#|$h?%!lG=xH?`z$8i+#FhC1Mm+3*3Fj`G%sW#Y?^P1VIv2#5|S~b6gzl!VE3K;LvBS zXC+;IQ-NW`oOq>6Sbj2)nYZ@=X~n*o>VvKUXTto7XEy_ z($_$5Pf!eW@W8!zMo$`7O={}i2k(>ZUJtWMvuggVj7OTDUW|P@;8{&m4~owE?uXJK z+I)R|w*CPGW=LQ3I_I%WC%?t|3Q@4p(|U+OM#AggTsc+kezR4i2WOs0KD2+%u@H1{ z`hu~C$h_O^0;~Yetn(w{H6aO35yxWgr4;lR!m^fzoMEiBSDZP}{I=M7?Ahw2A-0C* zzS*T09b1#iYS()pbe!#Oo_gpZ;%$Po1=zF;rq<#pUhHEWp+LFFR^9GSc9MWU>G8KLfU_%{aq8jUH>nTn1^J>MT^G#-zY|WmIsS;BGVzLUzxzWu zGc%XwJMlyjD@A0bBZCP~Zaxvm{CyQ*XkMqynen&WdU?4t9g<;eNA9T1deO(QJ)!!% zV{*%Kg5BQ+g>}+swD#c@oR>vZ^WcIW_9f8J(MW8d6?S-CsB+#5=o? z41>zQ@ih_Fg7(WIyBRT$EqVFtBIeW!S^sQ~+nQ&$yJ_wV7Y=IJcli-8%;ew~N5gdS zzV!0ni$-`A1}mznY>Z!MMEY~L0r^xbd6?w zy{YGM>j`oe&p{`$BnIP#jsnRxx_X7wegsF&&3bYp?YZX2Fsk2h3U&q59Yy#LY_iDY zAWKFpKF|jLgN8ynD7|Bw1$kVGOp9|MIY#R^6(bNPXpDq47~7{zSgVXJ+Mnxj3*f>u zzwg=vKZl|Gw&A|}i9&>z!X>Zw8l*)`KA6MGMi~2VN6fSBSwB#%3Un}F0Ky5{-I(9i zT62Ui(W=65)!9`=*0{I^nomjQ#^nUZ)EoStqREy}%<5fCYZZf&G5t#UDv1}rpXtjsfL4}6z-18_}EJpJd@{I^24%981H#DYZLxBa=_bVt}B{yP;ajF7FV2?L!t(;_QlR1@4T9byrX zK7$`u>5fChhG`xQekI(>75|VUbSsp<)5_JijI&)V!qFVy&7o$=3$g3J`*V!`F;hoZ zK1RzMjkl4mtju_vlua9qkZYi5s+<;+k~U~DoJ!AJV+8lHa-d47ULd~I9MaCtfZH&s z9C2ivM#w_ZvIC8xN(r>znP2R=7QndmBYLVP8j6$NH8!S`mzf*nPA91GAXLWqx^!vv zdmjM(wC-uy(tUs;`@IL&)LBiJ!-n||oWhhYO(AlY%+4NjCHgwr-egYPujO;k0lPvc zn+SIrZddPgJFp z^GT6*jl6I@^&R{^3>yF0r4G~f{|K@wPSoB3l7mC&iM+#Hmiw@P5+qzoLH7OFK69eZ zn`h2ti}S3{I92aULZw%X)3IqE$8%5Ec+loXA%U5Qv*giGZT0>=Np2NPn@9&3lo$j% zn+f@!L#*1gg=jm-l%JIVe$t?8AAQz8j&g~wzpN=E?}@OaPIAmnA`X%VOd^f@x2FLj zPI<`ZS=D#@bJ_Je%I^zrwQ9P(L;y?%O#g08N5S^F3j33z|Z^w^jn$0pf+oep`D^5meg04JrD{@e}1NXUwI|mK;pSQO; zQgHm=F!2@rB1W7!$v&@gmuDiHmmX_PENyy&_YasmUtGS+DEPDn6_8g>$qbhbtwzTO zWRLn#-n)rNP@rkEsW+Q(8eIgMZ-@4$->j^Dqq&4H?4ot7bQS`CsD+L4n=*gX01*1i1@pyQbMtIen%lN!=0ju8X3;hjB2k`({L;bP}qEU9Y>R(@4@{_mg++6apzt4foi_;IUr~_ zqN%m`%6LBq>CkM7qDxv`#_Q#AJC4{Rhi-EXBL@$XBP_Ka<^it0Sfn8xFopqnX}9+v z849Or^(n;?_wJa-eCB{yjt~r)5e-SEU~qWH3p3Um4`%Lmj44=p$9ywEu;=ThtWmct{fiPVA_r70=1+MpOzU9lwUiDIv8S3vU zKnL1<=WNar(zdY~ad${KS8J=zY^lmi3;=ROJ8KebROky^mmryFBA_p?QiOf3JQ?z; z_~*P$Q+A(~Y_dKGvY<=6nEvD_+5r+SNVA8zdu$X6Xj|jaad^W}(Qe@6Pj8pw@ljro zdFaS=pG+(0Y6@>RcZI*DCCkgd3_YG)n#^~R@h)dp&uRj|2QQ^g@8_q;=o0!FuqJm) zrX(F*{Fzo0%LroA4j`RPC{u`z3`MD*3b*|7siuXMpj)OiwK>-|J6!(A)%^q0(1-_A z($o2J4Y^Wm-8-)lmn?zfZB6R#xw)=X{4zlbM>J)}cFnTQ)F(+z)Q}@m9^(6{jjjyk zXynd&9}tPCQ88~6V%LW^APP<=hNM1jyxsnd5no{Yo7Wj2ybcvjqFKBX*I^hJ-qGns zDyb`hLN6?aL81Kh#gIDv^R5)da)pTL8g=_>E&Ug_DG;pS5wxQ!EzMskXD(^8>a6YB zg2r~)wt*JOc@;_x%@I5`dK9SX!8+0U2^kN6XyDiuhrADuw>gBe(rHKWRazAKM0;b= z6>)|;7wDR{PMAb9RoOF+)k0YwOn8dby33`?JrxQr3-$Aur!Ih2)z1lmBRH{w^?L3v zCMF85*(l{zzE8tQLmf>)B>R1jnDC#(@WCX%I*mFiDoR4eR~T)!Yn>jlG6Dr4L=r#Y zpBIbauuafTD~N?1qDQa#mxB8BEd`M+X6yJMX)xad7O}Q`=+=lc&EJ?UU?nz4{#N_q zp{}?8*DXQPhx!|Zb6rRjf&N<{98SUGQ=(JN)*~&(?wp^`WhD^R9E!bxx=u<}gL)3W z*e*J_lkD@4e@1i~_P!v_2;)H`Gd+w5>XKRnEF*C` z5!|GBx3nyfS?u`dXurArcrn4{ha!qLEUcRJskV0J1N)b&Ibrgo0)#C(kpm!yX`PQP zp2Cc3D!QA2yd29>G7F*obTqk_S-V@dCe*A@#)2P`ROR*C+h4Q>6bI!x#f641`%}Ys1&04lTc1qj#n=_$P=T0a3&ledC|y3(06HTl`hiR~C@;-0!X*~-(RyAGaF znUSG02*|bSJ;?AlJT-i|7Co!gt-Qu&pJ`P3)&L%Br`3k3x@C&wWmk$- zpOY2v?_4}s>B<}#7r0fwPWhu8Mrw^(|Gz+g{zf`UV=Xa0-B*@3gyDINtT#u0`eIJi zO!`y&T$)kFF40&zaw+K1QyH zqowSs!eUSvcq#c-P&WoWLyWR9+{ENF;&weVc9eM)=14?|GcG0~EC(X1v05&Hgg51U z`%~xuWd3bRy|cgR63-hpp7|qc`;?izj){2@ZprVYY9oDt+Beed{f2Z4)PG;nTWv9= zzo=s4%q=&oy>5}$&~MOVnpC3l7zE=@o1n@X=TA((d9pqk zekRHDHu{PVSa1&W>*M&UPEctfE0p?l(+z?qKxDP%uFM)|>w6hC^u9AgJG0b{mG4#| z?2YXoIVtGGGfs>SF>Lx(+G#_EuI<1f4aR4_gq&SFgz4rY_S_-_3z|@ftBZ}3m>z9Z zNtpH-HG$eZU$>ssf5|HO(<-Ivd*Bc#7Ac)&+^kDZbP`$HZz%Nvw8ku$QJaAmix2%Lr?~@m z9xJ-BB=80$stSBSz}8AlIB2A7#zaAdl*OUnYK*LPS&npZD;b1GN>&?WyUp4<%eQ{D zL~}nEoT>F9bgG316Sfsn67|Gvr7^JVIUFm+b=cY*1S@oz*KK<-qa~!j7b(rVTTh6j zM6+1^ddVQ6j@Fr^S1PRWKx1vBna?=njnw6D4$<-Kd zabVm5VWq0lgV>C4S}}QJ=>?KM$?L!?!Bv-^#d0G+9K8SJ{Kg*y+umK}z1b*wlnC%~ zS})Gu_SE6CPueTF1{Y+mHrFGD297Bm(~}RlxKkXs?O(YDoKvy>XMV3E7gX`QVa3;{ zOJYC$`V@q}G?3x<`3bbwEI_zzt~pVb{D-xsRXfizR?+C|jL&Zopac>wV{x-7IGm&e zoXo2Bgi)VRWo!t)Kp4rZUrCxXG7)NBP|HbnR7DPY68PyQfOASV{^|>HQeW4A|DQ3x ztT^_7VanaqT%9hH#;up$58v2a?eoSo)YC5M^3-61*h{EFD^gIAgKsOK? zmWEKPb;r_L%1thYI6f>Yj`iJZ{eJCR4yz6fsd`31!Sg%bAH-*pzp*N9v@Vghx~ZV| z5(*ShS$zO)sA}>Y{Oo)chAL^YG&BOxqJXs4E5*!c;LVn-InO>7OJDL(qR$iy6_q01mN%qHFLIH$JrErT-AO zYy7ZUr?Pv(yXukHua)Bnb}SZdjT@a`OrELj4(XO33^A>6W+j`S>h=-V`e&VZV&M%8 ziahYph;)PIO||b%>Yg?RJ#_1AKG=&HJ>u4>rJLLNJ704Q2J44IC*B1L=x_u96=ppart06TQ#lrfD@tsslBq{Opo2a=nQw6 zA)q}fU;79uOL6UZi(UjDms0s`i#IxDr}Z+ei6yc_#4_YDBj)&BPd8r%T|CRgs=Of> zvgo4wJ+jx@=b&$t#bGe5NBI#*uLqFWDtCA`5^3UIq$y#MD*!`<|HJ?N*?SNrM^ zP8)-dx9@OhIu1bFe3jq#%2NMcf~?xb*Gugf-_-dMYft)*JxJn-^{Mf`D`9L{bCUV& zJ2pCyVNfRSjX95=Et-}V)pc#OPo%fehy3!(wfH^)8Z94M6pA{}Dr#lEdbGMg%AXD4 za$=LZ60MLZi3;Ch?!<6)4jC*7fm_Lx7HVYcDq3cZxHxh_BKr7E!|SpkP!G8UF+P3c zYHMUWZ%plC*>JUplH#J8?hn9&XhUlI0OFp>HpD|W&JC^KfYpFQQ>e;5D*X!YX z{6k~NDv?&c2m?lG_h%R~@yp~{r3%KEu$U)zYEo{3epJRmMFmI%;xEI|x0QH@+WhF& z!*R1Q(FLBe6gR*h@B-IdP{kHO`6Pm(!vmTwpv$eAOk!D+J_lL|-$uDhQ0{ZKxQs&b zs*^4vj81Y^9BcHDlV@946yoetyE1K&O?3Dw9quEriIE zxx8RiY`x&&NgyTmbX6(kk?k}`dm7o)nZY1TIw`ni1O2)YowzqZ9PujjAdlNY>AVg^ z%r!yw`=_hQE%Ohj$KyeEo2FTjBP{`)IH;~THNWmNEC{{sW$~g?H2D>Us~@gI@wCi& zKWq2Efg6(#5dRy^ra7gK=)a#}oxe!1rvE-ls9QQPm*L^`qt4F5%SX)HW${bEM@}=* zj`h)2WDMRnR3A_$5Np5R=Pn5D)QB+mUg65qVQFXe%xvw2@@Xh8!sD#1A&P3f|QR z+Hq|jP+)tTkoDrcY7wH?9Ba*BVDi3zXh7vrxqKinnh4!CEof8?3GDMmrWvB(#QaS= z5vcnj?SPT)?@)y|YjaD%)_YKVQE6xWf|aYPSZc!QcB8ORDfQ(yg>27Kg(iU}#z0kv zO>8K<`d0gl|02ioKw5w<;|^S2<{>Fe6ifUPgr5=*ffIM9>A?6b8hci4WuKP(?tr59IGu!6L zdg$wPbup0*&6a94A7c`U-+%+xrfOr!G^=fa`)~EY4Ow|%^yc!l6)W%jJb^LEnafh9 zcAAoLQDJca9BT>tf#Io2W>x?O@P@WIRdp+5;&8s+dcnD^K-TwQ3XjO)B&0%YJe2k5 z8$UJZ-Y&VwM4^w|8ewVwV2l2t0i{vH)!R~-&YP1#&81kGC99?{qLZygcyTb*NN7et z5t_}vis|ii8RS{~RF9RmYSE34|9NhT{W^rd{K;6L`n%9 zpm(P2Zyt+gR}qAYP)^9Eu(Fs||KSvFRuQtH;3-mbl}SkqW>tV%werMc1RO9LLyK2* zrvCLam~bQ1^0qWKPYJD4&5l&Dv&y_^j%iC2Ob^371W7TKj#0li$%;(3pXL6_Fh$L= z_oymwt);DOqaPaD2oHQc^4^9sxGnkDM6?`( zuJn9_umQR&X>gLe*YCvcofy%~HTTNM)TH}lqDa=;5+&5vRN;iv^fiYqivmjkG;rwo zCITL&@v%fHY;A+rH&>|NM`Iw|zf0a6h{Em;?lw!{Dn!If)|mkyK6;-vIlb4XS|ftA zWgT7_($UV;^qh#h@N*B4Iz}|B@`qwmSOV7YZ}|Re*|DEa}1>` zI$3$5)hrnzwOil+V?78A#gxE-+WRFk}8z_%;GxGVee8 zM?|x3U#C?~xob=7+?Cha**w-6240UK1$v?rI7~E!1_6smTqzinYM!zv|IdjQpQdfM zHz2Y*6A{rPNu}pTfK}^@DEmtPR(0iJIwRtBlC@zWjA36f8A3!Eecu9YVt5&HK8o#Y zE0#wmPM|9s9w@B9&X2kqRToG^Ebt=srD%y&R`PJ!b5ED%G}feP?r@~UGnU~hIfguv zfU&432b(TC*`Rgs=;%|c#Uvfo3f>egCZDT?ByTWy7n%~*>K#xTGVSKbJ7PoSS+B84 zo+hKIauT&ELKq`AE2&djl2ZosIyr1wl#EkGAlglbCPb8|w8O0cN5UfF``gfFMwivG z3$%@3>FqvfZPrZRYZ!ghcDFIc%96>ofhiX9LrLII2z->*Wvg5*FER(IiHa`)e+_O~ zN;K2v9f=S6vAOidhT|ze0##@ou+?sbbpFs0MaMN^U?j@JJzjNDP!9>Zop^0E`n5vJ zV`~t^Ak{nDc(LLxyujyVP}6`l2~U;)ymS?;wjHhd$=>tjkwARq1_wFOr&v34%EoI( z-jUKAjI(Vf=nT#qQnX_XKhqSJNtC76B~~DD19EntHnso@R%M4v7_MNG_Wd8co2)(BSq*t_AC_m@xdWr_VV zZ1t-12zjUrH6rwqS3AYYHD)YJ5cs+gR*D=2a7iqj->aY&VJE%j;^EjxN_oJ5K4EM+ zNLYZ@9J@(QV9s059?Mdkj4xOr-{uheS%cVhN2V{S9H|d5HCE}|KHt|1epbqRtjiy=dYzhRm&q#)g8cB5*Il@ES zdpyB!T}YC^)hJGv{cNfF{mBRF)sOr?9$OKB*bsO>8|U`()8CWTug%3OO}Q)G+&Ze* zDns_Lq|X0%b)1iC5#XfW4}AXWW7N+Js-xHhcJ`mfI$8?Qf2|JD|9yloA{l=>a1FS= zez#hm*fJViQN}7e?1`CV&5v6i#JUXaO4M;Q9G62RI22Zq{}CKUprJpQHuo;6en&Sb zIj;?-%)UmLThF9{EMGe|jTstGwiKC4A}mUW?5^q*Gnha0L3Bwe>!NWE?oAwe=l2=6%grX=^8xe&Av*`OqwK>QI?R z(0N=;w0r?4FT&dxq|a<4Rm81)UA9q!1Y!TNflL|*5CCXD#pxVqflQi|%XU{Fi-E4S z<4&k_HrtmN(OTHTjw5Z_B^(IcQ#_JD{eprmd%RDtk4SE|DV9X-G*KVzy8|ZOnoZS>}jVs6jMi=MA7-%^NFD zUZO5!pyi`NLxVLYCNx%g;GZNW#N628^g(s{fjB_qj;Q|ewz@py0>_vUU%tiA9ncB` zG+>%2e2W;6k5uxIrIo00aNW7R|M~Q0`C3G7;rpewD)52U^VEgAc@Bv5rwD1(+b|R8YxZHCxi6Ui>vd)mcM0TPMPEO5f3hH7)^FY~7w;WF-y2d0&dm(j+mh>a>B}8tA%TZ!rz2b>cJ_Qt-uL z@?NUXDj>hgu;Q>F=GLf!E}b)YlhKk9PBI*$a9a^y1oEox%2q=9#$GFpd8m2--YZrG zD@ROKBJi&0{NVVR)o=p5a9ArKE*}B(qkXvAgGoFe2(bbRoZMKVP@oQt_lykxo|^*` zJW=yU?sflXxI;4uhY9Gr*JCFRELv8Bi5^Znm@mUkJonJw~G1!=~R* zvFttq{tP^Zw+c>shaLxyAkd3)78~8ib~G6K_EnQ9m}*x11n^4Ce*p4hee?GO_YAtf z3_alYdU30V-5JmgWNi&F-ZKE+yOSqM3}W23m$RL{dYp2ejMCHj(%r&6Al>}Q1UMu= z;dD!iW|UPhy!!&s>ajNHf*D`ud5*KLp=5Xt_A?TBA2M@$B^}*Upqkb0_*A|Lv#3a8 zoX+e6Z{+7Cr5@P=uhyE&1j;CetPw?=-zcTQAtGeRTj1ou40`&i?5E zYTa@F0I8A9Y@Y^2dWNIqE4wL|JVBoyE6#48hO>M?%&ohUewd^EFN5@3kM_cF1bC5}@1fe?C2edppiU)q`P;v%FC z;cb0Dh!TFU*IB1nv2adio3up0@${nU_3&n>>VV5z@nsQ5?0if0DZQh?(k&}N6NR>L z8k7+N$6m!bb*QmG#PlKT%yA{ljtC~wx~f(^UmV(32$58(H}M$+5!5r&WC48fuZbXx z7g;LOo4j;r*Yc>9;R@(QMK$@7|LUz;QJK+x`-T3)u~iW&x?+n01EpBV`rUtj`EhF^ zI@B$v4LiSxc7bgZAC{Udk608a=y5(_kt+T+0>%r=LP8R~L0c}}ksiv^?SA3Y&$FOP z6KwVgeT{fLM+z9&;?S4E<#Lg&CtrU3Mp+B$hNob>fD%U~lA@jfT8|PSKwL>NiJB*> zwijKj<75g(8hr6{>HLs{C~PN@7*FLMG_?}|CH*iRv<)&rU#KgbJiJTbMeM7WdIZXK zTKjS5Ri&o1;@**m9*aiSxS94AzYB$btN^dDUbUhDTkai1W;h!;!p6I(Bk*tcx=(vv z-TtIs@=jwldOPT9{Q|$PY|V)0@pF*wF3DpRDe2QSuY8)JTEgHy#vU@*$rph3#+M}U zOxi^U=~cD^Jk1UkWRz=;3Vqg}W}rk48=jA&XRZrG7)iteM(sQE|15ov(o3{ ziQs<^EOFZ3LB4a|c-qGPu*^C*-}PQxqorCX50;eh0<#e0<>2vjp1#8!< z-D}J$mVZW9jPF49{Y7{jL%d4z0E4jAbiWRJBB=)(D;cUAN;5(0=Qm|9UP=2ZNCpW{ zrzDVT(gxdbxuZ;KrmHg2E)S!~od2c-gY)tMMt@!JrM8(i)coBcqkdlQKg?Ry9Q0NLPTa#Uc!D)j`;V2RU$uK3Fh*`n9kg2zGVY)f*_j)zw1BA+v~XgL47l z^klpCYkZ*bfv5ayFA{cEOJQrr1_Xr@16De#-YbFlGp+%)NVY}0kx5a_SE|idT&aM|JvsKNrBa@tD_Eg49~TnGkV{_|$>teGJ`XHyoS$6d`ogu8cG=1hm-- zlY=%0xLmshJ(CG|w4|Iejd`(s5QCAI8AIL|MX)_((ynPFp?=69Z9rq5u+rp$2GL&1_x;`(6*B42l0LE_acF#OZ>g zbW)6W2mf%2)1knaS5HCm0C4$+InhUS1734J_8DBXbD3~bD+aZC{V=va6d;e|SXAj$ zeg#e=fm4G0k`vl-N^dMYy%~AppSS=&X@B+BJtm7;_|r2cIB3BLB;ps_@ot|x+32%cogi&A-}lzRH<6f(9YH`GYV3ExxdTqDC*@CP_!$HnEKD^ ziw~=?az9db2Ct*aCuWfn2Y!JP8;Tezo3!nvYKms9h7ht@m1%w=@!R4A90fy64@4~u z;c)Ul*Oc2POEDS(q8m9c6;%jI>L_-Fuhk9=bU$X8I8|$xDlQ+yF8^(At1@k#s`35` zAb-!@dl7d4!y?~1WySbWM%;LTldy`O&zF#rG7gg|uYJiSq!lscMqW7((E!=kSQa9! zizw5KI^;`9Kd95zi?~J>uPDunF?&sw_k|24Z>ehfLB(uvgD5YJgERO`C;?_hzdDiG z_$#MLkT58A){a~>wx|9hhhLm6JtAFN@CKxe^fg8jXZ4UwXS@A#}spvuS>k_oZ+dWhVUhi@MOHk!X20=MZS=tNdh{eCunT% zht>uRliR~^f(VULf-ySX9D!VH0!Mt0iay_S1tH9T%p>yo^umuf+cW{cc)qb!sw58& zoe*=Dtl8LUA?9^*$`o$KyQ4D)fymiEJD6}MKGmWhaCuk6sm1-dgLnafZVvn*$V`ex6xzBKYG4wl&_`OWmO^iu$@p1rEv% zDB>KfEl@t2Hl}&cU#cM&HAG_OJHkn=P8bjfw6lQEUS$B=!W^!{6C*q zU+cq5apXh;bBBB(e&zhdsawCsU9mF~?UYak>{TRHl-^WCxhscQzgNi08ApfNOy39# z%4b?pQNMJ!;-%prq?k!RvSly3gj;94kK?Tf&+$nlx63!jAo{ zh&K|As;6WYYKNt=6^5)f*(5Z?jsyj(KRQi@OrS#>&Ytis89)mJlpskbVoXdEoel_H zv(+Bn7{RLX$At^<(0>Yz2gPGwZN#rr@bltx^FfG3{ zByBGz{0x1sxV6|u&KnCzBk>vIM!)BYth!mM2`c=_Ubg5{Jd^n3;z5^{&WOnHj9Odm zH&A#z;Gw~zY8~J?hxc2PLcwO4do++=1EV2ugi~;CKrg={CAn}tIM`oFj4mDrS(sx; z6ODn%eNeu4wrFRODy^mtzH|}n{pf5Q0O6lWUw(=WoIVDMr>G+@;0DlFYe)I1`nDtoG|wJPJIXMFqXZJ14kRQ z`Z%UYl4w~j*=ny@n?a5E*vIXF^}B*Y;AH#(m0&~Nei|CsMWTnfte!K3{=DlZP*pop?hS zKfz~P2cz~Zo|bFo%x<5WcG>}Sexbmn8R6EqzNOp8^UZfl?Lx*@S6C9C79aofJb5!X z|LB-Ru_HoYB=rE+0AoD<`0{l7{~yi`bJ<%mhERa$I|5pf8s|8dtaNqtcFM!-jFHRXYFHhQ!IGuA9I!YQO zL)XU^GwGc6fJif7Jy_AQw<;l@jA(@fa7W2h@~rrfmpxyQ#&eM_zZX90X{RNy+BUrz zOgA()9?$sjn}F{3khpbB3B+x|A=9P?bu3d91zBWM9VL|c=fpGtCE{iV!t-eg$Zg6+ z#zvBbJin(B{|xyvI_Vul{v4ASo&L=X!eI<_f{WRK?DLe!=g&O{u@d?m#7ZDuY_@GP zvA7Y=-X5x$gD*Q-O9b6OJWZSakGn|{aH|Yt+Sv+Xsu-g#z@+IY11Or9`?Bm!LV~FT z_O6!ZpDmEBxwSYpT%-+qsc0BJ5XpI%fsro4|P{))Z%`?PP$Bfy!vOuCpg_d8PF4hql*@JSu+f z&hEl@ZLpK-oJ@e*91!(JEaG7s&S4o~ZxtLdI?4B~ZRog3ZQ$=N*N5e_CGe?pn-W;O z2U1$yLQ%deJgC=n{gw>-D`mKRU2aO5I9)3-7D?!WCO z%Ymj4z=532_d^5%VFCz53?o7kMDE>_EweZp`mkQq^{#+&9H7+Sqh{`(t$NKLY+~d5 zx_v}{)9#of;iY);`sL~Dm$QynXW|YU=LytKA3Tq}Op>0k<>#N&W^!}@q3yCy0&y2P zcqe@vyT_kF^)(xBDG@vUs3`#}VIoyH?vU>{;qEf+(zs|m4Ee+*1Un+Iz;kAz+%urU zUwt4t>fSS8ED|sC7+U>65NV9t$`cTO(+c2WuxE*8!Ic@xVf6j2ddf}@wowq;ep?~$ z=v)@%dN0;TH6cZu6kZH`5wN`NV}quhVZg;<1#dM0=#>tDtKs2=v0dg4Wk@jN@LWXa zjJgNO*Rje$+^KcEe zqhmp=hl+U#o`MAslns}F6HkCdfKIb~B$TP^7TqG>lN?B~EQc4v6EmaXTAZBg?-G7I zKL$Vlsn-dIJ~)yjlS=+z*2pQtxeqcmi+SZF6gSn-w~MzoKZ{A^Vj<1I; z$OCJWCkX$s%iIp6nh-brml{0Ov&{Tuc-iWeXQLpyKHAk3by3keP4WWnXGE zTLp34;W%8_xIO-*X#q=mgd%$y8XVI`8|3jx?%hO`%h-p zWWuxkRjTuw0-o<*iCcc3t=<*l{I5EJLmvI6e!PDZ=cQm|)X^{5I1+!2*UimLRtXJSEkvTQ zUYBN*7>>i?l&@`A)C|Hf!AOTRa%jgAixiUlEfKS6iH&Ih)rB#EZhY`ui&FBz_gFF!Bt0$bsc)YIBX$u!F}CuRMt5^iG1#ek8QwI0Elinhn*>EvYm>IZ4^LL4oIP1U zh>iwk(kykhJ8M$^g#U;VFSO(%aMm0Q0;dYy`!QL|%cXJH!7`G!F!rcA5c- zn}6q?y}FkE<+cPt+99K1)seXkt8xdX5ln4rU#q2{MB)4<6`+8?~1=L@| zJD=5)k5|WwepiIC?82RI?(pI{;%TOG9<S&E>m&koJo{7(L-$zg%+w~E$s$5M01rlQG2xN6rO zI#0R9e~9(9`u62cRTS~(z6-poY8eA5oK%3#*O5#yJ!(u<+HK$Hb97=&S_o!+j+1nb z-V%aobk~G&P#nC@>DVH!5(QT42X?Bkhjdhn{Gg7BT=BSTQG@PXq zBOF~bf{{Rkg`n^k+1%UFZJ2uiLSC4(3Exk z1DDcWRVxHlyJbVjUyWmK(s~RK5Ld(@E~yWsmIpJ^>%L_^M6N)?Pu6vh_~FWPL8?%^ zi^1TNPXdcaaBD+>l1qrY*N~%;O)BYD4Bseo=Y(d3f7cOYTNpn93TtIAJ{h-k$P+l} zZo#q(OU_RfhdoWYo91AV%h~(0fN#W4{X$KdECksV2nCLz$Pg7GVam8o8RihI37H9siFzM^V!SAzFys9PTr+&4C$^%F z0k&EyA?xsoLnSo^ggp-fp(c365l~O%qoc8=aN4sueQSdkWycMm~E z-;!6E9E1MYjDh+%Nqwpgex?9asAm*AeZGqYh8tMEwjF z`@*XZ|1cA{vpxay`8(q6-YjM`p+Z@7SY%i)s1=Gy;D-E*Gyn3AC#XE#fI`S^t){kN zJRf9lw?QPh2l%nHNd0zu%hP(vmacfR$SOad&ktT_ws@GqD*@{X^ z)il{sijMP(uX{IaSg=*{pZ~wRGl9RyV!-ecq;6ljh{ru~ep2}qnX#8auHowRp1Tnd zWk&g|Zg1;^l#8|Y9i(;&_f#-OQ|LkIq|?k??!~Lw4=5jvQh%@Gw^uI2fc>revcF+Y zABW^F9-T4ks#S6%!S!$#k8$SmJhJ|sNYQowV~c@pz_2tcfxQHE79pXPe8^1fpO*wK zGW|)A!N`qZl2Wr}BR3`dqEP{aSw$k{zW;K>`U!k0io?;Lmr;c+v8a}xr|2q9vpI&c zrZNSmFvW0h^>IBjR#5q!^tb#?0KFia6+UcoR0vH5(N@fy0Cm7Q*>IH>8H!B{xx4%Gc*8KUUp_OaC})U#W_wyO7l8u5+GtxW(# z8C7#D_Mmd;3FcNdi3R!pJy|$eQ`Ya?wc59vIh@1d1(!-*uSbZsH9k1^qqg;o8?f;6 z_TIMhw~fWyM^^oS;kA`p?$xbm5cul~^|zi&O?^fn`Q>G+cTo#3@fL=xB7G+KHn#m& z!wcL{Ri1f<`&p?xZ_dd{Mo;Bfri3zXV9t^d&|$qx(xOARp=dIZ?OGA#VwbPZ)V&B! zD<_;8z~|DyYBp+w3|L^|^=p0SA6e0n&4~M>mQ69lktZ`qAi>&QN8oFWxqwq&6mnQQl+MD5L9Q35aVP6sVY9T5_` zxa)oCSfZbYhYKUo7HgM_O&>0h=m=3Sc% z<=v%n@EihRbQoOdH~8UW<~4B9R245^ zMmjek-6&lG(p}P>N{e(O_0laM(%s!1f`ou{o}2Idbqu%2c=mc$%y~^fxN*>v4sS3| zgt9{P6DdSvOjX3XQOsp9BJ+R5YZZL@yY_-F)YiA>eVjXPTBjUbq7Dm4*b-m;1Xe>Y ziB+H*kjxSDJKc{4g0yuYw7CHska-MIK-8JRk!ujM21Rp1*X3A${Vw@0ZDUj(*$)8U zmL?r@=v{yMi29dR!u#r|bp37{psN6uGlP4L-7hybLKuv4SmXxE4`A}f+I%<`CdzfI9=oILzfehd9IkwW{&x_(BOQ%tZ&R#E z{49?x(K_%$vms+f=kQo*@!?FiZh7q1Plas)v3~41Cva){e*o&byr=8|=0U644v-a* zi!RSD=OLA%up!@>`p-fxGF~ahQ!+xvz z)XwRF=cnn67<>ucc$6{ zK0(Dlu#D-8wxbes`L4PaMyNNyc=<92fFm9)+-KZ~z>Rovco_I#n2`^h>3VQKJEE;- zc_LF!amYlnx18}{LWh|!!uvnDJt*yx9w!*o6{+`Mc+8%hDBnAOkOR>i%CO| zNI6Yl`ax{pEpRXXX#?@U=44q}4EFs%-2qlP`pnOi_aGJF8L)9${NKgL1$AVWQZEyb z`>H*_cY@%N8bk&pNTu?3KX4*@8DM~zAYa9nms72W53{o;3NH)ps{!uA0qTYP3)X`d znjQ{X#y5;*Z*@vxTG(6m^Iw#`9}e_zlYiLJqjA2H`6J7V%sT0Ij*pEhld=osYDXaC z^rZ-2uNg}u?5coZabVf=-S2`=(Q%O;Upp3dbE$2}adbc6HeN1L;b^;=qr(<|K9l9; z7xu7QFV!T%`J?whR5u+wp;%C=F3#?qjYz8yDVUHgy7${cb2(Y;-}U}%nPqY8YP#jT zznCd%bmWDr#o$0Um+kGEbh%`0@_)&E>k!HgP86pQiHF4F$w($E1#Ze)qDc*9XB<(CNEy#ib0Qx#Q~OX8IxqHn_443q z8VjGOZF!<}*lFdo1h zB$4Sv3duW%R-G7(;@ROU>O5T%ZSPO1wH$xl?t$#aJJ9XaDSBzr^R4^-1G|+BuA#NB zy#WC_nL*qkuuPs#5tLOiA0}8}expE!nZEru$fKM|!}aaVDKJK~SFk>tyISFu0y)js zuubeYwDjkT@i9!_(@Y^exDefs_(EnX-$jVtrb8(@z}}SKv?ucAL96b@Y6Sxk>n8U2 zC$NhH#WfBhx+sB6fuP%yIz%Qh#u<&Fl12vn0?0E%GXg>GUr;)wWZ{g)CzHHBLh=K~-oP24d3YkKwU|>2rsv93G zJ6dZKe!F#Q1RF)aU8<6_L9>+M|Ha9zGS5okkm@hiA;rX8Gny|F7HMwYt2#f3D*{J+3L@fKg;&h1<;IU%&lweTHb+*>+k( z0Ad6Q3~uIB5#Oka=$UiX+whDSWqToatM#h&j=u1sD+*FVN-?LA)Y)WXhlV0Pj7o}@ zwnlujW32g*_h!UThq;95TJ^zbV(>%Y;hX;$|6uJg{gc+ZtDtL}fvl~;sf(ub4JJIf zxOdS9ChZ{WnyPQH&DprL9mX1eXi6a=v&4iV%)*c{YOOb6Nra?=xZa`*xB+w|0V6O> z#F7}6PHuE%wG17^3HWVJdas!mt?H$TdW`63_WNMaB9-JyYY>tk!(1pRQaedK-z@@h z5oWeGx#kcE0?8DhAeW>6E*nQVU8Jm8hv^p~@TsaYKR1N=Ip^Vk8zG(F(Rg=}*US zQDvM>aM9{u5wK^q-oEl7G0OyH=;myj;PNH58vvR7fr3MtRST0!>;b5s)S}&yK-g^G z%cjI`d@E<4IuD=HjJ31bI(o5YRO35IsmurX{17}YJ^@l`B%QZu+#k_|{}uD2bjrWF zrV%2>d`V#jSu2kTbh1Lc`XDBbg!!KZEE*KI$(U3>dPo9VP^BEizw19KJH=UKmhEp z>2c#RE`4eAXu18ckE}}kL&WOcHHF6gc13O>@BQp)xGJTOB!yhhQ){jVUxgJS!2`pN z!%jXjf3SfY)faFW0JRlwxP59*V%Bxci;Y(#sslxp8!d#bZz&{mS|-#1q3ATx=<8)l zQev@=b=U-~yE;OYO`vZ0P_he#&POB^edhnNk&S|_*&^^02fwrQ+$6R&h`LH|)|>ON zVM-++z@qBLFbVP}=f=k~OwSMqP$P>@hA8&OZ#0H>CM&&3#<=XE7GNV8W|Ig;9y)e9 zm*Qa)gcY$PwyFJNz}aQSS^W;hDn>*|1Q!Y^2<+Ka8fN=YxqFt6w2Y zKNN{f@D@OT^}iR6F;EGw=s+gbp_LNv*AljFLb1Y^5Enx0`?%M^?m>P0Q5%)9>~shdjj?nVI01lQ{Xb_2NVW6v*w&peE>mj3vP18CP9cVexjF75{NbRmk{Ht z5sp4$AY?71e!%E~xq@-FsAd+7Zu%lhYa+j}{Ysc?Vb^Vn5lix`@$OyTdz_d{?zwVWk2*CQZ!Q+Ain$^)KZJI9OZkAcI=gCT#EhyE5hx*-h82 z<^!2SH8Ap2&NUqRcImi&&%4wg_{cNoG3r%U6dkvXI2?fKoA~i{$%ba$Pa0Q4ha3tJ zo>^K>FXh#Qt3V0!WXHwp{ZO>~kBKC(Pz_3Rj#s_(c~(L`({{GrNK)`pz;E2^$_}2J zREXA=;o4Wb7fB>7_>PeR8nxg}i}J=QYuvfwf&~Z0b3!?$Q(}+~J{)s$jWgAP09s3* zqT7(f4I^8Fz%k7Qg$=uz6M)h(YL?01Pvb&D)bQ!!4PgTK!clB&p14^*lrYYD5Ozr+ z)F9&`nZnYODRN?(Ys0ijFX&1N49{x366uuptxdY$Ak$lP#lw|)KlIpXy;QVf?(Di1E$I!J)+7)SACKxT@7cNusQ5q5t`kZJ)i5e^LkG@VR3nsZ1{5$#7Xktv%5R_o^*m>01PjHo zkZ=q`>qUZA_ng(ne}``@0Tp}O;h1#qaI)dw^mv=^I(%H4@Z)ya-6txcfK~}Vp{tYG zI>qa3d$MI4ZsLR4u}o3htMVm@5gY4luGZZGlDeX{`=>)kmFItoj$?Kw6AjA`b(XxN znX3~u-Q@>=+h$u;$KT3a9rKrHw(^Pg*;n_UZhkq9#>+JOO;vSu$VtFsjxT@NUy~$@}ae5UAyCBWt46m}As^3+B#sYR3jv$`& zg_H`~KX0HC23LlD&W4+7)fbxkiK!o_3@?~85!yFXu9G3@IvVH+{#2cg4Kgb(WM8K@5;kend9@pq`0{F zZN*++WgXd4gZ-bW3GT;&xT09%n$v;aJ3jXttG#|@MRqZdhWFYWPg36+1|q|2s*_6Q z6g5gx@5dgRpod=Xz%C8SE-&Z}Pq}jd*tuY+*^^zNd~I5*LG3vHRdEQWC`jo{2NO$a zm`h|=ryZZ^%-gzy2ZAO&_VL@D1X0Ep)y$=UEP@b&%t9y9GpJ7XabF}F7X+=tWTz^giJ%7#-g|wEI9dwzzbi1vL{iHOv1^G+Vf_Z3nEe$ zDEfy}}&TAlh3wbq!7K!t*Z>AcNgIjes@%jHQ~}^-4|9Ei$mc zWcWkg!mfjfN`c8N&t)9MuFuN36yi);$Im@o1>VK5aa$E@w#rkvZp=?pE?{Ht1h*WM zt)Z7DCwFh^_^vtvmY07oQ!c8Q_1gu^vRZU`Z-<^)3n7EY62PsXOE=hqyt{%EaO8ai zdnraSp*o-{>`&a=1}CQj-G|}>a9^zlTm8^8Q%R!R^01W8aA_{Z77`z5EFc^cQM+$p z;Ats)5Fou*(B^bzdJ)K#epo@ODP559r2ct?iuy&ebR_dwB8h1f^askz9T$AuH0a^^ zfV+C|D&O^sKS#h?=h@H;3l&ovT*`}OGc4Z+9dA&MKAlYfh z(fj9vNZ^aLlbEF4`{hM<_puN}SkD&Ye*VMmxaSqYRz=I4`{dQ3C>W&lo7O_HFTKaB zab_6d<7fHAV8&rNB_=zmix0?uS6iD{x6$9zDh6@!-Z|BOHnpiw5oXFAaf9`Qc6MYQ zZ%Rj#G+MH<1);oc7R5;GV(Sf)>}Jf8l_|?L_^5hQ5pIf_N?5B;hez9(nD`zdf?HeT zPd_2RA&noYlcXfUwCJE$Jx{F|q!e>G-F!4|lN_8ftp@XUk|6(>q#FaFIDSdb4$9Yp zgvBC2*~%H3kCd^+Bh>%y@PSaZzG6=ST1#Z9f*`Jd|LsR%d0#XHma@Ql-!s|+RuA7j z_n+E98k!~48z+!Pvw%T4+6Z>zXu23XV^|+8O6PpCv@Bu@snU7K;~~2bs5P8`#LXt| z=zYjbI5r582UwV2TN~Cdj7`syf4OQGOp&){jbh?Z|C7WbHmE;pax`D^Ns3Hlj9 zCAe(fm_u@I2as25P6QziD2na>t$-2ucN@ohqAVFxS`*$9J18H zNjH`fkAyB_UvglRIjd>xn4lJei5N`wKwxGHt`dz^s`3wDu%8Ya$WA1R+tIYfS3O2A zx}kWJU#cEL;N9_>7U}Z@Ed2g1Rw#Q}m^yC&~U^X)dq<9F2fow2zW~GG1(?cS# z5QaR2OCM?;zA*HTs2f)S$t>5zPE<@yBbd0Z=6esi08`<&us1=XnIMQAj@f^=&lwKrS|A7o9FRUkI$XTlQc^8nb6@_=cdDFiRTE(e?5{j` zUSu$Y(!#>4IC8p~?ZCL`;LgHG@&;}wkxxWP?ocQ!F}sO0N-0%r)qI8<3M6CuNYD5I zAI+@&sSR6nhe(mF`2uL+UZk9q*AWH!q!!US=KIxek*-b_n>G8x(?;KjXL8l$6&n7= z5`A`C$NT$}%l;;w(l$o7T=`$UMfRx8^i1O$t*(T zew<|oOTv`iJ89Ztsil@j_h%7**;{m;5s}=%jXvYmMaZ>f+v8k4dzKG7m-m5tf9#={ z@%ok)oOY~cz@+gjgJ<`NbS%(vyXO9+Z{Dr#1NH+S;KY*JVXa!q7$DBB-fif9Gj}zP z^ATYaI|(CqXV8s3^%L)F82WhT_-~2l(ILp#MqsJSx9X;e@h;*`nbIis+rT3=TKO+Q zJDQMuHW|AHH+>i+Mabfu&ACM&0~4&9S!59LSDZG=@%rxwcBrDuLDn*M)Y57W*hZ?b zh>9$^$dVB=aSVwuc?ihK0Eozd7|J-pfSB|)|GV#N{oHKaMihB5Yw%rS#mbaO>>QpFnTA6#LaJ(2&RvWbm`z$kj!^bx4O!WS@&mcZ!2rRxZn zNW-XE(U^X>fq|3|jhT8rEZ1s%jLh1*F3TXXoIsTWVoQEZfiTn!pz_^=bA^plSgA4= zAH4%mpvl%xj@m6ZL5jyzqz7{qWHFx5aA|}V&Xm!_tEgsTX25y7-g=svrLukm`&Yo} z24aNB{gEPAO)R+28_zZ?0!#;0&AmSGo4s&-7FXMCkWY>sf2;K^ z0}?C$f8){E>uIwqmAY}0m5(EfZ|}A8~7Xo zK*PmV#OSf5-^%4S_PYLu-pvrAWUUN~F}v%{`#RF)nJ4|ZEa6L?Pg%+-`W_9j6fG^> z4SdCzRr>mWU<@Tn(9exwD-Mc4imA5Kdl&s8l`L;C+lqjz)U8G0hRDIshpn1<>c5zE zL|Dw(9}c^jb`cc3sTD6VsF%O^@j?fQbH{X4Q5Q@H;Vq&sik}xioJ)$H4YQ(Vky6dO zD^;Aa1UoJnNzo+l5STQ*eEM}u^4lWFt$LqQOTEG`^?aU7XVf&7?r_FLx<+Xo4XbeL>zi#W!L93eDm78B9^lNi86#o7yqeyWhL;)Pr2KAM2%QUr)_E zxuA7v)=HSZKa${y0i05XZ$M5;y_lG8^G68QZqaJ+9qK18HC&IAjhQej2{r1Qe=<`A z(4$%&P#PMqkvGI_Q%^=pzpgI~gPc`^5iE>hOMjNB= z$EWG%wdXxkr8^R5h#@!(W&6A1ymYVa3WY4Hb7;>O&AxeHkaG>$d6%zxtUH5<@$3Dy z7qZQZd-Gvy$MXK_P|UYyBM%*Wf5KVjOQR*wj2ulAjt&R-U)CTS8{{rO*p~m8s755U z9QFL<;c7W5oq?r{8AIiBdy&k}KVF$NP@cTUek{z-$MeZyesi0It?JiVCjtN3^VIU2 z^yQKHnMzkpsbO42OdU`2lp;R1=_0;;9w85hhmG#iHPK^#58M!e?m9%+(cv>0EKc90Q0L1xx2J{3|*fJ2-4spOQm7ty+3Ed zs58+ZL4K2V$G0JbQ!;ra9#Q9o>Kv5?8DhLhMuDHK6`TQlL3S6m_`@k!(z03BkQXDo z?%oqt4QIovEbsB`+QuP6!{n7CpLmm{$o%v4mlj!9H_RYb3GxLRsX}Bhogw6_L6X`i3&ej@m8{|A?0plffc1kwI;$?%f~Wu0bME3@DT{l5^#t zpTo#ZMTDj+a-FxjM^0M*lo*v2vob2fEE*?CLA@)Jxr5}pKXaJ`EuUv(gBkm;?MeFx z1UvrG*DJ40nGzhMM>n~4NrMcW9%<>}R)zT2?FVJb&Xz>+^CP>$PpnOfzL+~psT#wH zkW>vO5!!u6#4c{hPWgxt>%a@8R=4|7nf}ieYc+{sSA)EsC`_Ko8B>&FpmY~;H%hl5 z)Zua!Zexuai7ub)S)z$}a@zf-l_OYimiVPgWM|^p+A34fwvrP#L z_aGA~Hv|v`Yt67C&HLCl%bzkICz07SjeG)DWR_#}eA5u`u&r!{&(d~PB}!1v*HIcK z>hlReD57V#JcQwd#A2J-&NoTBk=l{BRl}{z5qXm;+{)9dIy6_A{3fRJ^MHVy{8}S!t%t z=aa5R<4`drs;JLZ=tLMS*~>25rL6F~dQ0?;eNq6|S6!WJc?ZOqw^(1J^WIDmB1PJ> z4r=Tl;XocR!heffY`Tu(i|+x_2mP~#`}!|G*=XW3Fh$WUCDIO^MN2OZ_<7W3GNGtQ zM;@?Bge#mgRe6GlRYHOx-qnFhyT?K$)xVLn3^{b8qa7{y8OvxT-=;f zWJt_`2~65a;xOSY#d71}Orc_bWmd*AxQ+cGmfbJTl*=n!!%7et(m7n@;9E za`Ipy#(A-?2FAl;KxU|GFQqak|P# zE%#;HFSQFlJ~p+uk^k7W5a#%`ur=BszVe58_DQ0S`eBdgngT~5@2VaCY3mj!$P700 zhAAWh-*JB&N&^1DXZcHsSUJWWL zRg^b^zRQjQDdb1B0;0JUAhVWqdN8N{ z)70|^lR%kJVPLBr0s3UXG7ACnDi;#VWT&kZBOK-i2JvzvaJivd!R^Rl6O>Mt7Jzc7 zj-nttC0C0ek)7$YF%u8K7IoC)2S*A{b%m@)2CKj=vqn)0nPgAmV~3}HmdH%ABx35B z$z8z}BCmOe*<~gTtIN%%ttf(#hY+_-Ekbe#tIBef;>q_)z<~23JX$tNDSv@K9TcNO z5gsbv6PL|!E|1kaL!8|VBLzb#2ph!P*C=UT)}qGxajC^i1rOfIA``vSAT!{QUx_J3 zxdHua!0)=|ygB=8tMy+WJ)~OuKpKO){hyL$tLa}-%PPmV0XlH_&$^3xL>dpM$(0ns zpAKv)E}d_mZB;o4TX4Msy*}+8c89sz#O-FIgz+k21wxwyLcM8;@%y%7Ab$@t@7CpzY}%6ijGQQq)KGXGM& zeX3{~P-`a(WeF~^?|ji%j;;DBy4`r6<8?Erz1(nkQZCeJt!K3WMd=Kx||8zN@sIj@t zhQhBOcD|}ox(v|Vl6e;m1%5K}QGZK=4ad3s?I=(OTNh4UJ(jxXdzXt42fnGzgb;@b zyM-n+NpCnCxO?n@<>fVSC5iiiB$1zB4At_vI*OtZ$BwUdN@V^(b4O1r4Yogb7YD@k z=>M6CjiM9TwsS|!<3bZwqX$3zoU=he7jcVZ_>r4nU8)beU^O#p5-H?UVPneqX3)qD zA6WU)aSLxl`db}+x5-GqyvY3kHA8@_8Z!VVZ>h;$>7!R5(XT5WrrSK8p8x(K3fRkb zTCfHfVeWIAM(PA6vbjkp9mlK<1Wiy9eWs{r7VFsvI?sj@hnNzKO`lWeGq`Xvx+O=? zd|P5$)Nz{CVuSSrJq8rka}Q4O`yygh6P_rFVBh%CeQ9I@$M>^Xb076+CM~lM3&Fr9 z%*3o~Uq}csZEM)Y?+BTZiWE4!ZN~VmmyiEdt;=L&4Msr}$4LCVzELCsHqn#MeP6)G z;`nQBP2r*!|CC_a+;-#f%Goxy_!Qisl?Cs}ol{>wW?jZIUwzi38ah5*nmLA~=WmY& zRk-+d>0HY{iJsrROb^~FO>TO4nVw*9UT#g$VNL*5Vh~`%D*IUug%M@>blwuRJ>BVp zTey+i86q;qpV?pkWb4GTr_P41ainz`pv(D=R}DmIbStzXdgmp2Zg4Oa*TDdr`YULm zo})fRpk`9BAV$Eu+DIW_r{N*gzb2ih=^O!4t*qqkGTM;R{`LFa5zOdoTkWfnKnUxncZ?d4X zMaZ%#!iVW}Pc<1w!O_nw$Qu1O%0 z@QA~~-Ba`@Bd@bjOG;mh?HU$V!FfoA17yItsxZ z5||x)y3wT8ytG#D$6FL#Cx?klwc~MX@t;(`X`QfXtLx}I!@-*FbALg~w;a!2iUr;b zPY@Unq??oAP$ptEL5*=^zZ13+s@nwAD2^qiLV>(lM$Fh<;q4@2fY9k=Fy?CGjB;X|;2Y#r%Z51pqbiZ}pOpnGx3;yLJ zCPrhR8hM@`K&`E1wzNnsc*2|_=3!|Nfi%X0G>M1HiH>jT6bh$x777dbCLTt|9eVM1 zooXEHE22$fM?Frg6kyCW^q>!>*dkhBUSoikq6AJ1!fuYBbYZKNhvTIti|k84BX_5Y zC2w>upKGqEOgxNdJNJQ!I)R5YMy5?$G1;yee3KmULueoha5Ou+uQ&#M)}fMelGG^< zAzXZYKd#r%PgZMpUoF>qb4;r|`ajq0gaoem7L39*_mOe<_&p>9Zp%IdxkD&DEG)DeEe088O<^eXBy1+_y;SWylphK&M) zn$k=wWDSCwv|bz`isLGMel}4^Ru#~jo~2bW^Q?Uk{H_eRMkW!>DB(pQ9CuX>W_>}pz?1#?JO5{LL>44SN06Sa+09mxcqPDP7j zkBQ6e*ppXz5IApzpKk3c4f3Bp{af~Edn}x6!&}puJ7Oe+wuHw?MqWT-M{PI zT%Hk_8;Nb82Lq_KJMpLf=lwr_UcM|Gtw-EO9c{aCb+e5F(r9_kfFLUhTx@$|S;Mjo zkherz- zqmJ+5NCP9D-?XrRidv@B6OJ3_DKNWH-uh%LRSsu+JMi>^QAAldPh+B>!V<= zu)<)sPsCu-8zJh0o+L>*qmf>J71e5}zHzsBoSfflXx~@UrlfupHyLS|g2F7Nt^ID1 zF(*~fVFu@Zl!~{UlXJ$n{M&zN=21~2#jdkEL=Io8WbLhj=*=3ED=e0UT8;f(cdLwb z?v`2)&)KpH^E%bLg)PR8vIN}U@qVKuXVTVy9}SzcVbHF0pd>BdLr>Fv;~{z*8s}F3 zX;vd7U%w20ie&gKXhC|I>LXFDD39<5#)lLWA0DhXJHS-*0vT=V)Z0qEH(Y>|Jk z92dxM<*qbaUM$Q&PihZZ$QOAdxPBCEY^Dh~ZvjUfm&efp3n=+ua^mv?F!_@cb!91v zP$2>99jM4qoYC9fe5`zr|H}6%+a!(Kyf1;Sf{;~bVs+IIaN5ds>yYxd`Yho+^PN!# z|FFMBrf{3+7k@gNERYokZu%E27V}+3`z;ynTEMg4+6yxB@+i~y4%eMDcc2aoqDV)@iN@6cx3+&~SGyvLl4njaUvQXy5&`8#bFd{4_oU7b9=$I>;8Li%$lP`VF7m zf)nVKUMyny9}q1^Qa`k4({5K>a?5<7`yQ!>_mqys562!cAL#pVW~C)X0ez+@$@pq_ z-s0Zguox}z+fWG`YF+)90$~{o+`#@S8QEmi3D4z?2-`^>FIOrh#Y?U_5ZY7jiH^F5 z#KUx1irSO(oLE~BpZkz9EgC-MiAY){2ea14RpW80(_r%--$YJ*)Hb7XeL1>ET7~bm zBgN9sLdTA+cc19#+MW`w)+wC-E&l=uaHa7fuG)t5t zXw&ZHbHrWK7Ej7Luh3v4XgGyrKHcmlc*{3q(^5J4EEee99d9$nhyC7Fwf$o4>z8%o z=9<(oe(mtPVx|4Xk0+s(ljl-J1`67B`ub=Tg?S@tUVhFc+_kN??S5G6wv!2?%E!A3 zIaehbW5rW?3q5oejC_`f4&{}<<4_wN3$m*5{HaVG7v`|U$xAvr{CH}eIElA0q_#MF zSj`}xz9Uff$Vk{g%#tWPzV}F*i6C{5Ia)tcw8b>p&R5Pt4S*=+Y~1-$6=+|*w6%%u zty3Voti0bsGWhJL%zdB!<>Ux|IssyD53uZH*KcIqVd_xW$a!4M0qFwz;t!kHIlu*S zGc1sBPhB5D5+o%Tt_I6ULu?hbX1d+C^Tx<;WF+m4^VIN9`LC}Y_hrRt$wL&VxKbE4 zX&SSGzmNt4Yv?vGafKOtT6JH4x@y7()|qkNy*HudIyGCyPrJr1$k*6dtb>J%@Gu+= zNlC1#m{1>SM`Bem2>C-K7vidZU@(>%%wHa+{C-IY3R*4&ykO)J1|Ldy^eGdur=&1B zgIkSq5_JZ@<1avV`*qb&1^z2W0hihVg<4(>+u2-P5C^pMIZi!@nLt;+6JBaraa5Cs zBqwr~>^rHSh+O=XQvTAVm3)gPdGoAt(XgEp8+O#4csMelx$)Q$Fen{n(bU9J)`q8! zVy7??uxG@YB9a2O(cgj*x??kA5<2>lJb8xA;1f}wXAP2&W=I0yI~N0cYOwuBf);VH zza?7W6l(nEuw3hYa|-fM#CE}MFOAF6;6E)UM;6DGm397iNk z1({k~RWI;E)^C0-o?l)vwg*XX^u-*m@~AB>FO!{2Sh1VvtS%t@T$+66!+c|AO*%3- zR=#_8k6cf&D$4fdD)Z|grZdC(jK~cC#L~=9>){FX@%Fa!HvVz34>^n5t!Sk-rO9lC zwo;`Mnzg0A?j;s61&FXXJ>E_6P{m*Fk41UL;@5j`6tx`L3GISyY64D189=)B*gJm1g%lc1oQavJv+y0!^KA@()p>#r{VuxjR2b)+o!luHYB3`Aq zu!`k=J81oA=KmjM9|1m@*)tIEphe*A?X5P0AuYcW6d^o99V_Z>9uyy#nE8`pN>_@t zgG7W2CzmHuMgZ_TA=96v2ZBQGW{wGZnWT<^Rh|^xK4QrihnuP&@*TAa41E=6JR#{jT(Vnbv{g)1~qA`~SFK63J+xUz+nsLrFexLLhiFOGJp+ zA*6!fUJI6Eu<8N-faQQgr+S0x`HafC_-z7TR>Mn#cHdTlEahZY=tCqYJ#$>)6e!ET zPQy5qz&Gjke0LqhcRB!!nWNvKK5&wjoIe8zo!>Uux(U4r>fim(vUt`Y<@Efsd{$N# zB>Zi2jDJ^BE{_N;ELk8YyuJU>MWO$a{O zw?!pHh+E4=?i|YL+iN=M8803jaRkQD$^`-@&kcmBuuUfgCmRu*i$#MbS(-!MN zN3@9d3nE(>p-j_lXqxJ9{B6HTY-lw_z zxe^#HHJwx)wtpbqex7QaZvqpdo1Baomdn#umVU>iH4C=7j|xkfozsb(e=4SG>5oeL zKvo8y=JLUWNxyssjqRJ8*s_QkMI&2l5%X-?kLt%{)5fwHRCN zzKgX~{?Eu&ziLx`mjkcDNxH^hmKIHPySq3s5V0YjO{#_VolHvE+$=2*qjmB6RgZ@D zkf+mJ8Vuwtzp&YZ^HR%EOfSn+$g-IK$tK+rU(+Qv*+^1&ZK3I}bYFQ{wy!LfQ{UW5 zwT3=!Pn&*83hl9?bF*kQ@^)SHQ*Arj`_rlMN-(^8Nn^S=I!oBquEpBEX2F1zG{KSd zzd~e1_(iuOjZr&_dEwu5L=R!5%?5q3B^)i(jE~cQL$sG`#F75L6=rlYpjhe%0C=}m z&ANhTdMxRBE>-pW1Js;-)GVbC z?i7U=D`DBm`D!nbaXBIhmnp(q8ia`xb@J$P-Yt4UNimx9ze^3a4PrSDJB$s|YcEhW zF!7=LK0Vw5HFIwB7b1?nE8y1>2dQhMNjEMyT~cr&PuAlvF33*-*Pm`)`umr^{F3mk z&R^%UI|Tm4zln;-GL%$0^T?-c-IVE0%IFF|Dy6%mV}nO1ZYlT9G(OQP zA&{OT(-WAxK)R9m)3*3rg+AjKW?XLkL1@8gLY(hTCoBx3msU5tH@#5TIL{69UkS_?_RTrw~4raw9r?4r9W0*q;Eq(rP`I|#;8!A<(Mjey zkK_EzLsV&$eQ%@NuQlPKudYqrmqWnNtcT5Zx+RmqADt((wI}T~REafDI*g1OM;p!> z!I+_mo>wqX*cVI2Ydf~%o42x-#-@#=@OHXPdDQ;X>eI#@0oj7C7PP^VI5d{yDSqEwneQE7nH$G;2NZG;px>qd;SOW zXlN*e(F56C`mCw&KD84NUhLiV@_GriN9e!Kwnb7yPi2ESzmOBC1Z=z}e^mj<13;L4 zasf1w!R6P0x)O|*1#4)0H*ghJW7!zs2$_}b3frLwzPnU__xgxqB4pSK94%b(7u zo}Kqb((GD6pw-jk`g7JOu;(Qk1=)iaQNT5jkgLfeqT2AamlVxkScPpGe7OuW3->{c zV}?Lbx~V&)9~NL}-&i5UG(qXRdFg5AuJ~UJa?GM;Ws^lzy4h#t%#gtafSZ?W6DV;p@S<&cTV1E z9UAe7*)a_h_X?L_Dp)5@>s-`7Fy8Zvq+_V4n*`_b^0dY1Q%cq2aF6clXldh?0{nhQo60`L z3T9KyJ$rWSny*vt?i!Z}@a-3>55SW62VfzGj?tB|77Em1(z249D6g!K{!Q8dt zr`Ki2o*VDiie1-Ib3esd4F+wsWf2b8hurhEYF3N-X&SQT_^#T&@+CVh+4d@!pE8`jXDOX_l` zJ!U)Q;e>IQ@=>3WRG}hBZ>0Hxm@u4B-!cmUXSu4-0sWw;ze(O*i_x%jLaI4K7gxa% zkoJ5bWYb8T1n;ln${rRGnwRC@^EtXpc>^b!F#aaW{g^OUp z^ZZiOLAzvm_qRvTiB2dDLdnp}m}B{Rb_*Wo81zp6g3;Mu`YC>}uK^s1WwtZqb!Fe9 zn*O64F!Phd=7i*hLA$zbw}ErDaNL9qz5TlFueI0n_4CvEix}iO00aaWxePK`!~jn3 zR5ksc9%})0zxW~rXb}JY#O=_*Dym&9-;l*;LV*U6$@dNNjl^)Je_MDL1Tnp26JZkiA$0wg(6;lR>9z_mYo!Teko zqJq5o48Bo$uk%4hdn7yBk!q_WV!|@WmoeMnP-RZG-N?;?Mu+7E!E)=R=(9QtRdV8` zB#!U*_f0k^>H0FF|7Ny6t$F%&&a7eQc)e@n>uBCx=F^J!FHND5Im`D>$3pMF`~sUX z20?nmzblCYJFaPxQ~&*X(mH#JFg9pq)|9uE2=#l3b59d0Wz0~-yx_%7{;X`@^_~Tj zAtxLoneV6#oW00BC4CMT+#WUK@AL|7X5T#uYdr1K2!36j%sO2sI|}Wyh}Voxh^CEt z03l0$H=7ZLL|cSk7B()d^1mK&(a$j0M+j-d(YVTnLL%@~qcKsCA_VJmO;FH8m@s=# z%#|z#q&@!(me9{L5xkH>YT0xFw`{g)&AV)h7!iXpL^)1%0BI$NTV!3TX zJBk;W$+<#FQft&SmnPzwpcbroh2f(MNz7E{5kksRK_{L>zM%MO3Y`lPkpefl zLl;qP05v-oUL-lr$yug9JYu&~DrM5_!2zx3s$=A}Yg)y@i=gI+=?bNF>;}jr2>GYm zVoIiNjNy=$=p6FcF*t)atT#OKdAZP~ZE?xs+F>XqY$xU`4Q+YCO6fPwi1E1(*BI5} zMz4$mq9Whc>$3k>L%T*AHlRN}U#@Frne8$pZ+v&yF8@Aas^Jy?js0v4zgE?~!lv!8 zhHa~6TSciG^ZUxei`B>5KWco->J?b{nzNm5yeST(*`#USVsES$>)V#EZioHE7ni2= zDw4j&$y#Z*9Fp`3P6b%KC-DH>;{CB>A^bLu&#B9w3E%45HE|fWypxQia=@iUNwx!B z#M~ixaW4P#dMued)+~xi6DTcyccRK*{K|N6PN8`(JHx@7Q~yZ#q(hgHvTeC>^sw;) zv+}Sk8Cjvh^!>cnz}|lcNrd#@MmvV(w^=-9H44*h9c&z|S+s_*MOyxkrK<|dvTN3a zAR*n|-7Vc65-%X#-QA#sG)PN{ba%H%cY}a*NGlx@d-47I#1oF>;#o6u=W#z?s^bA0 zg!9hcE#YYuZ{qNTK#lmY9J0)LF0192%Ag&kyT6cn-Fd_BoYNVnq%ByNZY{nwkx!)3 z@njZ$Ec(zZYA@^cL**7KYgml3pPrg;)jesnO^OOuK@2n2Yy$_rl#xG&>=Ns0`%Dk+ z4bji1zkZzv6Vy}-zw^-LAR#?wu^3MR&bX$yf@=L0iXN=4|Q!`DsVkJtB0@f8Wps%T8 z%sajV8iL6j(dT3hm7c!deHOZn6=WIjSbJ^kn=s3VxhVy^mu(NzLSKOm(q+DkQ+?njv5uBb+7_JT#)2$ zMbQ!P!VdWC;?&a6X)R%XrkaSECOO1Qfi``Ks<~8=)JQ#lETD8nOFAEcg+r?rqEGVZ6g&!Z%Pzj_#T)w^b+i~A5GnL0mYg)9{1M{tce27xWZBHrn1K6Km z`XkyGdrm=fBS<;MZ&bjYo~|+L`PJ%nmSo(Py6m_U;o;TQQ0X2iS}4&YrwCh-&l2nC zGA?}kU9x!cYf5E-U3ytar$GHy*%sSZxz3qn7O%zSOs4C5WB$r|eCCDwr~`YqHlA!7 zh6SWX_t6N*J6juvov1jSR)%dEl_9<}{>)L@b*)r?($6X=IEuheIs-z>CDKj?E&RSF zfWpFpTdsi&0mry8kVdf!74_8(FFV{=R|@$o@|}P1=u1Cu?VPCZScIBzZ-%bE+AoL8 zUjh~S&tkJl?>c4@71=WQEKkS2=9;eGkL$f|#({@dkPI1q4SC{w`!>13XE&os<&QS2 z)+kQ4DPy(+<6_;)eKZ@(!qyv{@+IB2jNvq2KS2=OSm;+u8^lqpWxe1(H`1@qxP6Qk zgU=gyf63n|jCEub&Uoh1q^_vR71Ur9elJ+_-^tJOwl=Qt&5?d5SalRy>MO-4M|@pT zsPQSEWv<1SM7mK!p@arb3eXq{#BT8Gp}r0kBrJr?e6dSjKZ0qBhFgQVM2F!c5$61s z%;+)lW2QNSg=^$f6cQpxvvs4%4@1TSxduHl1X{6aX}`zPspj*BIzUHtwE7KDMSLb+ zE(}!F{yImO{HgJSSiY=S{_!y`z3)s8j1Nfl8u>HRj4E$JuDa<(mxP3PM$eK_Vkoml z9pz}F#1CC|FuoZ1H zH`n)VU(GP!N;9^C;k#Pniot0=dfo}GPPFC4U^u~86WxhbK54Wq(WLJZCZ&@${o1q% zLg_ZtVdn^Qf;&ARjwfm{ts?TFYkRV=H&}RI3LdtTir>0F^!tpd4SHR^8BMG2A5&$_ zHu~!OyKd{7Hv9-^zR)BTwyI z{Y_t(2HnK`q290rtrbqRq%=l#vRyTcPDL!1k2dP*&yP)o%Jg3;$#2y^k`(rAH42-_ z>S!EU*jSEzaRJHeOZIubFZtHC{gFw&vNv&`RqT;6H5$0z9Py>*_@2-2={uwm7`Rzo z;WG8}5b@qP*^?6g4bqLz{n(S+704o2sIP#QvJvv8901q5x}_PXMD*3V?FZw0+V)4) zTDGl_rkObi318qG$e>L`Q|9Dp=URs_;bA%VBr8k4Z2vn<qgJ^|aNe+*>fkSZ~=N?b6r8Y9lk_~!VIHQ-TG}eJ62s5ui4g=AJ zzgND3n3^x039Gb+@wGlubacMdui06uB&1*^><98F^eA_kQrY^L?f(8a+iXtWz&|naWTr%*(`d*oDwLrBr z2z;uv84@t_i52R(jNau3YAkuKP#zLXfDnY0ihQL;8THCdk^wJ3jK>cVT^g(FDIf-c+?-={V>{1 zZPg!z1I!xi!}@Cg)}4o_^PZ#1dBi7x5f(^xVJ{kT>wAH*AvPEIucu`o?U5N#7gN??uVJK`Qdt>8FB@w6hjo3^e%Vl-cOAwZ3sT{^n^S2Kw%jy?$#_QoYDU2l zFzYXF%8xVOgun-=i&dQ`ivc}*LQJI=itnH(7DnTy#EjCtznk$MjurbD!{pyD%RNi~ zB2%44hNdZiKr}Fzn#xMs)j4lg{reLn#+w-gQbx2Zbqy71vbR9!i0dWAU_r*c+mZxp z_G+rGN6=xZ5w;_1@q!m_eTuCfL-kdOMOhX4ZZh%b2RYMk8D%?+>1yelRJ;xD%;O|e zt%DRvH-AoubE+*e5}zbfYuGf>?JfI9Zdlq-XqUBEL<&rb5%wqhRL4C0Ccas0rA;k; zhH;!u2OTOA$b0dDmsGMgBgyjlzB2By_AK0b(G(6+6zds`jUA5@88l8E8bbv#ULG+d ztE>DK7mu1uYesrHjV80H4k0V><(W;iM)M-QM`lQZ0jCVqb@@uMUGSH8#}r@Qb?CyUq$4$l}9{r z<)ca<5|sd0<&&@`pKnd9kn6CTLZpb%Evli_p!AEmkvL16zj0U$a@6@ejz1$G4_V^Y z(o+yfEg(n8nhmY1NoVsx69^RziMTe;F}#*fa2){!MZ8XH%zVSsiR~ldMxP231Uc2_ z;C1lh|FscyFw=G?k=JHWPE(adBsR*P)0hSz4y${1I>)8Pic{eR5tHA$FyfCzqcNJBfOz8GZ|$zXGerX0I2kawWYmk|ye{jY zH{P7|!F;3~mwStj;tgTwBpF7+L_A%$C9Muiuv?C(pAb;QcyV@($##;|(qhtUq31^1 zF~!fZU+W>vC)d+rmPZMJIHNw-&pwbZiq&7{s04<^XI}jZoRxC@4YpNCE5jCN2!Yvf1*+iY0SZR#jo(%d9Am<;|OX<*ZIcTF!osi~We>!YK0Uphf;G;sL+Q{^up+O)@Vz~B{{ zo<%T&9ZG=a9wFkjkC=oU(|_Wi65B^VL7JX&=i%XDGwL!u+e-6z3p6KBr9X2o@Wzxa z7#Ufo?c zIv~q3FWa4q?D}q(@n4d~y_X#T{VB0yp6qbzo-=Qj0-Lh5kDE6|0Z;^XcB8(&1()yk z8YWFhIsbnBMz1dIji|al!}4u!7Zmt}Q&!qzYD0c^Czs2wq1^ej*UqF}&4z;NiOoqR zAlPJ2w7ifO807JMkCF*sAc6Nv4r@X+4tCE?UAN2yO^&^(l>ySL0}GX~Oj=cbLHz@< znXkvo=8rcUV7cqs11|Tg3L=%Q;J&3Y7M8Wzwk{2f?ZBIlOy|?S%VKxvi%5{57#kL8 z{5c$N_VzK8`F;>tQ15g0Un04t>(@|eXffw$^(R?=G5&-E#n8i%w@`%1V&CK50^M5p z=laLZ5M1h?5*Sj3pQ*_4gJI;~9%@p{G?^f`QPbn)(<=grbFqEZSbN;)S2fNQZl^*D z)6EE^56e!thzj2fH>t?(B8XZen-{vplsdx|ZHtDw9X}pUfhfY?ht-gh$2Ck!s&L_- z?(hxt2AtW!X8=tbKzSedeBIp5((R|1kzC2%Qe^|@{L&12+*5HFx;TLTgJJ$Lf+|kc z!(9Rx`|1-tK?wOvuPUQ>GS+o_F(=g<_WmKE2qDD-5)VM=6FIh@@P-X$uSgS{3Pg}` zMSdb2z&PVbpr@@3C;0mw#%Y@)w3ou)r|gMt7s0*Pl3%}7-JPIRUfm@&s)WHD3EO55 z#xq02YJwOwj)*S~8LS!Ehk;<}L?YzP?t?`W`Yw(o?8@I^_WmL84CE4!e-Z@^SWayR zv`#o3RaLABJ8(Ak#w@Rg#bXBG!q^HDV6D&;w>bQ{P4lNqwBPQ6V-HZE$i*~`uNc$M zi;ywi6K;DU%<)IdsW6k-fKS9*irNH(Z5FGL{Vg|o9KqeKyAJ*b!lD{cBLyhVhe$OJ zcZCiz8R`<4Q53x$CZVLnuTvW%_S8{oi7h#JvSJ6{_n{Lxjn_3ETg4*B#zEP9_tDPO zbY#I$?Y?pY;$L_B`uplq>Kw}+eq?ggAwUnKEnccF&!;?a{~e|~xuN5h?l&#X&v$#c zby>M@`U(4|qrF0q%hluG$dMagN4CzwSBK$(PnhktVHt;+hwqAQ4(b@c_t5aV8=}WbXEbsJh>dL&uFmE<*DnOf-t2du??s2x-LEJ#p*SZmoM6% zt_!ICTIlwfT~H|89rs$OTy1a|Umj=Dc35gFtn*Q<4XWW)t++%><#S@XMp^hYa&Sd- zzfiSaSJ>SWcrn!$8xZEN$C~L+U`MN$$zE&q5IQ~c=_D7f_B9j8oQ-ZA!AUf_|N1s? z@785jP*5PdduM7+^tPl}AoIFe{fLa=*k0W8htqcxUKyFVdK79$nqNI}QS^oIy>UX~ zHdD||Cw~q(o6X3?LI$x9@;TtGtPz_?4u-SP8t}2i$NWx+kH*x7^2@YNapMs)Q%7)6%j8HLyk z-k3-#Gw&(;xnhu_<`8{ea)Z@!0{@1P$t4qp^=-9{t9Q3&xWf2=RzyjWe<{LL6vxFA z+aNqKbe8dRzHezAJup~P7@6gEZ9(jnHvJkfMq*&F3Io8bT7*EuzsnZTq`^WOD=HTw z%$OP)M8|xRn1U`xh&k;U@(J{`JsrkeMCn~?T+VDZ6y(!v-op*K(}!RD9--4)0y z$k{SP;J63M;?4N8^ciw)|!`u%|YL^M()zBIE6J0&jcC7_*Lh&{Yt#1JA&T zq<+i1e>h*x($LC`2up}8&S|x|&pn{~nn)@wKa%<{2&nHqt{a7DX&kej#oxbBshl#+ zBi@XZju>K?9lA%e=lJj=ilpRqp$f~N6Owj|(LJE?I035DISh;XRsd4O6V7Kl zDdIF2-oxJy#Ngjd3^iAe>DM;3ad3T+w}>utDqHwk#Z#PQ^(bw}!b1)JYH#-LK`i&& z(Zked?k_&dWJxTKSG*vN!SdnZfW<^ zQ8#X?B3tKNnE3v!D}Z)W6f9Pb0qggB=v~mg29u!cPRVuLuh2-da1@J)|^JwL^U)S>jZiDxW_(*^Us!`=ka@ncd_a0Cc%1X@WI*m0)m3O3Z`)U z=OPzEGbKV&_R#t_VvV-HuZzgXzY1rvRzq~)zE}Je-oiqlj4iu00sIhXr5&yp!`V3o zBV%LlwFpROwzXj2rv6CD+Y3FsF9lt_aZDiuQ5|32hwamHav5PLroRRi32}so&&PmU z0@5H`5U8Y>%B<$-)2CBUNlX0-ee21gZHodMLXRKy2xOgb3(UJZ2F>bP8l6%YCRA#W z=zdykNX{m5#An}9g%)YtWV3Vagv>HdBz zAP-jfN1IZPfX_0->pn7sq6gX5>VS+ojl1~Jae}x zyp4C_1^i)V%VVt1z%GWosI4(dG#_<5=xZU<)QvJAdXp=y?3{aIxdAlgSzQD>)LYsDZn^p)bXL zFh`XR`H>DvP!y{EjX6jPdOe zXVVQqtaic%p%e7OGpaeU26Ekiv>)cFKwmJ-TV5>5 z1gOM6EU*aX*Pw*&BBk0tEVC&}k2aQg@pXxLQ3;ke0!0-1Z0y;P_(_4fGq>ka2wSEuC@3dOqx{N@@P@`Q;;Ojz&pxK!F{Ir&>1l%X8)RvXo?iHKfKh1`f* zKfANG1A+K)<9Z;M)%Ys#AX$xPHCo3D)4ogpwXh~)e;c90Wm&-4dIcsEtq~F*_mt?= z!Ze5Fua>V>YDWvz6#l<%zuL^w?OrUImWr~fPUv7B&Z*LBkaBd`O*{UZ%&7hL*{NP8 z74p-}r4o+%uc+sLg3pth?XRf%BChk!PM@vK`AT2Y*g{diB|_H_>#$|#rWcfO=0(L6 zdw7iG;Qc&c28-Es|Iu7ic!_pBha&Q&6znuY>g8^(Qi%A{nZo3gn>zHxwdyEaJ$wlp zQ(?0tw}6tc)hSY7Ne;Qh(D8wJ%Zn( z#1ck|k55&9uHZQlXh1@=Je5islwdHt%F`B4d1o`{{OhGqw>nPBPpTiBDBrLW z4fB0XXnQWLv18OLS6VwBMvb0khVTeihhj4lUpji0?W)6^l~1`0vS+jDg;>{-SP&~H z`E`>@3`x_&)1lV_4>fY`fh_1A_-;UT&pJ4JgM0yW^-{rdSj))Ng!Dm13(pi6FDCVS zB6N}OPTYA1ShMP&S3qx3FzK^n`oOI)EJto!*w!10Z~{Vc%f8^cK81c+1^uaUg!X8* z5FBq~%1;BNMS0M*K2w{)pTZ5PHnD55R0xgOg+LQGDFwF-TEWEp(NdDuYf-AmD0%{y zFO_Q&YdmizegB}xhim-am}0}& z#|jywB&72>o&E?z2J$GDnkM?prAheT`#|>C5Pd1BLYZVQK{w&p4XCcZ^hZ)Sl%QM& zzrQ`<5tD#qr|LA&UX)W*C1!k=GtXu3E!)ToDZP$Xo%y0UTdq~5cfa5_y5`qhI(0c6 zALzX(-7fri%vH^%!^sT+sNdJBQ`5%@S2zzDF)oJ$OZPi3Q%m%(J>-ES&xbcVA zLEq!tr#^pr63l`YN8`m3-<~eVhgN`1wCR4m&zXOa&{e3WV*|998s~*_>AEa)K0{wz zJ|>A#oZS_V6;iizxy)+n5uTTPRIQJ#YPHS0-U5HApYvtsyA9OTBvWJvWb&ioSR4v;ZTu1U$RshDc74jcWqyfHUdKP;P%f2kuR7q;7tQgUj zr)-+bvR!bL=eU;0Cu;HtL=mXvmaA#sTBi#1$$9AdNV@BE@8?Ccwrs$lpe(v0g7eM5 zzfU?rF3~LaN+##FkIr++0<%(R{Q{x+7@bsoJDO5v{Hlu{24(A8t3opDk%sZ0!2qZG)m}#nd zIIS0tgYht)tgh9;f~3u@4poJ& zqHDl!3j-?$;vCTdLZg2BeD{N-w#k*vCflYx*C!h}|rt7+7fAk1!HVNuZP$u;{#((gUk zSL=G;1w>Ye7iGDbYoTcNbWzKjWR22a zZH<|!9oP2*9(wVD*F%q}KZC~Gu0%U8t(-cZ?un|qDN^(OWa5uc!J;4NJl?1+dex`l z)K%-g)IJ(7db*E6CEM9{+o+A#Ef8=x_bza2@_Oa@JKoozvvjMkfkAgOU#F?|#xrMm zT)l&yn{>;P+4eg)0|G)CA^b@swl)kgr|C7nPs6$SXo3CLX^0yWhA_To3g66h8%G6OL3p6z z{{4fNZXkVeua2DxroRA3llP8(dK&uJ=aQ+YD$G1IRm8cJ>-#^7 z3MMb^;7CwF-~9?NXrSQ&OBwZ>V(cvi(yx+mIiU#t*aOpd{56*x7ns`b5g=kR>SswZ4DA__48DwOTDG;deG#^qp{@rpbR$Mm z$}!|$h_dO^V@$YWK?}{`k|zl2Evq<_N3@X%!~iM{KSTxtLK65vQ#C0$<{XBt{K#6{ zhQ4CQWpenWUJ2AZI|2?3!UdTVt71;9ZqnT6dPOy7%r47u!b5xbh|@vl)J$s&55zYc zY5J}eU>%mUYcXB{T-+qm&<>iq7#R>2Yd-N){=_k z#z2#OW>G9rb5%BCmyD8ny0)sIp1dP{qa56WZ%3s+jvl*>s=ha*3L8fN*uI_1TnxT)$ zaGg!PrIGWR?CU1f)qp{RccNF`xh<E2(SK`PZvXP8_Wd=SCfXu?Y#0)N8U|Yw+of z(W!51m!%D|b-cJo7QL<|;Ia~Wen8eX^0=DuT4O~;QO@D;`4PI7x}emkrKI8@pj~e1 z=3@sT*k_9+<}exAF(`VMIV%2oVrD*#?cCNi;&3PjhWfWT-SI0w!Xf1ug%HZlk*7q$ zwhr8C%1-zVM5ND|hZmS7$co?2YzLcxTk$*5OmIC1#~Sz|5>!hhD5g zz!sVoMI#8ykm-50Nuu`V#cI!NWcG#2Y64u<$6ZwvpJx%Vn^nz4TQnHe#HeWI=+%YN z2;yY}G;21QP2y>4(6dlhgl6nyH|O?MPjE)(b^G7nKFu8pD7&7oH5|oqd@rF8H zqXnx%05!4ZKdJ!bdDHQUXp2y_%4lbRM6L-Bu~d7l^a|aMamX{HnOj%fPjZFvE$J02 zFTTRtA*$5BB>mGN`(F7V1)SrDVI2#BSu|3H*a^5@*Or|=P;K>E=6SzHgH zH|W<6vRAqo$ z>+hA0=N$irNWa##k?+(AFtf4nVMrP+$beT2ku0qYv-PW*DS{jUE1Co$LDf_SWT8-Y$G4|H>R3@((jCHu#%duo1vtQds7~|8WkbL zyJCpEl_JYgJC0skY0&=E^^es1tUoOrg(zW?2Qfyj!HfHMW?9Oi7)^>lmgB%Y`TE(! zO8I(#orj+1ty(zgig4M{Sut75bB~^&KxSKbtTiL|O4TnfvW<2s@)NSNuQj&If1yxGSFqHq02-9XxJP$AKXXk)i32GYo zY?MCeR7dicFf!8vVga;sm5@RH(#d})rN5zyi`Lul#7gA5Vk zH!W0fj*u#ITa?hY{rMLT7C}CUR@Z6nf8egm@Q5ckqmta{^F-)4G$~5B*Bc{>6PPig1eYU{G(~`!> z^ES)Bug`g`Xnv!*ylTBkdrm{G8VjOF{I;dsXK4m?=|8%59`+xDa3N{aeliSpCiNOw zK1+-D7r81I2Ibh#p|Wn@*~31T6vWK^shg&Ox^n^X(BKag1u5xNw;`FiTJ=|IDsD9>%93H6WoD1C_X6=4(O;P$B zySC;!%EHK9NV~<|zn`#6j4eO&YL*fCo9{4h`8SpNK2wfQY!ZD!&~)hCc@_+6a>nqX zi+y$MO-Q7TeN6WB8D-#&)t=l`h>b=1Fl4DGhlqCf!!fEAH{ttFONi>o7lbh7bHF?) zFfkOo042Pg(Hr(lbzvb{l!NX?pFA~_*c>mAT4`zwhCzZtfIDd$I((MCzEJUL0 z-ph3{6d^Mpd&vFRGGFzdt^C6rP+sk%w-}M|@1%YmtP;N#763A>)ln@fcx!%=E~t1@ zHB$XY4uz>;eyzt;K-0aWuCT|xyEd6oGf^}|J@ZTUR0FN3>3B_mz>SFcAw_YUp&4@-dhN3K?a)0CHd*m8nO9V11w8k>}IGgbMaaikZbOwp0D|h z4#bj(LVod2Bto2hk%>L1p5Xg{Kkt>*c5MPu2tImsljxj@ z>`0vVSXuP1s%CL3Lu{uM$wCO;u7=GcxEvr-g^FbsW9;AQTd6={Q93426n5P@JzqQ7 z{sc&Nk#V(t>v=WE*|9Lh>6g~<5a*B%k?7K?`jmlIIL)KhG#^)T+1c5-CCRK(2=Uaw zu*ic&eJl2;dJBqwwFp$>zKRBQm9(K9zydGq+sf~tS7HSIIuobpoc@8b??eY#{TZj5 zu^gApu;MF&&@Y#}+2B65+6*}K{HI7sSy@?UOhxRxm@!$01prZwx_mFdVbVfKpwaSO zBAZ{GN&2QUEnK6_x%;he+#7eGTB~LdJ6$`K&o#9Eo_GEXcvxp7r~19~Al0C-A;V!a zIRRZR8A&+xt+kO*S-!S`hvvgq+TxbI=^+qeWNn_?MDEGJFM;i)pYJ*WH`)WK-|qxK zUb0n7aOk?}f$|m2GR#T#vQ4anihaz0oCs_(y7Iu?@0>|0gT3aitIC((9I#ro0b07j zdV1KT2+z%){rivivJyX;RsWq7zacZ1)?e_E`Uh4wM-S)2i-u2>OR5f0HO@L>$^P+q z4v6nZU8w%$cP$_04PySwGS^EMI}N32kP?)(i~tf#+Q%3r zggG1=ktf)8vKa8yO3kNYy%`UIGvm!pt92Gfys^4}5@bm_kE)Q}31KAzQrufJg>a9ani44MvCjDU2$glWev6BR@lPe?t@c`(ckk1cC)k zV*l=4e2dMi>h|j*plGY^>@>Tr+0<)toY=G79*8Gh60Rtuxm)8JS1HV5MTH3Hg`-@h z4P0I_XSLgv>Ob_vgOs1Llzf@^s^s!=?J9!?=N^%Ne>CX1`L_W*RtX7ZJ+Rhk1_!gi zIqDE#!ER%n9-_ZpUB?j+GA_*Y19?WV3d!R9>emU#C=QAX=HDH(OB7V&{e661yMYcJ zuHV{BcS?_=YRtv~7*uYKM&qI=|3QMUDCG&n3#I`HuNf9?id$XqRcwo$56VJNYtkh$ zLV)JhOA4yv3_lA>#d2z!WB;2tB0PFL%HN26Z$)95G-)0p0}IW6g%nFdv@)7d=eH$l z`Exirn)0fh1=Jpp&N<=|tMiHlaX3v1Y@4uHPq<@n*L<#?H}038e~Fnrj*{F4Xix>? zzFbK!IqXP)dc3;AAGE-~uqVMs713;;$Uu>gjh`JA33s_AZW>8 ztlmu>orENT%c>ut5oy8FB-0a3I>bCsf)w?Uoc?pw2Vdrhz+jqte0d%87R!|M5n~+b z$&W)f9A*Q59YG4&T+vXjt^f;yv?YUDj1>hhC1y@yp{0Zh`+g$6(xnZA3pE#G{u2{n!a~*m@iXxG z{;)-g{*D=(UL0&(sZ6niUHwBG-85tqr0~u|I6eq^t$A8CYL!8ll4z9#b}$y_?V+Ha zFXg4gAybmT%dS^No9)7y<5b3t(|lRI-e%hSsWF|U^!h1otjPagn}msEm5p0hP3!0N zFO&8|7QB0$nMfy+Ct(g@r>>I~RjpXED%K->HWu)9yG8D~Pa4q$+J4PXcqmIb)qk+A zowJ0QHzTr#*-{0?b(sb`Dl6v+VousFPj&_~va@^P#E2Hw)bP1H&41UV?))}Mm#EBO zz#C21ZLDv!I4;?AD|$C!5#{yE<06r7jegN}DQmyUVXeXD8TQ7o#rXy#aBxwjDF!|@ z+RVyq3Ln=+vybuSGR76PVH7AtT1yM{3BCw}cDVzr<>iYI$rS~fLEe=DGA8*C zjZaTK)54uxR;QeSV{`UR{CANWk4Hm?c6jL*&6pcxg8#`Ut_jJY(sXu~fT(Ejz~d{4 zvHW1J6xyeab(dEO@!)EQ77$AR3$3>SJuF|{jiQ2{EH(w^7tGN`VDy@|d70F~`AJ=s z03-fk`UAbDcNhh=V#`{Yzd}2_VrE{|kZRpagi~Ih!g^?la9wu;rAvw7URgBR{Zu%+ z@odja(vB>#OK1V@QY(79Pf}6V_MlS6f)rx-;2(eDpog=Iy>X5HU2C6_6g7`<4RHxC zuVw}{?-qs)nM+_O%*l2wxAg^UfkcBi>-~ADdcndutA6z1grJ*pOqj;4g`V5e2Uaaw z#x_ziuoIoYkc}gGARU5XQ1+QV{qhuitH`*_-;gI?%o(CB)wA>kUu=jUd%9(>wAzi6 z7x=B`cE24lS{nf=q2k|qB!n&tQx=U_2m%#+uBydd9vsHI`VuNG;(}>w0sc2yenS-E z+Ogd8JY3dgL0>!D`=Lh@ zox=v3zA>t()@egYsFenK|6bkr;9w{c?AW;66X9YpF`bC&f> z939H8fr(JLF!pgp3rBFopni}Ie|~x;%jsP)XDfuFQgFjoz=2Lyn+^u}*pSQZ-xzXX zzL#og>969F&Z6e?6qwV^TiD^#OInXy_|w?5D|>_bhlIQrAEST(s7aGw;Zy_ zd39~S+JB5}3$QSZm3tg5wAKy%J1@ob0N8iA`K>0xgD*lNpkWnK^u~dx^+NwfxJ)e6 z`t2{fb)VlPJha4W-YJ0%0eYAyrAJhgXqBVLb`&$FWu)YBUr+C0P#>22 zN>-G8DA81p_s|9}ZC>KHu|Ya+mkVURamtU4`${RVUZiSETF5_|+$Q*CcegzrT+5%7 zRLn7vSCQ3TVpLuAz>1ds{N(p2fje2K-d92Ai0v;WfCxd`-alM+of z1rRv#4O&>BD0?UPsYPiPhledS9$gnzV4ob-7ZL-fuO@m>ko2~Y-Oe}W3)R;M7>l;L zVoM;s)v+_Uj5f5<2|Q2Ac>o5-s34eLm2(P6=I*qVo`ihOf&grJuZAa5?2*|bj4O0`|%N}iDk2waqcZbyXHgP=F!267}t<$fADHS3xo3BXD*ipm! z3MTnG)fWhRBJMbribGaF;oU6iVWxwDNsoPhSQy?WArhZFJ08Z?Hytg9axC$peDmIp ze{1bwMfMa%`zv(-0$lUG-IN7|N^nH(6PGsGEWH_-x*1%Rl`Ef6jMjx6YrG^Xy&$cA zb5r}LAJv3IgsEQ3p#1qmEb^1z^jrNwr~6S`9AfLi1s(ITEx~k#(@1e$|C7Rc)A$t{ ze4?n42O#(Re-k%cg!xQIcoUTy&r|Y8&;>P`N8H9{P{*XWp4-vvju_vROt@^z#_rpa z9Wot?%rv_4Y7AR2_3CnxjO*r@`k6T2C%XU~)t1qmx5@~lJrVi(`2l;tt!wKoK)+aZ z&IhJcZQS4eL8K!N0%DFmZT$YV42zGU+=_SH}DW`5-e@U$CcKdVZ%`%f@ij1~)lJEI?Na}#VkOiyA?YO-MkPSo0t4^r0&Vg{?&LN`w(Vs8!NcGo9CF4S~TOFgI9fx1?wD+M6t8kz7s zoRxF)34|#XpEzP<4^?kR zjbWxe7|Y^DcR`_%d#G(wUGd;n-IL@dU6S*uR7oo>Y8(BPr2JHn@st?5q=8kvHoY#T zW=>R17B_s$I#a4bMpKBUe>ZUH{Q;RDe7g4gRI+j0Q7nreWTKF|O7h$2wSQOp?=mTD zgTsa%0cq#?A?Mlc`gjScK){4j`T#(B&obwM~JyLMEc5PK(Io9p*&7(Zd$rG%v=` z7eH_u?wjHkYUQxP6CpyIQ!cAHb!R^~1VrF8w0jqau9fRHV=@fvAT_THwL?1+EKw{=w((c#<_*_9Ey!5>G-~3%VC+f0xs4J=WuQ zecG%IR#UH&R;$6P_QnaF_g`xDX2*QSFK$TuzON-+=kWXLYA^~{uq>{3-|gb%v|hIn z85y15uPCMsut9OiR0!-v zaBbL!Mw>B7KicKE}gC1U=oKY2Q_J$u}R<&#)Vf+L?oMQy`iXLnkDfoJ=KUW}5 zVzz|KxqTk`^7698|L4Y;Po&P9S>clRz(?3BdlJ3j_F2i&S_C|K_*a@?TE4B{Sd4k8 zbgVymGnU!$Y~q)wrawz~pE-3;_%gOT5rU>qppjqZ&8q}4iw~ug8a8HIT>8^;;$VZEk0NYhx)xCPRfz`_qV#!6O*=m;Gsm$@wkA0no)6^>54! z-$n$JTJ{nU6TMTYR{&vjbtz@;=3YLU9xwxOWJ~82UET8>t@~V5UJ)()Mp|kzseBB1tnR)W$VU@x+nHa~ zI8Z8ujP2R3G+o>Lw6DZrN=3nKX4Zde_p3!spzY(w$_8^T9Rs=6_f6w)4oZIt`0Krn z2t_`1r|{nfA{);Ftvim>(=@K>%)J3#P3aUQkD=cGLUTRCL4*X2879q2BGl`K z#Y#Cb-eg%QAyf(?^rigI;JP_;ZJ-rf4cH9B>xgRgfDJk_x)dAI&Z9ra57Q?qpl!Wp z3OqXqQ>Tvhfs^~$V1t#8U90Ng_867}?*C=HJZcw@{(xoXv0rpc?q}}x<~XVie}|Sy zNJyxsSWW%SMT;rZk#q~@Kn0uDl__JnW5=0HA|<%;~9Pm}<#4B2wFgNhr60FKL zoY66_43#c}c@bCK-|(h%#V#7!i1{e%9{Z@A#g#<7Bj%um#-47vbo`mBX_NPRuqv8t>8&Y9Eg;-%6qZ4tioC+_p&lGL6cqwQVRr|>B>O(oziBGboSi@DynO;f zuTMs614t4Tgp{%f)92?HnNN}}zA|)V`V8M2A-qYBwtt9O!;%#wt2?fLY%S*aos5GA zYIi;jxBGrZaZ=$Y9_iaNcn@A2JJA;iIR8&bF-m97|}z_I3P zFqUs=dzDUA4}DTd{+DN80@F%z_y!{7dsqI;cU0(VOfI{XR%Xo#(YU*Wu>qjmZ96LD zqa0jgOb;JqxjElSZj=cZJq-@dn|X=E>%PtcWJd>_Ddy%|dG=@{Y@eO%a+d8?3m$o2 z&f2ZysD2|n3pL6Iu&==lGxHfFy!_=TwKMoXZ{c-&1ALGExvx&Er%3K@hbNx>Jr$12 z>91CWU`hua9wy?&PKK4#_iQCN|L!J(s)A*-m)R4;f+ep&V?bW_nF1o@`ttofsT037 zOK3(m20@jybBsMI5p&N=68ES{ruOX>EAE`StJduIv-b!HUfi!B#NHbpFFD^c8RNLq z&DkJW$M`z&mtgrUcVa$(QQW`fx{#O)g-v0>RVcvD7@AFGkBo@K{|*h@c*3cLR);{D zNICJ6k{00jCvqNaI%9$q{lkIzkvsS&9C_|I!TzAQ=H*b&5E@U12?FU)>wsxf;?b53 z%aJJ?u3gw3jQ8sDR=^YZljkxQCw0mEF_I$d<<36?3jOr)8v7+qJBO9OtCSges~D`O zM~F%>tumeimi7Nf(^+su*)?oiLK>t&O1eQpkd%<_2I=lD5x5Ddp}V`g8$r5DkOrk2 zq`SU7&$r$`;9`w)U9Nneu zA6y-3g0kP;$o5Hl^Lb`rxxVj3W`DSWUfotB4LDp}|8M|I(~V>UFMH5;H1IS#yLiv) zv$IH$rTEM~j|%>VEvEOK=STIEPxtfDUb^+x^4@%S(!+D#rI46mHo63;_yr|QBVg8H zWsZ995z$ibRa={zy<8nMU1WVMrBt)LV?k7rpmx^C?ryFqLV_~0%sj5sjOtxcSYuDv zRX}xnt8wrBCv<7nczY{ZpUTAEewA;_bCoehnY}3Tp>~bd=Vx1CcubkN_jK}Poe%aG z>FH*pBGIkw3JL{*3AUwN%{TfF3TZrrG0jZa%am)OwQiPc{*TCA6Zocd)R-326HzF; zK1F$bvDYYn_VD^@B|mJup>`H=jv6)lBAu9+fM-5D-!abO2;kT8?%QImJSpcIeyaBS8p)lP8$36>8Go*jEZ_(zi>E*xjMA98MEens1z;dOEF2>Z|E}$ zMhv1M%yaEfN5s=+jUS;gULwW_#+S)A2=&Fqx$*iv9_O7%Up9{C@2K>bV%)MyDmeY1 z8(@Y{n!=z^JSK4x3L#NatSA-0FN`?Y9to$6TjFXItMvx0r{3qim-Z`5PXUx1bA>%Z z>DT=EcGFlsM<(x731$@%BcxOCxa9--+W-d-4BKD{jzIB{9aA8P6ut{At>2%lF%xOr zGV!Z7TyRm#X7+_Z(t{02`KWeIrl=~25B5uWO^_-fxm@Fi4Ph$T8SEwoe`YXs*h|2y zMUJsCEVA<@=rqbk6n;<+GSu>o$>)1M;XB7J80gYnl@!dJ^};J|wu!yG0-pyNmkUrU zk#QN|mf>P=uq1i=b`{0pi`6=Lx}D)zPhK&Mdwv_)(yYl-Jm3`5-}Xph?O+84F0fq} zG=>NF4*U{ek05d=g!_B;Z+U1v+@%&8Zftp8UKa_b7_!N`nI>7pavOUM9 zS)4}7VjWm@-xhs`X=9CyZRL(u$HA8m?b1dq8i0jq`XWy^6GgfEu=?`zxfdCBCA8Np zRQ^Wehsm;+xOfFQWSm)vh|9)k%4*7Y!GYS+hN)47QFAs34I?2K0qHE?bYD^*UG zd-e;xYjbmytqtka)ZA|_TU*VCm5Cs7ov7%*DrmyPI}GD+DCw(nb0_JHe7TIl$UT>VZ(he@Y0aXNJ=Ftmf}haT_r z=l*WjqOK*^!i5akH#Ro*410oM`;4oqi(9>!M{~I|8-+I6-_9btbJb*BY`kn_3pGdy zNnGJZX^w5Gp8wc=LssbB>?|sx#3U@`K z7chtm6oRQA-oqCc0`X>pb{K5@YV5a>knq7PmlC{Xvm7w*Yp=lF#5-j7U*64j)H zO^`Y!ntoHZFL#EDqU{5cB-`3d3!$_LT+HQSaAj6PyssD$-XWL;o0q2d2n+L;dGFS@ zVM<-@h@Dr(MD5yfyAck(Mj0|9GgEH?oR7{=Z(b8N$^D*z2?&CWca14Ei88&M+9Z_S zO-~39#m~zovqlC>m-2&xq~13?;%Iz@t@j<5Dt7)+eLhM{Tp!G#K~rl^gT7Sva;tdy z-S!+!EMv!tG>)R~x^SMLZbJ6~Z6<$-eyw-C+aL(?4|IkNb6LBGf^YFO*J(nY=0sQI z2=ps^+rM3W0^2zUZ{$oVOr8O+*ce12Q!26G;AOlk!oMU9;G)Cp<>fAeLdfc@fl2YQ zIX7{O;a$X>s99rVCxB~mtbtE(8qF%==krzd@>m+Ne00@@jlly^s&UDOIKw;mK3$(P zWk?s`YXStb+zxVrCFF02(4$c%3|YOa$1VHC=#seO*v4zwitjtU8ti&+T)|zGE#SS( zPy5M{y41`fEv&3C?A87+;T3q8_=o+B2bY58ksyG%Kq@HOCt~_5THsu&Jb*F<$Xhw# z(yYs%l;SxH2eeXQHX--+{2tMX)^aeC68%CQTXn zeq&F=oK6Qr*`Gf!k;?(v)ywD+_R72KkNnz$Yvn+EfV6Yhfb8JO-3@ zRsG6D9qoGUn5YTU*RuW2jOoe2b&bY4s-7M?xeUXI+paRbagUUiw95@nI%kO=H3eQq zrn~dDQYOr-6lf4BOo9Sy-$|Cx1*KPbM6}YH}R#uIFj_Ysw|CAkWpz--e2D# zy0)^*q1gPJ6_e~HkldhSE8Y6rGvoOZEBq&P)p<+t6*e6pjMYqSCeU`mblQF?Ae7`g zr&?j?TeC&f8-ddwPB~9&=E!NFp=mXf`Gz4xscdg35u{3Nl%Rwp&Efh~loxEIAvD91 zzja8+`MJu!Mek~k!bb#K=v1SWO(s9q7*k%2cHCK7{f|1SF&<~z5c0gS{o0;H*K0pQ zzX{O{k{kSu%7gD1Yb$h^#+UdxL&0*`_(ZcT{ra;vGLBnf3}ijj|Gdh-=h2I*6u|mL z>QlMJO57FZtE>mkh&6lj&R44083y!F6`*xRr@r+IL}Ko9P4;q#7Q9}73h9Lwa2IkP z%l?h51MNe&CA0`LuM4w87`y7L5dvOBK?0_kwAB=jAvfwSzCqEa6&vj z)a|vAB>6$esKdg5jdNWi@5CkeoEY*tGP@WlSxdZuR~%P&T=f``xP(7?e6o&ntW%Qu z)A<50{&>3pa9T3Xp(z#Gh)IpaHP~<9WnG{ty))l-Kgkbi?1NzH*UJkw6_r(!1@VKc z8J&%tVLDry?Xvnu6RdCY$&qxf8E*8qQV=Jw*3!g!9ATQZwx`GDg5ICj(?R3E2xE&6 z!kOutn6!(-Bkg1f_+S&XB|mhEJP#?2f&4nI(W~>>t3|sD8kmHx27tzr6eN3XFN7I> znAueNLk@*V3wZ3gXC=T?WVON5HwWA#JDBjdeL4 zDhNXP_A68FEgPy(FEtUG@-U@=*I`pJN2;jFBL~9+RW4lpcTRJf{hTb7{BRT*K@(~r zc9Ay%5c(~{0GDiOqpViiye>FO9_&2Vldw`O<>8ete?~>TxmjhjKgg>*!XfT+OsOd* zP%E+QipoJ{yxGu?2fmdAyCI)0Dfaat6%(MkGlXVH`SA|B%zv-6sK+Mk08fKL8_Vnj z9KU`5YOQn*NcFB!+T!XM%?udrB&&?abzCnU0!BYQvP`lywWkLVt_&l}sHWh!CWo{| zdi~=0w0oq?9ogj6#oK2;SZXDrh+l%wqCmNC<1^OZDKi77)jlnI?i8Ch3x=K;c|Y&Q z9hNk;6>B$oKwIndclL9__!guUW&Bl{{QOExh3g*xh=p7;X5G>lkBc>wt%SzZNv=B1 zC`(%PgSFu}P*X;KflAZ^x}N)muqE8#p?k5kGE@Hre~YkSGf2smTZ)0*OGFoZ)$W%@R=;(K1VFH!k zV2Fgg@7ir&Txgjp{*Qjf6yt15Qs$1vdZQGU9<_SJ&eMStwKFCK82A*0SdS$%ZFF|A zTI-d*2p+TZg5L^4PDd%yrI@)|8c5mmdM7?%#{s_vpc{N`~>2sR*)UlgrUPmqS zIXOE$_POEEb?`eaO{ZSWo%}3ux%p$xs@1aF6XZ3X-fTFLvG`*wv)S@S5QHZGuC)H( zkpm8n9-D9X_aIb4hr*UIE^^DU9irX^7eH~8&l333vo5Y>gSHlQ1}Af_nxgxY+r2{F z?QTjs8Em$R52~;>ZrSu|qp~b&YoNxJ&6G7JxKpKDF*dX}Y-Q3Jc-zb_*&QG2vB-}n z%A7xJYWSl|SLf-Jo_t$|@%>L{J0v)))YUEd8>f5fN7+rI&b6K%h|Hp|)o^Kt-7PTe zc?VkiNy!K}P8O z&bU9#MK!S6m}tD;w#QW^akEwaVn(Sc!6nhtU$IFMsXj#=bT;j;90hqC9hbT>{cdpt>?R|KczIVCImjJUed`q zV6c>6#w8{{tqiB9-_Q)1a}CMd4JjZs}sT!JGTGc~^QH}^_9k(2*LQkOk};vD|Qz#iaM?9b`jdzoh%QkXPo zC4_RFL~@gbyJtK%1b~mLz`Kph%BCgHr5AH{NFjwI9Sllq-=KARq~&<+&!5uhmAI{? zOb`f;x(r_K=X?4mHlu~~zx@PDk7DNC-(OQ>+F;o^FcEsu_P_?>F2HFhE&E>p)0sSb z+tZbn;dqHauMV$4tDS9rXk2SB^2#A<_jM-;Wo&~mcs8`g2@YP6hOk4doo}}<7fl}X z`i-`}(?%0~-)FP-9ODS8H}AL5yhiXB-K|_R1o83*`v0n)-I{UtmEi-U&7C6c*3Bz| zT)qO%4G24d0oOw?7qY>;j0UP*r@wkJ?5zG(B&p8kI@8{0G`bHe9aq`jr@DH6;d+vx zdGhAHk|=%jVZG7kx-jp#P)uuc+6WZANy+-BtSaHESXvA@%ShufT1jD#n!NmW z;l60M-XjkF4$Ek9=6QuhLs&u>0>q+e`!|+X3rE~|UR_MrAN?NK%{e_cRB{;veR}pL z6y8>If6$uPMNO1z(_m=Y`Q5AI5)|>A&wS&=8}Euh6nk{>zTIBvU9v35=I&W$ee}I97~UlLvGr9`-^qp31sm8d*p&uds4id19!Y_z=-ch(6!~ibsi^OU7r{~I!a6;Vth7y@d0Q0ef z{CTf9%!5fc;{SCh^Uh=2Lv|6BfHlHk<#R$}0`xAbj!J1F130YFbaP)|b6=->i!h@o z|C1ZZ^(szSXT zR^q}@-70LoW72@7<`^jmKhnD8C3i0M6i&-tBZ&|y+}-g#f4*LhJ9)RlB9 z`vIY=co{^QH+B(3e5~1KnUy(W2rSBH(XO^^2@S~B9FjBwLD^+x8s4V{-bkJf569VW5;6a zXBsAk7nO?gRAm`sn7_nk%II}=@e{;%$)A~PoIOCZaNz#@9$@*DG&SeJC8D_HAW;Z3 zgVUkeh(P`S67~J{v$S!Iaz}TRd*zCmo*BaaV|AVDM^DdeN>VrUYpD&4{qA6F!p{y3 zl+2@jD^~$eW#;3#6uDOe>;#g+;|9J&@WCyn=;k@l44;9M<%WHnM-|1h(fjV1E&lSu zkK?9vzXhoS!SxE`fJ|QyNPZe$eT$Z_D)7_JhuKj7f)%2Y`zym6Dc0K~ z#?`C6M&gR<_lFM+jrsLf=Lvs{c5GSH%MU)P{9}3k$d<>&RY8+nImc0$MoX1mzQ-{g zblt3B_uoO`*SU(tv{7z?(LxS~k>U3-Gb+4KCM@cuv@GERc}c@NBUh`f(K+(z+*ZkY zMUiBJ#*U6TDziN1W@5*>-0?2Y8N2Kzv?LyW;gaBY@}7=N1DRpIF6Yt7~g0tT`rK!i%~5PaxGeAo534l2Fpt4Oxh3wF!dhYuAn6QRq| zw8G9)Z{h3ZPtaZ$Q?0M`6tcOs6&DZ6kAh~%;J!BPZ*ix@3C9s6p2FgLE5)BFD*nlr z`58FnRfPNf!K z)2flw|IN>VdyNVBVn*@pHlYu`Pe-Ir1;>MK0Wdv&n~N;qNkEjCO+RaEA|bqm``3zx z`X3>TMPvj4d={WqVUhZM5@tX-g~F z3kRuwYXmUQ2sP+22o}Vssk>O|enX=(-IcHi&Xlg~#^H(Ev^H4KJWiai zW*m#1f`$Ftik0}03dVv#i?Yg8R~K4!sbZ8ywVz3kW-D^sTzR^0fy-}ZEuWZsS%k+l zUs;M_{*{=$eR(b{TH7i&S%p<=5b7%{XqZNL;CYP=HzwPP|2*W8Z%9)}@d}Kad@ayb z^))yc;R>cP>#xz~z}I3+#5=9bJ$ssD4H;VDnp*&i2K5TwpH5Mlr_XpSzroA>;TuUzpF5*)4HGs z*~uu;?zMad7L~nm&sPUx%;?A%(KuYK_mTSj2?%}pXJ7r`*&{*&J=8+i$2Nohi3s*{Xh}kDG(^dbA30EaGG?{3TT4V5;>r;o1=~SYY;?sw(jIiyDBNOG@hnrOm$1F17ji6;V`GHUB@!j2!q}Vy&bj-elA}`CaYohiXL7Q8T z&}^1PWB_|@?YoG;g)FP?teLrkUjQ@569)i}e)Y*q1W@l zpbJ7eAjH|td>hfw=-2oIIO?lD4|ZtAI=_+4jt{o#Nd|jFq*sRVgM(!%?Sg7I+a#`B zRZ<(&hm+$LofDfx?Zjl;1U2Q=l~g^WwYlfjWG&Kzg)XLlyl=mM9vDyaOS(6zzd!3u z*s@@9hZ!uxtBgaR%uO&+ElnuQZgsIx$oQbmSD_|z6nbHiM{E1Ls1ihWGKGAbYfT1d zI%N5@F{ckYS>j}tV1EQXG!Whq>tNW!BWntFAnIU>{DNz@Bkz1eF^AjssVhLxADV-> zg%kd-nC8c?Ps>i}uwtb$GAg^2`z81g47Ql8HEuz8y`TI$DJBi%GSxpIB*!Wxrztdw z>#@C>2!)M>sO@wQ?VN$@1v%-Rr$^WtryVeo| z*mqg1$-2N+65!bO9E<(NORvN{_@4X~26@qGVeQXXQE|+th<>o}ht6`n;>VuN*rqssX&}@%XC$LVn9JpbExa83#hR^rqIxct^>8O(ZkN*P`SJti#96kS9oMc|P1tPxl)}l?X#{IKBuBAQxSF5zD z0#DN7T)xq^H0iC(PdkCk>Y|Hb3&gV@sc$o#dDSP>9)2(qw|%U5`@{9BB-y|>2u4Hc z-7xAD+(cavh9XSyUJj9kt2i3YJC@iWL+?zwPe0Wk?qbyzw^q| zIFnqCef*KAHVxtVAdQ;mFLh`XHo$HoshG`fHdA8MhBR6^A4V3mXHD~`+0Jnw;)}~J z>mEtcBTlPraHE2maTyltkz@YnNrL4utFq3g$_rHETB1wx=j1gzNabc|=|2(EbQW~n z@Zl3etS$nTfR`5nuoZCU03W4G{?7KtDlQ>}wYx*oSsBaj(=NQ8y?AV^t%d+(IuC6d z|8;CN-h;u@fhK0LUK*UUKSLiMUD0Q1*B%=Fd5*#aYes4f2CA`=^m@|J4AD(sB$IHu z>7`PHvHw*$sO%9o*LA{V=iCI}c+OAYIMoRZl}*iq72HI-S6^KsiCM&=vF%WJt7Pf` z$rB=H#WejkS}o`_Qx%Jn%22qah-kRAjt$jJx`>ewrJgdEth|onhc&z_-T}NR*s|0H z_`^nHS1Hg_x5a~fnm9wgjJEQsHfvB5kRix915S?fZ?iXWJ!n5oP%nDQ+WbRH z=SEG~9Q%5>+F$L#n174-f{y9#iYkIcokSKZe3i95_FFV)@xH!>1nGN|Vvte|dyHaf zt5}d$eh+l-DXkpY(F=jBzwf!0#FO~}zN!etN6PSXgqT$TbL37}Pk%A4EA(&+Jzl*I zL18j(qkmf&tIzqV&5^U|*O?3ZV?idUXU-{v=Pc;BE{7JIFPb#e8=M^;9f{>;n(C7{ z^kNR-1SO-{i@^aOhC;zo~$6VKE-2IoyEKcg|YJxA~2Ea<(r$k%?4$FAJoirRc- zDTZk=m8}RKqKfGXNWh=MZLH`1Zp` zqKg8{BGvuJhti|piDPzmV@0-2jY;-Zh2e>6ymt{fX-tQo${N9dgYIFasq?-ygStJa z0sn9lpRBuCHt_bX(PCM0(5)|`MdJ8Ht>^o6buWs$!>(m|yPa51^~qi85f-POYJ%IN zWer}eF7}!*V|2c)jZfkVEm@pxhA~x*MU$ae$E7f8N6jlYLpE``tw2rUC6;yTe0yXh z5+KN~&&$xOEUfebH3ajQrQD0mVT&)!@~5S;)My`uQ$M$QyDxo^^jbPyXW0(BNGIu% z;bk9?W=RaB67-s5{lU7BALCH=LW$&cKzUGfJ~6Un=yntDTViX{7e)>%^=JHemyebR zu7@a}K?HdrmQLv$WVtLaDcP|ee~t-}Q@^$5Z^L<>=~h6e=8i9n?jTOR2ji^I{qKGJ zDJvHswVT@_#G3frZU3ay!J+4+_|p}GZIr)PZh2fYN6Y6tXIaDvZe%AZ%kKRVY$1~* zrFQXHTD59=P7hI1SwaMMWu}~z*b0Tm=$A90txpnZ5dTu>RsIj^xH<*BF*TfA^5HuC z23>}r*p!sH2dS_^h7ONHlC0_0XIQ%WGYCaPO}1d)0K|V$B3l17{2$x{SgqMt(@LWJ zWWNPDc!16?M;U`|J&^qKlE(jji%zKYOLq>V)D5Tx_6Q?&o|Yr}VdBnz6%7=PEsCN) z|E$?ZG1ir;rO^!kW*80Ccb&dZrQ6Kq>~jQ`k;mg6OT^%qTBT{rr1rRfoI^Rie?+L| zF9iasGn81rMXlf<#O?{q6fK>*CCPyxM|TxgY1W^YOwzSS;R` z&YcmMb%K>fAleEBI%de#d(iQyr6^2*OjJLJ{$TaaY8pI^JNT&H44c6i9cy;pt5?Pm z#z}`WsQntU&5Z250#Zg+9u&ODw#aN zd6WW?#L=&p0{{!g1Nkbcv%vxcVDwI9{{bv=X45#WT7%6|r^--BH)%5{=c`pykzW(@ zcRu_%flk7CVu^4oZ{1m5Nn`5#tT_e2V#yh<=j@l=m$%nofgu(;vd(39JtNmPJU3cE zHaSDKPkcKmYX9xia;%J^d?DW2^L_E_3CPQVdSyx}ev_F>p_yA-NJ}=5J_nWpqTXBh3x|FVW&fq=R?B+n3wu7fb)Vw`Mh&`m1nfPTJ?+ z@CZrhxtlf2$1*sqoE`Y$AFW5%40+W@EvD}#j^<)}IrJ(MlfYEr2p@N%E#G`xIfh1- zm)o(~{HJz%7a9|T8JX6t8(|dJ!-e=smok-cB}P5@S=Zwz4Gc5#JJy!5+z_(%ljk2_ z8+Je1>(fM#ls1#6Iy3xUwQz{$*;?y;^Xb;om4d5o@P5h5v1-vgsx`y$<>`$~#2Hmn zOL{D=SQC@qg4$feKPy=37#v|WxS==Vxs-qNekHb76)XLb%I9CRbA0ap|6)hQRn#bH zbl0MOt#OcNj>kecck`Gf)3VESHv2St3?&pDaD%;TFac{bUzG^?!%Smb|H}XNcx_?B zx)*$bifPBQg@l?sygh_r^~i=lj`S2MS%>uogZBT4bP!*n@5_yEGKyKe1X=sloKAJy z0ppccFvn|lUOTs##={930|VNJKnbdHOyXjC2z#Lu&sh$!vZFDZu`n*B(b=AQKsL=D zS`O1d&Ki8oD_0oMSBaxrTKX;zk5qucDKmtoq-}Z)eTj#SfK~GBAG#dD4{GK3<}e9J zJk*Zv5~z9l5*12*4D@+KiOUdlQnGs3KvcnooIxszbxpnD>p67#NQt64cp)~K$Gnf&QkDwRs+eT7t9sbiWrYa?#LSx4QZtC@j4@}1575hmMc}lrE3@^|> z+3k%?4*DduO9!4-oRf;k_y4LS=iRl$8W(qjHX}HdkO1e$YjgP*vXM$1??El4Op8Xf zzFjuIfi}uhhcYO9@g%d8+?US0?Yad;Ic)24LM zBX-09-0o2I!R+^<>omNk>b9tjeecdpM|8XUsNUoobr<>ZR2et=WV_OY^TN9QAWM<5 z*{uhm267C^a|aW~fNhn+^77*pljyXMz8aqlmg?N>TwIvS;}qqs7yX~ln<@ibcE`Z} zaU4SvJujCH+5;U-0M;Auuh2dZuqMVLc*1~$2(otz|5K^J~=XgkC zC>T=+cTHVU{I7R~h%oxZ&-8EVFSK5(JAWiFILq#cKy4HKcWEQ4-20dh&tT6q>HI{1 zXSXh;ea%BmrqW^M_)mjmaZlzxfG;HL>%DWDHp@>BdWSJo996}`C^r21vW&gTQ_XiB z)gVTThIAK&F12bxJLa}QD5^X(L9~Zo-M=Bn&+#`El5cOdN59$^2KuYZghy0UDp{oH zR&r}bnL{B)a&LR3A5_u->nc-}7mdLYi0 zr`V$~$!W}30UK?*AL4g=v{_vw2;LS0!P=`>NfCBW+-pnKUzNCIc@?PSVU9?A;)JK0 zrZr#o(5R?;FmA&sm`!=f&~_BkxsQ8L-wT}e;iT?n{RiUitt&4EFY_u^7?uJ zk$4Xar-zE%x{_PeC5IFIFg@FtV=9nRqp{hqv`pcm556YQ&5@rkviw5-G-mN>bB*nP z@ja+=9X=}Qid!bnp84S{*A+NrWl+9FnV|Dwq@rbm<=meuO|RU(x|sS1YRO%8qn<#} zcF{0!24#P%5#?tkG{qqlK>;W1;XC_*BGADp%y=44Xd|yd9Lct$osk zaNEiFT+gpgHljr0=pcYqc3s|VX#$S3k1^pamHW*aMfRN!iy>sb`ANzHoZDfUb4_;S ziSk#4zwazXtgkwG;O0$mWfN7tu_epPXL0-kWD-KoCjLyal0w`5g3@twlv$agY6r*V zxeXCSGGKd#L=kcMXTlONVSA-?W4b0d_&zKr>$!hhxi@}^F}cL2B*GlSq+)vw@!PH+ z44gu0wu1Yf^`1I(bO#y^ElitBntS&5F*!d;l&bh#m+`+R?S-q4arrZMGYbLneADL! z12enQ7bv8M#56q*UZ{_oi*K^aZH25c7ujhDc#yCZGD(4JwizfqVV_wCJ9J;pRa+gv zx*W&%6^rWSdk$vhBDUTN9&Sg-hmh5?@N9k(w;AQQp9n)b#^cWXuF5W|)abq$kvwiO zJdv-2P@*GpVFOQ!-~)?cZk5SJ-tbCX8ouhrtmh$&?jAOj5}4k@GY+J$tx#Yea9x{X z%2~$2^kG-uV^+fT;*w~Lv8xRCD?vQZ*Jb#F7#05^W-FEtQ}%UWi4p-(s~`55pGv;w zEd~1fz3l{3J2hv*$>Q*(9-#5|X=ysA-Q>>4!cot_Afw1e;oR@=&TH*#!DGQ^>n47Z4lu@SoCAcgsSpR5x>Ra)3d|#j>DyQROobL-Lsj{HKCg|VZC@Sy)hQe zzj~R&-uF-VK3c5S z?Iy5Vi{748lV~@)ErJ!xMwtjxxY5E=D5vCX^aEPG_g-zIYsfuIcPnr<#E|QoNw(Zn zRZ$J%9ga#C6wbWHw{5Gq{~IU>jhFb?ynX+GAUmx%j#1k5VHf`r4R4gD-A+D8u26%F zWa#5Ar~F-Ua>dW5Il5IJ3&WZ;Vs>Y(7vb}7rdC5=WPD;XXp$JtmDX@WmuuE5IW6Qr zJwgJsm(Pda^~)xrURA%Bot;iQ@PBr0oAaJaeV5ie+EbK7JtGFgnr^SRCShZ0@_4-Z zeEeIH?nR&3Q&Lt!lP!gCjJ!wvtIGpYdyq~YCaMvIRFa#ej+d8?gTthF_U!^Vj;<{7 zw#V3zkuV;pPcu9Y3u)S0*~=6*SHs@<3g1@Zw&OgjQD`jwYuG)~;~zFL;ViwxF87Kn zFtI_Xtu-q&K{N+W7c{%HJD!d>?+p$4Yz+7 ztkY(Z!k9@yLc1yu0tN?kOache$WxU<_~zXa$n857(G>i!cepUk(pAY?9TIe46sm8- zk=DHeAd4m+m_&D#n}Q@+K8z?Wr5Qq+(Ybkv;7;*rY*CTCA{@hvxi)8`{OB+<1YRda zWa6u_D-o!R98NH}Qjxsr`}C#7F&A6Bdin9=&ogu}f=eKAe3pdz$71XzY#)hb@tFuA zSRR)nQb@HDs_x#X#U&zWDCt4$dk~S(eTs3NO<)**1-|co4CdkhHj+7&LEt~2&9rUB z$=X^G|K-Ndw&aK4!KfyTK?jF5hZ66gwP0=k&fD-#a*gn{8A}m08<*GF?pRbXDTlF? zucprEFE9wKY)?xb`=Wj5d)^U|(vRi3f}K%M3{5RrZ!n@E1b&sEL17Rf%LUT`=ior& z0q$xYc?pdxyKcAXffdgtze_eQb|;}1xp8OtF>ur$d==&)|2|N^jqr2q^CkfE<4;0y zP{3wx-V3z(y7A6sJ5B6I`y+saYg912K`R{jTseOCH>*lpN0B1lMuE;~ociUtAZ}d! z_oAA6O@>X?cG_rb(%7l8i9~dIBGaYqUu_nRx!P`hGvSIE5Wv5L9$aVogC$L|H-j#r zX*FN*eN=i(%Z-_$^AExs4SnA70TP*4j;M1(iXaWP@y(s3CK$))g^ulL+Z zlK$7X!g~Q=(|`9C=$%)1%~pfDgm@m4TKU%%@r)CXn|Q`*FNCSh2$;YAg1R{Qew6bI zIXo0(nU2yU|0x8=Va(0GG~5FmCfiW%L~sV4kZQ3wEl2XBaDjqgpe{K(@2m6D3~YvI z`twa(_TiNwS90pFU%#fa?#m8V6+^EC7{fY`RmR}oE?<#Bedy&k;d$-u%6sa8CL{12 zAxO@|^35rsD;m0jpJg9rG(~auTij>~9^=oV5IX_dig&+SqcI53VM0*VZfS7iDq_bF zh{>pskaPbaiOT*8fSH;`;!4G|p?G!*ZGbmLP};5Z$g{x_+~^C2Z5Pd@!KEpB(G<>C zw_nIvizQKQAt#MDf%CX}I`K8&RUT6_`}*HQ_pJN=bYT(dcUlQ?u`Pb(Yc0qXihYEn zfDsx=P*@IUx_)(uId}9alJ=h|)8c-e3_>{(|8)CNaV=r7UP5xBz;=)Wv341|;x4O` z#MY8M0!u?H{l^Ra;RN8cu?hf7A)O$)NaixeF6snEf_x8kR{??)YDM>sVVi4()fQ2K6w9mb>j2MC;g2k_@^5rF4pTL+UPnyO3XGj$%d@ zV&LODpHqsd?|t|ineMyLAv`b+_+2!!W|>8M8HyKOlI&pi5=$>O-b?gu^t@WSS&goK z)RcUBkt4)ugTW4ga7`*kbJ4&$)zZ#brZ%%fBO->tTFoLSeu0X#CaK7>)4z8lO}itYhmRhq z9<{kXW$86+pt200B)8z!K9&!^dnxKy$q>ZbYi{-F6Huq55wTZ6cDLfSKmQhZL6K90 zA#&$IA~Q+pFo#BQ=oAvTOc5FM_2c37G{*WRVjpQv;*XRi3;B8(v$F2Lhxxz@u(1o0ShlpJax#8@njh+oNde6f$)H7mnnSLzr^H8^6d@Oyt zVMH_8IM=8SLhrGln1>eeYhq(+YS_{Dd2)#QrLi9vvAw?%2!ZtnE_I+roB(C=WwZjS z>C9U#9!I5Ag$E*`2BJ*UUky=D3xtt{HIEsh6=LbVNsIF^VWXvO^JEW z6DVv+(T!_c1d;nig#?ip;5UQnDgegb1N~vM5MXJ~2~y?ZwM?S2or1PU?C=L2TDOy+ z(C8%&$;2S)!Rdms#f;l+#vQbznJsVHKXGN-4~!?8GXG{ub&GylI2Odc9@(n9%TQ4p zF}G$3>SLU1a>F40XdP$IFVr+|j*J`W9i0g(WQZAH#^~%#u1RlAwkbI+ zfZX@mH3O{RXi-xW2I|6UCrfeuhsFN^nr^mSvq<6=7s0qm@ zRsTvz<+Rx84mp|^EaS{9wH6_{Ct4hqR;)H?=1sTybPn0P)@pFj)V#Sixf2<&_LD@O zd&Y7+d>bC6@LG{rK%#6jQF84#DnZPRW$}%~<*ni856-PS((zuq?^D{0RL>_XuK!-- zm_&cdZ?z(X*~wEP3PVChd3^J_bNCPVZ6P#HjJ(FA#z3yg&X{Ea6bE3+CrVQD3?f9^ zF+MD8q`jKY1T>;i^w0WQjn;|bnPO{%hB3HGVBlIL&$yaDY%3ii$`NTF2slWhebof} z$H#@@sLq;C4>V5huC9a~;$Pi*j}#=5XYw_mj!z7*^R>ekLBOsT)vDihe^M-ge!3H` zot)Dfxmq6nj2jb-DA{Jr2IfB#Vmchc$ddo1?CG^p6-6~Zr4toWBEqF2Q~f?(F8u2= zh74PdpP{AHEvZin7CRx4lu1}EE3NbyR(6+24a{q*Jqmn`U!OTB{XEc=e6;9yVCIl8 z?KxBM2FhU~=fqe7OHAqYgWkIL16%bg2pNeg@a-3XO5gjij8N(iXly;b<_?i(++9?g zvt)R<#%Kh2RH1e7wZt7LD>^M$_IzYlJViK`%kj~clbCoo6gvaBJE>;XbxAfwHDyL* zKIs}AGwyxKExO;f6IX8sKH6$`@ZSS&<0aHMCb=1L#YmHdNV*_X;J=Q-exAno$T7?W zgUm=;;YLV#3dx8zI%Tb?8n^zHZAnX2f)-A0R~|9 z{&yv5At6zbb-~7ukI)51v1I4wm(R90ybIt$pI{DL|S7aTiAu?rWt#I6Cs4&?wC;Ic7WsX2grN%E#)8Hj-#5Red z5P}Pq<2&cZYPBQ9M9$1Vn;~W6H!t`5hbRBpAE(KK#Sx}$)8^eeD~`&Le#;81-@O8| zRPvEWWK9owcMr#%7P-S!RY^?4;^k^`8j{(qW-hBkRqTL|G7z!v0)S3qoCd#6UwOby zRUa;aO;hxT9;*#%dKdzIu{jXq*`>Pkj>kq zEAJDy^jpvsX!Tw?;)zcw}I|3iak{UenOcF7a+!{fH1 z_!hiXQdAop*LxX%cjR7)sCYv@$AH|4 z+9_X5Q3uo0kON;!wY*qt@QcfdTZ~Bg92$(G}yx=503Dnr6z;W$&=9cLY z4!t&!2u%TWi?5fjKj`~+v48M`G3t%-BYW(kqUc6*z$C`mWHH{v5+?c!gNELe1MfTZ zVSwqCl_M?6fgNI(gdy9^TiJU-B_TuDxUr_g^rb47>Q z*Y(*sVp?Ob@sfOmjGBI`C1s(DB|A}_MJ=k;Wmo&~HfUu)*K4@s)Y9Hq#sdor=|YJO z&f##!;j5!$NqTlmuR{6=Zc@4bl&@{s%Y#l1f>(o%ttK%xC)=N$!GI{leoH<|{*J_nU7a*8i0{x3&J7 z%5Z2b>}%BBuT~4+F0;dA;TJmoz#@MBd0=9t#+&Ft!%+O>+`fRqs(4daq)7gdi+!XmxR!27?&${V4_TTUC-`9--2?kRfn-*2zy zJHKZtBF}KqmLn6|_R6I!{FwatwAjuH{QI`FDbz4Ki@WqI@1;D`N}8bNf;%StgddKT%m`wjzZ-@z6o(8q7v< zP70`QxEy4J70M?6b?im|y5fZB-!S+k=ojHD#MoTFW=NkLdyU|;=fI|N^4yC2YjDw=K`Za*c`XU~YW zKzF3CnCu>X$YYV?ej)6C&tu(N;zt!6HjNF#_WJWSjf7<7gbqsb0qk1fKkt^+SC2*E zWKGb!2DlO2j5$+;CZWQiM#BFDsPgRlnc@cWsDg)Hpah!bKL=2rFG{?(Dz#nw??=*O z0!`xVYZ{@SqZZDK{@td&-^DCw?xb>b<+Pil=C(+__-#3i%#Ga7sd1~8C4>irJ^|gG z7ZTYC3G^_I`MIh#z0SDdho|6AKT5P7oy_IHqr;j&U=f(=7M zVfoUJaVkl3NjGXeD+(RLxw+XTfrHAg^M9RJaTGh+O=r`VYK){2WPLK!9Jnfo(_4qz zsS}2sWH;WXx9YNvrwe(lKH1{Us7v!3(0h^(Heb$=M%(wB!~vV-I72jl!1Ld*=>?*n3J=>A8gg))meOVDid(a&12h@spcx%x4D%(#|Nov0 zEwg-5WG4<%lLzc);GbWBRq^B>q}qsz3e8{qH4o>jvjx7L1BTr<;BM_%bjomcBEyh_H3*z=Inbau41H=oS1 zGxn}-@=9M`28_i|zR!;}Bzn7jgk|F>C$FeadAvlB*U|Zqj5%@@*get0zI5aK4j^+; z2EzeZ=~y5B4p2cPFOMhRou*8ad!pUtvU;q=el83V>qF!);iEQQj=}GX0UJ8(e~kkW zL5Hr73h!(IbHO9mEwO)G>KVu=qn>-j^-jCax~bOLq%cP z;BYxUR|vv&2P=FB<>4+ngtb`A2bQox$!az+L=%(p>L!vbL$=q(eVCBut$328O@Csz zc4Kv88PWx-u+1E2)j-&f;q-zZd}g8N(oAli>V^=N#wQ z2lFD1-JcOp| zuuJ+dNw{a04HRus5M6jf2mPB&-dbJ({ET~TU=JU6r9STmrQXxh8{qX=1B$?~eJHPP z|9t!;p&cI~6hzZMzpdZ?p~6%WJ2vdtCj%NbZJ2?sTGbJlcACU4)I>`&-06=>bMI+ytM*9e?^Z28%ildW($Q5zcn zYvH1~vir6!UOsEbxq|yhDjd;fGN^~iE-)REP6lQt03~s>u%5=ua9De{ZoYm^h5yJT zcOx?w4FrfKLDEUm%vmlaTESMUAsfIAkrht{^qTm{DLd!F)M zCJ`;AVYr*Y&ygQYCY;uUo9sQb=kG)}Y`arm3j55zS)Qx;P!htrY_QTyOnjcBp28Fe z0JIpzoOS&CN*>iY3K%7*<%ege-Llln*BwPGJ^`BAo_h`iMX$UZ&lZ@AY^@kol6>Xh zuxO9oOydJi2O9u7$n5w})$w%r{ekcr>*a8baqW)8C_+Jj)oh&q_1EYOc4}$upmeDI z-Eh}0FGo`f9L@ZUj-SOeq?4TRvq%`h5*KUmK)}6`G-x{>Xr_`FU%7N|1iC_c^Ek+7 z22#nn9f$qMzR|KoO1Ino{T?h1*>3$IEyc2q&Ez!-?Ioe}!s;xAam#ipJnsnb+Ui|E zZ>I44q%qWw1Vdq-;cpEi6^DvJb5Toh3<9-44YQ{>kxztzZIi;C^ zPsMUFtcsvGTzOb5&lddKS36lfO*;aP|KE=_v%K2*tVvSaU|@P~ZcbmFKWZzIHoLyi zu$=Y@@>ta>th?-%nl)xoxgptRTaAtYhA)s(3&>$8!7qF0XUmonfl%Pic~tz=YZ8ZI9P{IdfpO@3`a zfQ8!!js4RqREfb(%Ool~1jCl@JUFHM7Vc%YnkiY`9Vh!*d0!1bD@pGdQg>i+6)N2t}A z;G^!U^F~{X3;Sq<)~lMBDMhXZ>prBO)It=DoCXJ9lA#*1R?X68iz|TZ5l*quTLSow;UmxHAIt{>x5qfl5UVZy2oNRVmo%fJI&!5T8StbmYl>n^zC+t8F0qEIWMRwop3Vj3~0gjG{0a0+_!0fo; z&HgG0`x=#6GQ&a7#l=N)OJIAge*ocdN(Q_QlHvm}72nGGzIblXmL5{!1x=zoVud%2 z%)!+ENCFX=B`;Jt1>2sQzRQ3a9m5yNry-vvXvsU&iTJW>{$W)_l=ymh{8BG23crqD zv<~xGSxEXieC{~=ENQSZDKvB?0V`^7FFARya-qciCf&EOnnpDUIQ&^mWHp|eG`1aY z2$C!2G|#<;}`n+)`K zEBfrbaa{0!g=J#3QUO~d7aKOj&V@QPpVqq@U~?0gg9^Ca7d1`$a9| zh9-yMuQ~7>K`Y+10mUVDT0h}|Jdx5|C&ATc+30c&T5sTLr4zgvfpe|~L?zO`Dgc;s z;3L&NORLwc`4iwC+yTcAe?63p=TIuG##;Qbfa+ILaU-wr^@v9PL6ig6 z<2xcWph6-$Y&MPZBmFuRz0mal8M)+bTf*3(H+Lk@@4!yWKC6Ge0$k^l7a4wEgyouK zz@|s`4W^F#ph##hBE3|@ESqyip)qvFKP1G{u<}N+`7V=~^O_+KKU*~+50`^9dxS-l z>KWK`O6FnFv#r>>*MI-+ZQCKot{J1Q|KWMrO~ee|X^%W96QKfw$I!ZQkYHrwER0A2yys8xL#Xc`(T++rmIl21DR z1rCqA%kdgs5@M8EW3kf2CtuW1+Jca;Y{8XYY#SbmhSIQ&2xFj6@Y_$@a- zS^0RAb4P}chUO|c!plpTutX5LSXg_pNsJ5cY!t=C9nVs*9cPUcN#B1Sn1n>L_CML^ zeyQItAHAYTp%X{DRYK4Z^8?6aaoT~>h}@KkQQl+(V#7xJd_eE-(>lc6|2Tbxd)RJwT&iJCk04Iq!## z^bMD<=SOq(-xWshqH!Y;5)mBsF)!3_j0Umwoh-MeIdyBf^dvZMkZk0|`I*y7WNRD= zym5j>I?FRNVA#pv7ltL#?jy}nw=u`Oj$dI6xz=!S7Y)i@mpXsR(i_48x~XB~Ho(@X zDb-Ja*jiv~?Tv(hXTaX(GU{3Rpd(AIfKqvj%UkVb%s!qVIK4^%Mxu3Iv z%GV2^J4PEv4J9INSC;c8f%ueN$=G}*+T?vClbp0^Hpy0L zSeoWrhohrP-p`|!>sH+%nvWm1+fBje}p`8Af_tNqqNH_6H; zQ}hJePH_-yMzQo9CSfJi_m`eb-BE=XADzl}b9-{9@IwRo-jWNdzg>C6SxO>>{uFl6 zbf16n5BRd)^&Dso?Oy8$yw51E8jRR3k$KWwaJ0y_3*(2zmjGx|?g$p6Ctu#jSFy@I zfRd^`?nJWSf?&n*O91e7(l{PhW8opW$P4NJrSSnT-Xi@!+%%vUdkok7-_oRlBYDGR}}gXBn>Jh{f2=Qa~xJv zuvwA9%lVGl`8Z_G7$)t%4vIvGv_8ZBqXs@CGcLwjdIX2^>*>ohB|yi4k=^2m!&1C=CV2 z2q0~mDdjNfIx*>7`}SyB?0^Q4WRU-Q?T0WnkgTgEHrb$H40u(AuXeeiZGc4Vb8oK_ z$9HXmaKLntW~%Q*m5AF9$ikbB)12DbZ!B7pyFOW~8UNyq{krFUv?LNj(mXoq;~+I` zN)vl^M&(O-a(Jk0u}{cBP|vb?db08H?w+d$OyziH)Bn+U;DMYI7-H4Jm$R+km&RwR z>wLLMuags#SX*3F5MN!~STx5Q8h-uKol{U;{I7M`w<#-TmHTL2M#S-ITgGQ3EjC17BEg-+0dhuF>26{1J?`YP z2OyFg>V2@xJHJ8qOI8groN};z{hGm-{jO~*R-peywhx}lxA*;y9&ceRap?y)K+o6j z`-J)<5eN&pBTGByVAzu|W$(J5+w&CD3S{L0Tr;g#v_>FEKYFx9}=l+Sf@d%D#R9Abq=hqDDN z08W95aYI)6T5?CNP#L^DnL$Q5XqyYgCxRYNqV;dho-ZuSP?xHyDc(XsdZg9ojVUXHXtm zd>9kvVtnsY4gR1m1i~MR9C*VEBB`LFa3of&6Q++hsl>1(67(71W3>h$4hXEs#Nqaw zP>u7nRA_NkyddC7>*Gnt+wt6_B86_5NMIRp5?NXuDp}1tE>A)a^n}jiaM_CSKDoHq z1q2lf>%z0qR<@3ldNN=nE*HBvYb^{o49Vez6_uURI39B4t3amACv4C=r2m{;T5VV3pB zY@RJSq_C>X&XLNNs8HGRn^5H;+$P;tiwr=a6(+79yBuyi*9W!tTHf#0?jEGY<7bS2 zqr+GTJ@|MGR22=Gw1l6k+#UT13-tFtzkRhD{>MtOQ&?71LUv6te6!i&>E9)Fg?8WF zvHyuUEl-`S5oo882h&tCbT9uI5iKeFoUM4_)%IJ~-Uyz(ZNzzu?Uv)nK^e1$HL*ih z@V4_h_PZD0=3D%xd&F(;o*W%tPuWHd2?rc(a6;Or7iBt$&Pzw8*b}S##fdd6APkLg zPJU{lreQ#P5euUA(#nuC7Y8fq_0^l3lTN$iIbmG)or_z1vznVQdU!5q z1RMQ=9saPm@?142Jjx`GY}jcyGQ(s8I0@f}w0xwM$vPrUt^^4I{_g-3uh&K4jP|LR zdwyYICy?ZAdtnI_v!1596e@(8gU64~mTT!p2LLFBp6#}?iir|=j`D>hh1z45=7QeB z@XgFn-md|n!g38SwOfEB$CEyLJ8hz z1I%C|WU4s+Lv^HzT?tPen*ZP0(#kC8j*^G2myvH4V4rOA{l7yF%2T)l8FO5L(S= zKu$F5-f6dqqi8GWk0K@?c&6|0xyBf-pFmp1Ab30eRrl{bJ>O!W8SY6?5Y5&%!NRWZ zaep5C+<*A@I@qi03ae%9y7$LAae7?%zjt@P-&%Dz%EqesO?fTgSbld3E8fty`R{Yq z_jjf-M9YFV{ZN3PcOJJfKAU_;OX|H4^~4-&Xh+-buYfO z4vJ8F*2be(SlzFn4yb6Sz%|`x9@CBm$z_##F zNh1<`WeL+L04P$d?fSctpHT2fQ?2;V7aCfuXc~kn^`jI+F5g27*ru8n!6q;rd*i!@ zP;Ew}`#)TYCKzDR&*%~DR*{N8Kztza3N?|gu3PA9drm4$`4d3Qy>D)5rYu-6YK2RK zBNaFW!QP&5Xj>;6ILEdNS+DpF2TAFSu*Ztf5ZdRhqmoEXUn1JjZw5nR8eCOrjlbuy z_6b4R3K7*@NZsv4{`6;VYW7$L8BTAOp{P2LeGCU-dIrA_8`W#4rqqduev-6D{Rica zWBR!m6kajA(yX`{@OGWs6@x3S~4G6$8X_t?cnznIuZ;qQwoVM|m!UcGcpazs$V1?d^mS?9IV!oUSL6CRW=l ztGx9a7qH0YKN-JV7RGO_%o^KkiHodxoX`4O=g)7^VL2*68ikO38rr+fQkbr8lHS;k z`2Ix}z&-++sTCYVqW5r>$us)aJg=HpK&9vrT2KvKH79&F`V*PZ%gmEKZK#*Pj9Otov!>GyTS?7Xt<8wPyE}GZ!dyPwW-o^Rn1i=F@v zS1&huoBkZH1TJ+KWN~%nW9eB#ULFF1rUrX(aPWu$O}+`h-w4po-H>(BPfzLX?R~P+ zd|&$&jeTjy?r{Z3h8Gqee_J3_veLCbhXb)-Qos$%%BEl11BTatRB-3DH2KIt2GOfiB-HT_nFh?zEG4Bv!4AsOaq4+P|NG5jBeWW^;Nv z)p|V?NF1jy$_?e)lLyt4ywH2v>rKcp#|kxQg_gpnknd-ABViY}fO`Gw;9>YRfY(@P zsvT%1{0Z#D|6bpnzoI~#3MzxwV~Q-}QaAtZ5tTGtCGyeQrH)g1-ijQQmv!GJmz1bZ z3M45>*#CxG@JlAA=>Ax0_`4Oysg{$2!3I}2*|sL}G=LBRbq z+I8PH_6zXN!1D;m^g&W~EU^ymhKA&NvV~IbPJqW?c6}z=ucFYM%cGkrX1B&=E?V4<^#LZ@Kjfuges#%YYbWw{oxLy8ldi{9%p-AFgus ze=}@-Jov2)rk?1~NnEjfZe-CbcMqYrmJ)@dvdhX6$2;0$mjOn+1zEqklq(8vC*Ivm zO;3A&v8(WZ-0Lvu9q-l2y?F~PvSCDBxF>-(ae+@xS+ zRQcCiH(J~4X|Y0#!5l1c`-Jt$pchly5F#QXRQN(pjGDqTjsq@h5icg{Nf^*Z$Wgar z+7~|Zd_+A5P(y&&+IH)|!f0?ZZ5EIlhDCt&u4hS+#NEAkaU|YcBG9N(McLwy^A3Ux ziaPqwNVro)nQGu*1KTnvPEVekbF~z;Mi;@1e6j6xtB5QcbnObK+FgW@D$%(ejQWPU^j(<4B4sbIHIAETnjPmvMu>yyU3k< z_R{M3h80Y$k6#)%zsUl;^K|PS&(0*QtX=}iZFt{L(?)n~7(fNRrzKeWOy)~iX6Pp- z`zmuubg;Zh6ESbI9NQHopq{en4#ATm&1_JdiPJ(1ZMVDq4ZPZ=kBy`Hq>}^K-X?)H zWpnBH_=!wLMGT-}90G0`fL+(t+-zdjue0}3sXy`YV|;^JZ;(^EAUviNE7s1y^jmZD zUeUT98|n+uBvvk(e~AjBXSSO9D~f>pHr2&__*;I!l@(G9-V+{han=unI2`%u87 zGxB|O7w>y(nYkMo1nWm_&*T*tK{GR8vIQ-bD~NviKv)>0%8E9*P(<2nLx#yp@bgeq z*OAEA1f2HZ0GKhc@U<@ql3BcD%oHU^JZ|&vv(4^6W5-~~@8x^k$XDjOT#t;Rv?WtR zf&~^x?XBDe_g8!{8Pk8HA`#ctc&|@oFlcu+Znv5fVh##tBD4l`eiav?a{42TY>f`G z4kWFs>7i`ElKmmZ!F?9B5b2qYrBWxZ`3i;Mm^LDDf8+rvosW|KoM5`}0#w(8-=iXJ z?u{pkSHZ(UTTZ=$;6Us!0CNoc6)4@&36Mcu#}Ba{(W7xciqg0L`SZt*H}$8t7HdX2 zD%;>xs%LeFf71bkYq&?KV*HFJEXGMkOZ2ZVS?V+xo~#MSKeFfj*@raJ+dE81so)}JI8mW(Dd$^n;kCW>`H z;Sc)@1U2p^^28=!4I>8o{Yt`g4r&)2<8%f1_x4Ca*gvRed;132mNhzuS{#>Mz0NUF>`0Lj$xTXHW+HxJ%iJZ}*N)w&}9MZUj zAoGY?xt_jREeTxS9ZA!&+K#0BjJIDF(K@kPE+Jq4X3fuX)@BP>^+Q-cnUl%Hf>YoB z!56G#xeEl7f?L7>`u3?W0|kjg;Ha4~Wb}u<7x@C-pG^Iw2Jwa!P0LoQqxCNOh*b@Y zVNmmRU#t!dE)mNqxe$iVT^S+*Yw*NEoZC|fGGIz6^|S)MQa-l)Npjn($kOB1&$0vT zL-)KmJ9bG{TFHDw#u`iz+MX(tDm>rck!M$c1((RCIb<#Q*dbBkimS_PnW{ekV(TnI zfT%G=^_+E;-`+U>_YiGDD2O$Sn%_eYqo?hLrp)&p^^u>0;Z~{jcvbiVco5Q2%?#rj zZ1)OBeWOTw)ch#a&PnFm`2^Oc?HqX;@L9?TNzG49^VZn+nflyR|Ln}U2JW_9)E@lX z-IoqM>MOzRR3ev$j~q(W+4c$W@U z7gx9Sl#DYbP`=I7T^I?mFvl1(4s-%fyJg1(*#l@EP*(B4fH(puX#WM^s9$^mz&i9r zu?m1zOkG1(O+$d^TB_uO?Vhjt`0@9#tnn{jEJ`sGSfShQw%u+Dk{^HW#q6+Cz75d! zUA}2>;0`!hXFs!F>At=7lneyoJPgv_==YKZ63-~nIz~>J!DwamCTA)#Hco$J!snKD zL6d|Tv4mQpq_*zcsq6){Liq}ca;=A=o#zue%bHG-Pg^VB1+wyxmRUH6noRbc2w3VU z-JU>JNu`2;w;S&gMATdmz{DH5{el(usgFo8DAfLv$C2dcm3#OR}K8Td+Hq7eO zD7Wroz5}*%GfrBbL-GwI?%9%(hs{Du^J$JG<(B|25g?xhK=jy z$H}c=rNc@$0KW^rejSc4=IQAY>LDk3fC=5P^7IZ)N=#(I>1V@nNOu&MlH$YfO(9}^ zL>2%FqKWa0olvXh(C(o~<&vQJaS3!N4?{#`>&Wb#pDIY0uTa#BkbDaKBA4IMvEtW8 z`1-kR_+hiD=g7ANL&G`hsT9TsLAg7Wu#4lB7MD*<6wU>O(ms*9YTr^qcGxE}6CGEY zpAeQem zx`h@+lXP%z^!t1e#z%p!h$YAfGjeKrN~%9blsz>ZVpiDRJLCR?Esq4 zeUO_>8q+j@D=C1=_XmwQ#n*Up|Dd(>dD^-adk_3g`1r+BxKJ+eNBHfhyQ|;t!WrFy zb^53(Mz3q}p!Sss48#uxluNWOK|Qo|Y{=G#3@h~qY-g9#aSHxllcco3&9aMJzf$gN zQ9NHxP3dv45M4c5nV3|gW!--TGR}o*W?)!KvD~#%%PBB#AEn|}b5DWu4`XoC4LldW zCwJ<$u}Eft>TpY@!M?!eI6EADDH+6m*T8*BTcYl#AqwJ-z*NhyMPM0BJ$DYyx6Qr zc}9Ih1&TTP~HvY=oT$9sywou3xf$8RS zi3(tK6n;#qr|(N~q*4@NhN0K!d8)BM8B-wNU=P$(>@YY|YDC4cB1or-+Y3|mBOQ#R zQ%!t7$vpeTfyefEcWcWo1{MsyJR=D^jk-rwnUFnH98%$Bx}T60{U}3gvVR)+Hd zOS-y7bD;dNT-d<0T91lu6-MwkHul?BTpsQO!wRFLg4e81Yv?jdr)lXde=mQ!2@v!M z^P|8iIpL>ym;np|?sh-fIzKAaCVtXZ=8h3>- zED}N=wA|=)pEU!_C|bg$9XBam!&VVHn?M@~TPt!W$f2OO?2Ir1!ok9fjgg&TVZ%Wt zE7Myf^O5=-19cltECFm*a8>?G0DykJlkqUJM{~qbNE}rR0T-f&O7S!#OE4gm0kVoq zH@geF6wm{qvE=qnG)%`&u+!mLzw0z9H7=F*(~aCpDVqGTN$K@%Ds&wq=or^u{3CI6|)HUU9LqQ~(}K?$(KEfrwRBFa5>-3=5!nV zG1uAryMwU%Qr-3Id+^>kji!>h`3vnFp(Eyfwk4g1S%xA8Bc0+`W8?4S?{1pOhab*0 z)J=x`p|05;nYCG9A-wMtTZ-VZZ1o0zFhKKajY+>z@DzTit2=2k-EnnDq@5#x&wi#! zOEczlrX{t9lIG%WePa2sx+SpaWcOFwP;>JIwM|Ic_f_EL{`ZJNN=(GATbV9Y!=5HG zexw85XKF4HJBO*kkDz5M1mRAg5%!oe!ap(Y(lZOzmW}@P?>_nkJ9p}j@Eqe}`Emt1 zJLA_aSOrhwJpEUdF*|PI{ASrFiBIeHIgHu{bM+DTl(qRB;He;Qm5e*&-TE5*ja)sH zN;vlGxtD7#ZI&)BnNjGVnYA^dw13a8&)wcCc(XA$Zxbki(S5f#OV2&c2Oy{Q21-lL znf@-8_LBh9aryp#0I-oeot2STxw1`%f0Nr#QgG-^LChQO%r-~kmYU_tU%a)=2N@qT zq{?`rovt=i`uOq4T;n8+k%YgEgHXNxnps>wIXDM`WrO=;AWKC-58QJn}u+0QPBsTJYidpQk@MygGjl z0hgSq|KK3feJtIT7O%J@v8XpjE!Lsf2`v`%j3@ zKb!hfygvSSVGqV5g{L4N^pUbb;b~-BnQGhxA8L8w1}uBQ8qv69r7Q=W)LJZdWmyeJ zvbldA&zAE?>{@&b`=_q(i?r+EcR+Co0ce^HD%#ovVan8!LTe4_?NL=iB_O2qA6h*h zjCVfkaj`cUmACc}8jO<@X(aS5=K#adpo@khK!nDFxuJs_5YimhT0(sg6IMTG5fN^( z3Cr2NQ10%OZ`99&!89Y)M_% zxS-%gSLn;6q^pBGp0{KX&-5HJM;+VX+4S`JIsDc#;kLOL)#5=B-9?IcM&BONl+Hhd ziRW~|r0eR%7@mh&U&lz7@9u6l?w%841@PC6@h-W=TZ}ThLYBlfQ8)pNEkr-$-zz&l zUOIM!k}(2L7IW$XgIqwON({2Bp(jnJK9&}W|D0ZiFxoL_X$kr8;U{1*RnupG&vV6s zUrbMb3#ciuWOYiz%uoQG|$hCN;A-45in~GxJpt zI*kK5d=*kfY0q>O9w^%Emt8G4M4tn25}o2cT!I=&z;%DuvEXs&#!o~eM)A^kagDvJ zbt&ZsA8JZ~ljLxU`!%V#^zc}8D|FHlar;WK(%*EmZG%k7-T`n|L%6ac4v9Yvh*$u) zED&by=)CV!5z0?Ri%%*esafF_tQ4%J1jQh{CQt(W+I_I3${`Xok?fPlv(`HUEu6UQ z*!U-iM@6iY#RyH2Kb~;$MxKUy??pl_>D=%%_>1E?+^gcrBC;DyDs+O#s$LU3mS~8= z&_RH6B-%+FNe;5GH}>AfcJH4EDAVCmeTpAb{jVVW%xkGm91zKm0q!TaT?O?hB7JZo z(+!pe+4Se;;}kvr^GC@1{r+ZelxfFuSOt!5B0&K^zdED`EU6Gkl9+fC5fO2JW4>?e zF;eAcCmRmC`N|xA>|xWd=}j^<6SDr!Xj0BDiq~0uV@5$za(335#(KWP)zz*|*7(1% zic$M14^Ovhrl5cOXYYVM#7}RHf;)+Z3Awg2ALGfs?0lwyB^(p{BEsWQpUgNwKx3~o ztsBU~?=5Ku0@>q&HrYazn1J0wM+OQ$PQ?O0tB((4gWr}cg^lLddI3{t{7+4dLFKav zor6!^7mCawr*=mfe7RDTV7eSPcNC%qGP<7`9}|Po0EAB*4pb0Lke$)5o5My*f<2-A z-yzp@x5fDhFSW+1cl-u3xCJfS1J2Y>F8xcU_uKaBI)sCY`Z8%%9lGL9iOFrEZLD*f zl07$Nl5zDAJL$kKas8TuP4;BDw3R}Rxzieg0_&of5#_k|11&I6;46rV_7!o5!0W4g ziGp{t9$N<=a6aYWV6*f-s3HZ!=-|?%s>&)hk)$o)?HNF3P{N;GTvR7i2FtP;3bowx z7RbrTWy8wpm5~G3$Qf)b*P7SpD&G2|54?4!RlFR%8Oe0G^je~6)KJ47l`IUXwC0j0 zoXPa31QMf#?C13N`9g)Ixd9~=aU;u}${r4=k%*Wmsm1RrW&xP*hivto61u27tmy*? zCh3v1e+0tbIWzcUsYEY1%yFxnT>)hK1g(mrfr9#j>pOiZIw5Sy<&R{DZiIWd7+A;5 z#lmKZ)gR@O*3t506bw)-f;&e z*XuSD%QxFEgc`^0&wD?By7_dnTv*l55%!du8Rmba4rT=zeU)WPA@BPcY8!lh9~_J( z|EMfcwc?-CdB&!r{@M2hd28O$6~I+oP`3#>ZTM%mwB-`1Z1=^lvnrop?Uh}BFxs9q z(NJd@@iYv}t8#TIcfTM7j_akT(;$0uPcYl^PlGkb=_3bw-o1o z%d?r13%MK#|0fjQ>aoaV@4)4<&5@d@?3Pp8+zpvA#wWujP1Ap=ZoqZ?M7%TIk8F&m>80)@(D6A4So=(6B7cn zY{Qs?y*u?%ELr&pAR}!T0%3`efQqXyIq^x-F_0qM3OQPp}1SO5h<*X z3QY@o6$P58h&8M7A}i7dw6W425J!-_MJQ!7@7N2>FZc9jJSpZ-A5{O{35RB>tr7HDkp>#pibya1s#Wj)ER`3}d9x0d-e*T8yh`|$_ol#C zYfjA2>|=GU!xm7~INXUJ6FZak6R737x&ylA=*fF;!WJz1#iNJPA&)K|jLN287SR^86g!O0!j2h;I5bKs$TBKI5H|Nz4CN6*unUY0Yl^+(7Lz<^n?011@Nyh>A~}(`_;%n zdP03*RuxW7HFfo206qPDT%aXYMT1}0Gi>P5yC#=U=~9L7drYG_ROKT{>rgj)d(KWw zQBhG0B>3Oe-2N8)-4TRl0$7Zg&8Y^kVhO%3hFzFNsWAVA7U&9OjBMSHj80}SCYNFR z!sHc5tz4ULL`iJWK>r|(t6eMN_^0GFl!GiW@5s*bVR`i2#oPEtHpb-eHQ`A%JS%(h zgn2`9+nCRns-#GYiXuV1UWPE^y86J=k!PTz{&Y?90~XmE(U&!NSfQ-uYr0bripb1Q z7_)RA5KU?^U|RP6kf6+CP;bDC*V6%VQ`NjCAi>pTcr{=HV$ko7TE|vBF8fH_h&}N zHJ49?_nd_8Us;NIg}Fnhw_YJ6e@A}BLpDvZ(GZTP1f>ehZ_Z+_h~s^ohbiwYyIg1V z!&Mxbjfx!gO$3rBv{lPlTs~Qvb|1}77Cbd?cTCForOla`$ex-x?&scc-4)aF4KV*m z_2h4RUp6$0DL58ec-Rrg0Ft>7=x zPp9!QNo3Qlec<>Sh}jCU!y5botX-%Q&Juey|h;_M`c7B2&Q|_EZ0nsxjJN(~;U0 zg^uukkSrcl<@+o2vY&Z@+FwhGMjEok8sfFq{yXJ%KP9zi0m&aW=uv za_Y@d(E6KkRH~=_XT&xLF_#HRuhBdK<`D$OlV^NTYqD!k{ zAi|3GVFlxcpPvsee~ybzj_~8U^5^Y;@9B}1QD~qbW$(Ud=GF5H*sr$AZ0B-2A`tZN zQpCEonb;CPMi~#o=FDQIKcmDFNz-O<(D)zUH-Y`Jy~0Os`Q;&=o{<#Mt1FsuK+d4! z;?UyiyX(my!NlKy@Si**gAWHf6~Qh28)WY)w3O>Z|6aU)6_(#cWL0c}RKTZ4wej~T zP?O9=Tq>)xjcoPDr7+0!#RAhc2J9Q%GMyfS1>fS@JN{}Y@_jEB+HXE&=#bEb4YFXyd#tuG4aL`5>* zAXG+U=Y3!#go@;E2-%~%(WFmcHP=5%$Wg^yN=c3-YWXpA|7Ba(&PVJ=Uh|f56DmX9 z>x>VP{z%3c+yNF3kUf@N@~F5jVS)UaBlAoK7ed+8p6@e;(!lCeehl>nshq9^_6D_6 zVXRpSpKx?T zj?ERR)W(S3EtzKYFmwWT8e*njc>Fr=l9K^y*y*N{R^%uE9s$O**ccHZ6{O>TOktOH z9MdndP{xZPL^8i7R?H%cR~HsU>x=nprWc8%`4d%)2-H?qxU$cw&xpbt!uWmrb8Hk9 zMd^Zgq`pbSCFALeLRi*77>1!f)-y${K~k)&kq>|fmt)o4_~ApYug0?^$lM&~_k`B$ zXUPTQlCsrD=SEH;A<85ZBjaCI%S2o$5DNlIJbMG07B&Oh_#nY`g`g7Axi| zHhEPm!=ox=Gcr-Iv9Xl7=qEyh+fbeR&#AErq4Un_`PFo(Q&CO#6t6}fVw{BQt$6U{2}?3m>`5V| zxq?@`-_S$BfriTOyx0;nH4m_=@=rPZNMB=E@^Lx+4Ln~&1T*9s*2OteusRzN;29Lx zAU{WAPEldXh5cA;8a4Tzp&QVFY~eed;v5>JBMvCRJDQ*v7x&t}cpg*QPoja_qr^He z^_+jnuXaQkentux2hR#I-Wk z5Rxr>{9g*-LUtZJk-pu^1ZfUtAl}8$o4I7S>T{9T#_%{Am%HeIyNlD~!h2`hj(;U3eEiRgI}_+{p$TwpiwbnmDDZK~Tp);d_p7?)C`>7{8i zGkT6_{(h&|JXKDnsITcF@1J4)mNp;?XSLr> z@{x=nx7vfnX!9y&SneD?l2oG>T0AdYTW?P8W;Ce(e=MC7l$cjB47-_qYR%24R)4#P<@Om0^&i$k1>^=S{~~x%3Yp%>4rd06shHuYp|LYvL!lf(p;c;rnL{LD?mbcnph3O6U%&7mQ*o-0Rf$z>&KfUBYjN+-_`%4Kxf%O8q?p=PmxLc;Va^=bwC^bczwh#j0>`NxmF$B?1)$xh?# zU)!R;vRILF<-c%ZZBhTSx=>_OH{BhebL4PwutN*Q)hXp@KC@GHIC){;|99fb1?N`~ ze2w*!RN{*5gBBD8bkG~nA>e-_FFI*B>bd@;M;^TilEi^sO)81t5U~Z%=*+_#?n<4@7rVMyM7j zN%{7UeW9B|3jPawVSF|M%bsQ*B^R@4TWt`&g zj`qs!rKO=+LPy4xY<1gtCPb=zFXelhey2oti=m<0$0~}$kv%!6b=(npWZ&Lz8{y&~2v8Bf2zsJ%G3QYH zQz_G|v==L}3ld(zD8c-I7(oAQjt{?TI>kp}-Dt`dL0Z#%Hc7U0F1=0pY)Q^aS)z!* zgN72RDr%b(PTNU1LPM%8ZiNqctga=g27sw%QHN{Fygq%d)RX_oE0{tG=LKaiv&snhmx9%%3u?|a9J9$>@kVbNa|XR z*e#vWEa0c#MnAxOcsEoz&wBz7BD72LSVAX1(MBs8GyFrz3S{=QL)ts)jzU_&FbW|s zYJ8~Q;J&%qHK%@drm*q_w^Q8F{5Kb+-@kwFHkuDFEMSrmA;J%#3?2dw+9-+f2`Bc; zXQd^7NQVZymsf|kSNq{st`ly8a{ioOfMybfit-<&^y9k!xWF8&tq;;w3iM*%vSOxe zr(e)>#dy*lzH5=fnSA>)}fOqq|=N%Aaqe-CJ5*NbJ9BPJ_Aq zrr|v5HY@OXZf4|;ZhiJ>`|PYr>!PnIKv&I;z4wkg!EdR`zdjh3K6BbSJDWJH(Eadq zk;hi$2f7s-Z&Mgc8h1^#^q2w^3-uPXmU38Kc3MsZBl1jOj zV-+?<0f3t$6ZVFT-{L~Ycg%&laghwsf*Ri*ylY{@)tWz;tp!9tf?eyGN^zglX8`a2 z(}=;gI?ll@5%@ypyz;zNg%A~;)E~;YeK32QO9(H=H%>NBPhg+b@i=ezGIP<&K}EoLDDOyew%t$h zA90rIq)8V(7HFK|vA6KC3&cWkyW{H6ppW~j$uzI^qZMaR3HEqixk99)T_)HQVm)nw z(j(6TRo@kjgWSzU8k~2({=PfIu5yZ=Fr*!b+DBh&g9TA4e8XzV?+coCb$q zk|}Z$a#I$ zY?2ZnECyE_>=T5!YU8Lw&CK93^zTQKr0OMxHg57U(N9Abvi_R^h%}zGDFY35aO3D7 zZR>;O2RS07i;#I}xHUJ`b|M%>J*X!)`h&!Dv)kMGH83B(0gFn^1o}H6VCtm#BGL@_ zZ(y@)NAD#{+~u0h0$tc@y*=AKz1p6LzAn_1Pvzb(r#W={7jf|LcXog8uN<78Z%8*R zp3f@5w{=@|T(%sU-zDZ)04}`_|0Qav-=xSPEgiQ$ve>z3Xtv zn#@>PN>&L=YmtWi5Jf-1J?bc0H4ohXV>TcPgRCH{9@tLsJ#!r?ja?KbC83o1)YW|e z-d>}n-#rrN<7e!=Cvk_hlm`;eqwgOtKCbzmI){&_YkGi6Y&@h$z7MlXbs1fY{;*tC zNMk(&0PYu;m$$|`%T7`)lQtov)#ktX0E5|1RPYuZIbeSX`iOTt5`*KU1w{}w4j+=; z5emUYuPkBoh=v-X1F5AAfGCN`sS(|5ot&JktPa2ar81KCKZrBAgbPtlwNg_6I1}c! zv52(35?DC{jCXSm8r3vr`VNI_utlkQu48H23!gR4tI{Cy-=w~|0gq##xW2h-^R*P0 z?m8pa61cQeVU@GjfQ!R^x!ke7D^eeavVF>qupC;VY@)-|- zZ+M8DU&V(Dc^jt`>AU zi9f-P>+9>|OpMEPGpz?uq$#-zMw?CX`LXKF1S9$wo>`j6wchk6mUeX<+U~?Fi7C;t z21vHXd$96QA=$bI*jJ9Yr%SKf{Gb7QYzZbfO!sAF0b?NHXzl zDp(o9Gk_W__usL_OG;-=EUZFgqQ9#`raFe?APn@E+;f1vKVE%7X+eN}CF+eonOM&b zC83uDBqo1<@A4od<(n{_f#K%?(MO7niT2iQZ?h47uSu;dt>E6AIn+w5$|rXg>@lla zU+URl(OT|u(3yu+k>fbu! zatrz#4scl9^SViMyb%N96f2_eya$gsXV{5_H1t4IiLENBSkT49SydH4y;%&M&HGG9>4eDxdzXr;>5V2^rBh#yG1Z{U6CGdW5(p2Sf zGC&$&E4hU_Tra-w>;xW8B)wM^r8;QH5<++(t`U-~r*+rBZ! zJ=9aHN7~HTk=*iw<+n-$#>1ZOtvIwz2eWkH1SN@d?!I`Y_>(Ac2lwK`avr_wp{FE@ zx2vd^hhLUcrA(O#hb2b!H{)=TB>?DAe84J;KDrLzqIq;8UUSKydW`OnT$Y3S~^@r11Frk9w zsOnrPGj>}E-^JBm;HWIdtH?6n_X>f$M`hGaavVj&na-U#iA3g%()&r0Fs!(lPYI1M z03Fim^jpuUBpOZ`P2uyWbc$l_zIM|}`rtaoCaAXo@oDuz?p}a~10*aOu+{WUc0yqR z;kC2RQu_(D*QyDYmS{mwtyD<@E5DXifttw3rD;gimHY{b&S6hwVKW$vikLeg&Pq0T z76M68&c6sqCgiY5vWK>#cDU|KU%=pc)ktPAHlS zHob~NGrGx&CqnbF`c|dES5V!KUn3~+Tc#{`Yk#CJ?Obc`OKGgLEI>czt7-q9=pZ+~ z>c&xNkpeHUOjtTaFIfK+&y~tmHeH4kH0e; zk9SWfmPZPy(*(s@uVaQTfj@?94QfEZfp;H<^x-99;4S}vAz^984K_sBauBlj zVcz}+`xW8e@(%n7`wdX|>0!CY9g>l=El6TA0X; zn?FD<%IiQ;Kvd1?uH%&O$>a(k?%7i66>qA;X{2U#e%_o|b z2c=!KYj1YN{OxF=5q5N?YJff3J?coVUE5ZcVN(~a67->|q@^(VUBHaxJ zIWD7+1I}tYPfRFSAu_mwq8@`)-J}p5G&Hrc@DyyDSrmBu-r+z7?vyfxWgxu)S7UNwHRhUJP*?@_alId z0kk?Qd*gF+G1a&Nj&J9U#t>!N?FF1jAmJSR3qI*mjvx9LLF|@~Tlu$d#4iZnS~h(h zy2Hhi$%NB1IQ1{t66*B9tKW9h?B|6>>$OJ4vWDWeD+g>Q1hh$r*-8C9jz_W-_@ci$ zElz`%)2_90Jw$ngYeylE(E0lHGiGUYiU_*321ZVY?AH)HzQqt zKYf{<3Gb6VxFi*6Eg<5W1+MXZHXtNwg+mYrYx~0m_%-r!d7Os~KO!tM&nwuS8dl*HNFh@0XX>Z8eg*ctfWd>#0aFL)7VUN3?q)M= zf0sl7RsRgg`AQ%Gm2dfLK*$IuR3H80*@%!!h<$Pcrm8(OgEvl_I*cWDCM-7x9kQ!- zF^9u|6ZPj0#mEa&tc443_StaDi`@&baHPeqLPIg6)tLL@+$SJSM|=A&fN~9VP9Rg$ zTL^~iMTI2mGfH(Q_)RnZRnmcwu*eu#?981!5;bGr(l3LxKMw~>jZ)Ph{+JNqNg%yt z$4K$q7@r|kh82S?!;HQ{{g*XII>5-Jz@RM(rmDRC2)~=zCx!69ob~L)2Kkm4Upue9^cKlNT7F zLsd1}^fcweFtwpCm>T%y!8u%fb9;c3CV96qjqNr@)jxC_0UcmiIpPsOX%!QMLD$bG z*_Th&-bOf?sv5eedhliDGw-w4s?+CY--T8U&Q0*w z*%v!1()mH#SbK+FK@@_8DHTqeOX(}(*)6HgXCGm=xl6@Kq@~PR)35?lxT2_5Q=RI7 z7mY4QPbnk>0rLI>Y8+~)n43+WpaCp6GN~v`uzE6BQI3vrc=&9HEfI{8CntXH3Rp?} z&ov9Wfzxtt!efC!*6>-xK}FKB)Plv4Msh){T-ha@?udQi?(9_`u_e2?PDP4Vi9|4Pv2-5^WvazGi8+CSv+Q<|}P#VKrDy4Fha>pv8 zcE=K!6^$3x<)4Ov-AP1Yw595h9Osx#WjTt?PrX9W;B&*IN9XaCQ&z$sss@`YA*M<0 zQF^Bx^52wwn{p_FXlW?BDu6m6ozaA7W^2GHSQxpmqFBS?vB1yFS^-G3gW_|Gl~IN_ zq?k%lEViiWn_V6ZQhvnBNR;|?o@Wqk5eExpePW%gl+0zse1O`bET&#F1EZ?fWHB0v zMxsaX3Oi4=2`8sE;Fb@hQj_VE)27*b;=?mxi%UviCY8in2K)|rFhQSHs`OiO9V8H5 zb4jz^2Akkffnb7|=V@YooSbTAlDs_2az(h@aX6`lw^Jw|C!Dqdl*&`i3<{4RaugTx zkMoPFaq>^`un8B)>T>i*$1`gg^#>jCpY{eq-pd+mp&I^NuHmD zwzlF@G*70mbQ=^1Kkgs;?&O)Qkg(HDJ~X z2JV&i(872k?5%@j5}uZIh06E)(s1hX%+dnsfFu+5N>7w;9*P(0`UzlmrP?%es7pRw>CM z0#~^Z{Ii2eauDWN*#uSW$m4z0ox*CLHmKfW9Fm?sUTpkWBdG{wB-`>C>SnsN`>J38 zix3RxOrckBQKdvS1~kPD21lF*U_n%rDc+(9mO@JkY`D|hYtBjVq`BaBKM!@yWqzCTWrrwU}MBz`40v>LPMy_2&uy*gg8`)UM7 zHE}PQnp0Ur+eVf}SlS~T?Z-elE1GO*f>Nq1*l8~lT_t=ul2J4JCVch8Ewg1$BrW+0px87DxAd5 zOx95%in_~hetU@{b4_RNb;Uh9CjjdQr!6Tsdlqy*W>*azYFzc(E8fUmGm0OZvc@rOk8J% z-`+G&_=N-N7;4xS0X2_~cqqUb%ZiBmw=IDkxKe^k5`1F;)xa@ox{JK>13NjG@w}`W zGZ>2r?}OK8n&y@*B#%-@)yB*u4k3JanxzJ(CgkN2B{Kr@szY8l7^ z3)abF?TI;u^svebBbHz$s7q!cV?}*G!YOzh0o-QNz7~|N)Fi{nV2AxCGe>`&FHfDNaK07P>Z!&}C2|wcLCy0z!E}m5HwC zE@uY8mtIrzIjZGsbm#<)qmt=Mk#+3dFoNJ=Jvo;Za8SVmfYSzWmnQ(%Wm1}T*O9>z zY$CS|56WF}I5jn0eT0%9`V;bGR6hP*JrvCp#v)GOSQ@<&8gjHuNCEb!D@-nOu8zV6 zI+;-T&ja;GhTG66lhi#_Wm%F0 zrOC<3$6z*T>}nEFuK^eHj@Pjl=a;0Qy(l7!x=Cqytk)7*mHwx( zxvDCnwS!nRlAv3Ge^_H9I$(Hs&<22TyI=eJXZPPQ#f~JaMQv)?F~asq8s7u>?yon1XuUBI&e<|*V+dD1U;Byfk~JLL2UpsxcRBbJ zsUJ|B9PfqX9#^HEf;s zCiPN6gH2=X$}|B~1z+^rgHsE3IS3^J;nXQtFlhbHSEqrr)}k22)6>&OPr=O0+^W(N z1wYo5Y+^f?jYjuPh_0le$Hpp|7yqY#4_$8wMnOGHFW+ubZ@ZC2d(pPZ(0YIUsvAx3 zOlHquHaGgboR;cW^50;~lr=`pIw@35=XVn>`9yaJH3ONH+onI^lE1Ya;(3aLrSdYCvo*wknLAkiO=zJcl3; zA`~@s;wh4}i2SO`EcmJNFFi)&0EL~jNAD(d9c-gIeQzQXC!7e{ABcJNgt#c-735gL zrwhRYw|{Z$KjDys7pg@1rlbgnExQu_ZX{yF9YMx$RVSPe_doo;5;X|SMc%*V28w||s_AjDuX;GF%q z+0cg6h?QlX)cq0v(^lDu!I3vZtu{Ev&we~`vBwXK4sSH!DIFnM zC>gCGaVosYF+XD?eZwt}vR+BIV(Bc@kEcj970XV7Eq_>g)gNHwV=nqDjR!g;`DMAJ zcg*uuT6iwVGbLh5_q%2?}o63T6@w)!nEk=H%$6 zu&?lckt|Cn(}|=dY(m2vSr^#_Z+8_y_vSiFT4Phurk6e$J~jsGch4~qwm6uzj<%Mr z{*J1y%;bCg9 zx4FqBQ1xjY88y1U*QIB$HK?em|Dl}K!4bh);FrP6B&Vu6U9BD0^Qn8Nl60IO4kG zj0-S>;e?~Zmm6SjD3ocUB#&;}i*%b1DdOcl&S2I5z95IMn2nMnFCO173`ncVzio9I z40=2#-J7Mplfsu#`bzxm^ziikpFgn=S`fJm8b6BE+(HFW5vus!632w;`ja*t$cC#j zJ2f;MM=rN5zla=L2$6CU5=yC{43S9kPlJA}QkW0lyjnfW#WcrJPlc^qk|M>GAV4>J zL;{7&UA;G8mcr2zjTlKBUR`mDy8^hZ)P?n0eMuZomJJa&!NAu}beCsrfh0*Mx~T@k z4s?s4pnh@^R|~hwpgkB0pl67UMWXu(==O4>hzKE^Wsekbo_utAK##6p?N&|{zy7*)3tSc|=TB}+MgOY{&>c;$!@Z4Z@{5+||yfb1^< zhAd(WM6`_W2H61Asu0X9#7UDtT}>;AI?MIHMH*^6k(*#3u(3kQP|Ct(H=VF<-pN{K zcz)@2`F9od-*uH~m(%cbP5pN**S|N9dSMg~_X6cSn=rEF9lh@RvzAAq3{#&}bsh@p zNx_DKo_+qO5>E?HOON_%Tq?E-CVj+y05_vt)f92b#E^6jlYjP;aIu13UFOMF?iVV7 z7bms3aPzsCX7N3pY7qnbjI@po%6VD|-yhG$^7^ z4{z^#83(i%EsU!~c<4zYC}q&@mz{-L_%c~8H)yNjcxfq-9ja3YKRAS$PUMk_*=(|3e%3u*moG{BmkAnl&-Scp;8fwMoIGGB9q`H<07ac zj?P68Hj`lk6r{E0{zCGOUs~q8ie}sN^*XbvTb^EC?8FAam7LX>53Is03CYf7MgW=7 zu-(%y=r{CNGjGz#LE`jviQ<7z=meUHe=sH#wGKjkZ*yGwCd)#6LnufJvPFx4bN86H zV}xSW=`Ko^sTt8iZdVsYteIy4jfDe``GF@`ry8}6xsV;2Ub+T4mls!+8ku}QHQ1Mu z9(URrs@QJXWhE?#bApOZ3MbI2bECOZS&2`q(y zsd0^?LVW;@=^cswj-WV@z%KMzp|Sn<_7{K_2g%^l{DP$1p3LLynHADNYEKU23~rYc zIrfnN2G{F5BD4r2AUXz8`WuLX#k|o9#0TD;s$-MQ!GtI3+CL-PS_vKsDtNuxrfd13{C_%#I7FU12o0*9tU)r}IUyJ#- zNuK5X2`f+YVt40S_m5WRBVCJ@6|!IQ`#9bFxpn2*ylhDfQFyFR211fFE6PPW7PNBh z9Vfkgj<*avJ}7Ud)AwiIx@T1uC9+%PMf%fcFzC%&y)OJ&I;KNl_&KI8a2Kj!#1>)B zhde zpvI&SZa62t{qmo_KcdZv$H!|E+Ti_Uejj0n6Jxoift@;ao_QT@f`*0{|T;*_KJJ;HZ zZ|Zly645f~iD~;46)DBaQ1-m=3t>nuHJODo*iq0@;ZO_~#iV>Hxv z;QUVKwE`|V2}zw!m<8AF#s-ix`iUXp`fsfcBUjKvC}a8tA*`Jw*ex+EjguHrIrJlG ziF#kl>gytm3pcqb+Y6D;VsS)3z~OkQj&GmyDBSC(=Z?)psGg#+2|f)9m>F9&ZN}fuVPheoj;AlsF0&fS7D_Z zv{}`(eH0!@${@<=M`Y1v3Ft#`NDsF9?g5|P9&I}2oP7fI0TTh4^Vr8!07ObX5;`2oYjFw0j+MCG zHmx&~LKor?6cOatA|Bwai^pJg8E2(NC8qI6_yLT;2P^Ull>$n{ChCY#zrRP$D48lc)l8spmp@=F#m~c8}t{*|Mx&v+;Y5E)1TAv`c<|3sQ@5%5KOU2ej{`Df>Sk&I)v&HG_O8H)~$1&TgL zucyCy{!G;_2pCZ9q{Kz*F;mpA;k4kewc)7Om|IE~Q1~$wV43TZzNJq$ii4b7mZhJ= z6hZt9Gn|+LG4X&!>5w*XXXqUZNhJ6p7%X@p=%xxl_-+p6v4!`5jxFv%&*gGuqxI9c z2%-$ks^I!FPS|8|rx9M4Dge-M1xPZ#-W4QTYG9v3v%1$<5d#yr0WBV@Ux?jJ6;7W} zHk%`W18^PgG?Gay1hmOQN`)y$9HBb`TDFu)@eoTnm`2|b*Fc+P#u+IP8cYd({Q-=? z(v;tp?(%;7NAW_ZMZbkhl#jW&?+-=jng*oNcuXeK&7jx}(S4Jk?XhTP9F8|LquvNV z-&{VK&lL=MdS-c>?SET``Fm?L&z3PvVB-Je(sxb3pn7TC+IW4V7*#PgZp3i$>w{in zW23wI&t~Zlittud+)Z6j^nMZTcZa9k{m^x6xlDi3TZOL zJd4F|?b?dRZ2C*0t(9KBmAy5h=clgU3`!mnJbirHYlJ1U*BAGnvTQhpFF8$%g13#n zn9Xv{n5%hw(g8`aOW}F&@$xn<7?`S{&rDy(Y|8%zuXwq)+`F=UOyX-+qV?WLXV)?> z6jna4s!IyfyGncDsmwGO;;Y0BPCkWXQC5f4Oogf_DRF)zS!;EHh@)deVT!y005SUC z;VJrR2dFV~oF%BZr;Hd$*!Ex>GjIT10Ir6y3LiCGl~CVP^xC7Aqua;DR|TJ^2dMYj)!;Ld{ke$y&Or1 zW7UnSbXdak8Tq&H$#(6^T^3!vK*Wh0 zld|)CPjY6WCOmkrO^iht2$jWX zLi1vkg4yK$8;}nJi^++DC)M&zfMD4>Bbg5OQQunO2tr0iR*Lmrm$Fo*D7cTWN4Z{v z^pvaWxK>MbcJ}-C33Is>qOh7fa&qkgSwJVR*zF8Y6gt^Kte91Q5)NN9jF-)TBRpR1wO!CgaF=Z%!)k z5F~!}ukI?@Sje8lEwNDSZX5M4`owf)^6AIM{&0z%`)FiQ(Y_ItGdS>hZ-3c#j3Kt{ z>{x**Ge3)nC@()3^}uW?j=s6J3#ZNV&_-dg%JS$8NHpQZBpJAQlUGGDa!z z-Tn;#9RIFV{1>s#G#(M6^XS(9PRu;!hKdM@7yZ$C(&AA=S|W3@F!|W!z$cfX5hB3t zqHn0EsX51{q^ddx%M-}2Nt`!mO5jyMnjKW+F=&>0=H4=@C6vSeg`G3ovQH$^Y3!>i zA`EpG?)YZv@8t8;5+iz_YC0eO0Q1AWMZ14;tMYsV^4{*NgLo+GY^HPJQ>)xb2n19T zS*UB%=?ce+cIl`M#I3(I^MOH&u)wNcKtLc@)aQJT;=8oUymI8<(fCYOBqAA1HEkr$ zfLf_EduTN+WY(9hfrSO9^NTE9b7s1E)!Bkwv9G>;1#UBc4od$jlwG`#Pa-FASB{Bp z!~A6LDXwaYOXJ0M+Gxd3H2oX!Zo0`J$2Ltejg7)DX429AFE-v zheHFNnk=YQA5AsM&ckR~N_ajxYiQoA<-xB8hL-e&LR`^Lo7%TYt*L%tMcdMim2pJV z36>w}@zwBh$(%>N*)oJH63?pJ^ta%!4^;)&>A&o2TF|YFD;&Tb!vQ(t&L(4zS+8(u zs~wN|ZNrYYaH|MIbSA{HlLHh?$w`BDm)*B1MGguPS65Fb+>j@u{J2TLt0p)xU51S` z1uUWOVvJ=`7L1 z*6THe4#=_uOfua4m!@5#lf{AEv3$RLc=Boz{{8hQP(#k9Eu+J3*y``gSup!qWsX$T?{XpO zwn9a#eC+Qc%G|`0uRkjv7kNTLdPN0ir=Mz6&b*3_!Y2%h0;K6-#h&!K3zbi40SqdA zO~1d_2LPWrVstV@j9(;z-iJfiB_}N3Pi8VWAG7?q((cPy_TK_*F)m4F1$?J<9@q?a zbeufsnQ=;RQlt#$G92ip`O=oD@!(X9=KS0=cRtu(ZN&)+tonM>dfi+cO6jOgQhj58jl#4v5aM4)^6=##PH8b&n|DrE^-O_tgWFTMD`l3 z8f#%P<9>Drhh0myLPR%*8$jo#=?59GpApHXLU99~^(PN4MV2HtMPn{c#X6@IIt_k8B3Y!nMcm1FmCp0ZQGOd4m!cwx$pU27%zCQJag`v!3 zWQB{{antHV;`amNP*L;2Cw$3^$JJ zY=63ru$-NSBR8)&kj;PwK`J98aOjFs-*ix%El?<Jf^UKjpz~AXfBM@fcSgIfSQtB5?VRn03(Al%xzrz{0;V(Bo#t-6x5ru_? zyV@iHKj42+gV--{wZMh9tXp8>(aQWmxv$Z4iaGqlsm0&$K&O9waH&gBZog*yUHVqjhvR4F*} z1iAk6?gLUOSsu3ZW3o1(3d}ik*C*kDDL;(~mC3+@UKd~GBe-)jJ2mw_lX`GEHm^CN zvhOO2B+_p=FdkB{5=C*1i@l(K36+aEgMi&Rv0~`+3rlc6txa3O>0^D5q0fy{f)-+l z_TRun?>)*eBfxTs`L@7lY%k&Kd+g@<;8Kv0Ky>%W=h`Ka0tyy?qiUx)}PBhU+{_mg% zay(D(HVpJRAkWX3Q88SpkS~cc_&FjcpS^_`D8RAV?KyT-IY$5c2mXD=bxz#f3xWdI zD^2ph50*d>UPjGw`M?7T5F=2^5@Bm`NaRlCaHwsdj4bIqsi>i=p?OzzgUIE~F=+yH zzLAO)G5%c;E4LZ&PhRSa*+#V)D_K2cqKxJr!WljPs4w0kS)@V*G zunr=O^9+f%>VR`6&`1IJ^eK6a`upKD{xq>X@fWa@sbCmvaNs~pKyDJOXX_{;I8udj z1xgLckrVl8`CXv-VbFf zpVy}rW#!TRhycZtKc0M6#Zz~u6OS>=fQ>jllY|XU^JwbP)85J9`TNF`=E=NDYPlrC z_SQDL8!p(6UT1{L`Y@12f>cUAScq1=L#|p zR$cf6SX7(9(Mz2Xs)9=uym8G-2YKsSdFS6~GcR^8lONlmzp2Q|glgbGV~2V|i_5WP zlL_EEOHs#f&wmb$)IMNDojaal0)JeK3dA+VT=gTH1NNF`DD zXT+>j!P%J0raV=O!gYAH_dc0b>iSwaON85G>1mvKF)V{~>#SW~O~<aeV+h-isH=n z+Dad7_^54JxsJN@#u3e#cyse;rFqvzos$R0%sxXVU9hk!>MfvhADV}svjg6W)7Zs? zK?h1~|CDR+G30T!Ss&RTN2spzK_*SAn0TmnQnwfBQ78|GVE3O`{}ui|-_52a296Ja zbE|hXqA$lBc6E+nXBk40mhXGu0thBOLT=zeh`8kUrfqMlxgsPi4l~TM{9f`jZK{l; zIt$l237K+wG)X)WaNc26s9iHc5wcv4_2(tYPyDs!__;OGpwP-@u>Al6S+h6;CXR=I z9ny4!zOqj-mk;q5q|x6jJ$)Eh*4ogsvmdCSj+-ha@GPOTi!e)1Vi;*vBjphKW+N;% zlcD{vQtz>aAY-z`uiRBAWRQ}W5_GuH5QUaG1zZXq<=kpYz8iW10jaS8jBAjU&CQO=5}F$pmn(rz8y~s?C8LhUvhWg{k6Zr5 zemgr~1kgJPN}qo$kWFtUJ|!t&UTg;*JT{`rCMPF?;55vtaU+cKl%!DoU3$8DXHPDL zT}^*ERQOyCaIF)gRAr46ez$0Eh3v73lMS0mItsCrwXiM|QIPpx^kd@PWz1#y9=Kll}q~F<1RTdVWu_yb% z&)wI7*FxJ*GktwfTAwgw3TY;REe)Rlz+5_Ni^XOl?vO_u-TDdot++ur}8` zac91tKAASxl=E>pjcyYElRg{_M!aIyEkW=f0@_wulp8dt&}C=`f4C5$LS(ykM7=rS zl3OSF5K;|P{D-GYVIAe!pbBVlsE5sr8IwVGvM}%A&KaK4^jVs+iRcW?L4e@8_rGLa zet%0hq^F(8Is#FvDy^gAWBOZ7qD4fx!fC?sQO?i2 zTJNvPbtl1x;km@_wW#4y@Am2EQ5s-%W?mO1cMb}AZm#dwqB4p0%wv|FlVzIOg4Zux zr-kEH?)TZ1q`&?o`aitA>#!!kIjtCX2TUG0*g#N~>0?-0RR^QcX)3sJcyQMN?)bvi z^5*Pp_D`OqgoMq&6^!73YYZ@MZc}Y-q#dV_V;Gru#)d{FOa@HtaOdu(a9fM0{r=C@ zRXGpE!MMypl6pg(D&@~^!}skEx>5W_Rd8l0#@y|99=#7FU=TTpRG_BeSG6}|9qBDb%XQZarq6!n} z4)HUDQW43m78lIq75hUD@Araesz0rPp$wxDZDQ&V4z~I8{nFyc8uJ2NA2M`th`3q< ztd16gAX&O@tUS}F;DDxpK1bGmswNZ{jehaP#nR^Ww!GPvU={CSmmSdNN*)c*%M=nsIi|8{eX@s93sm zRK9O{gv|pwcL65;ZS|jWUG9D+gB*izfduDR?)K=X!-?YzF4vPe@7cu^#vR{ZAHE!u z6nUW~cRPD~>Pz_2lElw-E1O0lZ$!ORUw?9QcijG{Hsq{OJUo@xX8$!0(c|w0;`uhK z@M&0BGNtK`@v1+YFX&Fe9@{e_3`r2eT*hN&EbC)TIRUB){q;XhYU?VW{Sr;;270ZT zpfOJYNuoAY9OJarai3+b~%(RZInV+P=G~dGBHX59o_GrN`b}FfRkwVg>vF(ia*{y6DeD-1YllpUQg{uPJ!CKZpblA%&YlflrpOv_Hs5Lh(3y0o-8 zXC_+f{d~7pYe4aM^|#0W=HO3Ml)0i}dfTTIU2#f{UXrt~TE)Kl0C*w8UP>HYAuTBrIaNBi0f_1_p1c`UR=vBR!0(T(4z z2u@HHM=X5-6)P1xDuThR5GBk~%d8L-q7Cgy7?GRb90>gk2)ry{uFDty!egTpg_)8I z4NVY(r8c{6Bw1GM5%{(ZZH=RfWGFhDw-D~DWTB=N#n(**1wcbXxP+G_ig2St_%B{z zhEY?k$fEDnnWht6-6ca#D&90kRBbsQnP^p-#Q3O~9&Gr>m8v&xtF>z6@j^4CRV1UR zIVVDJ`pc;JQ~;&>rs)nLXyI{x{Xcgj-S zlNvrk>XhcV(g&S!K8%p{R2*t9UgNCH56_CHca1!{DeGEe#YJPR8Dx$kN9!C+va zIbbd$+VgercWBMYfhYr-T^g>_RPe;zB1kiF0U9xr0-+Aark#dUnc2G|>r#mKhdcFo0 z%^mJUQSIwTB6Et2$%Q1vb`&t((Wsua^+aACP)w>jKRX)+d1~6w>|c`s>cHM1Qy+_I zmx!J1$L(+o(Xnnw?PS}~FdhBo!oYl!Mj2?a@hqq53uv|6kuIZT|0y6&DQV`$Gdd2{_kt4VOaHzgjm`u=BTfuGpofG+Wn=YG{2C3esFY1`ELa?9 z?yPKY*JC`}XRLhheF&%6cpAbHySzA=IBb5{|8~U3DN_!a?;9!zp-~Pm!FImnZ0MAF%QchLsIVjdf&BPlQa|9e^|^I;xJ; zmkO$t4T04mQ9&H-n4JZPA!uTfW z@VK4ks|WU=?=!`bqd!SZrQqAvn&JPJ&5%YP?J)L~LW*BnULFx_ny9IHYk6AxZ+9B# zZ1e-SfdBHB8@Z9C(l|i0)}!-(>mh*clvLvnN5^z9)gZ*1EmeOpgywK_;As>|t9}lP$HC;H6#RfZ z*Oq&Ql2lC()%&9oZc%YiqDAaQS{zgX4Af_+Tneo{8Q1<&Sh^qGI%YQP< zoF#;foc@w6WqQtBsHrIHLrv1=_73B*Sy~HptVs9oonu@lZjYP z6|XDmVH-H^+bQGkP5#ltHA~{mgs<=(3lH!fE90vqUP+UVBln!fg6Chufa(<&VlpH@ zr-s#FeQR@px4yo+H5G2yjQf`6T%!66l-3)m%%cErM=>|tl3oC*>FU^joUFej&Xv>B z5V-x51Tm=vrLyL@bhJ=9(DK5~ZNLMDP>>R79k3I=AolP0pP`N~7L$PU|7*{H*NNd% z3Or^Vg8}5^zuI$?^)xX^mVhpReeC_h1XGI$OKnFkMfY2wycPezxI1CSLJ}kmPVH6O zI_vy#rRSmbINv`BR@7$uM8VEN>QYHAhBM4M5O5d7Da6F`KxsoD;c20Qf`Y)qt_5(P zPK1U+H&NuZdzw`(!v6zjXV0ed!Yl%C)efe-#t?KQHG*z#`HO0bXR;kQvk<9~wHn{! z1%NnrwYI+8^~F}+Cz#o_T%oM1fXVOA>H&BYHqVLVE5hV*1~IX^+bn1vJ1y)Hz6q6+ zlqLZz$hrc1Tbcg3AAXbZ5}SHz)Im=WN9)2J(Ts^z$))>t`m2cxc!F&lxbNG~*O%^n zs4c~xHnTqfCJcc_UyXwYGu!9>_Wm984}R@?e><|U&7ANAeH`?ORcO}X3Bht${f9oJ z_Y))OkCpN5ra8WDszTY~@>alj8H;wEzIjjKC+oxnjZ{O9zu?nZMFO@?$G6(=0hPLp z)FT1%NanFpGVNaFy|Q0^U9t|aku`YV$OY&ZL4N_R=I@iiPi$~x5A6MU-Dv0)tTpuR zi|`s=(4jC!?bRUw{+jWOWumjlIE<0T_N$oDhQ8?Y(}4z z8L?Es?k!EoD=hPEg6qX87XJcMCWC{T_t>*Jg&WM0G#zBiBSt_WcxGQ#+FfZmpQf)h zkzIYBO$kG(z!X!ulm}ytlo{fC;2~(yhvc2hhoCjfH(WyJIHDmqFrD>YKrn#q?Su)Y%Gpca( zVCU!{if)SA#H<%|E6IaQ!+~3Ij}&#J*fO!y^hC_Ez2PJBj+8dWVamySRrdu6&tJI{ zT$odrk;h2OCa|!WZD+@diz=$8BB-1`k}_oJaSGxkD`U=AK}d7sA~i)@Qn*_u@y8$) z)=q446Li_q7bj&?DVrux%2DL)Bb>*NV2+7_;epN>dwk^ATW0`B)Fv;jCgIfNj~pxi zxsriAFI`#!1I#aGx?_sK>%8&k-}~1eXg-h3K=98ZxvPJx+JoUV6ZMX*r+mKulim_X)CcgwKhmj#399nYN_#7?VtF5@2f=S(@{7v#D| z8es(|(KIezy$~LL%hus}xKsR23E}wLF#CR&hw~GpGdB0j;HB=zS|v_yf`k)JgGoN)*mt|WGD&Z zscIPHT$n`35eU6!Au5vA3FW|&K8E}^tK`+%4MLDGdkrn3t(~aMu6sN{Cd7PUU9_(f zCK{qA)}NmCHYYW3mj=@)CbK?%y+YVscNEjZ83_%1FbyJ;G-0*uX^o?$Zxbt4K*aTg zc`=%@b)2H!|6PBP!ex?X8H(OK0qb^)VVHW6^`L7{Jrg z8f(Tm9!oTqWaTQZ)cm0(2Nx~^n+IE!MLN_~p`-|2En*NuRA_bs59=2xIjNnydz!;l zlhx#JR^|Bght4yVeBqfLDJiMrpUI}&GYH$wV)u6B4?EZ+GwKvC14JFZ$Z$1#JkxKh z0TD|cTnAKyh$OkL`c_5Y`gpY34!O%I)Z34Ra~ykcXbUxF2S=Qr`7-Hby?oq}l1SJ{NMO%CU!;t$uOg*8NSP;!9uGCZtyjF+G8(b zJV0ROS;+b^NckH8u4M2d#y_eKVrj$3Pf%f}@4qqrrCg4m{#sw30D<`t!_oJ*pKG^& z0CW!ji?6KH>D7;J-Qv~2eB_=s3DOhAoPc)PU`@2tHzY*s(%1P)7 z2}wF3p)rS2p4rmnYOhwVLpv}bLFGxLMg@4uhr!Y*LGgS3DEvSNv23hi`k;!WC-5Rc zk|7cHV-O)PNpndgRGPz^E@`O9K?Bpr-27v@S9BBt0o&EFI=cqZu+)5#O2WxlqH$Bx zVcIa)(}=w)`at#9@l=?UzXxj`kC|B3`N7#55L~$4fpJJeEKyBGH(fUO=fSAcKD3fl znvT%|_k2HxDd0ImLhVD3_q5Ef#>FIOavkRA_ufC)N#6dC0eC1sY#27Kju~?5;TP|{ z&`w;B(H~F!ae;PQzRl&ZDdA9NZ6xea&(rVSo#%1*`rU_nI%A|I&01i-Y98d}SlVL# zM7LtpX|*Ses41F4;u@DDyqxRJ`<%^V}b_l3A6vs z%u($>fk7EnBSG0WQVGY;jRjQsH__&qs{ujtv(mx*<;1eNfwW%EDb$^Dg@4#%}7yvP99E>@w@YHpS%r>9^sU=#g`4grGDU@-ScaR}5Y zo&e!o!_qx78#+qEcRQXsyHHkFW_D;*Y_U2-9%%bA`^Y6IWbpx-N{TRSUd+%FaS?PW zG=Bz6*vH-xJKYp1ZX{&Ky01Jg)HDep6$(z%SF@&n_nto8{vh!eip%>1o;fnq`SwJ_ z_4}w?Q&HnbN57q;CvaaKmed@JdU9OyC~pel*^lh$&_s08Re~=HB*q?r1a4>yP;y!= z1=Mp?<@zFiv!q0UdY1wY_Bl8O^0!TR;M&w}~^iEkT?ZS!)yisj#L*}p9WT4V{t zqdmSsm!&kfUB5^llT_kt>dd0}Q1Vc+XxwE^nI|*iz9}0%?8Om8S{53s-UD+fb!wh_ z*JMHl40UH7_~vu#CL%E@1xeGefisTX5+0#_(hzzW9NIZN^iKCIQH^Rn$fWYI1CX_DL6Do`R7RW_gJKdAvuSAU$+ z@8ACdX~EUWNndq(dODDB`%p0;TV5+75r-X1YLxv1m1pO@^L*tp{fMp*qMuoLU&`2Cv7Q9&Q_|-a3pr3H2 zoh1RHFQDWC9C8^<++P?}AVK$sZ~hM#v`nMhx*URB%?ef{U46DeJKwXmQP2MLk_`z& zi&2^5l$5o~H})Gfy2~5*YvBH35X<+?OY^GBp{SgMTUz`vxy(jvIB;0?fHV|_r-h0h zT=3rqQikZHv-_X;0_YO-&)6vb8Z&)WuYkuTl-B%qF8~_{FRz6}CtM8m8)~5T11z#p zA(|=Ok~E#;eG2>RXIybyg+UkAqNo_*haRlFJ!^x+DS~vtsyx+U&mgdg9z1la)!1>Arz>auaph)D_)`qx=8Sn-Z58k4VeCn>feOW)cZ@u^C z@oweuZUYiqUT<%1-s7$;gxE{S50tk&&99xKP}E0%qSWeOLVfp2LR!g93F-QX@QyK|I@%=!k|cwLjz zX-)v&UD!EV)G^)5c22>EAZcpJiff&$Hj8Ggsf#~)zLX`dwhYbSuBTc5|fF57$ z7bvKIckbRTp79<^^o!$!CKw9Kf<*yTjYUNKB~b9y(^q zL@6`2IypVAc%TFVSe`8h(Y3KAC?KK<{~@+$R30xq{H>sqU^Vaop1~)3hTfmVpYr# zL~&onflx~sWb@2gj=?JWQo6d&c%cc3N6-vfIi^s3nE@fQ(mr!M)Y6!tu6vokrQOw0 zik6D`y$Qh)G@EmC>r0zilhz7{MA%5^Mq-C4DIX1X?zmNkcBOTh{JzBLjHo~|RAd$Q ztzx)}m8KfW`-7Qox&HCP8xPH|eN{l?SLPw37RZ^oTGtWf11nqo$+G7?{3_)xP1=59 zvlr-(ak=H|=y?~Q=s}XsnmP4i z*03T1>gR1?ln)oOXH!0vCqfw0K3Rr-R<@4?XcHO|R-Aa5^HnIp z%GDQT-}HX|xr7a7?S29=UymjNNU~#I%gv+WZNuOCx$aJ%o@UwtY;1};yJr_RXSabx zE-h{=9~wCooubZWv%==a-jc?OPurV0=g!mK+`f5Az-a}tfR$8Nifrc~z-xYu^kp0K z#k)EQN}yj*=Dr-_LXS4ll#k2=Y2JTO_a0Ed)r?VCDwKQ=CDRrCj5(t!WClwJ+f`>T z{?KSui-#G0>bSNTcQ{N_Yz3aA`GL91ZW{>gI#HU*%uj`fpiInIO5;iOw1X63`<%ng zff9zosmnvMrd0S{XFP`u>>|Y}=6;s_Jubzn&(b(bB|7QJ96zFv=1opvBSTg>1?82S zredST*Mg&QK6whUaTBZ{&T4O*&p|Od!*6%H7@7p>rB5$J<+7+V%Rs3X{W*v{8oSsV}?^23X0YTE-1gBF9Kdid#1T4C_6Z>9BivSdIXZrnmryPc4V(zW zw5%2m-sp9oy*_G3+;m!5;_EjYR@qNM$6p>s&!CvZp@;T6gmf?m(Uq1+PL1CDz4ayT-}Io` zJBZV1###t@=t8U! z0Ol#D>?uS@#OPs@bktBc|KxHU4UO0TN|Rm*6uP;~d$GPf#eH2DCn7eHBTMhLyqiOk zgVElenk)YV_B?U_@WX9H<H!jVle@zqSv+K@{KEv9oO z*=J;27q%t4ozC5$AfMrAB`6VM!^HZX_J8#;deTnyOR*S7`@{|i05tUKsDa1@)TvQ} zu@9JzAy^4bhO8ZxR%EyRHVic*OO$mv*MaW)xEa~F(k?J=-P~U_w~@)HMe=RwO=rk% zgO(L0x>74ZUz8%9SqW0UAmH5+*)DHb@-$v!y1Gg1V_1GuCNynuT>m6XxBZ&JG#cYO z1pv|$9JYkh+^2pCT$bR_6x#cCNh5 zkFrUmPjksZ+=7DDe6cKQAF5CRBe-3 zF{2z$`m-&ndnQmIc6ry+zxMfrVU7)FX-3p(gr-!Qy5J+*aY)}E}g z=ikl2(8S|(UfksDur$u_8c|oK$Kw(7Z6U%Ks5!^guoLKL4SCwW5T{17$d2teQY-V_ zC%Bs2+ed1L_AFM!)vRcWPAW|@sYGyYr7DP3ghpm(k|VX29aW}S4L-Pw9e12*?h(KH zld4vgQP`ksyOXnc?8F}aZ}Y#eXqC2+8O2-|Gr;;OE|M_fV;)|^wFK3-$$2@HfxzP% zFP#spq!X4mRqYSYHKj|?WLB5||Av0I6&OXBP@69OcIiT-n2$pIH^SHR=cFWASxIS4 zXAdn#xvKhJb6<<{Mn{10K z$vL6ZqMC=xuY?OxgTqX?}LuW|#?p^D@5uMDoBtf4hWSF1sfgxRY6U zlz1>7Ordvl3ZxS77S&)`T010K_aH(4UN}`JRHhvIOT5QOk}bVlUkb=RGu^n{2;ENh zh4RmJrU?Whj~X>ewZn-rI84T5k_gXAl8Anml4LTn{z@jZ8f4r*Ze);1vfK3n#rDr7 z4mTlsUkYHNlubKmG^Qv2V%I&;BJ~qGY|tMLT&VKYo!(U-Wmu|I$Wc&_eqT};ZZ7cb zJO9o7%s@`kam1yK&?wI=Iysa|k;^v0?ZBY2kQ1gFW}w3Tu!s-}(+9KzKS*Sf!jNnI z1E@$p|65(d2mw0{k1I(21}%WNl1)zA+!k4L%ya6A zwqW=n8I?|W9Gk$ZbWCW{8GIqFmV{(PV)btyDQfL*sJY8W9-2z~#}A>IK8jrFZrmMT zPWzh51}z=9${Otj#|~bYmzo2o5AVa*6cJ^)mgZI+6362MZt3-2$c%_yIl0aHK@=MS z@9;yfYibK?8B*4un@Lg<4do>0X|B!>O9D_dE-UU2-uD?#8 zSZlsLl}#cS@*i+Wdc70&DJSNq!SX3|JO|lLOoDPr8SL2~nhNES`@ni4R_L=CE#`;{ zj+6PtQ5B=1PqR3D#MpDW&TF$P+gQU~TxIeMpCx6M&s9`1tLM1=pT7T_6C*pJ@Ls@7 zL~Vq%eKQz&`z-ZI*CfJ(bygch4Ud!>Svcqw9gj|l@To36AWC|XX7gG@EEX8=A{Jk(ABaYJ#QK6EFh z?)lW-A$(;%!-XmP7SDST7~^herl^kP{)K*&CSDPCXxJa2e~z$_)*qA-o^Om!-P6R( z38||`g`FzFz5Rpd43aJ;#+qgLqC|14yL4iA-x~d0WWYmDo%|h%|0rG9uJ}i{P2^0( z<=E3G+VI932fll_-AgR-uupmkoF%mcZVrXOVMD#SS>0<2=ox+z6bqUP;FHV@C?n2# z+D@1bT@fcYeOK3Net%$zE#~*EPPA6tV;SxCb*S~lsd+L)S6gMgUME^`bQ-uE5BLc; z-jAE}Rwc619XIU@{%`Zt=VW3)vXQshtPH~boN;5AxJxf{si;eMSvA&6*4 z$ib;7yE%ULvbBxDEv>J|5R{hZ_q#g*_#555@8`YFE-nnmA?frFd7Q~IFH#Ss1he&k zENuHRaT|C=$;(to_qb9GXelv{rHX>Ufo}k0CGbzYiKStbg(`yiZP-G*+DX}!XHiDJ z7{*S7gvPQ=7Ef9cyyj=DU=gg4%JR|(TmFwQ@L#?Y%gfRfJ6}B(u5~2oRDnu2Z|3Q4 zqob!fZORoj+~^Oj)=Pfhnc4)b4ZKdgdz?<#9&o3I4ZZ(M?iLGu_||^)I>+^I?5(PYhQ)aV6WC2I5SGs}%Txofa?0(<(`?(*f2LClJAO>rMug~}GMYVv0o zrXgZTr2Q#v;S!wp&KnbF_kK1yc29A1$B^%hnh*Oe2)V~cYqE5WB3v4+-R-?Dk2az= ze?s5s?5MNT$SqDm<*CmLx$oc0I|M{OyL>WVrqm`A#lm6ecG>O``*$n0-ReLMCjJKBNLIz0;4JR+oeE?0{F=Uk@46u2rO8n1nB$@w!M{YRKqb;z8-oyYZbyAB505u?i*}=qx!DaC^IaTz)HeUBAtl=p zt@bcztlSsVwLxY}y`qck=l)x7RI<%Tm2n>s7l+>LC&E>AOtQ$Z{HU7{cYHZUnF_%y z)!fxy=QQv|wt(}iicY3MJIFpy`JhHUXZWZ9<2Hmd-yWj`Z>)-Yd~hT$^LZ;EblY5v zPDl7+$gI!F*O@^8=7u9%FzR`{Yexti%1n3QNbAseX_{(Er&E=Qlkuadza3HNt@o&e)CsQ|kK7574EM zNS`7$Ga>o@LMUC&AzT<-swwLVEysftaVh>7fxfygaTpB>7>NpM&TZH9V6|hymXpyv zl~L)f#@th0ReA^BkKN;lN9jP}v&A^=T?R9Q@{>=JG^$@U*Udg=1Zi!IuKW52NE-4f z43$L4ia%Rj*Uf}V@bf|;3atkU!|Q)V(yu*tWup|qU7eiVE*v`yMK4qQJ1^Y#;mpL6h zU}0lLapTZrE+Nk*ksLO4I#18O1x?O%ZQ$({(7Pv@jVN`3md2!P_ zFav>j4e;WWOm=RcMcyluG(d51jLuN{6@P;Fw0&k)-VrP^LtEq!hoZnA3dXP zE?@WMnNQDm^(z&Pr*4qA(Ck@+)cZEyor_!(;Za(}Nv)KigKokP@&H8T<0PRg;2*P6 z6n&wMf&Z5VNYphn;{75HSv_xxcabt$z0qJ_5DS$-c%s}n9!^y5kdeghEKOb?Km184 zn!2{~J&9U>5p*92kvx!c(h^7;XR^~$QLK^^bq>vDbit5Aw&u=k#{T+=Z7wxV6PxIU z7M?``Ka&Ep_5h3;#zG#yY^ZW2-_itOw`@Fauu^f86(t`jvwJ505`;ds=cl(*DiDCx zuj~Eu2s^$5o%UVlCt3KZdK5G}d+rWUa$Ds*4+(AL678+7-&Q1O*3JA5K}& zXHM*FVrhDfr=QAjglLgysq2<6mO$+INRrf9-|Ayh)Tr4f8BtZ6TwN{Iks(+kybEb# zD}%eWdzOT)5xpR4a3~WfPN^EN+$;>|!R<$@zJ+z0;95)?W9nZ~-^eV=xYhJzL`5S( zwpn>g;lCO~A6bK4+u zLt1yBIdUy6so46Xiqj@&qOc-`i6Eh_w{#W@M$GK}Kg2X3dcWF>O{QYJ{r~az{H-?! zXy&x`p?t=TKL?C5;`r5$8|_$X`jL2}DD(JslJ}vSBGVBqCYCU$+)8-LR4LOm0FkV< zJ`gRCF^^ZeB<3@WX;`@xPu^pHB*;nb@F&|mkKAW(CP>;2Qu0ymX)Xy4cFwYfQi_yc z(5cF_UAi~id_bP+^jrjckqmb8>tS^v*~4G28spB=`U;#)eYdP{s}a8xTm#NIeQpN| zzw-}3tr>qN&qCyH6jl+(Tb;H4+6d4Kp789pW{Z>Rv#+J@EH0D`qe1fob-YMwZ z>tlZH`JkrsIp-)Y7iCZ z+>!1;eSaf!MZo^A!@F$@*Rh6>22PDFePS8KqpwW(^g;1(_;LPsr|BP&iANv^H+b|T za?QuS`jzTL^Jt$Zt7~D4bAiYJf^SS_8atfB?Rx^DVy$z*4uW1nX9fvdmgNxlp^6Q^ z^V%=moPSWweMdswtI^@f>FzlX8qBLASwc-BRZEAM;wg?J{mTUHRzcy^Xf{J?ONIEz z3R;rC%-j@k8tm{g<%{#=!@Pe1J8NpVr)oHuPYP)?^) zofke@kgK?bUzc}2o#EZD0;qnQq4|5JE_L-ngcs8o_XLP99)Tjt!O1xE%FSyr2I3La zLc`jtpyrqd?8&YcP3OZ57kemL37ZaKarPn=&cFElur|)l*lr@SL2XzmaH|dK+imXo zIFH6XOO82UL`u$6cZ=$d5sUBh{N|oxEnr)E0^JYn=B)i`0z#a~nX2WCVO zlNd&QWCo(7#RxPK@aGv~HSkBE<#dhK`QOWy4JTAP<)n%BX=}fUA6on%%|sj$ z&zZMw?y#LJ#t8Zyj*9ZZ^93g>5<1qp%g6L6Fg>X2Lg~u6Bh*nZ3>3p9nlM zW!w2nsN>QjmzqB{zV7vlY)!t{RFt$2?Zw-0^|Hn11o5{8M0%{BMn-Phd3ODo$bYuo zIK+1wrWC^>HE7&_!Wt7w@lwh4P$J1G(9S6+2`{n3c1pWvFyOE@`I~h*>-ulqi)E55 z2sgTkCAC1XimBdm7`^j{-;C%>*H%8Xj_B;qK5DdG&Rk}_+((~s4a|dD1$z$rye~wQ zNV0|rS31AZ&p4Lqt5V%i%;I;f6m}yhenqZd;T^SoN{hwVV-&T>UkM5B`AcOI&!2<8 zc;E^IM8w=`)4IM+XNu%$})9t}?-%EEdJzVfUnh$mK zLRt(OQ6BNaSy6<=7|Wy!8hp@q|FryllQLz+{g-rP00h&dAH^B9bbdk{Bhgyh!E(vo z*?JkA-&#?A8GGt!&P-AO8l_LOplKeJ8MG*wn@c@voI9G^uca9!j!xzo9X%VB{WdCF zEh}piVbjDbxI~)kxIAe2gIp#2%h|Z2NEL65y&|Pzb81_TBS$SQg728WG^sCYTESY! z6dGqoJ&e&IwAL?%nC1$z>=?ul=v%bv8nABds(qO^O{=6k=leXPqNI6e=13i#2?fLG z9$P%peu9>%jesxx5YzFSc|X%pv-#Fp-IwsU&wM)Qxn^EJhHbM);j+)O?f#HHq;cx) z$d<#MH>8aXCCs<4JE%vhTq;I9Sv3UDsCq zoM11`Mo)6L8^(V4G&-edfmo3^V2N$23ME%b+61Qwd-L%WOb70^>SAjfn{ks)?@Khk4JcQJ0v;Hy z&wyqNKI~$>^_yi6i7a}ps($?nA_BtJ(~OVvRu_@l7*#c@cO7ebF79AQ z1XEc*w)p8zgDX}1z9St+I7NZJNLE=5dA@BOtWbJL%os1Gj1p<;+R)pqxFtEcIDYQq z?uNgDf8V10@Hx`J+i42X>O0cnFGiVo?kU)|`36E0^q1v^MmpI%DgBJ>8>J zjZ9tjk@scGUy54og%;DssI%CW^X1Dpl3D|!3zHPIEJYD-vw!DHWcAu_=Htq+cOPyj ziP=McqL`kpy0fL*Ic!nB(soy6XiVE3b9sT#Cy}_L1UR}`bUqn(TMG;>qmU$Ig8Lwu z9f>j`9}H0OSw&xJJQU%hCM{;l!Wot&4S>Isdp?_YgIOk|o2=5Okx&(10Qh|k4Ck>O zD_psCRs7MuMef@E_G3>`{R@o|yP<3xfTk12j0mwyOTe;+5*th={_d^3GLeGx<(9DF@1pjj(I>h*~j*1 zoQl0N+4%kYfmMFb#8Gzn2cE6rua-2caQTtresi%UE`>WFTkJ7iR zUoMwmaq7wPw}LI7`*y)ANz2A!+Cl*>ZjWEiS68P}=blslJpYLu`Sa)KMB2f!m`4;V zQH8-mqcJ3Z&C-53$Ekg(+{EFqrY{znE`d39-KVK<(!DP8_E4EX%vE{`a(Q4_VQT=t z!Yo%hfH2fKan4<{XqYbNQJV$DD|G9o?lu;zRES`qcEwo1(cY$&7mK`?Z-{E4e$h9) zrpC~^!0))Ur@a)uEsqK6xFfo@SX%&%bH|*u99af)yMBg zcz=(%iA!DQo0Pd_;^+(x6@P0e<@T=Y3A@WH!z)Oi1g}6 zjX(s6zkfJ_>m5`3V3B`V$&^E5_ovIR`g6`KDc!tNd|tsI*5Jq(a<~0c3VnHbxu3uP zPl02|?TnDhtsSwo{bumLxBpm}2M3lNhRZCN`gu-$L^cpNK)`-7U4g`4VxWfX+O~pP z;S>syq~$L|`KGmt4rWiUSF)V}PQl-^QW(H=x@#~XM>&2qB4ybGPo5G?`sP)>$x7^g zu-HN`En2}WofmuKz+|T+ZrLWUQdPWk&o2gT_bId7auffx1bJKzYQ~qb%h3_ox(z|n2^qHkh<+y%XK2sAwgGH@Nzt=lV=U7P%1~%>lmuIUD z2>F?@*m36!MIKJBxCp#~tc@RNm{iFzqQ+tZt-K9^zk<3BN@`}HsRGHYa>6E(! z1dzV|pU5*+{B#2Y{(@;VXsHe#46VhS38*z2&j(&kIukN*R-t#p3r|n&;woX1d*V{L zB~3N#+S%9Xl#%7-gMKr{U{~k(0rgyBYbYmewvMa8xX}7oq2=49M-CYBOI}kkY&U4230o@fRaJ9FxMexUNTd}_X0cWYNe&}g9Eq&L`oVdO z(LdHwm|nF^B~sjRG&0{Rj!qV#s(5~kw*;*)jQv2k6w>C zEqh>_Pa0xB%Yad)#@NAO5KAi4YCvkrhW(9}wCr^dlz%;=@hz>qx>;71ezcy;nvU8cO;PlSwKU0h?V@JTzgD!iz|JD23zImh1f`QCTcE~5&qrA` zO<{{qn5jg{iF2GCeWroTYqBmdu}~e63wT%!MWF##IeH)`QSiWVm=lyPc-cC2`SIqH zuA!@&fufEqn@9$bGR2i>*jVH}=^`~C-<(%u z380}%E}YmUu#jdqXo*=?#_UQ?)Qi}|9!5t~k4QO66-WH);O3!VC|5#dh!3xEp(>|_ z61zhmg|wig-2R`yLOLVn`xCOWaV$yZW{@sIWgfLX^M6LQd>1#DMnBA@%eX$GmoyAD zZ(D4~Rm>WbJCjwWi^KTz;`$!v_Vh?35ZPQDX9YIbCflTw(NQ=iwPDV1TFDNv4c~dD zFDf+YHwFsb_|fW>XGgleIbXW*)W7J^vZZ-gYMw7t3U;%J-R(Hukxp(^rvEo|7(FWc z_ssR-{pW6TNi&m(M4y%|Dlykcu5nYX&B4r9*iw;adO5-qazey1qx$}p6cW04O2gKG zU;3MTtOi@`J3ZQ5-v>Y5nl*FXkq!gCPOdf+uaRS2POv5wX$Sk0s!s52mN#;X=Hk{CRz>crkw5?$w}IS)H^=i9shWY|Iy*|(?Cfp zQZ2HjizZy0=#i8IjVyX051^uMv|a-3%{9*CkG$XxG9$8XLBC3PVxQU>B!oDA=P%}1 z+(kEBg)tWwg4)`T+H@XzG#q;h+&^esUt9`#J(h4Cqz!cG6)`_UD$>M{B<_4_fdQa~ zK8C>?w^DJxsY^n;7|p?)>WZ>EGW55|o!~>s{S8v^pgpodv9yO)*ot>vG4d_H+Kig? zjdarNl0LscXR4$NsDujD3!739UyD-NFgGP>SN5n4A!DP3VS%#?wLazK1RJ+Zz~8p> zQ9(EO@OH}g5$T71QpQ(C23XVciA|UzUt$6jGITAOo&V0khXHpl-(C~aaKmy9A&s4` z0xmTKR{7HpRr$VnGCB=^&#pAt$%F!X_Mh|eXM0xjDiQJ-aC*UErZWQZ2nZSMBy6Yg zRpf~(syBjwvVc0Z*}Ghf!H<+ea*Q>iZk?fC2$cGml{&?8`KP^}l*t$W<+&SX7bQo# zt)+=MEs5#RHweWGJkLZaA z%?}hN12Ysy$7(UTs69&soDZ}-PvX$R=^)>pa`8VTuiMZ;CxIK5Z2xd8+A>9 zEv#&UE&?uI`nVst2$^5z#-{?M0;9~X>=Iu{_R|veZVR_USAoqt;8T^ zhG!qj=A5ckE7g5St5R<1Q*9D67xQ$p+0>4>GG!ar?v1&ZF?-vU1<7=|o@)_%jrX-s z%jJm>lchf6=~|k>cSBKbtoB^Szdh2?^&O>rKdh3|_Pk_rzWxfI?Y;Z^?)rsn+fo?; zmh|n(%YhR=T`}#T)^j)!k+VB_J-P9fLjo&?jwFIG zhn2?p9H-#o^hDl;7OTiDb_OFx%pAT0F>~*q9Yq-WVm76CuTP#}!I5;8G*ud1(G$iCN02Gamio#ZekUSQKm@lPjhBwRQQWb zBx_L~tRO|wM~4z>$cZvx1|6&hMfF|0SWOXAt32+JR>ioSjGt}6NB!c`BXBVbCjIP_ z$5L`?e`Ndb!b!fAP?%EW=Uj^6eKCij2W5zD<@ib60jdsk_3WUJlhchk=JC||iIiOX zl+mk^+U#?Mg;#@yp+%kX;v|e_p(B`^djvBWPPru=ACOBt=*zd%8BLVcVAAZeAvDhA zSGS%Ch~0md=}J5vVwG_OgPic+tzl_jScz-zGC(XR3sMLBRgI@~6C<#sI+SwTwfX#w zq-&s_78a!=ZyU~tHs&>XHuPVJCKCcKwv8p3f8wNTy4y)c>#_m_4I@DiQt08MX`2X) zaD5u|e7|fNSyZYYd3M0fth^P6Dtdo;iZ?ltK{?fo4Kg1HCaBKh{ZrdK(*@|D_0=Yn z7*AS!Z*~B%6l{x0GStr~@)f&|o=2#>- z(}Em%ac^(1wIAY=N*+U%GRcE}&jX%qGcT`}l9F%|qB1#LHDm@c4h|@fuB)cW8R7q? zmTPnid^YTJc%3%@%Pas)?gPwaTr>RPfeUt%0lV$41=Y3)iO2HH7Pl?Tdf+cVfZZ=IJ(%bZNCUX&}0cslHXixtDB3eE!Y{Aj-w3)#p_o)L?94a|)=i3U?x{>5lO=r*{& z?RRYc-gm-N`uXJ03}spd&s(r=e*rQ_CB!#pDPWSatcMtMJfX$46H@7O7NgDL-EDI8 zikML&#o9(;tNkSM4a@=WPp7}4_(kva8`Lk?8ZA+H*51@m=&^2H0HGV- z>mz>8M+}La@LTIp+}EW|fZX)Yh4gpie19nVBdOrOV4KbzSlCP838UI&sL$PbrpUxOQ}o zBB0PIS=7UTH=-t^TQBVEXo42T{^?QDiJ&WvokhCLQGSJ6hcTWMKTO^&UCh)`AvMZ#=gY_UQeT z{FRYgU~$0F+0>feWaC{dlw#CI0`kgCm4CDImtmT}!%z+eiMI?{g90{KQ>3L&cJw~2+C%uRxktXokv)oc~&5`$Z%YCFTmO$0%8)>uqM1^`A{tjR&5M0OGdJ#8qcI` zSj2|a!WvV|d(J4$k!lvZbm_ffQ>7)tlBFeOkfU5MT;z?%u9&0I2E757WruEN0N@y3 zcK-%PsG%5^X%w-Chlc|vxF50)3(F<|tgX{)gvt8n7mU~9DH_S-p>^PLQG%;cSa_|9 zx=jkr;x297k+S-1M(?hCQa!n|o9TCp z8g}0e|Nado{nf~bSOSL&Hyk47Jlfp5J}+Gs+eg{n;YRt$kuH>e(MSCIM9Ps3SQ0FMnse zP{Mj5k>e>Z!~o0?zy`-sf%^~ZW55Bg1}&bLz)uL;EYGS@$rpANbHAfx+5h<%0PjU0 zuz{c4>~+47pHF5)Gjo}4=rW+~j$+quNC|?|-s^nWa7+&WyWqU*IV%!PgpG||DRBvG zf*c*T)dPbZ{|pcK#Dk|{(f~OUVHN^`fM5~bVjO;Vi0#b-{G>HdopCpw6el% zt|1TCtS?Tme0DrT7DeA6qk}M3nVTJVcURF*ABZCM!v2C^01q{e;ztb7~K#9JZp4)^4o&VMh*t*J?hT{;PG$r+X(V(6t6#| zEAAv`(58JZswr96-adYwIa<=wtLt{LwBu+${ymbj!g|J9Vz8}3T?6sq$%#FPm2sq- z`Me8H&3E*6p1@X&rcvrxPrVu%*uJ+Z(KvL+%r(8227CBoLSB$nhk53{E>2jUNaVRE zNrkeLrk)ial9X!~`bm~6>2tXo*o$WKseE+HTZ;B>6B~rd1Up;|g=n^kZ{kO3o}*cg zKnB;O*Y~o0bG`e+ly1`LuQobYOay=$xcUo8rgnnjAJH)n-IJ>2MM*A?E7z{gPx&ee z^+6{!uN%ZZJ$i=pBo^RZ9PX8RjcxBgS-@J1LEZL57bum{8;-=5UJ~SCuB1Wnxg(yRuG6 z$aJyFiEQf~ln(;A_`fKjq)azwQ}bO+PuE`Lk}{3^B3d$w(}3h5*!PKr?R=uKq` zvuePj#>*dRP zY2$>&gn3X7@4=O9Y?(PQmJY>VE_|^_X=$}MzKzo!Dr?%plcde1r^=k=Zz8^Tb2Ias zOy_!eiO#f$Abz6COm=s}&pT6BWC3pGLlp2e|4EWR zV|awpU049ySZl7muXmGceAmb-TZ;ho7Q}d(>xsSqh2aK6p_bxIK7+4{wk4sx>NWD$uzm$#K2O<+g*Id?iP9;lkQFlA^TAq(ZEOoN@Tt%>gf0w#Tb&Xpz5 z9o4HysBn+0&9)GM@o`Y@YNbll(T41=iknj=4emlwIbt9tYy!O^1AF3qKUNu!w`uCF z-NTJ_o97`;?7C-eZ#|adx|Rz%ko0CP)PMjGmDA@-0X}1nOw-mT-{Yq18H?-)?Er*e zqB`kl@a)yPSeNbJVaI6O#02idge4O(VJ>@<4o*Qbu#%Kz>i(k^zbLk{itHiwbZm8y z6IH-H%(}29b5>#5GSC1ZA&UsE#% z-4CVgKiTyB*Ui@&>BTzd)~y2NgPrU{Iz1&4w?&eyX~(856Uf4Z+bgIc2kS#)bctV^ z*e{Z6@_$KP(Rh52!-Ily5}LYFBMIALyde~ud(WZf3gx6DnZBA$-fCmR52xOYU8yzZ z+^OigW7&Y4+jFxRZo`Xoaoj_5kTO$hQNP*42({{N2Q5`O@g z3E=wNi-p=Md8J@{3o`=sL;Wzo{M3OM>aY00`}jbJ&l8v03~YvVUw6gNfei=9jlJfj z0o!;*%=BW=pKaN}N1RS#OD``R4rmG}Jt*{~P}Q)zjxa7@#Jd2!v{6c`=t#~_pClFm;m$pPFTOo=+EDu^;Q0q3cN{GJ zNG|&Ndr@_$>M=H09sj$+YQUE+)!m+_1w}S}Kta2~=VmL;`w>+4wo$`_wmT;=jOjSDMK zVV=AOIuO=1Vm3$EWAL#GnJqEk3)60G zZNheQsyH0ZQY0iAj@f!)UW4%Y;)=oB`vmb>5Rd)*=M6ieOUg*m4Q^^Jw`eM9u*lAz ziKPM9*7Yo--s~JQReITj@#LdNJ+DA+Q9-O9D=Zx$#`*9&{_^_(x^b$fv%DA-OEqNbXxmt_yrfqeU=4K+G7dj~@hn!q) z{AR!GG@B10pf-ufX3|m+lYE3NA4Ex8GwX+jfnFzn-9v12Za~5)h%C8lh>AkU*rpWE1Am64iSjF3H0SI#cSm^xF3d<+wx@#!0R{6~Bg_No8 zpB*#N-Z2)svZLf2z+ep_XLNBs`J`!bj|2vNB$CsL>1z4zFHEp++s9xFhd#K;P)cFQ za{9L#ML{BHJr$S7reiGR7}6F>a+;)-DFgF@;;&Ox(vzk7ayDfX(*@$zhJAZl%7+{o zv(`T6XN|wJNOyk8PclQ@LU-2xq?2zp_*L=jc?fGR=NV9HM4G%M>IN>{3zlD z&bILk3GY_Xr4|Av=kUQwtLz3orvrh9=i~|(TlepUG-e$oWfjq1kB6We*R6*A9?x0hb|2CX z_z>k0+!~$yr#7wuz7CrnA75SFPOZU_3B|#635cvQ>?;;)F;?l<>ZojS`Ir_u3T`iD zazep{i6MoIKYru1i~X$3q$Rgo~>fA;|5ZiP)OJ<(d~Lg7>-yV0vg|Dy(*$>X~b zeACx!-yg(7h88ic<5G^^!yZ}!^ejcJI_a5AL)m$`x&3yZX6BRK@gM++SFYq+Sf_n5 zoC`EdeWuBGx_>HDZ3HL_T)^5D@bd8Us4$0jSUtAo0xB87{~u`9iHpGknK~D|NJ=n1 zejF;~-y+GUg$}0?->IQ19h*0EZ+)#Q>;6tIupte8t`H93DGQpwl$^Tqa%=eh{f7qA zBb*tOfQ*BXyKG-yPsy^b-5`W+w;d~r(;deDVb}}@lS<|*!+QpWs)CBr=PoA3es2rw zzRQaG?TF2BZ(gD@d{c+34egk)^wjv=^h$Wt*bD0Lpoy*3>UH$9-B)xT7qV|6!0|tJLQvCk~eX zRmjFGi&SpQ-pkyVe!E;@|L%o1Wg>TtX|9+=w`be~{975oPTT7MDAL)kQnLh^`t&bd zUKoX|`M==mAL`w002$IOtcE z9sz&tDEK_9b z^xJG}cL(YL!pRJFQ-}I0HRDeh7expn7E1gc3gxWq==aDtBY^|Hy#cMfJfHM)>i90F z4O-EUl9-pk#x*l^?pjl)S@{jLMFhg)ASBw8Lp1pAz1EQz3Z0yiNmS~(Ny&+WA*b6& z|2>&&=@Hrkec>V&ByxdX!85IvOZl+kqPn~R;I-9jhK0|8#jSGfTJoXFyA3pQ; zmw4<1EYB*L&0mhv=!$w2^4&uD#cpsFg4a#A;$9Cm>xN2NgT5zT1->s+N7D&+uPsZ& zv>J(hcuhbvEip*Up&%GTzG{%xg9$$(UjDsz$;Ez68sfh@tW^U(#4*kFm8`KxlrOsK zdYZDFTVrU_p6nzeV0618aTdz&IU}OcM9Br`8YYhs9u*xUNYehW)Av-hvKvk*n*WBp z?93b{H`(+_DmkTGV6YtZXJGZ2IyT1{qf<*vn#KOwEx?gw@7ROcMmSpt|9QV^`s3xg z`_IkpY}{g|G95Atxp*i~6WP~+nCgvsd)WnUxO2v*Tf0SuvZq^aL+@+^=cIZsFOa1g zY!Wot#o5{1@yC4k%Ex)PqV6hQC&M{1Rh8*P}5LyeQX()%%HJG1h z)%(r6KT*!#*F{S9iimV@(t{;u$B?K{kOziH-F+z)rpqEJQY#Lz=`*a0w%!Ji6but^)OPI4u0)01#1%!0_k6+1kE&u^L1%6myPC~;NLHWQIqBnx#-ar; zx3|?zWjmV+xn@3GRWP#Kj?CAlsc;PigPf<7I`sm)T@TMPHI?7MC^ZWCgVyew>4{@l zTS+4)F1}IXUz19wJ{VYL(%H_SayzR`pZ2~wJ;m*7JEk9ffbQ42Ha5@MZ~E&#h#_?V zjFJ`jkG9p%xSY4G#a^r-_2V8ILPoz zf7Ib&<*#5XD>&Ve(GRK-gJ>EYlly#8ZY^2h#S z>39xbza-O|W$v>B+aG`5ZpcLgGovupR#*QN09%DNhw!!PvaeUovoI2KM@^G#fGz94 z7QDK}Ie@+@_UTg*8Of8M+uq>6^bBZR>@Dk>0_*S?b&|kr!ARO)V7dTCx=7gKoG}=i z(oQZ+2TUT$DahFryxqkg7Z*vD9D)1rI&%uG*U|?p;Q(Rlt1V!yhQ?rswaTVT4cbp% zRL!^~e+pznni#S0^;IoWt6e32tuy|>(rvR`y$qBz6;uib$L&t*9uMobu+0Rvym|c@ zfb{DfXw6vg#r_$Sz;;>7(Q#bH$V{@H*6}=VDhqlGs?qsAf$tG%fvh*@6uE5BTe2|j zwXeaHXRKtu2E065b((Qy-D{9d%oC2cQ44dkvIx7TkUUX7AqD(|3q3gC;1Z8FQcHGh zu)ysg46HR$-A?MP zaDLY@KPBqaxw2~963B%RGlP1~T9*_`V%+28h%=m_dBua3P)2D%C&TQVSaPaH-C;}N zse5a5B4u&{Rcj|lYcuB1pJ^J*=_2ppt26WRj&UBr@*M11AX$9U%0GaJuk72!Q3I8k z*)zvEz(gq(OAlzpVK2SAfURY<^wXQ!1g~V zUTc8{aWz+<)B_l#*eDH9_DGA;beqWOs6^G+YFSC;n_oS&@+d{hkcnVA%#JV+66wvA z^S;bP_GJ(g5?UT>7_upV_%sfBw`3Dc>{L8ukcK|wem&Af@7$sYIfgI!wAA3gnB{j{7ao znSA`XRFhr}rZ9gCigb}nzC#5;t~pOH`%jRM-uMVF;f3_bKLHY*t^DeCOJaE{!v#|s zzK$T>7??zuTR;@I)Lo*DoWTE};_iIHtnHIwt=T#!5+@?(aRMqM_cv-n`n|?XK0kN@ zCqs#59^>mseu@};R47>sY>$|%j^~@cmrIS#y z#=xX63&0u{pcmcu-2MChr}=3JQxh{tT%Zuep|NT(qlj!m_yM>{h(0qEy#W&~z?KNo z*+rVJNfC19ul&mBRB7kK1R5GQ8tg2oFc1jz->eup!ZMok-xJq&1a?&7wM(FKfmO60 z1B}p~fISLx^?Y(}4r2f|lJPTA^#XT{EwG!I5c@73uGBRo$Eila^$_y=GRrof@-H>{ z6H-ICdL;If8GCjxfK{yoyCi&ke~uz{*@GZKS*$&Jl%l-BrxT9-gsDSP%pIJin1iE^ zRT@N?i&jJY_+qdmiKqn+ZpfnhI)i~$MNY~3j{S#bo7*>x0AHs3WP&|SV6KT3DU#%0}km*a^FgnW>M7F%~Ysj&u0f!6r2bV>?iWl^`- z62IyW3cZy|Ih?eBnY>c3C`SwJLWYH zFfYebOk%WTgCq-Z#`3)re0h@$gKhfsM{eHnoxvtWsC)8lXnRECq_ml;|AVlQ$6^+| zbxj3lPBW2*X5{OZJeq&H^g9o1C1RF=fNfV^3QuR7hP&BXONn@tjQk=6cEYongNoaoe(~9YYH_I9O{k>qPaGr86#M443fhBrd z8erN!_ew{Nx{~HNU9VGr1a?9HhfSAV@ zaO^6xl1u|7bU&KYGjgxfxl89Uo&jL4V5~gd-4D$qY~L2*nMoTXsB zNSXIf_KHfh_x?KIuqWjWK-@e8{DrF_Z>zu2pD@%5m>|#-g|~UWJII?r!ws?v6fVW$ z9(FH)MJO>2s0}!C6l!3%C*+}-Vkwufcw{8^E#qH&wPZ#=0-(i9n=y`J(bnV%M!$_4 zKcuJD(4^}+u3KvUa{R9PqsRAX`R!0PQG3j0VIARxef8sAQAA0(+ny+}b zgZJ^Bf#X{_db3SgOFTuZKAHzf&c0qgURr`d1;#c+vePCFKB|D0~Q&r2u}Go zJvIa|xMq;By|M~F2AxT=peQ8=wj9azAWmD-5U_fG5~c$OmJ`=NFguy2b^H6(H4t`ktOvM& z+B+p40?aUEtp&|#Xpy1Nyi_yjFqM9We{EX=cwf+Bp(7May1+CgP@om~UsR1Xwg*z) z2GVJ^s5F;vy)!aMkwvC4TijLmB_MO>QB9)~SDMRsy^|mR6jKX3<$CE?-ALJ`&J5V~ z{qoZNg22>ibY|tfc|Rz{R^*MFvTspR!~fG7?aAO<;2Q>ZvBZfAM{*;Y=eJWeHS$gv z1N((n4C+H$9GJGFy4vG_;B;J@3sO~4{GY+oE^EO>F}!!Z0#2fBB^?61M)~?$B;;p| z-mE6yE=jGRX?(ccvls5^e)^Q}uo!gfe@|OMz#lW;3b3A)YCeusriUIrRqKmtMF_R` zPmJy0`K=btwK1X2rHnr%_R5SgjBaSpcEfHU-0-W#yR%1_5F;x2W_*)QfBLHov(rc# z_!?jpb{W-IzU4;z3)-#aL~vviuoA;>`W-ROd9F2P2aob&#E}_==o{-g9W>F-WtBc3#mTG; z-^t@G@eqMiYx{-TRiehH?Q906gz;kqDXRzHGZkCTU+r*M>#q}vsz-?}j}}v=lHZ=h z5#CZ~ug2>!RaswbIyE?UwKhsC0;CLt>SCXyyumg!k!E)PQKzdPYbAebmP{DKsruY^ z*Ua&6jRuCdIgysbaVfGO7WSTV+f2bZjA_Z4SsX@a-Y0Ee85w7PS4NZUi@9sk?6`A< zm4-SpFBJFXCE!8^X2>jpK#o-q4fx0;WC!!{MX6qsg3L@Py#}mCt6I!8(D}a$qpHaL zx8l@jvVb!HsaZ}nv)?#I)(uep`A4GepGiXBfsDp>Y{nKCs70D>eP%HiK{7xY zDoIhnqn6FZWr0Czz~WTP7Snw<_oS8nDW>ui|A`b|JUmVBE;P0?R>%~BhW63h3ooyB zU%&BZnnTgC{=V6|i53C#k?j?C+oCv&abNAv`P|N`&%e#i2q@pUQi*al+ee%yf~c}j z*z0J_&(eDs#!dV>8xP@s5IqP)e#X#pZ_+s$&cfeF&Pb^HY0o;bD)=RA;-E}LHqq#z zk@~4ziKN3_VAw63Zil1Bu zD|+ICmZv7^nh6(>L(;vhpipM^D<#r#h0Rjk%-%g=b9Nx%)RlJ)-+xF_v8^D;1q1Rn zSiT}JyOE{o)r37-fvzHgbDhBYVLpRI<(Di5ot$Xy8hJ39N)M{+XZ#!|e)E11R?Yx+ z2f_B18eFpp0s$#0?bUu;{g3y6uUlFb#)0c0&#HgV2S2b|$urbasvL$RrFL)`3}A-q zVt|Pzn!o&U@d2I5JR0=|@I1wQjt15@?qUx_L`1~?;}VmUKB_t4NEPRFlKa>Bc3bgN z`bvvIX8Oh>VADHJZ!C^nsemmP8h!EmgRY`fv|6GP4KXxcefrAzA&?9*c7>Ca0&>5C z?ms(U=;`S(N9-sbfKUJdgh@ZAoFUSG@cwc$_7uh>?sODBl>|GZ7Nq4&M8#1^-yily zm7@~G1t$4(e%VRzx4Fw-Tk^xZS zS#Lyfdu(9K=JvKSpS&bPd6$GivJ&{LpFzTb@B`)5e7&y{z) zT;oSR?gGE9F4v1*Yv0Y@dq=*#3Cs_ft;q!i0QuJD+cFQyQSz> zR=zyXk^3(VIAysurGG|I;KH}6n$O`vxAi~BnfY01Y>+v}RN1C6zN^`QW2D1``TBfV zk&j(JxbjU5yGzBWOLYrZ&_L(?wa0Jl&(?6imL8puq(eqUAgEJ=jUP0F3>Wv~X=-Zr zTSG09|NTY&H5;d=yzaFD)<1{?uW>VdH}Z{6QGe}b^wTEVKen& zD6(OPM%vHM3Zm!;Fg#1|POm4^vM);L&oXuRtUq+;Qh31ZP6);7dP^YG zfk(pMR*ib?wkIHnV%9z>%ZDu|dXX&F@sV6&=8djfG1bGrtMjG^k)^#j<%cX7SGP6C zPhtHdlb)>dJep3ChB}hiSq;0wgi|e(R>oy3>ce_?_5sd>--H8}U_C5#o4!<&ba zSql>0+nb|K&BW}C?O zofj%%`%dTNLdx&OX_Hz9d8hSYNSi^Y^1BiLswNkOCvUAZ$>tKJ;*A zt<`|XNm|dVk>W>`TI8N2un2%tGqeDlwUizWY*!?X(BA^@YfP=vpfekslSDAGw8yK9 zJ^-XQ^S}Mi%iYz$T$B<8e}F~?+{VA{BDW?~eIpjbh8LhWl=un^W4r)ob)8Pd^K(~h z!_;?H%v^CuoLS6SnEGbV1zw>`a9*+rga_+C7c^P6bhpw~k7L*g~$@X*{N8`?+bWO`l)^3(x+ZMWqmWOOz5L|fgA`j}w zN>H*DC@ml&1j~bU8s_yAqt{{PYIA@^_3aV(B);1-Yw`5Nv2*KNW}k3Yex&-DOdV)z zI0bwT^5}DvFA(aWK!d?(aqT>@EhKRqxGO)#C;W5;ne>(Unrm5ctbq2|`rmrid==!b zx(eHWJ=7J~>C0ymYpO#Vu*dhVJvU3_GsV7o7#W%Rr^c4|Hei74k8^KSA=N5 z3)csd?#TY#%auA&!T;vWeF95fY^0h$i-J5Q`(7bT6@3xkCOtmj5sr zS;*=1)H(c>L`bGS6^6v2h{vW(J)K{j*=;N3*slu5Hqz*QVsh2QTYFbrmnYj9-oCx( za1BjUD6#Foai#jqgPa9V(%5E;@tgCXXID(kE$3*c7kF5NpkdGOYZw0k%e~X_;VG$M z;GCv_7)C8U>bg80*h_E^7`2U#>fsXbY5>4i48G4g*3* z`T0r62U5QBpo25fJ`N;`L)cK<#3Sh3nqKH17TKgc3HbJtf^Y|NVj!bP%oS{9En##q z+nt{Dve_m-f<;8p;Tg)P1{sUhjc63Z%GD8I2>wCD{&_&>P*f4=O;QXR7z6ru?eQr* z<`Bv52H>3bTD*l>WJ3qbm2>RyO%wB-w5y7X#S!pL1Al$leK84ue((4-N_iI za*R|Q|Jvz%TW+x7lGs|M_;DY8{QBw|Dwav1jT|8>M^R*+Aa6dE+|M}Ztw%w_!6``e z8wQ~f*%G%jEtdodeR{AbBkhCA4wpK4er0<3y$m-OFPDek5#;DMPU8;^27ge&x(>6$ zs5}Hg>x9ZP`<}x=rEI=7mVt5}e)U|>eP{fD!+iF9;#84XJSFf`qO=O%VjlZ-zoK>B( zh`_T!z7tc>sE=Bpl&;#)M4Sk^#w6Qo3RUE(*8?p)0B1)CU#k%c>ntOdc1%!7Y@27t+L*Cf=%}c0KV<a$TE0#@ZGwy^mKJNhfpJ8P9f< zsh&sdU@cCO^=&XJWlbO+>GrFhha24)Dw72qDyOH1|93UiI9dcLNzpkD1=M$_j9YvZ zH-%!BxMnSkZ+cRTujT_q0%;|IYr`bR;Du6a5NZlTEK!Qg=jQ#+uT@ngshVR>d><4- z?ah8kZScq8(pJ3^eI7bF#kWMMI%7vZzazo;MDK%>SibV@SY^|NwbfR`k<+uB)pldt z_wU(yuj3oBzFp}4Jz#$iqs9{b(>W{h{&;v1MR7$y|M>6Y|HI<`gLl#; zH7D9eM__!Dpb!>MwJiv0tEe~?0phMWT;|HpbkcELUhy*Mk5G+p27aMZGUuXjSx*|_;L3-ndSbV#Liu8GHDQtP};WYUAw9R!FogO<*C*c(E%6)B{75gi^ z*aC{Z)8SCV2>r+N-~Vx=;^0;=23XpNx2}Q zEw0Snn)#|C8oU1|k>cxNoogBFK_x2684kBz4SzQWeRo`eXXn(zNBJ7 z4`M)2RsKHR-xAW11&c>=PAU~6<%9Rw#V4XA%f~%;-VKKU4lJ3(f zjiJVy`ArG^0aQR;E?qK3gnG-BFOFtIxVe}KQf{I(V{Am#|8T3MstP;S7=k1R`r3FT z&_I%84<%4CU?MgISx0^aMvUMFgm3#{^)U6I)8@XmhPr8u_@R@FCJg!^Y|v^7!6!$x zjx4d)2+atgEGPqW6!Ks@S=fT`dNG z$sKE=F}g+OMp$5gbA zJoHpj>q2n`1s)olsx*JT+k)Bb!L#;G$j;G8x!YW;WKKTL=)R!0=Uakg+{Koz!v3y| zX7VJV;$Eqb`lb^Pf7#k~4c7y&grARps55|7A$W51gz3*r&>9M=N^-9U&m(*N3$LUIMf{?g9j`=+G8 zZNj1gFG9w_K0<;}Hfej1{&ge>iXOe+HDKa>&&YeuQ1rV^3Q;+&M111qqsxaVbH6`U zwk8f~kMNN}85#W)VW5l$Xt2%g`BzMaUC|mo{{;3Lk!S$_O)Chzr2Tfl3G?*}c?pu( zgYopPtzBI5a`(J$$|||b4n!kVKXHX;+ z>61V9F#E>C08eZs5wg$R_O?H;L$h0N47C(?K~H$Daqx}CC*y;MSsoi51wdaps1Ov2 zyDmV)2o&xJV#`W8iN2f)jWX(VLQwb0>7u-O^3dBpw(@G znrO6t3f)m==Q-T}DO~U=Sn%mKtuJOsl8dx-tGJdR1sTyQ(+9>}o=SW=HK$}NC2mFr zC4iW5m&mb9gEYpxs>U44&CQMZ0mh0$*HSzPg)|v;4J7*B7mygpt=E0L)O{}Fk1Pc4 zG7R6B4asp(C^EFeaL}b5Gi;U?m9}WFyw1v322Uz*)|MY`)9bs%rf(9LO6GM^;)zBl zjt7vk=i-=pD7~5gg*%ewxlm6Zs6rMMSasUDohr!Qp+y;eDg-edF^NH~!5QXfhSYfKZB5RA^PHlz=zl zvZ2av?Jq4vCg<^OGhe?*vRbS&SdNGVEp|JND@502ZDb3d7656a;wIg zTi1kH{0pjAwq1rZ?kQ5Qy4K90o}MZli<`#d=i5w|hO5<|Scmjtt4qmlzkr(NPCWQg z{Hu!EoZ3TWOqyN6LT93xb~et_DceDTA{RmI+MF`cB2NHti1^+fzBefdjJrW*ocq!s zR^LuwJ`=CW(+ft!8E7%Asyq$-DJe` ze(mDXx8cZrNYdDYvNE3-;nM(52iK5Ty8m`5AV?7s zpJUV$f!}!sL|+1G~u2V3ApTzlRark53hp*1q>JZdFBWXjIX?9J0x38It z$oXGtgucI=aSd0@pc{jaT>oS9_;`OznkBg3i)NId^)B-Z>;S3t-N)Sqv4%%PWT9}) zn}eKZhmpr39ORQ^F^h(#t-^Rrb$J@X zfGJj^8f*19UOUfyCym93@k4HZ?l!FA1SO0CAyI;51z|S;5S-x=1Y8ayBpgQJ<`|mn zrWS2bMCzm<>+|P>f9f5aDIbMLLLSBsw*?}?_8XG8Ci<)l-Hi_S52Q^AhwXt++OoZW z5n+sZemf>7GH&hpXHZ;ZQD7PK zCmM=&GKs1tihvju3erH91#75;`U=cM%;94WQXzSV*@3}A2GKmP-o!ay>(mA$5*CgDnU+hHkM>yI4qPA zxE!amlda zoRnZ7F{|;AK^vLKd*fD3A$`L*5wx$yoZgx}v&NFe(B0x}W#$jA$ClUmE7E4q5N_B? z^|%{^TgTYq+bESFD!IXtw(>Ehsc*@?ER=5WkndqHF)vdeJMP*5vRQtdoX!aO#8!zV zX|OaDpmU=wQzo~chNrXt`ZHG35cUUNYf(Bo&UeJOsfvHdq^GhQQPVYzWDu_;^a*8# zBC~C+*$wU!iMs)TsgI3KLDzpkOrATc<}K|LJ>YYcsgjqX+-SrH0jvFg4{B084#F5; z0L!~pJw@ImK%Nb{B4Xy}N7!td73c!iPN?3*m|S4!K*JU0ntM|drDy*S$)PMI$g(gt zJo1&8NnPNjtjpZ9g9L688I4yl_z!8Yu0eaubTEK&WPO)M`3GJlT8dLpy9mSrMxdUd z)K7+}r|F;h`ViJ`oj{tMhL3_-Ylw9RcI>4e9BJpLu_!al?mfCWY9*gc@0tEpA-8(W zQLfh!_BHfZ>X)@K0SUcuRcPp3NkU(AMVX~C!}s@h9mp`iW`zvC7PKaWh+n|H*86tI zxag67vq7b3_^Ed+6toWR?|q(jU_o)c%XXOoRlv4j7?x@j9F;Hngu_LVp}3E`trjU> zq{PZ#GbPAFKujzn>hGfgZ&Mbh14TbTFW?YBg&@#!!QzRI3rjEUMEF33tcilb9#1sL zXX7x6W^@+>;H|o^7jozMu*o5E*CIK1c9JtpuoVP`pp(zpg=E12T1aZIXkwCbjQNg8CxkpAD_c8OytKJ%SKUsWxBj)xeH z+S<48LY-q+g1z_y^nx};KrXO*pr#R_2$^~o6ZalKA-<-<)ffvJOsseU{zoGv3DK3l zF4y@j|I`Tv*T={2pt2Lcb;g{P=3BoAr>C?(I=3FEI_kD&wp4STcCJ;XnZlV;uDjN( zbx*C-PqEep*xW=qc1UVgYc`b(roCF)jq z?2b21ZWe6)&Z||Y)soh~VgsZ-(BJ9SaO#qAmy1_|Km>52dEBL|Pi) z5@hf4)xaTY^WM3bu1NYPc7Ni(uQ^zY^9cs^d?(N6R$A{zHOD?Rll;QZe1Z^sB;%Cw zfHII!rEfrl@?})C9wt42CJGA#t(}jiQgujq&uK|zeT#rqOc!|$A`m$p>PHwG4JsyV zxTir7!$7(_O4X`SJP2z9H0Co9@GL;80jgF*V@ZEwdyG>1;VBLFM#-TbEPi?Qs|3+r z3q`vFp|z~?!yY-NM$~sg{m!Dt?L01K2Lk#8ZW{sy;l^=^K98)Ai;w>e`7@EmMqC@5 zu~QaIB{vKy==(H8C;?pvX*Z8dI%R+XKQ@z6dcwj#GUC3gCQi*!ME!j zwcw^6X5W9!GH)?83E6kwjQ$Ih(X^O|yQbq&)5$-PW=InRDO!lr{9=LKb6-S(^FS?^dD^jI{lrk%da#-5KPYgCo}X<82= z@64V?`jIVD51Kq8#;69OlHRUgd{lSms9FwErd)XQx6M9G$?#`Yre-87}W_e2{ft|P;L(JPT~HVpzI~V zQ;7cwytk#Zwp#i00(6JN6NSbB`U5EjgkgtDISXk1INe=T{z^_QB3<|Zh*?Bki^ZLl z&d&@#cs!%;fvet(;D?V0SB+Ar(T_pkMd}}+@#V)H^q7o*8#nn|p34lkYq%;5al2+e z8vSYi0?+>6?T=S~!v+&bFzj$f-xFCLu!uqSV65aMjCpMGKyO!wnsi7UFs*>*wSR-) z19!KRjGuM~bD?rX8ZdZbc~XdFSREeBelDo&0m^A5)|%wgbSm)TGBP%3&2U<>kud4s zh#Bk53S3t7=T~d>-tAonVot$1iMZ&(xZnT&5a`*Tvl%Px76FOrK2Mzd{gL~)eLa91 zk>;9ekQYx)6~98PfDJJk0`YThphWg?BFCI{7)q$>NLZ&L)dgoVtTUD2c)UwFGmJTF zoM=^Mv8Qf^fEQ30#|1(+p?8 z0ulC&Zx*O@8gf1*IzqGQ<1xbIAo(|d!OFKy8FSCb8tvXyLLKxjit49M+8BIgki&I^(L8~;Lv2k%31RXpkNXb2y z&T8Y!{gAiGZGQq=gjYcv=|sXTXQV)g8s4}_!0jiBxNdD@&^Ui+_wp)FU;Mh*a`S(0 zz)TEAbE<9Izi+_}PyJhLKpQ#K{}-<#EM3gl{BN*L-F5OTT#Iyb$|CZ2DBe_{ghJv9BOfhNn`d%BO^jlj! zYR0JY|8NQRiwpnziqqpz15azaE(gCMS25AWN@%f)SF`b}Glu1n6o^Bh%G-?pfpM|S z%@3s7Q=>)wxc&O=*Ro( zayHGAc8`ikK2SFx`#?^@ zqk-r2^Xa%q^2Y*33v#3T#m48e`o+&RMM4oXUDG>%d2VhF;4UhL#@7mIzV-n(>q4ZS zFzAdW$kO`95?Fj@BAkJMaWNlY;hg4p_JRR@T1adQq{U4hy?|vpYa$S4a+S}TLm?6t zt+#TC&&3H#MuUE&Bv5iUt>L=mx0z7-llcu?Va1Ze=9WxWiR&IX#|hHQLq`@{b6pOX zHG5zAHT4~5I&3uUjtS3ALt3~uMCgX87YitaU9wxzp7rXTmn+F-QwRBYcxK>L_FjcG zi4B@uEuH*FqO!P_r(o#>w=KoH3<&UXzs+Vgy_qMr@Riw;OPRt+MLT16$YV8f|2$8c zvrnW5w2wc9s;CUpju?Jxrr0PdHq-ho=RmWt=zb&!ddAa;xcjW|9- z`pcuuJSEo6AbS8;AFQTEKCiK=(AC*GSm7>HWg`GP9Ui!n0l6$GtG&e*USga?2cZO$ z5Ao3dl8#_LnizsWKo`XpA4E!f3Hbk3YC;!+kp#vQ?7+=o$HM?%0~Vw4x8-2Bp;^Sy zT6X;}Ep5@@p2Nm8Zuv16UEO9dYvh>^ruXuh8xXbjBe$hIN~|!-tk7M2p?SBeU5GNBOOy-m2&3#9gjp-V zyv_S%Y6lYeCPUgcq_m^m!Syqd>n3Lnu6lHC(8#*feMiW~rxkwO3_c{w+x*BazF5*( z83E#tgi}=!tN&<5R(RN}QNOPFEpMsA#sIgNXCv#Z&t|2%4cv2~HiL`izSzl8e z(ZG(_Dgil8>qXqnlcDRJ z0dp~`7*Pb@l#F>b2BV!}ht3m<(ZE>h+)O8spn!~cAs~Nb1Jd$2GCMNLH!REZ>+EHc zKMYv@_t)VAqkV#EK2?Gpy$GG8Ah?c<)mVYMkXV1%Yr?nusLQ^+o(h&X>R)0gzi4nt zy}&@l;eiPy)sc(-7A=Q;&q1PxUXR=6QA<_ogZtlupzihVNGd7bZ#walrmh()ZU*DK zR5)BgAW+bl)mjZCX_JfFnOH-|gO|U;)Mdk8X=+C4x>NIH@g1B?|DMwBC!v8P7ADyg zYn=1uXq$AovnG4gPNHMq6-&AZvVxYe7tmWTmX@K`Jg8M>7|*MITM^@x|H`kvknP@U zjG_XI%(AI|k3L!ORfuv_G=`E8>WLbx3AGh=SFV$VRffq3Dkmog*b;JZNDE}>gy4;$ z1=5)LiC!=qQy0rORgVuysj)zmX%xd$fislPgH=m+1CCxg1P}&CJn)r2+CmCOuALy~ zD~A^#SU_{0Z&$YKUvGQ;(wu#^>8p}6T6YnM%Zz- zN{x33>uBSxui0Dbj!4j_yc(cTc z+2c7TY1%*0xm?d-MH1w`J8*e8DaGy5F2K9LceU5+YE-(6G!bk_)FZZPEp2$$IQ|j? zlZoGP6C1s?E8gSYOM7#jTGMZzfqBxwV=?M!70ahhPz+ywdr+FpFaWion{oOai@ye|JAt{+ZXc&Al|vyAf!EYtf>CzuIF+TzFesEP zuF#=3dgmOK2tyW5GaeG29Sn^WBkd_34dKP65{H`-E|fI8vOBgH%lo`$X&R+{WiTlM~#o{Esyr} z4%isL@uZU?9slOrW>y5PRRMjIri8Cp$TG6?2SD%mdsp8pZ~T|Q5M$!g{?g%{W0XSf z92nRG})l;l3wxN1sckg=Wk{#8*HUDbTUtXTT46=R6F=_Buudq0bdbr~9-3;Aq zbx;Og`R(FYrm-ON8Gt# zM>|t}GwbnnqJ~<1k_s`#dI{F8!E6ID zi-N?9rEHZH#!y1(+{-G{WWqCVMHGH4)5QpO`7KkC~a-a;5qUK1slMM_9d9+#jqUucqhG#V~}j z8eK|8LH#E4<-HNv&aUtLoRpa4S+S6CP{8H-46r$aF%tS*7eEvGcsd%DFC^^1`^^5x zs(@pdzBL}IU}s@Gjy;eJ56fBZkuyL~YP*ZYrElQH0XOjgR=OKRc3)9tP8(csc?xN=^8B8i^ILo~J11kghV@ zUBM5An(c_Z6GqH{_o@M41u|gh6eZ=qM zaQkeM)7DM1br8h5;;?`uH4)(iu7bZQ<@#Wd+@ug0q z^H%BN>{k7*U5boql}?agBf0u2gx}Ud)%A!g2vCe z@>&R3RiHj>jy;Rb;61|n9cD~swt*0TTiF#ypa7HYUrTQUsDCG#U|S5xNT8qq^{T9_ zEW-oFuQZ)hoCt(yaxQWf*#y;0R$JSkn|*f*IT6&j7|gkJ^D*{FZmgL?PnwPiWMkfsJ= zdPFb@k(ME}e9i|jH;J(<${3YdkKYp&$CaVT7uxyake!K46P&lyqlxS$t4}+&wU1~) zoHi&FQUXZ{#LzOs@<^>vBh)|Of-#&bcU4*04QWp+nl0AQby{TELBUxPguobMY?Pmi zE51QQ2t_!7gd*?kQW`0Zv^zW-K|7BZpdZ{UsVW943(+Xz?A;dtB-$rS`u&m{nAV2O zcU|?q!q6i>0}To!xoK?3yCrD`CI={?h=3Z92av-#oe3fI(1v#Ouc}5RHcOpZikuB2 z)x&HQa)9o9vQ#cHW0GJc$3NJP9)Tz?1o(g)nJC!Xh7F_;kD(M1n%_m&U**de&MT{# zLthDdZ|l>w8`C5-RsJpgEDi^r$Dlg}UemLmZe{d(-8^YmNTQ6IRGSR-itpqfrgqH# zlo_Z$Y+#C*gh@t5b{!&xM2Fx~8HZ#Ur1w_F$9K)`D8?;DE^j^Qy^S9W=I5zrzd=Q( zgU^LOr)~awW+j&3{dSMCP~nhdPBXxlhKm22YFX^HS^gs1eWcZK+V+nPMae-vl4#{* zI2)Sp5CZ4%#qv*S3d?q?Pm$dAO&qOqYS?Ah$8T#l^NEFB6XwPo zwkSDt*V}1{mzOh117A18p5@~!Xqt&38#(hD*pN1v9PaI#L@k0!8IyDE!4|$+kpM_9 zBj=1?FeGWHF|$m4HZbQDos%t0=3xc#tEO7Fzc~352pxp*ZgV!-2Dr7Ry_3jy%me=% z=<_Nvo;{2XvyC2g`pw*Yani`FJ@UAk%-vAlZsFu{oQooDQ#+@}m`n}5tA0dur8jKh z+g{A#SO~~4UX{pFm>02Lf^W1OsqeC?(PV(sFbj3UA0mI5RL5}**-lSqfWo#m9Rfjk z)*R(Y&BJg(^c0Lz8T*UZC!`)9dtt^EBh$w2eZ14~e&V{eOf%fN8g<4RxQtJJoA@0& zYAJTlakp@0k)sA5>lkS6vt+}@rifrMubVd#)Yxb|oI0G;c=qeZszhONAI%>=P~ZRn ze+3fMSAOA4dqV9tTPG=7K-399yntBKu*n>O7t4LtQ;GVl?jJD8f6p?c^j0natKzdjpd_=F=Ti<*vuc^K-FDj-^x4@v^mSJGF=ecJ|TG- z!iZEbh|!!r9nZ}ka!Y``<9-QE0VoIRH`AvU;UZAzPFA56MZC#4Au4of+XUyN5 z+4eo#DFun=0G$u3 zhW`9f%8(Q2#M-)&T--9*xyZEoD=m(b^qg1TR+zZlE_cEdh!)SahbTXS! zSD^j*zU2u)Y_HP{2&H=-QZz}Bo>t%MIsO~z>G5q1vS-qyy=uctNnKsdRh=29ZT2*DTi zJ;3p~R@j5{f9bQ7OXuZjN@L%V{SlBzbIcGPo@KXx6MsZSvRg zb@17zC_xBz07Kv!tTyY;N0Fz(#STTaL_`>fF1!(cL>gsGypR+LflAY{1;K}Ya_Aa| zj1^QQ6Ae(tGIFvOnHn9U*FXs8l5%%OC}lu|T<`-T0l*#$ zVG+Qg^+a`@PmD4CX$k=j#wst>=pqIPa%_9i%#~8#D&pC^O*(A$GU?2mK`w@2P(Sq8hq9j~QO;u!~E8dbx>j;a6L5WIl zzv)v}tcqsU(>rvTVmGT${?sZp@Z+E*$f@@@uMzBUaUaWl2_)6v2eyd6`ARJ&+a8mO zS8SIj^;5o8X&^D`$4N$KRZuz-BS!AJ=Mp#VzXZuNdxvfrCbX3_vgxnK1d8GXBnNI+ z;)9pxFk^~hX|5*Na0cb0x^#>|MLzo}^g@ctx}t+H))~e+*Y@P|^1ONbJ{F9sfp4qO zyeNFBZdB#KO!eZ{VYsT%VeR(YmobkapN+3ynWEddv2{m(e}`k>`Y80N4G<|5p+Fv{ zqQJ@6pAdJkxkAt38;&U_P3Ps@b~Q5I9|W%H#RA896c6@fjy_A|Pr_@o0%{2mA!i|M zA!sNQ^RlD|mZhkCc&s*rt(%DU2aI0TinYlT^zDP)o*%F2sBLFkOw;(^Zsmhx16 z+Cr*@IL>S^%*-xYZjN{^p4>cKJmmZi^M{|G4V2CDSz_3HhUngY1|YIH(7oXn zgN6+wF8ptc*%`{C^K4Xcs;nO+!v<<&>HDygu_7IWsS{)wD;9?9AHVQD`~eyum#T@kD_Z8iiV`JWv<08h5YRMb z*1qE&AgoOE?>`pTd$nu409>sg8TJJT9+%Gwxn-rTmxB@kcs=Q7R8bd_B1f)tAFyUy zgbM{}i-OfycHQY}7V>1^S(ulOj!HUrVLbVjzqEf5Lp&bjCC z@(S^Qx?wEyoz0dBpB?DjEU}ssop#IT>l2H-9_Q)P3<>&La`CycRqMT=#=@kKUUmJR zeDBNk-+Q&$b}gt~-#Wy{tk+ZFqJ(A9P1!+VAzY?1;(yJX>^6vZsjXx>SoCIv5apA^ zk-?W39y^rO6bsPS!B<~;okmVD`n^9mY%f}pg{tHpp6X(Ys>UYOE6YNMzc6$k+&8s4 znDtUnR>t9v=XC6Gu5pg`YW}MCTZ9(8CY-`Q)JiibD!?-#|3|y}&<8i|^;gw35qWVw z7p1{U)RVRw_Zb`<98bIGl-JRC@O}U7Lg!A}mxRGwKoFLN_!kHjpKOf=9au2yrTD9ehh()jQ=xyak#Nw%#8_ ztx}@Rg$v{18Ej(W>RM-mawy&l%_Ja8iwOxzb_Q`lxt0o<`L)Xla=j+#hsK+d`lxDV z%@tt8@hbStt{~EmUnt>`%SE2mz091+2o+9QeiTzL7+M?Erd#+<7>CG~pz4~P4oZvP z8n5&w4WUdl*ZS@z_cD>XqT$2%mD%yU55gTZ3FM?SdgA#MSn2wOwEA-IkWJfh+mc{6 za%DspMUbqL(Y0FEe$=_DFQpd5K6AG4xyQlW`|7k=v$9h*M5h!UvgNJc?8I(&Km6v+ zrFVmKRZag&-tfF+0R>?!T472a74?|iL?}N+In8VvNlwrw8230ctIql$6x}UJ^je_kYj|x`?f&u0>J#?8dkO( zUa3gkZU*D7ycmk}{rCx>d&6Q6?ysBS=*I>+sYMikD!EemvL;Hfj+t#N~J`^c);cgXF)M{c0xDh8FFSp(?{clG6pN>{F zYxSPb`u-Yj1DDID>b{rdy0`td593xID2RmqlkptX8VU*3a`hxk!!;nyDeHvCqfM}A zYOYVoIk(#9I=?d)6{O~upV!KaF3SE9QVMkqdk+U$;2n%B46rAi+na=lRwxeRqO9svhPlS%afz~vFF*7 znr~r(wqLK>%%O|WRr#_tl#>d~!AT)g;v~_T;%4`Woy9#PR(j29qW2dm=Qpm#w-Ag4 zbBo#*r;`Kj%|->Uf8+`|-bb#*+Cv_1OQ!ILe&=!;Uu~vH1DWGn_4CNn#zRRO@h2Zu za1`ylG)4v>jWsc_r0hei*=x*;meZx0BCq@%J`8FboDjL>&6ZUU2)IJ_0elGefh1{NKA~?U_I3=X;Go z#iGor!CW*1+Y*p5obE5Rx4?KWT4lu-iOU?kU2)w+Ml6$9x6oRn7puX3Kq_yfN>JP& zJwhiC!J|n^50#oY4S!KW4&7EW_e=(bjd!L2w@OVu63yPTSu$NUmWj!5jR)hSp* zS>aZCNc5|Eu0SOiQ^22{tCN#JXk|QQp{^L8=8`W{2T9U8Bi6K1r93!=r#m}DC{6%^ z40!YL^_Z5H*M&><`ctE^;WPE}Ky0}%xh9cSC~!UAGwXkKdG*=#aNp>!^m|#O zZnEnST&NySpK+~asG0n1i;1P5h_qKSTbce#X$YceRd5cS6$FQ9)mt)95eWEr+Sf|JOGE z*BeR#pjV0gEVXq|JJ#A5PXCTobsk7ff1Fl*huo*A1p!-CWbRm^IeOcL-0IN}{Wh7Z z#1C3pMXAiw)D$2TRY^${Q9Qq$KuBR$gqnrf z0M6ser`opK^3K)>9NuwpaRfZ61pMZT@@dt@T?2))n+gmvi`d)J2P#G;&(vpZk$V~; zpu7X?e{%YqCPzi61=VXxVyA@S*;;$r#T9Y*@h7-(&0Dj7-)GX5j3bInosa4EkEV~aBT-57Xrqqo)eIe0y3P6&JHf|lIL7r~n}+CyI^WQUhlUc%YUUFf9?m%R zou1Vv(`wDtS>w%HGfa4pVnl|3;0*eEQpj@Uu8GDIOE)}5$k1R4-|KnPfk!5id6aer zrJC`gu2RJaUm_Ax7@~41zQkKFn;>RGYFY(|=Wl``-@EjpZQFvS}41C^SaHq(UsZE-9};>TEp8=pJSYn7OTaIP^RNQv)H^Lbn1ULYkm0 zJ}l}!-FXk5=w8=1`C#~IMH@*j8mrP&XWJ&~o)h#19c#gOa~fPpdXq0o`^WP|aF`5a z*?oZZdG(SBWer@_eLt4d5AcoPV`HD3oh4CB>l1w$t83qjGJI_@TpV*siLZW1Iw~Jp zuvb8%3d%?i(JS@7*zq&<^E12>$?>(rp-G!8Dk`$|XNJ$8(6-1~-r9=odIHX;_d`a1 zY<{5k_8t%pnNqq!m>17u$}`QhBjVeshmovtEgS;)8Uk|gRNiYx-YbydZ?#>o+#i$h zfA4!cEg=1lNq?zdUyoUyFr4wGlz=RGAzDZH{pG|$IBAL~8s6$SvKd~H2x;u6-8pS) zE$}5Hb0s373TDABXj5j&=q`^}=(wj(@QxikVv@<8yVK9Yql!QTjWhbBO7@z5t=5Z* zMVY>9HKZ!mW{8tf##1|6SEJ|UNW~+Fm7pBT@MevW^q8Yh*$Vn4=ge)sPMOrWvHeibxQQ zKtgFMB4b%*o%q~a;q#b#;WTW9w@5K{=*FP3R;23EXVVP8p@}fr_rYrNhRXi~R9iOy zlr7(PuRwH9Nf<5u@##VbMs@GN`FWdR89`#6s#;kEQ4B0Ni@7sNV4E|GkNa(2<0B7# z=L)Z|7k{NDA#A<@x)2&AG-`An05gl_&EClOzvs_`n7x2R=?%nJjY3_Dsg=wT@d=?D zVn>k}rnnbuL`XKBB>gD&yWjQJl^-VTr$-H7)Gm58fm!|7#~Ev%F?THc8HPHIc!2qM zkZi<(a8GJ?v(42^4&yL$>MT|-^HLlvGmnWh`s2fWfXEAUr+3$v9P+WYL9$9+1%#)I zj)WAp#rAKM%>A{m`w=^=SQ@w8wo4+y2a=X^BwDlEb0prFj!a~% z+}w_^p4dIq;PsKse@v|NsJVPe?^ zMnUaXG<8)zt5xD^awl_ED9^gJC8w2>3;sceNrn!lI%RPH5yaKoF|^{&q@mM1eJF;k zl`Ii}B8WMzPg6mD4V|>execS1@T&eT-h|f8dfJnbszpK$8$}kjDgAb79P4_9neuMX9b?~-{?!zVmtvsGcan{8s;oA_~0OMGrzF0cFJ}HXK=CE6xeR zBDZE1lQPmW61DyDydt-Gk`$0MiM2uzplfZLr#w$o^TKgeCQPfF2gb0{I0GnFJbgIJm7nI zQ1pLU1Tah-+v_uZq5~JbdZU3)S>R_ET!gh^4@WoVbu|1P%w0amg|yEzOP*s#w=0uTR3j{&)!o}QN^*4w zo)QN4dFkTptjKMuP9tfv57@>&CEar17q?y*e*d|!a5<;mPqwp!2Y^WpuxdUAlhJozZ%4 zmDPBpJFlH-9b9qU!@yE=!k-{B{jIC*zWc11>-(1@8`RXC&3ou*lbaG3sHveuF_y5V zvU?muVZ8g45q>t&5XAa)Lve)P1p(PsSe8u;s2>cTw@xZ}+$o0^V3f9*E2KF^d+$=Xrc780}KrxH88)iu?%{-O!k%Avi!Ngn2oB_cFn`A_*6sbI9r5w*> z#cf*^mD5icOGRlL3V1Ux-iYl{*j4GBIczjM<^?IGN^vryl}Y*yjI9uCZYojE`M~Bl z*5G`4VDeByMIujsC<#{lER)O^uBRjjF)_ekLz=6=w_(j|Hzd<1gF1seHd7r}LveZg8wqklzyIm|;v?xTm$4^>a z9~c(!yz0Qgc>&oH0l?*`qD&b|!qq@!?lKgH(09k%*W~kj%hAX2(~1|GBz)h8U?DRS z0We+^CK_Csy(v}mpQN7ws{VgtA5VmUmT36p;Y<)PrGR>1wSAg&^FH4G7;FhP%YdjF zZVS^LLpKaVcXxMpmo(A>0@4iWkkZ{9(v5UUNh6`8faFUE2uOT~d;RM_opa9KYp?aJ zp~9EY^Di&|TvoVDnm+?Ki&DeQ$vi_oiIAYvn6HK8WMt)#e~KuJemKiO1YzjLMC#MO9^JJ>GMMYH~JuSw-fBRIRDl${b@k+11NvGM0WbTz9o= zQ(SVK%te6Qvy9vh=be0^j$1A@w3&LEukPtwnr``N7tXJ_Fx|2r2p7Y)^%LjU_$)Gs zWx)MK2}66=^`V~+8;89#tstHCXaUam+xWsS{x*wV{MGQE;0(t-%(t$7j>PU|lki1c z!$Q7Un2dz)Eqa>dje5O}|0!CC_Haj~x0ud+0a?dqiRG9k zsi)n+&^x8`^q9t7ANK#qI#16k8#aFyBHiwJ6P;6+%jBT=H|EmyKlGkmPtAz@JB$1H zaepyLO7oC0Sc=7I=DXIsimb4hy3cWOFVgfOT+82^s3r%o26*;e%pQFPG4D>5z2a9y?) zeR)SCr&Z-9uTVQDR5fQNMY_3yMb_&JVF|2tj63nze`inM|KN8jF}IC-x&q->ARC)^ z1>i1JDx!k`jx!0jUL2AJSljHK5C*`CNYpPQgvj72)##PoPr~td@9~Xx>L(4i#mr=_{WYOA!ENnhmNfAKVUVbH=hF2viN|r2L zwGl1Q>&x-d;^)ck@y+kS@j`L-y_$5ZvtkPPsPnxqMvMSGtpDjpzx~fw#`ddLAoK3s zxf*~k2k_MU6}j#u8?!+Nd?Xg$cmp_bvhd#DX%%=YK_$Wnk|5+f8{O@^yu6_6d8IJI_G*}2` zz7{L5vbwzZel-33@bFad9eGnr>%QoCtQ?oSz@Pi*UZ0&kk;()P6Dx+|AdepyL4!oo zjOc%C(^lh2Go55N!mcUUOH3`B;%8RUIWW&A6> zwe&TC7O8?#_{>Y_2vetGFfdk9`BM#h7PSFY=D63&uqf5ZR`?cno65`W5r{)`DTLes zLJiS2qD`ljw$nOirRc90{1U$Po?92qY~TO-d7QL7?D2E_h?Y#kjsz2QS z{nz_ z4Xx6q%KG)~#OFAv0kj5y(Mt1b zUY>BpG|E>=DoyB%X@z}XUWKu>;yl>#GeZi$J0XZLPZ$T^wiNaPonJgzpMv)23Llm# ztD<;c$y|Ma8VDdIf}Z~rzFJTad|+U}Y#FVbs-3Rv$kT)U;~mBU@Z$cvqA`W3 zah#6ltH3s2!e63Mb4;&_d1aWlG(%>aNg>Ii)Gq!P6AAsykj)hwxSS)9Y3|!q$i|<; z?&@zXUeBp%R(vw5^F3W)=8fS-d&&HwL7dHF%g+eNIZ;NgRFEh-Qn838t-h07lJ=O) zn?yRH7Sc!?m8pV38eZnf_=l3LrN1eJq?z5;GqEYcA`cIae?C2LhvokFd8I-#@SyL`PySuvsmO_tjuLhl0=33#eEdXICW&uMI;UW)s z#Wpl~#!f}NpDmEkUwey&?wwsn&+9oDfNjEs>u9VyMA8ADno={8+&5=`##q+-OSrI= z1f;+VVS-W8&uNUw_{hO8oWbks^@JC`CBt|m3<{e)1^*(( zY~WCE4E*Y>xu)g$*1a)Geq~WE)-0#DN}^MV=F3Y6?8~n2K9=g{R&qq@esgW{#GuXa z)qzr~CoTZuMm~^X5v_&J8>&GY6U^MZkfGrPcC1W9)qQpo_!aof6UPJIc%vi9vn=lu zKrqRgc}Ofoql)oRnq?|h9WGn5`+yDc@pBpgKXn4!yRPAVtF<%hz^) zo%zoJCc*kE>YB^_(w{kqG?NcfwVnU4$$iOy@s+u%au;D84^HdI3Ctns_LQuMfHl{s zWa+_Io+GePspejw0O#%``c2?j8}NSB9~n;Q*u& zV0@>09hrglc|>2G@o-GwEHJk-{E>`?k_QfLe1ZGJQ3+GG484BnQV2nDe@cPs*0ce$ zI5yD)JmLm`zAgf3>J*eFqAQJk?DJS+1gDplV&FP`o7ZLV5}t$>km}w!;e{PyxqAlvasnbk3X6xTT-KrG`xC08%#Ig1q%g;Et8FJz+g0s<{Ur!DzV_+JQa zMS>PW{=6n5hky~ApbLEgh=;K1shGb_+W8m{N1N=Xs4G@mPT#7pCE!LHbxoKf7AiL( zguaX4a~^cqdH9$p8ym{VZ@6%9FHEakQN8>=7| zjLw=8)74xbc4W+s2|upDxQZ#LunO?{mC!`C`Sz^6Nf}L#ylsDfPJG=emNo#GIItv$ zh>K&{bpcVe38nH{plt*owNael{7bISc~c7Y%_ud+ySHOa);a+$nZJQZdb|pPOMTyi zbH*?rQf+?NlK85G%VE*psE;B58GOeN`I=FP6E+k0w{KGaAp|P^#{sYFQ91`t;W%b+ zEKM&d?eXV;%8-cl$}g^OA{kvW`qb7$!m=LN9AX&LpLidbi1tx%y2AL>$*uDkcsQH( zj79uK$9jS*@K)|uZj6aWcGzczMlkr8y!bo|O0bJJTb(z(4g^h13=Qkkj2cXS{8%AT zbanDp_A1y?wLReZEt*h}IKPZphrBO)ps$nI#%z&_YB}v?OIV(J@R791k38jvj(z0* zzxN9nKObpJG5ev|MbSEAMIafTZr8K%1gZwK1Fr~Kl%b20H`;~yq=8OGwtJoZ&QH-h zL{wKM8`B-B+^&k6P_v|W5@SxC{(lYFJtAyY^T_(P2m0 zW;!$UD}}OhliQ!>ok;Q`|;OR zmDq7)x8nE3w|l7T(-*b|NH4UOEGGk-5~X#8k9`HP0!)EW1Sl3-FHt4~&yRteR7Kiz zp{cBXa^LuQr<;Y4a5=)m4!O!QJ%pp+k;iG_lffCJ-tzS#}4qa>WzMY-i#LSV<9AetB^iA{7nQ4K*QZU5Bd8APNTvL=)&=|`bHxh)6+## zx@E@31~eICA?D5_qxr%oYa^e&E+nCsah8$yQjZ^BE-as?LI>pwUmx)MR4Mr8cfhxx zrSRz#$VIDgAnD@Sx3*BWVbX(7$4Q)IOg zg_`~*$4f5X22KE~Jy#zva@ z5rMxR<6{1vXidWS?e`p*cDrPhi2M`k+Dw~YypRXm#5))ynlY~!Z~0YaulC+z%W=mA zwRDaTiSC(o9}vQUlef~M>liIeT7wQx|ID79S&)trgSE$`{?k0QUDYNuh?VhKoTU5B zUWbdkgtRg4Vz%EBkH9Xz9o{qkso+ZLaNsW#EV|T6w8(6$8j6Lav#(rch2zPc!o`J` zOd)UXtr;{GC&89ZQlsd5=x;437T`Lo7W%BjwfXFAJ!Npd*;suzY7*Q|$>2mdlQG%F z9bZ}Lys!Hg`}}1*XStH-iU@>`T@q1KERpW3Whm-Hw6_Q8$uh+nc|J%K`_HOFzE2d) z%j1ZjMUohyXQIy(R3B~D{KL9```CuH!=VS5j!q8{nKsR^7882v%)CgogHDkgLwYZC>T46Ia zw5Gt=v834=vvBJvIjF+rt$s*|w7Wz2?egv++XsPEgj=sBPfA6K<-V}Omk6Ko$FUQ_ zLQqvc;+0||2yx00SwWQKR_940Fa|w;ds}S6+y0gINNz-Rf1k-!6?IsPK-S6 z08CcD#$IRwU*O%2bg1rjEyeGD<~?lw2p0S8-nNutDx#(grj_RxTzhvB@8)p2FZ5>W zr1yR{aMd<&jGB*hmOUOdeh|uohAfQ_F3#&V%YWa!A@tkt>VD|OsBQMidkJ6s(+X&> zysq}x0UmE&X<~XX+2Ww<~rU=Py<12d$`l`}WPU zlUrC)aso>hMNqH&A>Gv}kq~kvb8Ug?6FjXiq_Z?Cd~2b)q{biiz#ZQmRZc@PwGlY4qwc7Wy$g?8F0o&<#MaxJuBoRYp+S!Hx8eWN7-+-aE= zgP_tOila7-Xi4QSIe0Z=%TXYWO8qt2SQW%YqYg)y4f~H41RqpZtR7u|*8#F`LcX6( zbKSJxk!8jiXKnt96JFSUV8zD%wqhP^A^0OQ(2%1yAYU)cx#s&{OGQ66q|jfzArRxY`U;cDqZJ_J=%9D<#6JQUMHM|7_(-`AR` z4(p`X9i+>j2*-rRMT661!(_6e^qQs1;N-&|*kQ`0KE>PBm-Em&7wKkMrT3m&Ls}Lh zGhRviu1b^N74*MW>$`7(a<2dWEfo8Z2$TO0UL{^uUiNk%3~~E3{2F;@y!h8-$8zvt zFSYy+G|ou`*<>A9dA*=_6Y_LD?YZsxl~JW zsNfu=u7wBSwE<&$ZkTOZBkm8@FmNf<1`9PW*%Jvb4qbumO~lGuE`*vz$iOxNSldn` z45SD`Z6ve2{=&`w7l;kLIuEAVu4Q-^Bf7z&^bSUjRw2!i9qt>ie#c~pUQUE28UkVp zGMdf00GjL}9O59VNr1)|b=Tda*T(|rK|0SWpEj=GoEOBlctv0Ut}r0tW>P25^zZNa zTiTy~zY_RW&ES?5tli*<-Y0#}Rr4!qlztO*sSr6=4g89G0e*F{Pxuwh^9Ab1Pp4Zw z_7<#ErT9d_pPo@-{Du$5@9zJQ5R)u@;bzB?Kf*j|gTq;Sudjoz&I?Au1YW}2fDqfUtdgUEeGQxGpN$Ex zp@slM^C*7NYiWwQPVu-@LQ z233U=X$8+)1TUmhi>Ce>ldq>;+)P!zi+-ENRzZToBg?*6Wti2`RA0YY>uZs#ea^jd zzyv)-b1t(~_4E1dhZ#Z!El1d%@?ie;>({APCl)#;v%MhZHm`@j_Jxec?gku;kVUHI zJbJtj6Zvf{CgOG`8M@9-1~(ndSj3HIGDw(y654nyl4+%AbyaLZiOL8VEGn(U&e6<(*4o;-{Y?d)Qi8?Z0;gzhkU3S~x|4z!Wc6F8R9*Qkf+J2@$$HBatS^*D#ti_;m*MWqFA5 zAjd~p5JKWO4TX1Jeq+@1Mvi6KbfrRjq#^q4(f6@gLPzA`1%BbNE2|T=;6uDhRy-A zo9BtyewQa%S;q@VOh*F5zjASA*8Cb&W{>8t1aaJaPUS5vEoyRFTC-RCQ`tn*)<_sq z1S#Wk^>D>RgsSsprKJ(kbLLX1p5z);Fk^l@&SHvzp+O3`)dc>^(8BC)JC&xgDy0m= ztR#IU`0r>ABETj!u-&CEnmkdK)!&E*szQ}y|5}Uk{yk<~oQOIsFd0v#S@8Y08MRd9 zuz(|lvzcQOHxZ^Cfz`A7;ZSW%?I~3yd{VQgrk$F1A899b0SUvfw`g*V!ta5u41;GAl9F+<|Ra{sfksD zI?9pEQW-uNAv@WdNM&aY!cI+x5Q~5bFs&wbWQ;qUV^@fF>^(%C z6OPW1+Hdp7go$ZxeuWz6BmsFxtQmttrrOm z?O5Jvtr|X~*WC5H)y6P?AAq6-yf{Cm$?*V+(Kbbgs9m< zDXpZiK$)~ius2yzx?ZK`Yl6fBf3fEm)wywpJC$MxfE2`~S>Ia7IXiSrGlPT>eYGCj z*xR+)zdqtCr6V|W|AEgsPbW%fAsgre)hEjp{cb3gYXdYPqGTs5CR9@}9kZr{q%C`0 zBjabl0!oQbvg-HOPoMf87NXBrJ-6bRY#RO2rJwBb1u*pcdR#OjtKAOSx8wFv&)ApfDjl(DW*pql;1Kchv`P zilr!=4T>YYU)2vFf6^xlJOu-)<=N1~c>|LhVHml#0=QPAG#tf;1JOq|xKvR^-$>=! zO#BV>laIRCLHfqLh>(#ik1YR}8mYFF#$9>$QQ7jYuCtojdKYJBgF;EY04EK8Mi>-J zmE+G8(z_^dzx)7U@)^yiVKO!94x9w|d~|Hy<5q%Rn~Y7Xw20UQRjeTgm-acN+5q)0wa^;s&T+ON#K))=_6Tz%%ib1YixP;TKWO$@Vp0*_98zj%4ib_ zR{!fqKK3bfYF?m(!FeA=mEkEghhsuKbOgf-#nY@jEsz00knv@uvZ)(0fI|ib+rm%McT3s zGa=CB5-`Ql0bp>#@d)?Jxh|GYVnEFh4e7%&UKMF$vAJyg?awydS{~AN(hA5*#cs(fUA+ngdcfeD@j1juCU3cXA7Lz@nKoQAbyk zi=`)=! zW*#f|bJp+NQQm^D9_(UR#$1uqj4z8YQI^$C;b-<-AaNg!xiASlrR^aBa%3XZ?mv6_ zI^H28I!0@D>FaE{f5?mdgevXcCeqYd;?u|1lEtrfJuIXb9l&Xbh_Flpo4M@&5BySN zZC@mkQhj?^y1PU;S`9}A(r?vCErNg~R8--eU89rRe!?xr47TL%%NHU> z>jeRi_MT01>kIyi2_0iLk>h!SE}qe4Hx~huTRliooULP$s7E_xzWg^2OUo%5X&Mqzy zsjmDlf3~IG>?et{{etz%AJI_Pliq-?%pC~9O(6wK=bkq_7 zgdYaGqdyX9V8L5)CX#s(DRobb{DJ};>V)@z=|-w{XQ^6mn~;a-yz^J$D}R zBw&nG)savwk}kee+|hm?gW*R4*U5kGZZ5O!f=s+lnLPxbm{J@V_eVF3=O;;e?c@-# z97`m7bg|>oi_9;s$ylobM*bR{Wjv}XJaKZy&Xf1?U8k#(hBYT{Rsd9=_SW_QgBb_o zA7Fmogd%lZIX;IpG2TDH9QPT1$v8+3DYRuutfmWpO_$0siDZvDqtW8s@lfF#k7!Gc z($u&Nepi<IVPSzpFP6H)V1ooo%ehonco++3s{z7Q6nn<}w2)v1dhAsENAqkeFpql2IzG2>I;MIk^;!U8B^ z&0xIxhl*c_HEN5z*Ku)iBZq)*RxB_`AL$2B>;_ny-F$-`B)>=C41AJy_y-hrxFaB= zy=NVOJ_#ivJJ~bIK3>0+GS$b zvIG+>kx~vsVNtOTkK7r`j5eNzP@@}+a#hDw7a`Za{dO^-cN@*_i;Odh-!wSRINU6H zB{ViHV%iTDls6NZ1l@l$g)ANf6$^`fvHGfeX(w8ZR@@A_lX^|%j%7U~xHS@=eq z+;%5$(uW%qNp;eGeOqswtX^@UwX6#IRJnv|imvHe5t;8*W3e`Lbzo!L;~eeoXpf~w zqY0cgWid_XjCfkrkLcYI810dRzbOr2k=fc4*dueu+HYrat9uEaaA^1c)H0MhnxwZD zV@9DP7#qR?8m zBf#>ADyf?n*D2^ZIPC?e`G}my&I}T#!inqcZ)gCJBL4;c7TcOYSN|y#IPq$d-i7mA z6P~=i^-UD(Ecn~=TY|C=51B$5uNd7LDQ^Vi$54U|>bY25B~1tiEG`l>4|5-Z2ShZF zWD^@{C0Z%9@SO$V3YhV9c2=eKl}kfIRnj`jhZB~+E+#aWu6u($1V$@r(<26wv&9~|KX?S*JUG14!r1##S^}_ zGp`Ec$R!}Dovx8a7N?n|%HIMHV;4O9U!veg%`DmLx*%Cn^LQgI~sk@Of&v`uQM~L zjAXoq%^d^Y9UJtBS7Rw~USeXk=;Y3tRb*%V0vkyUswuP(yH_L9dhOGjEr{)_UZVqm8SL%DN9@yF~ z+v=JGn&zaOeMCR>{(H!GF~p(~B^Leu?L6Rz1WnNIb*jvI;|{MM47rAN$7Wwbp01W_ zbIizdnvYaR3oVVWA7f8E^4=p*zSV9sw_W_Mv9U3w!Im*=gf%rfP~6@3>pp9vr ze!-+j#Qmhsk_LPY321(LO>rn&`A84a0KKZ9hHpJ(oMJSDyXZlS79TdE3T2h|D618S zcVOifcnkCMv<-Fm#vZW{Bom z{f~hX`&s~K25lR@%wi;#nRcNqZUn<336}aIrM^yjsos7QuB6@BjQsPlmJy!D0K6+Q8eSw_ zmMcPh9CvC7X$x#TBH`>Ga7P6)*tYFLI1d9+m?U!4aw0D4S>{-(|8G7cewF#m9q*cc2BT z&b&pWEW9-Sdw8eP??(uLZTer9RGtBvjPa@C5MMt!L{N0C)5ur`ETry}s-5ifzmH>zRc`{-2h((o(s@-5Mbi1GsQKFp-B>b=mm`$|PVLyRnzv|sQ84wdDLSry`UwL5%Z8tlW^>Zj8Kc&rA?e0>hC zp7o;K#$<)tdxHQ#cTI;& zqm8HaQR?YCaJDR^c{=}tp)va3eqh_loOPf+)ffd7GWZfBjf#g1Ca@<(i)>@i7GIny}%+fN3V<0#*k2fG(Wbzy}h?5Ebbjv z#CI`_iTH#V@tbeW&c!8F92sF;I;kY(=l-CoBLg1?IoKvAoz2L7v&SExOm2H4iDFUy z1#*Jz4Gp-JO+6nJ#4{*q3fVIz*)kgF#RPcnSLr@c`yGrXSH7u#KI}UEROk|Tm0fWz zvHrAe`=ww#upu*aW%}pX@4tWhdj1MFc+|T21>#EFmcI-6m%9~my`vOzcZgdUdK)E& ziaR^Yb-L;ah_@ToLb5cgJ26JJBktgmHjDdgO+7pERN3i&VP<3- z#jOf0H>_OZ+FDnCYWWzltY_)XMImoD*~}_!mvKl|E&8#u{HVM?pVfjmQtBqWp&>kL z&gdQCM@hms(o8@3-tmaGc@noYiC$G>4%FhW^e{0-J^iSjY3-lre_Fb#+Z=wBN4*?` z3l)w5KX#|c(CpmY;ZhzGPenfnj6F~sXFwB5P=@wNt`mye4Om1()Zf#murV|nG|ucP z8Se>?`pR;65I=4_lz!ah1Z%LY6|t4xg$Uq(Jg zI9V}P8vcwWjV}Uc$taT*u3SKu3a{r)ryZTs5F#2bsL2AUZMWRFJVO~2oA!OlLYLHl z%&>WchB6a4TVbK~Zzm_AwcZ)UTr3+CE&1ZXO{kM5%dsYe7m-GUBi-ng6%QiWE+x`P zXk+C}vijkG7OagevfE*KQBjBVi&o_h1lGE^N`O_lHz=Cdh z6Hl$=r3p*E~s53Vo6Mt7Qp@(U=wT^CLloPWBp^mzEkM>pJ& z87}tzpiQpDD1mF!b-ng&#lhcmvFED-rjUyfl9vOu(3`cF%PpyYQqQ+>mj0Jf68m00 z4!$9d9<8TjG5Yb+u`#8aDV`g*iS>4j2{?xlA9j?>Jx{f?tvc&d6HQn;Y_hw!r%Su{ zCw?i(Be#_z>%jg)f>%GwDM7fg01?T8RM5giN$8sS3AH#tIgCJ;Cx)A28euNKC5O)I=8XQeR{;E;s)F44c zcp!mEP4kr#0fg{ArSGi$$LchASHR)z+w8dU;@!hT=1U|Z&+yZrrBSzDK!!ALcO?_U zrcQ<1{jv2dxT#d1xjo*z_F3JA6!z}*AlT*X_3x}>N>hrLcgX$vYv|+GLLk*41vqYk zb}%iWA6ZMNG2TndqsoHl;RuQ16b|vKLXMxP;bbbbA!XFy?~B#48HsQZ)w-?~Hx7uo zG;`Z7LsbKX0Ii91%Ti7s+8eEpy0z^{-R%$z-Ps74MyxboAAKF#B3({7nX4I=rJdn# z?i8Sh-JHGMkz{l^(qQ3bCp?Uzehw%7%j+oF5YNl;;$h2w>noCf)?RL3T`~8-!z#qX z6UKN-pw3jH9ut5Uo}Q$*G=(M!ARDp%zIN-C7<*@+Gjgbo|07QzTtayWMQ??FbJj+R z4TbSGix#P&BBPd=rhKP+hlZBMk8r2J7_9VJT25{lSOL&wic$>(ZaQ}MiSV6c((Qs( zGUmeSNCbKC%1ODqnXmNVkdwe@ZcSKDRG4z|Xy6@$V^8`dGo3t$p!-iWDK|W#CQa)B zT#zqbw;A(;yS`BO9V#8sswI9JfEWU3QYcD7Urx8+MQ^7}9%)XMgVa+*J_sS||2 zb+E3Kv?L45hS{~*YhTs>+78&@&Dve@3iYJexjWk0@CL0~k0y4SnrIiVzI2Ob_;mb} zxtu;KRn!*L?fiTfTd~(1xtPssnuGOaki8-vljR+)ZDt+!0ck@0@?lml2S=v+TFN)O zF~zajJc$q2BbR({|LOSHI6qwM4Aa?`-Z8lv*OS|G4SXn?ZvId6YfKaWA^9XCDTh7@ z?{rOh#fODr{7e0L3^hTqep9(l$D0HOXu*Q5{o42h(gPo(=yn`2BAQHpfFR&4F|gd* zp0z7;p^QZ>#S1;GrDKIu*LaL975d?F$ORXE<4hyfCa2XLdaekfs_#%T!S(0;4oUcq z?B61-ao(|=32&TH1|YZSvp{*};VZTQzzw~T3=|IC_CyNcUB%MQm0j(h= zhQk}Mw>9e-BQi2?3jXKocYI$isy+3>uPy0v^y&Kzm)b>TzYLQgJf4o72-7^Ed{)K? zzZ`ygKE!>wzy)^A5Qs$uh8b0EhWS>?1sWuf6~78Is@U#2+lTV0`Uar2kW5RgeNYg_ z0+U0&r5nCrCH=P&v6=uO)Z>$WS3kreZ=iwbr%zvwAPeN+-=JQHv+_pBY6cid2KmBCSJiWSF=!nU8rGV+8=Ru}2EQHXc#oY&jM?pg)@%|vvI$$kt{)mjDFP+tIq9^&Y zX#MZ#g5bgSXua?HldPkZvzkUJ8tG%vx<8LkkDXoJRT(bdHTj$fngdo|eBPNEO|y0# z_UhTs$4r{oLOX)|Z#fokYC;S)GB0aomW{N+vW^$4qYJ&CTFpEkn~!!rrXCMpSSPQ2 z9hswvWn2O$H7+wPEtBluAX`W%7SmK2%a0P^mFPWvpL%I$lBNNWuV!Np!k z-lgUBt*B*mAzM&p-vwky#AQqG09M&8AR(B@6y6#7^2`-_Kjl{i7`l3BIiXL{qzIZ_ z$iu|4WnMrw4+`TC8u3}N_$vlv{%BtAzDnITeR={chBU7*;r{yjXvH2>@S=f0M7A+IHILs&q9o~<5jKk20qs%pZAP{j)6 z2bV07z~}rGAcU_DSC?-7EGm5$2GfvkhHeWmVr$!thR5+YPqrQAEBfhwTaoRZMw2H5 zwS`m4$Qwvc=@oXD90Ggko;mDyRH43V6n0W<%Fso0kvsiK;KTxF!8cqDt=zC;B{Y_n zD0W+o!;66kTp(3dc;E8!SlEBN+`sj-Ff|%fkZd1MT3wYM5LK;d$ZrQC3(i7UB(oX% zDfRqI3aB{#xMr~(Mizb8o&>82)A`bH8BpcfkE4(JMu>pEoR}&BMHyCeqSnHUADE1^ zyotZ0Og_%K=#;I)A{_itxqo$LU&XrF1_Xx*3U92CXMlGQo)@__0m>=ACt)If*1MzI z*aWpIkJ7pFM^=;Z60;EI!N~$$d~vF7Zf=139rW^VD-17sK zCfID4$1*pf_fpf4l3EoW_$_X1L}gn2#EhD}|MS}ue0Jt`q#ll5Nyv?ECvoa#)&#=L z#xcl3DMQn#Sdx?T>Cvuyc4U7TmZp^MhfqK;z_$R19{Y`>wY7UdK>N#2c`{UEX6gS4pmE=#2tFH;5iV z>KCV-&7x-3-$|BPmxe6&&4L=gFdS|)kvlyamPN}PBcEj|qV`ZSU5E0A`08%^;lhAe zMGp|sluF7H8BYjwI{9vgz5uw!{PQ5DWF#h5e`&zR z^y=o1X`hon(YLy2YZx`2>(`G=tKkL{GH~}<{%M-x-3viFQI3NTcR32p%@^EtW z6eubGL(g`OVGsMy(XDt{xxq|Oz|M!LW(4SR#ATJL%`LJ zERcnVILJUcVfYg<#~64$l4>=P$Gx#`h>JUv*0941xRPk;;JTFvQLCLN59e0*$OjU^ zi+8b>>!YWqZ2xZ0{{8o%|6e&*aLhctuej%KWMn1anPBxrCNsSA`PbGr$2rXO2iw6r z8Uews#l+^@>n*py^575)cUrY{-4Z*AuH@NYJGG=(aX}srGrT>Ejg^57O9zlKbw*9! zAdUdn7VSeumR`n!0m(T!9d#*UWV628f0L?>D&CrSj~zd~FwKNtrPS{g@~k&GkKRQb zW!C<>;aPM_iLZ3$&n^(G^>V_E*K)ttwu;AbCCO&nuQ*F|Z$yIbxTzyX6WLySVD~D$ z3jvC#CLZ9BeQj_LZD>X~Xyc25GeYnbJfpj~=eE|@ zDdVbz4TPumS$%bXhY+1~H>%L9D*ly*{}oOLX_uC;C}-!uz>O}6nB$qb+Lyq_J|^*< zDL5<4$(ayrbv5p1DC8;>4gp~21-&BkYj0fL$j==q51oZG+q9y~Thd4Iq@*@dgwGCU zS4Y=6P1J=5o9i$ymy9Ka_<4;D3K=k)v9Z|<>(t-!{hs~Hb#RbP!gE7}xa-T;Va%)k zrLK-4J+`)Lz(`SBO-qVVHr9QDTm45@8lUyYt^u_GYnQb|qI~2urtPBhV@7m6X6-HQ zx8`up3b`y{(VxfG=@)fild8fc#fD|x3ktk}+4Doil~~rAMIk6mc^1r>Y++|3r&(vH z$A5X}X^CbVsi|%jJMn|KF;wBxbkeuPFTSgF^}|^uD*VIdLoqiL=6jqgmII8(NluXw zsr&F$B*WwmhyzMJKqYSXPBg^@A^W?ZlfOOz?@pQ*KLGVG=LuOV&v=9)!-px~ZKFzc z0z*tVV&r%`{E#716buQhrckzXLmhM>V@^st^O~Yn)auZQHQR9wqs%)6ZrBQOUR^{l zR{)a)dS`2Ahtwaju56pHEVLZHQ1qqNX#J$903JlGdxR-FULpwdz(Au=)>n{bPEkZF zfjmFNN(X1?o8p;E^YqrE!^MJSlVgVzWAT*BF|z`koiSSa0Y@WkBb{0@sZs!wETkv{ z%B_uoHe~F9weRgDT=8p6IJbsQ|L`l-@ZZU2n=bxdzsHN6N=v_kk6IF!hqhAd9ly8l zuCa9N%#Mo4FlF@(?*Il=IQ2EZ+{iiOEOXIT%}K2tQ=q>{n6`b}By z+@0N>oNlHE+Bjr0f?;sNtnjB#fLEwT zUI&hlh3Eh+`GB5{2%h-{T#jH@J>)%FoQmMx-_?~p7X+ZhxUFcqadBO=CG9xz=fWUa z)!{K{->U%)dwyYIh?gEIOh(us6)0LBVOBu7TAMLxgxMfBRiKG6GBQSg{OHvs{s1O+ z@O7te`MQWSl|g`6o9-b~FNXjAbhGz0T{D;f`f|F}Unnhaj)As=CK=`t3AHtr<1`|r zq6$19yRrWeeR}Lt-}7|aF>0PUx1ao#nmU(swL7@CZWGgx!nS%k)!bf zUHH(UmO7)6B`BOxel<^>oSYmjYCg&F?(zPQFdJzjx&*^$J78`NR#IZZ=(!kDBjLP$ zx6!i$9Q-5ymTxquYkZ69Tm1Pw%h8>akuS2_R^!|6)CoS{&r<36mVFQ2)s2oO?=_u$ zM{AmHYEkl_n){sbBn}5`%ait*<`3;+?&trR++KX>{}OmE=}~rVS3I ztg^|j!A@xy@_rKdmr8KRMI285VY{Fs$O}&=^V6y}@ZcaK$tHcR&z{<6hCl(%*FS+S zGc5(uvTpoqQ4nn!f(Nfh85XB}qGe2EfK$1C{apbG6L+HsCs8b>-dEi7r+Hi4t(W}J z$IHdp_;~f~_T}&EDNc^@Og8f9+$Sdj>g<99%lu$bxK?Ix-7qpl0pYk;TFGs~ecHm< zSUl)@b>t2!*VgERP$H3K4FVz3@h{^xW1Vv@=Q)I%Gjh+tcRzovK$l{nCaOWxniF0F z2#4Biz(!(vX{00r0v}U>uLEE(8)sAN#>2byHkWfCEXyde%tEyDSzsvm)(Zh4t5n9$ z!-OOfY-H|<>}{Q4TBZ%R938Dp<3XB{WC|NDz%FlUO0EbD3xw6cmvj1~_jHjB7`CObkbNH`6ig=EneJ|;`{-__ySs;pslzrl_F&?@ zz5WLL?(Y?!i_Lx>lWeV|i~DO@j+-l6TZdXD{(aV}$_@oj!jQFXe{EU5lB)Uwrde09 zt}N-!t5mcTq-=io?Jl~pK-4QMG4CV!gM9aQ-pRn)o(^Xdg{xWnPc~YC8zVP5Aj{1L zm#(aDq(v@qr!Dinlo?@*XjRV9Sq45~Lj|wK+=dp&t~^xQC*co_-K(wD^M$Uv7Xp(OL!FI` z$oGh&Cp~QpT55n4Xvc@X3zOa5T^{RIWQ+G&l#DT7hh?hg#{P@7>c1P~Jj@evAt-qK z7yR-I&|Is+KKTRw76T(A9&4vEh@?s_{thHYA{W7_ZBhAMQGqBI&OScM9A&7x7!wPx zeLv}VN_2-CdUX`eB<*#MH@uc*AUIJzgAk?wC80?hF3W-nXPO~^ zmsndo&zB4I_H%YcO#>`?TOFNRk&uC2`3v*e;;A47~gsz>!!ky?z)1W-T{@pEja# zs7%`(GjXfOJk1YY4|Tw*Qg|I5%t7N}g?rOgC9HV@F6INR@}x2!$PmrPSao2(Q{-}8`>!xL}IB|Q@(40BB(5u{w0|E_eLMI~Xn+d7fYNt7od zGHq%Qcv`IQ=yLwBIU%vNwx!Ifz5b_9;JC@Uepm4S8OUL{nVDQ`j~4$N!+g!>Z!iD7 zWLhCXaXqN&4gfXC?Bj8!vw5A7F^V^_aJ&=?7{1i`exL0em`l3?_GB2EHUZkeP(;8o z;)hod#VZ$roQ$lrRBT4xCm;DI8ULsMZzRTY(e*Y8&fCM|>>T{P(M zl_p@EI1O@PKRzV~O}=vNzbJ7b8?>bzm& zoMndmBZBpX^81T7_VIj<1rS{3VX{S=1kfe$C^x*mslV^I@(DFbPBvH(sTE{3(L-pX z;qh&u(VFbvPvueOad7f;^4=QiQwR(L+n`XbByx3il?Mg&`9dm#$xm`C)x>>WF4-P} z@@1sY%|$ zX>>*P;VmMiX9<}D7=jm=*%Pa@yG;YV1NE!gKk&D`u>_7WC}z?QDdz_p)8F~mWm$@g z=Dgfse`^akeT-G)R9!GG8eIPN;5$_Uhvvs~YJ9r2UKULM%jSt^K&Ff#>hw4oe=Vxg zoLMMoL^1QJvk#WC8MRdgc93feV-6OcAJwrb zcD#-oT&fd(bitgQS&*2u^YXr`7j!j!SQsi9djI#ktn{v@T$qYlY>u}2P1%_@UEbU> z?$1cy92WP|LS0>UifW9i=v>T~G-ZyD3xU627e>e1%>n&Y8D^NZuu}(iUZQ{3UJGLP z-_zyC%)WM32#E@c3btB|^tgy}Bnk@59h2;G=~GbVz9FBjwZp(HwZnAP);Ar^dS>N*jy}aykl;R0X^U)3|d9cH`*i^wLqNr-9vD5R3 zun={G@Eo?s=dt`=Tv0Tk)YRhuN#SSd(Q7+!9nsTf7G*m>@5w|GRGx=rx=ekKkJm{S zqSJ2<_yM541`>st`T1`}mupI(@9FRIkoS7<{$PaLH|(=zujkuhzZLV_AA}Es^JsZE zOEUrr6{v&)T@dBKRr5(G&hh^RxZj5HutIN^K};oA1Lww;Dh!#26mt3?@{ zA6u;oVkC(WJk(HSsL0Q7-_w&5SD-tw4L;Ls82XPY@Mg&k*ilz3TOwdoE2cs9H~-cj zNHHU%hBrM~fZUCqwlRaUQYa@a#LKSf(J=mlIb+4*8;E*v=l!$Q) z9}E%j`rg71He(iN!$`qEfD&wmTLMbLRvf&f7BY)+o=Bq9&m;_w_b|s5sIH=0my#W7 zDhF%bHQ$fkO#b{_C>-RyaCQ}YeUN_NO~Y#JK4+Upv-3gH461Qys=5|NsbdNdQ z=0LN_wIuAO`^)#1VK9<~~Z~Y?lY`)eo;M?*K z;AVIxop~GK?*DpKPI$pLMMpBjKNc z3QL9$k~kTUyCi8j5j=DKDb04qKHL-=Q!X`Wn&u)Ad)EEyZ9Yn%o&t^8EwGt!q<4Hn zK|w)DX|r~OOAU_p!OA;}Wek0jlbDz|8~57t-3MCe#CJ71ftQEm0(F%Gz)f$~=kMa> zML^?F9S=jH@C{?s2vHS7ZMPL~T} zitX9eo9;5k&W3OP6O?WP2jh9`^`_lcD-X&aock;{8dw{9en%O(_IRJ#+|{}T9_1M2UFleVZ<9C-?s083;%i@}4ykhk+ zyTZw^AqihYR_={Iwa)C2u?&N_=1^1|pLL85C8c`Gs_O_78G#l7VQoc3TunBS-0?jl z-{oLqZbv%bp^gL>Cng;>1YtY4UcTNZ1CsuWwH@mA+U3+3mfmRxC=be!SjQXF+4 z!H^NnBq#nVl3|$F>HL(Pz@S0arA~(D;YXmX`~jF#;}aA-(ufgz&7XU|1(Q*i57GeO z%+@sFFB;18GWkfd`j&vEhx_EN#_IR#r+o)*>1;QqGhPAD<%5u$<>JPDg z)Mbi!H2{LSe-XQ{nIq}j_$aLRrO{RBE3AgLGuz#vvQ2Nq+miGaEJVd@B*MmBioSzOFW zUidepq=V!M2?JY=t&2O*zWp{8+ZaT~;8h*wC=HZ^BGMh^V8!i6j)o;LYE^ z`3#xxReIq543x?!-+B7|SGddBdpBIN68*rLFYa~Y_mWyR@n8SpDRJYT&pi-e!cO{| zjDyu^)@}RI%#9(>Q>L+-W_NFGYj10--Fa&|Gw>L4eh(}ne*g5XC^z5oKU?f5_@8{{ z&-DfaHEuR`Y;QO}>ql9fjZqweKlgoWRh9UuZBn`DQsjZTplcCc_OrT5t!3dt&vh+; zA(XgfS=-I$szlkl`y`_H`K*E?CE-Cq->1eQq^9D}<|tzpDDZ3ClDv)UyP)scffWOg z_QR=itH}Nba4(5Kr>|+tQ`)h(I8%KM4fbxi2cH&JUrwkqb5?xJjC*iPIEs#QYBH=E^$b+lF%O4t{Omsc-mYDD z(cg0Q`^b7_a+^m)6g8}B9S2)EH%-%OD|nlK_4nbscuK+`$BS7pAVJ53IBB|pIc1gje4T$JXXS7hi_x| zVNG7AOJ9CjS0qv&!Hk`BMyIyN;>&-Dq;ULn7{ia&mcf7-XYtljMkUcj6D_3DH297d z4K9PMLKISz=zfO>8ZNy!Kfeb=<2%-Y->eW>*4bd)Z?AkU&Yp$Z;i)m%SC0dQG=z8zL_4aF zHzoID%{sN8^lp5P|HKoEwpP9?Jm|S@UONA5wk^mfbgr`{w^g>5_|`!>Bx(Jz9-_x3)_qz7-wk@XCV_YKhra zDd{X)=CvEK*R(v07{YMS+VglMu@pkk9osV5%=)g#M-#dXu31k}^QeNig#>lE)3#8; z(rWxsSoN?4owxme?f&QO(`KkkW{{mF@k1@;`Xs!wA?y)BlGv2bCOb*v`;gBLD`5aG z=o4uz-nY?)k=SU`Fj|E9NH4?&rAJC|6 z@kCIV2rpnib`u07mDjWRfaG%+PS;fp5F`d^JSBcBWHSY*Xu5wU6kl9aTTh5CDUQ9V9)v?54ikm(2-2l?`6(` z85^_JHcH}S)4Xkd_o8F0*Effu_}>K$ES1G{85PNkZFVj@^xN)Mo3GA9mg+9~db^+i zl5UDuostGSl9X`H`-S7*6a#-Eho}1!S-xuoPip<*a1@?KbxL)EyPaMYRQ*n)C)LF6 zMM@rX9uaM*IR?^;TBdfETxFiSV?h{#2kpX1+<#mR?666O;iTvL^e_j4T0 zT)k%lOMG02OX;vT;ji$Cl4>!m-q?HtX8xUuLc4^ShBtf&4JRzYL8z8v`UmWH5rni% zr@SX}z(Cf2#x?M!#+9Om;2n&DJ@p7BU9!Yx0)QWL^Znt-(4&du0^v_era8hvkE1i3 zzW~c_a*1}rEZ|yr)u6xh({YVySV-iUFx@}c()Sc!c?HIY1(V5Rjf4Urd41+SY9bBF zm5}XhkgRi(t~Y@!L@09uswmv+%a6&ge#u)-d9ludaTAx?B{ku%Ts-4&xJhE{j? zw084uTNuQ{(!$r%Rm5x-D>(^AO=Y?Lxz+BUdV#Rl;rGe?rlV0b4z>yYz*@-Eilnmg zO43Y+k58u#ODNSS+E`-9UFhH12=|WTgFZ{&=C56YO=Sg!-)`Qknv_NuiqTvn1S@?M zZ;4Yl=QxOXP^b`xGf5N?=D#2s$bE#+iLn@6h)AU=xqvero3$w@W+}wTxb}RfW4~mX zal9!p`J33Ua{;`yP&{21<^HE+?i{O{IYHXj@SaNO@x&#BpiX` zAL_i>=F{U0($6iGtop*+SUZcjBi{v>-u*Qpu=}LV_?)5G0)*Fs?(1wo!NUis)6>&nVBP7pZO(-oJouh{ zGbMx-zF46_R;*ZvutmBO-2jfx5hDZ)l9hCqY=JAV4}o`qgL}DoFDs>;#scZneUyJJ zAJ$O+Y?!MDzpNOkI=YT13n@`HIgecAECp3L8d7@~7lOdMqqJR7o*+9>`I<*W=ab7sr|&?MGwK5@tmjuR41qtvZ| zYRBo1x))%6bpa>YDRR}RgnIYTo%drhjH-p{Nm`$zRab1%0*6VN9lY_fAC2CSsJpRxIo0sb%(layZON z#2LI!42CXVlYOt(7rPQa>F#-3Ic{9Ny13{)l~k}BSgUtif9Bvez3J=rN!_S|QkhFH z9*R!e9QZY>ek=N7~Njwd;$6!Q1anB^9ZvQF|ot^6H?`J+W- z;dk`C6Xo@~-8P<;#ikTa-VKxFyFTqCBBd(3a`OD9H8K}2j!^?-7GufaKyKVs-JjbX z;xkt|Ar`_>)eYd9clgoB0yEK7v)U33jR|!UczPl!;_f028sIZvbfG1s$YcWmXrJ{a^#k~KsO0}ak4=@w&V%qB2{>J*IRaddn zWesKAy0@+Go64(W$BW#4c+*x3|L2W{m)sMM{0)_U#T@(vl*G)`*jUkSP2KFUz{6cg z_F5}HWiZFaPckCrmu>3Na}4H{YXmd!(9z8AQ%Djs#{3$wk@?o?Ry0b5gnr1mnzjgs zP3hpb2Bc%%A*hwY6i=@upht(1WjCAHZHS2&r@>hZYD(YaE=W;Vs0;##0_qodl1NJI z?=O@&5iHg4T3@n-6n&jTZzk`hrerq1=X^3 z`i55{(j|NswOW>Gf!IL;xqdtatOj-q$$>A?>MO3wRv2G-MCty76ri`_B`JP`=PuJX zYO$m*Q4qQw%Hg#G;{GFqHrrZARVFTIvc=`rky3F;$rbj2D-fk=5wP5EAT-zSb*dIy z6B!NtaCc>K=!dII?5$Ly6~|;rn{^5tdas}ZVBQFbk^-a1WMhk39AX;NEDY%IlL*wK zd`Nuv0fomXi=t?**4>%~v9dCtM(tkU?(ljmsg_UM*TY@hKaYtxx zcJS~HVQo#7fq#fp+B1Gk1~qwZo^X|yh=pSarwWS<_v><$z6u)w4Z;-{KMlVizhEcd z7EGDEi)Z*myQAzD_^$-0#eybY$4SZ^t~)&*f1-Sh)*H6kZ034Y$pwY7K0faZKK#^q zfrV4;F0P4sK5BPsZ+=`OqMZ5i)oA-uj~qEP6Lb3? zuW{~E-qx7b+)1Cb{$zY-Ch-xg3PW_3gRM-$Un$4`Ho92r>9WZUFUH*zL=i^c4w=(G z(_v%eJ5r6uh~+))vzkys4x1e>w<*Qp{;b3DZ^qw$-EDJorF$pLY>dKQBkwc>ayf?r zphG0IG%mOh3>swDDVVdj+001U;*Y|v?+DZ>#QY|49Fw=3{UjCPg>9RoJ<@C)svjQk zxrN@M>qWlcD?}-jfkbq!HcoFARu3-C2YtZkl#12yxbC=1O1&)kzY8=|v0b`T}_ zlOCY!U_C@%`%sQ7UrZ9E1XXO2#={N5EkPVMNM4DvhOgF{=_M{TM5rRE6Y(oLZ_aAe?T;UcS&l82 z1a?SjmVP`N!4{(}CTinV#hvuW*O!Yl?k;5p5#4Y0V3vTvCxoR#0xuv(%+K8~TieY|3D^SV+U|JLx_9s;3X-~Uiji6|JOOohSA~UzKoHMqE*F@tBqwWW zDfByxeI1ZB-pyRpGtdZ!tdof}p#a~(pa+9;05td+1~&^RysD}&eu6j+qq|f|ubUWT zWhI~Oup9`y5}Lh`_8HD!l@+H_$W21+>8DL32NCUW+hD&sT_GA?w6GA|xbSv=%oy>c zx(cp|)pu2*%Cz=LCDIFwB12C|6p~>fA>(woG+>L9wl)DgWIQ8n78}yV+#w$6&;4qu zb3jeCAJRbf(1Yx0qL)a9PD^zT2l5Y#0U{)e7PPA4R=a(y4LuLA+Q#mhZkn0=q5`v! z-$OXhurJ@PI|{SBXK&)9vQ3+Vw*J=U>AD&YI8FS`Yv5$aC&8wiYy0rcW8q7IxBq`b zfx9NG!KV_BMO62RFGu~I1OLWn8n=1^FNpMh^up49kazwZyqlX-?cyo@=&aT%G*Z)} zb|@$S1seH_OH0m%7Twx3Z0>9AF^jZr!rT*++ZfDVY!)hpFcVT6-rJ%F&*&ZogjI%W zY#}}{fy!=)v_A2%S}9(+?R<7uZQ7;JmFGez#7RI zy@g;RWIP~V<}T%Zua0Dq9(N0u%EzKp=R=)^B$PKDkOw%?7 zX{sP45oB=sda>Ew(OnMCmy=R`g;3_RP{adRoPU5T5_rsN_7OJ4s4yXqM-e}^E3{Nq zpfZ|%O~>AhqdhW+zINnQuX>*7WR#Z{q`}mjw|Ong?5&P7Pa*7)l|q|2Z`~3>qc&-J zbU-j?`LP5FG-pY15{k7kld*4j}XKoj;w^{ z-HN+e+g}ae!w=^*{8Zzs&6>H6@L!ioNX8p2PcubIz23^CM;hu-QMMT0rXD8nK&JYS?R+;?fbg|3A+S zCY9fgyuGG)CaElI!d*z(4M5ZJgM|!}RxrA9(KzKM_DKjQwD<;^2rAE(i z_1Z+-_23@<0DE3)m(Tp~0X`@$Mr=8U4tA8qRIjb9jkET75Wdy$)?GU5ocMR9A6vST zO^ON2XHr-7$a+V-*!S;k_{zAErM$RlbuD#&^*+Xl{^|i_W7gW^yP0CN7k$J)*uQeHXu3Km6#uT)uGYm3vv&5%j(ICGlAedJg*G9~3(e@FCo` zTi&I|*0K%|iDma3?!U>h>#6tw2}}k1MCiF&MNgKQiez1lAdjdDIq$s}7%YFTQ_ zc=r;-+fje9G+Lo*>sOA7A-pC(KM4Akq-sHlBqSy#0-#~7EQ?ex(yBquAQ9b)CFYX2 zrIG^5YMlTj;=kPwMFGS3J)~ka$hfD?C7!*nxHT#uHRnqyz#eVCxF&%)O4AhVQwrkwNp%~yv1ncELtAOPU0qJIZg*=R z3=PSx-fz^NoT86?9BF1}BvKY2*R^!@HSH^Ms9|M-8Kuf+$5fvFUTY0sd6LocEoHX- zy5?!)?+2ALE2umhn)wMK_3NeW5K4TN0V>Jr0hJr}Gm*UFCWOI{YL-_gm6|)GV zn26%8Mi8Zmi?yY3v5#M&-awXY_LC4reii!$ulqZTL>TtoI(}fp6%`GOD zwVt1!$0Kj{b3oSdAaf3F&i4ORkPR;4Z0bVerRGh7ee!^%d)#3@Bs}~7h<^LTxNTmT zOZ*m9wCY}+@|n=grQ`^lFHKV!>?xbW%C}lT-7~8;S z?uC7;2QbZiF4h6#6wlUzior|u0NRdX2Yx#MgE@7$e3cIf_&#|6WEwjlSnsZ!sCGLX zZ=1^$UQh9SvfM)TTb23&mj)+=;GrJ#TWr*Ng66&ZDAhl6M)Es_-Ogs7KZsi8odbSp zRTh4HjNIi6`fthY7cie?XS(^}@P^rTAKmqa%$+bM(cCJq{nz=INRHUd&Ir!~ARps&YuzG)fxi|Vv zv~9>U=WVS~#=CK2)C~*H)bzq}ig2ylYFpVX!~*o}H-w0dv!Lv)wqJJGR5SnKFjUxD z>3lKdwmW+Nl{*idhgiJ-Jkk2!Pltb>;?w7%mWK!eZf;i)H&_AUzc`X7%9eHjZjZZ6%_*#CcK* zTA5LMp`XBf>r=;9*YpK@OW$Lx+pLbJrp0gH7P_;MQ zWWFNlN|mc0XoTlmjy|K)i|np0W+*WRj4Y5~L>_{pEdx=R9U@(!+RP**(h{d4WAhco zZXYjB=K7rUIy*Z@jlUQ(a}vhK+oteZ`c^>O2{+Su<44M@tgK|FA_`QhXWV9|i(%br z5OEL>pEw`?LNf=E`r%V-iNeH0R8+K`-D+ozp<(XUNshU<@+C?L;xwRO+`>f~Mo>F{ z-%Q`tJ4-NsDh^TBUG~?MhL6DKo}@7Ug-TlX3g@fUYb3U@Hsr~DRr+3?s$n)Prj{E? z#Z*LcT4ff{BOoV@5+HGe1V9nz(1a!nMSS88P(V^4WeUl_U%JNGHn1joFauDdFq7Pq za3||@*P@>RJ`ej5`X<#-EV&ZY6AFn+AA@}if(|c5!RzoUQtfjmy_>#+v3gRMlpxGQ zCFXhS!ct<8$j$Lll7j%mjx5g*k~V4yoP>;VTFV^W%2;#y?o1X?rYU9QrjH^NRYZD! z<_oysDbt+FDypi@=%er8K#NOzK|g#peAtZygoXR<{+j_T)H%NP-hY8qmxmLP9FI{ygD+_vr-uhsN2>Z#@EFUSfh2O`<5FiOR(OH@vP6=@<|-74xB*NoyfuFn z;EPGudu-gA%(2<*KjjY8nWtIyOE)?X)!V~scX zFkuneL^wvG=mSZ8k4}k>*&}t!L=Q)aiw=j=rGZ3}0tiM#)J8?<_Nl&wPbyG^W_Ny*7a?e*ZY5;j6~O^|dk#ZsA6s$sc4 z=QIM>YB<^LM*FZOjZN?C_!jX~c$>8Wf_uv@K6C%?Y1Ri}h4#fof(Y=?0g^%sbwXD_ zP`DqmCLBD$1)(IHPBu;aL#N?)VfL_0_$Qeb{0xeB0k5l%&UKJ|Ih9eXl>_q*GBHlZ|kZJy;y5 z#mU;g=PV#`jZ(psSWIb%<9UhVBUwCLl$FW7{+ulx+0Ey#3ld*zw%aJ%HTJ-2fF)!B z0fDr!LT`Xj0nfxIlPuu8BMTai0Jw->er5K_$j};be*HK@`9UoKTkNrKqN1`Q(T}0| z2XXKd` z|MvFwj$fVzUWigD#BGH@QfDO5?MX=;?0JHn?Sgu%sPZ%3**TUqofE5QoI{R0jFv+& z1hd%|a&jM;>dSBfDG_Dom@1elQ{OVjl`@B*AKw;RiH75?7!Q|SRO9^7u4{7q0;Qfs z?uc8X6#Nv_((=L0!Jf^OkD}MtJnNc+yH)t+D08}0kKH)v9{8AWInB1`wto1`&_0{1 zL4m%k)lZ@4os24hI_!@FM?|sm};x7F|$!k11CpXdMQV}UNN9qt(Xqb z!cjMg6g?*3d~Ib%f0%yQ^#M=@1M(=;Y$4I3aBoxMTRlSAXOm6cgcCO{QMH zoFl)Yl%#sHYV&+>EnRId!tmXX%?j!I(6ZXN(9IFF(co$}&@V{-VQoH(HJfOFzQFWL zuh+!M&lygWW{W_#PoK6y@$nexk&j~0k^sPfN$=<={aCy)|I@)SFDgzVCN`Uhub0t` z=dHcgz89=QE8EW2KPbSHVgC`vijHE@czm|CyF0fhCdLuBL3V2(>LT6ky(S-*1!us082d$hdIscujWs)M%+Gt80Ab>S3G zG)fqyBYp9PFDQIj9Mb~7g715qS&q4{_=r?CKRG*|S=KHuH@BGUCAQCetI0yf&Q8zO&-wSG#&YZgevY%2Q*ZN> z`QaCxk;KSHf*La&K7^H6JKiZ2R&TAcaI4c~Ots`L4}=lhWNwekdZ&LKz;6Kn%CL?? z^J>npc3(LcV#PQrbAO`H_*G&A6Lw>zBVLHKc*n&mWWlGsQQCfjPFPbJSAj02#DOqw zV$NL4@or7gr+Dwv2eIccM-I%m*odQXe6Rc8C00+23$w@;ykBItW-@CstxJb6@ssNJ z8U^Z=%)ZrBjC1(U6j$f9y?|dII6HL59$qv4q#3KF!)=5lwYuFdHz9hfhr42aGc{mW zg{>N!9X44S)DgReaHvz`hq422N7_m;Ll1XI zxH#ltS*}Q{^NWX+SQ)Z|wU(;I;;}!=&Ni#VGL0CA8<+84nk$>I*)~F!zuuoQ>Qb~W zKK9WEHmG7T?P3YFEE7a?$}o(HoZA>_I7Ef|kWe=PodtE-=)_bQP<3D9vwRl*&e>eS@`(i34_-pnvODMUBNBa}k1wjrHqf}BMG=L*V z@s)norttRT_l4)nh1b#gRB@ROR%a$Ja`TtPzq()EF%v>6zz9P&vRqx%8eEjjSrH(k zrx@jGt`zB1NDCZ39Io__cBhR}QcP+1K~4Y(EhMDKjDd)b&m^bLCyO0(hKZNMa=19~ z52Tpv`G87I!&6a?3ty8G7XZmN7}jPqMzjwD$N`}$@)t*20tzv5Sr{hPGb(g9P9Crs zGFYO4V8yVIwSN%*XEQcEbQp#naX!p}+*?xgdG!x=)^fyr^L`sQcd=Q+_gbCXc}Bzt z2DZl)AOf;E>CCd_Y!pG8DcwIy9D^IEqsPvaVG+*Q5%MOVMhmYps2np? z!@LX>^>@9)nWc|QBKYQPDmHfPZ_*xRo&aYOcK(Hg4#%9fj6`>DC%2KQrXTdvPwC#B z?0G$coN;eogS;i%Ir2h0Ki|#CUe50*@--uN50wh)r0j{IW_znEU7j0rs)_7hJ`C{j z@W@V(=jPT1g_t0WDATnT%=Bz;=aG<*7|$f;o$IHxv2=;qO0Om4=z_0eP?X|b>D{lo z`p3-H1OwIYO(}o;lj5)P{JDbjReP)pPX^D1+SDc(%aOb z|LST^BZwxzTI^96e{^luLBzJFmJ1SgVgr>PEg3Zovs@N>iH>r8rt8M-l{2OT7o+54 zdLKSC`mRO$=~H%C{I1*^5?I9;@aNjg|8ft6VHXH9K8|hJ<2o5R-q)n3bBpr(_VKwkD+E@9H2?Kws(Mj%tq4zCr6&%q=I8(ndEI zp@xmgx#MY);p67FRV+Hulscu?xH%9U9C&R(uf~8Y-R{NjdW_`d^yRVWl~=k--Vu%M z;cK0jDwz_O0MJw&Cvlxpm4pn+b^2QTUDSVYy3QsslbmImh^o*#x>>`OoZnT54=9eB zP;lxXjz?Z{yZ!VK3u(9w1-lR17#MNXetc$M)a*IYpP;{e&J3}^-+xpFfr2a zI0suFXH)COM=3O5&ef4{9V3|XopH&V8%xSB^!NR>)%QgK1vOjRKyZmj-P@MOq}s2{ z0m)h4gYicfbN=4|2aBL)>xc%=lm|hBbL{bi2W8Y86KcDKLV7k@bYb61QfE@tq<>si zShL7sV`sK};6><>bZiWqA01VSOJT+PDd}iwIw=!6UPtW+MRaVOQ$G|n7`g@!Qr-X# z?NrKLxVtyR)d(`O8P}y4gzrrx-Id^{O08Y2Z{JWFpF!xT4J3P*2~!b=DY&I?X`f@u zX9_EJBXiyh+AXuo`u}N#0?9cDx5~KDwqe%9ZbkRj&i>%p>UZN=)$7WBx*`2)b&H62 zjIn?QASjEr1PX4}S0dsrsv~u!#{5w|b+7mLt%%3t&fy^#{S+g9BAIGMJ+#WGij?4X zF>%upXhS0{=_3lvioSOKOW&H9vnY|6>vuYsuo30u=duvSLp^Cy)#`Vf`h)j}o1eY1 z>Q8Kq#MZU*TNkLNj5mQ7Bu?Dl|N73=?aCZ1fy-*lbuv$mfw=Z~c9KcSz9r=3XziV! z8Sc^ZDXX)y1HXszT>z2JHTk zX=byiwo`4bUcB|3zupGJ?!`~%alFO{5z8o4>4dld(Q`lmuZ*azoZ4W zhC9arRYt7Ua*McXf>H++_Ss&~!$sMkhRdU{g2hIYeWGu&(`M#tD9PU9QDs!OBVxOkQ0<$hS6HK!%)2FiAZ#h0Jji(9G3jtbdF-!XU z!O>As0Ij{GG5F~MN9<}45E^FRqBH|T1(lW2SULjibQl9MncT=r21H@*#fLA8F(3PD z8(l_)DstrM(_{HMIx%!%Sxu0!%zrbn6 z9gn9axro^E|ExLJFlJ+{|6NlUrQF$||D}eRl9l8S?^pm$RRmVGHA5=j?9FhgPmRRO z?~*0GBvnd@q9W32LUeii3B<4b`F>VfMlv#DwnPbWB!aCKnbSZPw0mmmJnT)&fyX$V z^Kzf&c*VErY!&nbz%~ozS1Wq=1Rz090e;{(;Pip^iwC3MH#1tqbzD2yVs}~F*egbY z@^B-;#JFJSWu!H8Y230LC)JsB>dAL@gKF&LtJX|x92_8)++oBQjWwqU`A>SzMH2@g zhKVhy#v$QCaPaWZu13&SNob^y!s5xSnTga6F+KI8Y%cB{!x`;kCR&(??*2X+TX^=0 z3GhgWYIzqpJ1MJ!3lqB?EHh3jlBD}ZxZfGE`R!L*({h7<(BV7yfizD~Js*kCkH;d1 zcbqN!+#T)Be+RsrU6-An*!JB=Zmm?R17!TWVMz&cZ?M#Usp-)Am)@SXkxlN5O-D~p zPiJRmb91;_rOL%z!j8Xx|N60*{+;f&bPaIK?+ade0LZA9SA+Y5cYc}Nqg|d^(Ck3En90lET*6YMXdvdA0B!@j$m?R>{`}*vqd`OVN zXq=&v+$^zeRMRn)duy?VBTnRThC%ay-yYJ~?{axfGFaL_gJ9J_M$8h_JzAuvtC#oK zd%*r6Ykq$p;899(Qb|$}9=)p&%++x^XbrV&Z}Z`St{T}&4O)z#voyGH2j}ppXrf7- zQEKH84-risHMtr3U3jb(F;@MnoL&Hgu`HFcoco+pvw)w&SH%V11zmG|mALPGzC=N5 ze<`Jn`CQ!AWsTv>edNxzE=aGDYeG_PsO$JVLM;Zn6~owCbXxfI2Q?Cz(elm==0HIt zE1Ae4U0SCBi4&I%~zc4TAR0!YMf0F8ic%q-RoJME%>J`}$TX_!`WjEN&c%Z#NekwHch&j&tYWR^oZVhGNp7G6z04lHg~ zX9tXGj**zj($HSOH zzG+q-6`=;2)fvi3lnQ42;+UUYU0uDs!we2|WM&fDJMfR#t!Q1HogG|VX-h@FNpNv< zt2%eLxbfSnGpqpLcB34vyk4{;Rs=^YT3W4RmLG%O35xUciirt`@Cfq@t9uWhoPIn8 z(m?O+xPT`|#>z?{Q?1zg(jQ$!X?t zc6JEy9}bn!>dt1s47;G)x0WCK&xni*6blQd#=gHSY1l~W4xK;#&d(#CQN!xUsw5{- zIJB~xZRU-=PwlvG=9l8GA`Ty0s%|bBn(DT!h8d2#1^nJ{>%L8DJ)IBu=@o3iMttVS zHZH|kRaIogw_b13?YrxE8->d#ayv%&@STVJPvL?{s2&E;QWtGVwKqAC zW-Ro5F#sSof%;I&0^V7UB}n%YWpXc8LASHTdlMefyIL))&9r}ikr@@WiDNmX{+(>` zPC?nPt!Aymc2Dtw9G^h;A9L51L23%nORR%S%j?DF=d{ZH_tS4w#Od6s-6E@%pM_ei zDL!N`kjy|Kv(35WSOzP;zsC+^48g6tC@Gj5~cN0#>==PFn)mpJ-D-@Wk zc_{HZu4@iyL3p_^C10!YzYKro`8wu*X#@b9D5zKbY&9Gkcx2pXa_i;fi=|H*bZ29J5uJ znQ}NON);K833v&Xor?w(C-?tsWGCCP_iO~uvHc9l*0t}y+SYYg zY_`fW0yHpL#tt)p(89pL07M+*eCU7XO8htz6bO#Y&G$Jz>jA)%0Y`z7Y)39)lzxlA z;<$~oUbpT1ev+{V2nA`@=rveOPo!3RZ*JnNfzNy5qnIg%10pjO~Os&s)&^rLPBz-t4>c);p|s zdJ%=$13E+v;=D89taa5e=g&SDjbT2DzXO( zflXSVjnR)RJa4}Y5lm(%Q(D&yA4V^(t|~@em4~w*EJcgfe-Q;Tv1?uE zbg&b}l==<=q3edsd-PcXy|K|Mf8JC(_NxLLHC5PZJ?dZfBHVogC5(B8p_KG~-+x zFBJaL7yp2!=*8iv@A0S^*{G)9eL z83?=|8Uo~v+}vCQtlBXsY1CTPbZ%2Ow-kY=|0vp;wK@_EsFPlZ2nfEfi~0V5P=@$7 zta7v!jGtLaiM2|jH{`M#RDT$#-f=hx0vJZ(Z!&QjOj5)k)lemV93ovQ%EOnO&NWIIG}vP1k5XO}iRF=zkrj=n8g^lPC}DBW z156Y(3(AGg6(x7jRshTr@K5M-^lPlbn7vavdRy3}0fG=AStSuPNz!+W)YaHH=({m` zD8?bv)KoC@)?NFn4G44&khTV51x4j;WO;JxAH;^VKyBA}TeR}FCE$4^zW434tQJsj z==$BJijBtQyr&wzEWcg*S&~}BD##DX`8cx(0V}(7-AnD2mjK^Obhc!+fWNz+2k?f^ z{HC!sZfRHDD*BhY>wYgsx~p~i@;C~8w{_vKMZ6!Zv}Nll_a>>J0j~+FxKe!QY>h!j zF) zkNWO|;)nH~%yG%bednLE2@SS6fsQ3bHzfo~9MZc|pN|6q67t89p$Q&cK9Cu=bL(D0$4 zBut@FUFGFM5U1#5$RH7M2^5BKZwNwTbcpDb?^0^y;wr#1D-tRiZGzeqm}0Y|xlS5b z7~Z20T-FmUj+QdVTSSa1r94Crg4)oiYlPppfTdj+5+e0M)6 z99UXicI9$ei{_WsG=3XR;Fq1oRW=p;Elq6*CF`hvM!nWgat1jLqrALYgFi$Sfu7AG zER@v0^n8<1tQxoC4?)w$=6bj3VOC4E4nFWx@t}?@J%}p7Q`D>)_+#g9X69jrpKgGk z;gY($REG}v&E36p9eInHP|KlCONt^IPt&rl!%kjop)$>PmX_HsTEg>RPy_l2mIWLp zRo&0MijX3-LcWix^-RY{wa)R9q`jYkQ3NqMK&$%*AQ2V0B(we}jX~D~V7dP1_PuXqxL+qOY@#a$&ml$u_^hptyK(I7 z7!B0GIQc&9=>KrJ-ZT~(o6^ZzV0U2Doa1IrO7etgs2Ua);wBV*lh&%FE zVye78^;kj5F$kAMTPp{5owp+}SB0O4A#-I<=Lq_}0_^tc%v><{=XqXgA7V1sLMIG5Ahvot?a&e-u9-Bn9tD$RmpjFc71JgqdLkiljP0 zglM=ya#g12?8FI^56}NqSpnf5p*CjO+kdCU@#M+lacL`Fl&VPGYGsAh`T}m+wCdLZ zw?X?si_Kl;lWFz-FV(YxcaJw8o4YT69DV86aq=@6TASTAJ+|sKj$PT-^%J`D^@t@uz zN`Ak1_f390{f_Eg6VWTWo?b&DtFT#QB1Il9P!S{8P7_7(wy9+P?&ku*X%6Aeh9>gr z@v|~doa8CFHY8-cr+#hrCR2cmU!Bv{mg}E>=R@PuMZMlw?DIMJ@OM^B*W~k#vn|n# zY4$4salq%$CD|7T&m4!7Q@GT@#k1s523$EJ91uNy$H6)3*K|}o*R19?AmnztWy}A# z{PXOkc*6RGlhiw0Zjp&g_*5>~D6cW?MPNgxe?df;Z`}(aTBznFWgNmt zNAB{?j3$){LJA&Z-$81)v?{E;=^(5U6STDIItdrZ>%c3?o+ibD3>N|8Dz?4ts})L6 z1*$Ywt5gBZ53$HUvibw4rSP_HD5&t_DUk-Vlo-mG{lq1r7!b9>M*T8gD&9edA&5pN z$&&P8vFyJ~;VS1ul(4$@)J+t&>YrP+?d{|AJ9-@DEm@5*e#;<9Rysrvp*N^KWDaB| zTb3~anYz5pS@ss*C^HI8r8ZJ}AI^L(G%vP39on?$uu#)FogI(y@VZoiJF`YT1l$-3 zru2t0OPLSwMQo_DlPIg4P)7=r_Wg__NJ4073u3{{WaHm3{JZ9=*4DI!tpYy7afHRV zST1F$9(M3NGY_-!d3cO}ekNTt4pLkxeT#je2Z<9o)olJ2m@Gt z2#^-q3JXPMR?yMWflU?&2@E$L)qCShRL77vibw((3q;O;eYcyh&l^|za0MFT_mVwg z5IZwa+GxRGHUmHwJ!X8#J;21s7_6wEu)ru`w`OK6#>!oaLIY+APnAjv5~_g`10N6bg3V zxxPGrgGXz5^`^W^K=W(D$c*s}o|u;`M=g-_3`2r5o99D)6)t!VCMxl({_71{@GGp3 zaVjmf$u-taHQ5_>%b5<-(ag+ly-JDZPjnH9*isd zyCQ0B$HJ8z$zjwQu=N6(#gMn7`jeW!DzTcU8K8b}{!{8MCxIS4jxoAf_7sNvgFn zk3T}S-a#UQ$3_$bogXOohQUZNfOK-}(JcJ5Nwbl+Q6~)~EOpeXvRxHlZj#V0)D!<1 zZGim5|1;MNk~kV4O3e(cDh_JDQaL>fxuzAqxN`k|3oKibGTB;wSe8c=tM8J08JYn>r~)H; zx$y)ql*8Y)cyS#~&+p}2eVajb5S@i>pYz$g_-sjOKWy95^~aM!oMVOKLd1sY#Ob2> z>+o1oJUi*PGFE@Ycu=k0oI+Q zm{{@AAO0s8?e5<^lxjjyw%OlwZf^RVdIK^4=4w-LhbUeSmLcAARREFl8vN?2*3HSw>-kTVKUkxgiU5>2HVi={Vnen= zZ*P5l1dZO){h3?VRab&$Iar^Ld|Rf6dndbpH>)3~{f{BR^GgdT=_e3wKXNEoZC2Xn zxql{hnjOTOD)GMiiUf2@;*;b$$Tc=r-Vl~)-!xCY7n|X#gLw`jRR!rY@Woy5X}j{K za|;=Lo=VD}ghOM&3>~Irt1n(=(K+gM*@#t9FuIau%j?8tVb$mluY~RR| zM?RWvq}6+;27vw_j|zfCk{3BVD4GQM<9e$DSi$ol3p}Fe`sn(QJ*v#djH0)%s8piF zP&_f8t(WWb5OXh(LlzaP37M3fiIV6a)C|v{mJ^G=(tg6IVTfu7)k=f~rWq+=FSU4T zTv-!|M~Y36Xqu2iC=-2Ct6k<#NvizdAl6=hnKy$xm;j{#ZXFR}A;rZ>wErt6sR(C4 z#_y39?V*tIT8sZw5k5r~j(T-LmBQSw#QvS}otxMtFj9&ZgC)J)PQGAo8D%K8EBwr> zy-j7kVUn(^adXA}(VeTyV_0){iyGDG`8)si+>D4F(2^cITX#K)z{a9gqSx(U8{}kN z7dLJ&+Hf8P2w!T^@QBW~=8m?WlCp(32(dq773I)QwH#=Ne6pOWMjZ4Q(%_E@%!bu* zY78D3G}qDf7f;V@^n0p`iz)P0j)xfP*)^@ETD7HZ>rQ)pz07U~;MEnkwUoP3KhCM_ z$xBzklKcdii7JAV_UwXA`>Yqs_^#VSq`)%i6Z)QG`ue$nm4?~6{JNCUNO+T=wb-$M= zN%(Sa=)doy=({V=ZE+fQL@Xg<^%j0*t{NWA!)(}ro8tS#3O^GmEc_I#C6gu0Riu(Z zU$mdmsV}PQ1}e0&z34yPqRDI+lJLxkTy8(|hbujJPL@;c=YkmkVHe^{@Obz7iJteZ zf;jkA^l7$rDY%&eUpYTr{ogY_K``~d3c|S&B&fSWN3>w2b6$_=WIY@Vus#gvy>}8j2OMmylR7@we?VZ4`;d}O5gXi#!W?2eeZMNOm8h+ig z&3?9bbbvBN@fr0r)ZHT0cvhB*$cqRw9F{gzC$c9zRdF!U6lf%eD}7K;R}(i1Q!8m7 zDFN{nZS4|+0>X9h0hR_rjB+H&0_x%4aDs6t;@j6tBrpyNYQZAHXS!`VCG4W1&~thm zk*CB5WyN+Wa8$xrO8Sdl;;1MJ36V$=8DuD#U{CL;38m4D0j4OhPcBN?YSbJwxaU8{ zzSH>2FOC%j;qr;1+^wEt4H1 z8$GBP7R1#NER6SV?laR#b(@eW-(sjv=iuUO1q!w$1gqpSnSYlZ6GoEdt0gTbguJg$ zGe2ntRiIVH)vMH>Oa{=T6d_@VnU&2bSl|)t6wqQDx`040lF5%&VWbNnLCfp3*Dv%w zC?ssWuLKEUWDt$-gbFDP5H+5m1#g4?d-c-;%#=y%tN-PfZvwvF#Bm^~K>%@-KL#vX zN(EUXk~s1Cs>bp^p;LG_?ZPn_nema4ZAci@JP2Gz`i3ekkrXU zY0*t~cw$G>L+I;wa;Zw56>AB$8C3Y4%e zc0allD>IuP=_562I7buY`rP^l4pf2?3j??{scmAGg9y}9{1~b$8>Bri)IVszgop6D z2@}xo;LAb88%x%5ESBJZyn?MQ{tE#9u!V*ah4Q4e>fHDC_AT@LJG#nml8Ih#Z`V#2 zXZx51SvxJBWWIwA-$U4(`|E>-Nmx!vsZC^%exp05T++9gL~3;a`uJ}nYFPzf0i{J^ zt17!1BvUb!Mn0|W%xYQO=6|SI;|AdNm?gCK&u`d_c~;VmU3NrM8p+cJ1jV7B`6vu~ za7`;n|4c|;iADJdE;%w$J-Wmx4gQ9x1Al|$1)D`Zg3u8prTv+?Ies=upn zRMcs=-B(pR+Sy*{P;1bo23!A-eu~vQU~@IGYbdrK&UNg1yU*1$k>qF47)>(y-f*5x zU?cdC;rR#HWH?Ruk+x_feP*Ipen^DjYjxl2Wo8qVmO^dq)zrHv3m`eG;c6jWI{BU9 zIgv^&UdvTgwI2heoNB8CiA!ExeOU6;W#eu~8hHygJ9usats;KK_SAQ74uNu%w8Vk> zbc$)R6s=0Me|I5@f*UOR!YVAQF042oM2o77BhDfdR>V(dnHW=?$2=7mZUr)QASG%P7YhX%=s;ts!-zngcsI)Zl?vKr>9d(vefH#I##0Mr?>|Dr^HWylRaT(CQb4@RE2^wt+QEvg+it79mpoJTc~ z!!Tq!M#`Eo5oY8cu_+aY=}P6cobW?PVC~q7KjQrfD9Hs)joe^FHRhN9p+%~vuslkz zGK*~+sQ?^>!5^Vya&ijhH06aj-c4acFNI6<=*OAHj--YYkYO|5LsBul)!Aya;`$En zW!v;S*^=$^GH4s*qFB*sFdx0tZBKtsscY_dKTNmPUFwdLlYY*J`^JXtUf$y7KV!Z7 z3R5PuD`@|zq2AhhyqqJ8_x;C*{C>E!1mTbXt4aN5;jF|9CDWC45)=$$i!kzj0PQFJ zv@B9MaqtCg3(1HpI_<9-gC~0N`*WM(XrU#8Azsy_$C^1qShwwsLxLI>_r*mwQwLE2 zIBRbhi%%S5ISC1Ro@9GDO#?9NtWKLkMrA1yFcn%D{u1FK8e$1IqE_5W1v~Lj(n<`8 zQc=xZ9a=O9;N*h>I#XWaOF!WturmS5X&!?KN*f_2tTIX=NJ>%0qb4s*;$PsFeDB-{ z7bmZnUmJzjVavJJMf$_ap5CGUW=5~oRMj%Z){AHLG14sLm&s-!x+BexyP&88I?3=E zB)JTQr19eLk;PfAikR_p1|lGj9F)spJB$jrY`D=4_V6$ zlf39>?8c)QdAY6~N94bh{EyElT;xwOX>5uX#CT3EtUOQyhC4l#PSnEy71nAx1@ET` zA!G?e=~4=vNhu;BzE7k9+Vo~1aHS<1xTnR0bw&7a3VVI;>jBr6m}&8#KcO_un#q-Jrn;hrR>*{Lk30a<)wa#L3=^VX>!o2v%5jZ0rZXvGTliBG?x2 z^{FN2*9&x#wbYo9xj4!l`VL?1$Yf|It4Edi?XD|uRwvyVZE0o*vk7@rbNI742i>-Q z;de!UvBe@Bni@0x3@zd^k!42JrSEVs<=D}?zxT&ys`8I6LzB(us_U_t4wv`f=Md0G2$o^B=c#)Q zwr#PKm&e%s@ejHlU@E2^YhVhU-Q>Q*gLBB*oa)}XLhuvU#XiM#A`ZV9b_N_8OynBt zS4)`QUDRCK+yS!ap+p7+&NO+DEE5qEfTkkwz#HL=lFybjuYY3RHA|@d8W`VXBG* zc>)}mvWgeRKb15!;VPJ>z+bQuDupmsSdg6y)rXi@ST-oW?i`}{`KY`<<@N^a{XO*j zUK@4F)t-5H{vk2rAWq$l2xQ1 z3>LTCZS;az~1hL(ISRbmCNUVLUm}U6Dc)(#p7jffLL3i!G{=)4dLYD8EWb z0A2ioR&f%S`iL5KI8hpLQW8?k6jVZ|=!7Wz1esx5YwM()U)cbV>Ks^3FQQW+SIdh0 zXd&G8T5qiWemXOq2DD^17fSrSJ#B1k00?y7KcBvT|J|Pp2u#kUos+8S9&=2J2dYGe zLML?L%$=c%8;$SLc6L^Dmi5tA5uV4Cq=95D@_lQN>EPz)7ys1`@FTn^S*#HJ1Ma&F zah|hH?WsOI250y(^~CDT2WEXL$Da{*5dEMvoAc~+ux>7|FJj#({FsKk{rvnU)Bp7V z-l>3F=&#kLS;5Wu`QXI$a_nRHyU;FQiBX2OD;JaVOcE^AhZqn>82eeK^|;lQ9d6hC zqs+w5iFc(H*rez0n^kCGp&}zjIt!}a)k`B@q3NOLckQw;!4K{*Y)h*mOM?|8Be1lO zi{!k{SK_qac%wwe0mwU5M2{;r+zGU73{S8O*>Tyycsr`9&{MiP@(7ec%i6}g+ad#3 zizfq9+J{O|&8hl+wi zt>(f!5?0q6Kr;(aT16OyyTHk;JLKcM7=;mVhtkSIs^NHN5T#8`%KPxBJZ%Wi#@*!Q z)m>5~Ay$QC82UWFhvmz$;}Q0|04d!QMTHU}l}V{R>vLN#7KBG8E*cX}p+}K!r-rOx zR8mySvJGT>gXR{WuHX&>E9$UmA>}_nB~Z&8qv0%H{r_$Wm7JMDeD)&<_&Fn(wK zUpIK&aZ>R+O_5#9J(MgurE>vm*&1?REr_&;IO%(2s}6l*hEsY%ZwGZDK57Fr`MMMTP?7~yDj(wj=b}A_14GP$Gp6}-o_k5Q>|gQ@hiHt z+qE#j!pzHeItvlFq6c)T^jHu1FH@F+pLg-aw9|#G4AJ)$9iiP8+y?OVgw_V|G7kZ~ z;)t+}Fa^O>?yxe-7M5jz1UO8!T=738FW!p5S@}=0k^R2YuZK}np$rH7_|Y6W9-d^j z#&I>xO83G3EKDD7lL(WOxO@RlC-R*Fe@vH)w5$KHVmIxFGk`rf;Qi84$n$tAb7sb4 zW4QlCuc45o$zN=?VL7zpGw7;9yN|Az}eY*j8V~&068C5i?Y1A z%A7rm5Htd-lo9sUqjd21^E>3{A!0zOw(pIXydV7L}eW#Q&e*f}b6#fGd9w@-UlgHc>8vUVm zZ5FQ($tXO4bRX@r!4>3F5{5t{R^HuH!$lji0>cy=9*(oxScdEN2;uE7b-SFfkT$F+ zSPA#WHyhtvDzU0Cq|H(c+QUXA6IQp8z&xXAcaotk4gA{#R{#$w?sZ<6hXWe{#)uXQ zxYI;Pqi-calvRRaod)n>zD1s>t*AjW$@auv9OBD!dj2(gdd}`u zRyAMY9+`UdD(#+IU*AZW_7+4R<+A6rMl!>sl;TJAG|e;_&&i{i!hTnyCGZwxlZZ{O z_gCRcwfV^d3)P@9qe=Tvrfg+};FD(gs=;-=g=5%TQ^=FdS!Gc<_A7n5-LYI?ktJq% z;Ze@o=ohb3AuDqVUUrTS{VWxlK2*fJS?ka2e*)gNy3UJEPgfnQf!EEA$XEdLUn!#$ zMH^`k#0OJ*ij)PEy8-4QonE))R#kZ=v9$;+5@hoQh-CppFr;W0?mtZyVq#)*`{~3` zB&49qFzLtCkXB)>)TCeq)``-U5QuZ*!Q{!(QFtYck8ZrNzz|spBS}{RdYL6v#z=x{ z>uO=~9joRYXJ>5<=WM;nGM-3iXK~SIS-p!jlO4^-|4-sgu229cRuc~iHvIWJK^A?xHY#vws@48j9c&} zPLPkt9GV`X3K`7!95Ji2s2-(U4UOhx^E%3$=*H!r?Yg>s4LuKSZP|Hx{wK0*cG!Nc z_kXel0%wJj&lDPYE;`}sYimng-NmljrdCeDCVAZFJGqL6IOb$|zp!ImJLU^*jOSUZ zoS*o#A2BiQYm9u<-}CVSLT$RDS6yD71hcG~{;N{Hk*29__PNAX1`*0XFLZSH4{R)j ze1;s}6MdX!3zzmaH~!qH^2@olca@wY0!6i8nXx&iy6Ey`KU+;t_kX{Te~}CH74U<= zp@cv{?CwNk(zQ8uk*C@v%@;~_>Ae%4e*Ht~runZchz&A-iE4;aYO|@SD9*EPw>W~B z4RF5ifts@8Mzj0FaqVWSyqe?mld%8rpkUua^8dn9jn7u=X;hRlKopyW ztMX{E(U9@)IOtkd>%e~)#2}HT;4<|YR%;w^Ys~cOoY=wfqE}nwBA^>_4h(r(7^&i= zCf0Tyt-;4i3Y-grF1QI6#^5vtfevLvIM9`Vfx!%_z(C2-A;uWMk_G|JJ#sn;VLx}! zM&VFZa(+~));yTb0Wl_EuK*cF{gNHJW+Szh0CHtDx`ErB_)GOLH{GDXPO{=o6h5qf9#NcpAdx zLSBz%8VNKe6qIZtp#|*k-03!2Yk;1vxudHGBi4gVYRB+_oRxZpp#$lej{?gHLOcVZ zAdmOK*7KSjNxCFFmjfrXLQ)8Ev8YdH2yLKxdY-#tksur?#yD$M$;8WrU*Zo^&iS$m zL>V^+|pJ5Thw6EDY*IfklOZF-j|E zx6%v^k*yI%w1eg z&B5N@!A`vK$H&v^uE(Z500^QkURFABm8<)*;VdUnnQtNtRr$|Z1yw)WO9B(m4jqZo z&z0F7Bxdr>6uwEZ?@?6g3EL7YYvX`nQiJM!h}ZOo79%0eQ#_<;WvDV@Z1egY?`Ef6 zyQ{i;NTTA5!t_jREFL4cz2DwP-~H#m03(0@J6Xfm{KZ98S}o7tW~8M=gskcHrMWD$H(o5M)oPE2EKJEY^a}a2v3XqGIp`YS7{51{_+PAO?&2sZidSX?j!Oxn zyRe&fhIwo$Iz2bVHX5T|dhu=6G*K_-%_j3>!p=@Fw* zAf&)G^uj3BxVwSU0Aq%fhDs%vRUIx~q?@=?K^}AhJxE;&>@pj#R;3;_R~f4=mz%>* zii7ptPn!mv5;cJU&AX~7IUfo;!5`k|V+~RBl{B-=Y_YLkCho1u$CcNdRVE1n`@ASj~V{bJIbudlxudjOEtNa?c*?+4gRnRo?oe{3sY)B71pB9c=pxzp1apw&%8I_GUwj562_}ld!bS-PLMxHSovuU2 zk*EKOClCw!jyky?WB7gm5cLUG!0?2eK@dTu(yYJ7G{cJyfw(U5vKkji)rI|P1Z0HT zCZX`PwYB#>^<`yccAS&!Wms3FtqlzhIIs?C_mQ{An zHY`~=5}hXkO^$)RW7p-3?2qSB!SOMjaBuy0Y>qe~Tdxb+F(xvUCe3B0kUibZL5&VI z<#dVES@rm&L$}8;Z%IP4NekR;+-zMP-P@lz@4S3n-abA&Fb-?&g|_Rgv;U5dk5w+o z<>mdh*Y(qDJ6%Ta39`GmYA$t_7h4<4?YE=jcIsO5X3|>I zzZfyq0Az*SgNLcfu zOIYAw%JHP)r`S)L2{EDK;(^v>?db>-6B-bAGkiDQj|;Nvt4B#AtAKW7-}s3F>Nlhg z35=1?cNp$u`QKpN#>C#ltVV2NDN27PLbupEo>p{k02~am?;bdDHkV@=DG7W73<5n@ z$+$UMX?1U;C{3+c;;)eJ*jQMRrbcADe+y5Fm&;E^#jRD@z zKF^zLFTI}AAVub>D)d1xkp`vA%n3#LnfZ7XX+O8rp7T}zt5ulpAq-M<2$WQRWfYqJ zpKg!pnP-`q+e|lt9?x2wsday3nqq+3hMm2wl@xo+s1KTfubai`bAP4yjy*LOBb}!` zE0?(?E^@Dvi;Z1Yh!Vw^qgLPDb=S?np}_N=7+{$q`!269&C0WEq}*3oS?Fl)sOf3j zk)%kT+uz3jw8%3hEkp>fD!rm$ZDvKx)rA99m~|FaLZH}rr$(Rnb67R>Sk6xNgEq(; zdi9t5u98p)-;M6Wu#w9SQ7#2Co!##6t&_b(v-RF)k20! z8pvMgz8Qt`mtnnJU-889V zzvNf5?+kJND*>Se?P#urIJ4M!*~})>b2E-FByyXLHV}-u+Z8#-1)k%KHmZWcf4lPg za~d8$NR|&o8-U6qQX?Jiwm#pgerKhvzTxJ^QSL?hzuL2_?e0#;&5`SATc4F$?N$r< z)s5v`ycG|7gC0A;Sv0BHTyu4Cd1Z5XZFPEmIaY?JPxmd}9Bi-_H_zG?OH*+K&7u9A zvBSGmls6ccqxNyyaboFwv5T7qkXM9$n|rdsLm)1#0=P_ptCk#^40y|sp@b5m*kK%I zkU?nkEq0K~%Hr_}kp@iiDDrhdb74YNgr&j4>7+pwr{%)A&PyfCV&UA=&D0nt@JBh` z(bQrvnMeJjap{pwg=v$ezO2TX3M}EPbUyG8FD|87G8wtGQP<{~_7`s&PaX`mjxwWD zzf_p3G5HYC&Kvx}6!|ox;}zG+XFk8y-;kLrud+(Dym#3e>L1ZLw?|`Bb>Hm!Ugv5mIufMI`9tj~ zwa3THg;e5ag216+ZZ-kST`)Xj!3#hIe~i*Z8rE*I0M$5+F%T94Sc-X^_8V${wbU`Q zfB=fy(A-+aDKp$eaBwi-6bTrPKB87y-q?6QkiF2=Q8>!*#PE$WTe^^a_4UHLxyHA% zy&}YC-W6;i`YFAz4M<35nfIOLn65Iuy*q}ke5t$O@AVz~C8k_xi5&v>44oT%GBL7a z7V~bb7>_Bb>6nF}`L_yDiaI!1*<4C%TB}*neD&PTi&x0XUa0M8K!J&7aNkX6)ocG?^aoxcYg@xv~$p@c4p-vr)oC5)>J5cK$X z5LDJX-dxEeAX7nwZ*Pa3?SQWK|FR@LAdDM^E*=v4;_m^^o7pk*(d=#^Ti!Ucafso{ zlUmM~;@~I;N?5smb$KMKO00>GojoM^LZdf-!97T=Z+?ybk*bT4?p!uZCUHT;x(kj# zyA$tjZZ7eDf4*x$54_#lGl_!8;*6n;fGRFD`W%8)P0#TpVVIUQYAU;!Oid<{CJAsPMK<<12f6w>ss-KeeKb|pLY@XR*cZs(&a(cGX|6pwOwuGj1 z87v&9*q3mnO2>Q&zV@nPQqoXT!I-J1W@KPeOiK%ui3Tf`7?@~ua{nPBuP!2QKCm=? zST0{vQ%jr6Uf0-Iv~>Y15xyN|MSJ|$=i^!liFxdh)ez79tVixG=KgqT)xnvS7$Htt z6qW~$6qZCXU&TW_^Sq5KWrzfpgrksWM#`|og!rtVyM>zX4~ztV^q#qRDfzlNXC{;- z48dW_t%=>VwO=_#vb;8$5DeQ@v}7?jqa#1c{Sdm@I7$AjzKY7xKWNfK5h5)Ts#Et; zVUjS3!uRfXvk5kCc6_)_N)7C(ECXI2o%Nxr_h9^cgRfg7Pg>5QmRMUOYLv^^t_{9J z#8|P2IHVu4r}k%LA^C*J4}jA?9uj?dSz4a_z1sA=+39gU{JvDCm_O6dX1~e#+W9cUCxRE4 ziipQae0hC6GdaMq1kqm9S`bwua?LL1zuWnphTT8onw0HXGhlE^9ZDmXSxZ;BJ zyEgiLp_rZT!?DZyvqaT7pYM!J+m-K7bZj9@+{|#7A{kt4s)tpZr_Sb}WMiVLN^8qk zI?(LenJSZ(9tlZYCYlb5kvri2Po>A-oiw@`R@@Nc8wOJ8jZlY!We2=Z^IpN^apJ$J zQy5(gnFsg>-FK=kL`V>#11Q$)Ip~zI;i5ct?k;-3296X}k*Wjh%~BptAyXsE!yOs1 z1rhnFk>?GHce)%2nvZM{{7z~pRW2dKHKf;RZuE+WDIuBY_878zUy1n&=@Gfp`|aS) z%9}Z;*!oTSMU6M{011I{fph;$O5%7uNkxbv$qrJIRP-Q)RL7i~E}h^mWu%!xH=jgc zq7fKHUWCO$nUnZD@Huc`I!+0~Zj%P9HA=}eAt z$yEm(9Jfrb)%_V4LcslYjDD4@b>pHb4smyafeLZe<$zeR{JDd2adoY#j;373P^g&s zrkQuB@Xuvz#MF<_kd+Gm9$IWLQOok5@CS{dpXuoQ$jWhDo)l>&)Zwcue_p~%E6Cc~ z)j#s7o5*%m1H~*aPy|$zU9T#PZ%(I9Xj zVDzR~wx{4C_xJb0X!);8Wup7XF@iH(n zmhA(LR#+R*7<#Q=dpkZi40LpFK>iDUC8+ODlB^SmmFP{ova&J@H}~57yzvedVnk(; z=iGQK*N&D_!Yt2_)6Pck(NVe~tKlQFp{FNRGHO8o(Np=WcLeW7cqcD(CQJevSuU&j zgudrChaz`PG?P zZ|C8f0T0=`;ei{3Of->O8LZSpT=p9!RaN(9w74@*u4|*yM7Yc!=zNf2FY{6^U%iLW z|Jo2nU|^3YxNxLBpGv)2%5CmSm}Ar$WBlF>fXE>4qoOl$gTT}t$rgvc7%A$Clc+iCuF2H z>#u9O<1fzplmPiK3hofuDR?)jOFAMDy9Z_UH^UTxyp`6!ArbL}wiPGT(GuZ3pgJ&)y|;L-Q+AUdI~IGrSP5cFi$fYt`;FX;3aWhy z?$i`N#`9+Kyx5PgVi1tOhZi*zYSG(#1%Ast2!YS9p*jxjSLZJYP1x(EJ`BJ@HW!MH zc!Y^cM+qh}XC92*Ls%R^i_(gBk%oxZIUY!|kvxk`loxQ3;ub}9k&#xTz%`eNk5igR z5=)9iy-6{dA@7bykYq+hc)pwMO`I}|n2OgxM(py9N?PFWn`N{6Ea9VJW!@T{o8z+{bh#|2jsaeQ5@y4T`}?iD&*Ww1CZETfKp3dULLr?*Ch1X1I4)g zdq2qpeEvhs{exhJ+cpl;z!J(-J^3@9jA!6;G`IgzaW{5~4i(J&v^DI*%NGs>bzo7n zee7QF@^G>XP{2z|OK(xoi-;o<#m&ktuabnoc?7aNMHedn*3AIw8n@P#tiB5sGzCcg z;UAdElnQlqnStTylk)sWu5YxH6Mpl7LIemtqKC4ywp8*}nf!(ACC%*hrwi)Xz_b07 zXmz=cowwV37OO-prS&J&WsF-)EQF#oY|&DVk&cNF{~R%V>Yw9*auJt2=M$t}$4lYL z-@gJr=h?bGeg)8TEwiRVH0P}SYnrpW*(E&rl_>1u|U}~9M?t`1>d+VR4O6li;e!8{lg{zB=#Zz|Nvel?OLauTS1QKx?}N6jU@>I;~#& zMO>VB2MIeEOVeJ-mwkvB#&raOeM_2GGg*6|XnT>Ob50^cNP7*z3`xxC4F6=bsbEzumfm}mu5UGyt!ZE& zXgUbBt6*+^08F9{F!l9)I~uBnhH9d3+(7iJnf1pMgn@83S4%uVEVAz|C+;^#;V zF7O|&i8B9PPHqAq^e$A8zd@X^DPSjf#Xv|`DmfRi?)Y#N`2KmBRv;Fo*ig=5hi>yO zl}rhLMkPm|xbKoHtdJ~js}mp~e)3v+f!-@_46(7}<-ucMV2q~S?`@{-pCI|$5$fpV zc)u9K^0~j`cc;Je{EMgeQ{~_7O5eY8?Y`H3&(EvXe}7^E-y`bMv^5(j$OM1I*hWmt z&SYu+?=d1+TRN6=54#vp z_u|hk#Vnc_s7Ns9@fo4<8Jz0LdKTC2k6tIT_lIi6*j+yRx5d9bQNgs>azhv6`LvX= zUc}b{;^S{*n9aP9vcYjcqIgD;sb#?Sdx^>`>Y@&g5bBV@=^#C%AWLGCA7Q8S4 zI$K=V+vr{a(Lw5k)9FI&Va^7_G@}OTG)i}@=7v9!xdGm#Um1ZZ(>cLwd?9#uq4Zag z;)txW=j5eK5{MJm_ENq7htEO@RVm@9IDJ7L!-B0+Mn_kN-~`shZ1Py%qtAiGh7J4j z3hs7bW#G*~N|XhIhzRL2x)Q2Ss9c>uGQqV1GHPe>)~jns5qlqtlL^`P(%SD2@tt3M zl`oyn1-MSHWRK7#+wE#2+4^|S5vkgdVLq5$nQBLR46s6vDM4zlJR);9V=jxeF`(-` z>WESScnXN4_*A`3!?^9Y0$wTv{oWZyo2%UCmTb3=IXV z@}e=h%Sce4-M@F&kA3x?u!VOtIG$VU*vJ+zTEE{fpQ$6_^LU=07&ZU$CGpdAz!F)6Qjb|Ov;B*G+& z2`37VUyi=MbjMf9vo4WEiKPHh==#bOeCF0eno)UDi;ewYAmt|6CMTCUUCiNH#Ar zF7z${asom# z*vXsa>Z|Tp_hNA*`p?-{-_vOhO`;!*qrbfCX~P~+FOd_V_=@6{1SY3TKltdo#x7^? z;)pxV$2^=(#R7y0Me-xFRw3o5G8c1IGq0woN=A|D{Qv|aPrmPUN1lME<5s(xlW#CR zDyi`MXiiRMbKAC0O-Dyq@7hkk_ULT!(b17g0b5xq)7*suyEzFNyQ&b0bBDRDHdQX+ z`4xax-&h8`h*-C;NXs;62FE<)Gd)TJWs1A8`$#n3Y6CrNWT&y`{o+ihXyV2b7wS7= zfL%`eFjQ#%goZuinC9y{`NN6p(&biU!dv;v4@Waz3?Rjj)m2~Gp863iXFqZF;Xv60 z$#IGI5m?ZiO?Gwp4J;|S^8RgF?nmy7AtJP|olHbZl?7FL>}a_80>GLee+W$+8Vdb* zOCZ8C#$vuLJx|En=&ajwHot&A`SN+_PnzF#>Zi_7&O7zfyJ@LjnjY5SB%DfZ5f^o# z%Si4xUtZ+U(lLTH_0XRjUf%1Ty#+0H7h2jT9vx|tfJ#;j^ZSfe#4dG(XJjiHl6b6W zDa^QHSdWE{yM9uTfO)cqi!U61qWD?pRbV)rm3NYRsePR#TW0?#kml zg3BWFn*|rBinU+zc)HBao7uIy!_NM+ZvlUJBd1xD;ol2F%j-fqJM+KRS5}uu6?|O< zgIUkw1#iRYm^3P3ai$ zb@*>ggDLrsZBlu))(~oro!9^%JO1|E_ya@~GJY^DMevrWL!c<$SuXaR~%L!a0{IJ{t%Px5j&*(TEtsMuGp6C)du#Lt z1)9J;X0<TR{!FU`)LNU4|+aN6@;IiMl>>9o;% z60}LE)8+H$$X?s`;}|urS^!VI^>v(PC3=<5l(;D%_T52F3OcINVXNJx^z&?~!Y%H= zwWEJ=e3A)}$x{b!-b5cDd4=8-W*5CIC^S|=j!&4`r z+LG{q3EL&4=0gujN_if2u1r2jea=;?cJ-gRz}TUN8_>E(B=Ln1ntRka@U9UZxMnGei$Wqdz_Y&0zJXzD&0oqwA&H9KZ&E zbb*j0Be79O-&8b2FhsVI!~{zMraB_vH|aRV=frCpp=!T6GghSyrP~C@1^6J93S7V znH*jhXYb{J1&HS~JO1s(O^!^(LL4yvqmz?uuLC7*!|&Lbl@k_{w|M9UO4*$pNB`(EnU|-h)AyE_ z9xnH_v+<7r%!0k#EmgYdW!rkrM_2>JT@XCi@o!NTCR*D5IGQZyisWNlq`{7WgjKgk z)urGMWJv#oTobgf)+Mv=TCn~Xa~y18sfp;_92~EjiOt>>^b&ZDnprexg0uFv<07|d z2a~{Qo|U3fpY=Dytf6#n?w!@{-@G#?)^wN2*?klyjmutRjMs*8xImW;Qb?|5YRdzM z@e#EGg(+lzJ9=gU+lHZeQg^R-Xz>eGTY`gQbvKDh{{gbkM_JfQQDI-#&p&0_Mndk* z!nAcJ3xgv|*0Y6Qe1{xSmy&!yvOD{E>K6CW)Lwa<%acO#mx*`Ztk|4}Rg<;Ilu^{N zfC5?J^3la5{P>`&KeE~vvAtncG0!+R>K7c~K zkjrWcA@)70Y>K%HY5pDPHU&cZ@H&vZfMZq$jLigvB03x>dpxO!%6Pxe=%ae7?RnY& z>?%8-Pi?fyxnx06698)906-~j^acL=FR605#)cfHC5YEnu>C}v5(T^(jC`-YletRA%}tlSuj1__eM+wU>yniD@$*-V zOT$?_sYt-SBxaXDZc1odDJ83xuD6sjT?CrRD>jk|M0zL#O(f+?*k> zj*+#RIAPssGn#uu@hw>fM#kwAE59nydFy~5LT7uVr%*t<7uI^y#r(pM5-{ImJ)RNP zL#5972~Hfa*X}p@i3llJvzCyxo{bo>0(`|uFeiaoCAyqYZhd(Ghuq0D+W=sy!e%iKn9%&pS z6YOW&GyBGUlqdXb2s5kw3eoXFNP0X+_dLzBVR-$OsIbxVr1m5~P&mmWBQ4EWs5d^o z_7~2BChm3QaToW@%^fbb4MnIoMs1;yslLbrd-_bX?^0vDgS(44I+>EiS>%wkeH;sU zOI#KolZhn69g}L4DCQqr5pgs`Q4)({bTE@R^6?;B^tl-fJaE>Y{b)uVcl)6p>p7Aj zDSdsy-L&UYD1I=_mGtmb_c(OmfYdfxZ?VU1kOX6;9XI8DpaaK&;x=@)!*D&n{t1k+ zyTP!hSb}0}f*+4d?vgqf1r8v<&pJ=cpCJ5t3TzQ?Xnl?o(Fla^b?;{e4NB{$lltX}3>VxM> zb=t)*LoSznN!suRFc;RC0qcm_)OTZw3QD3dH6)IP>FuiHlw*I2H(J+9ONI0d?R`Fd zA}R5t^<8*NZm!qw-(@b&3FPIYvrLyO<3>tqInk!y;RDn|=Ef>9tK5t0S*HVl&lbhy z?|i7$nxcV7Z@Ce|@rggc6n&iDD%2IvS#U|+0WPLv{bP?3ZP?3R1l=r8J1eV_Bl90K zl<6}5>^&25C`A5ju26}cLDiZrw8trREr<&yZJwsP}GD)*_q z_ztuw#l6+!G?)Huvs?J#zXrfx5)mkUE#EHUi3M66e|LI6SmD*uqakT`4n?5yaB@1Y z0_MHahcW{U&MLqDPk6S7@!d;ib)+&p-yFWU0LaB6DL+Wn(LHCd<`mBH{?? zmGa+AJq5AZvZIFiUSy{b8dUqedjmRd`c4`O+A_wRX9(egVFS+0XsH)1FEccag>%FR z&jX&ZB69mv@_C6%F@A1aqO}Y%;K{1|B}7_j=AiZPQXq8lXSP)DY{*;^iMm1Zok_Rx za6g8{%Ej`w<0OBx*I&Su4EjU}SSpLEGtEa2fg#>Q{kT2OaSD;=+XEmjg(cxZkg=Hk zz_l$J7X(z&tQ!0O(e&?WZC^9tH6zLANP|pky~Hgkru!u4DYjg(KegS0d z-nivGJvA?1QCEH9#iS?Uu6y5VS87(#CV1=6tCrvUEB&-1vxd>jNA5sh_&BGjkRg0$ z?8!R-cNi~ELXQY5D;|QSaNl4)4LNI%BJnh#lS485wMUC{*TnVlUmJ_16s z^U2BRa^*a;?Q$2|Zs9_G3LGULq2r9rkja15h&hi)^;8;M>(5`$)$}JfOI} znR_j+KzAv@N;r6y!n#a340G(0R55I?|0ry)a@!BpM04WgZHt9#q8Ei5FBFaH&9q3P zA}G>!uNB@2h3Ym>1&bl8c!+#Yh~gg*`mbBxSSpgsnQ26T2r`xc=L`|E{ddv6`E zWqV>NT#=cRs2`Y;EWMy(*h+(1ml0~Ey5ql?S1g-nq z`aZ5+Uwtr$xY5m`HE2unq#k2jDkyER>S{Hs8T85ZnPK3eC>JR~glPP;FGYHrj+|=L zqiUjN*}jVtpv@D+4+fWxu2>ly;59~Bw-V+cT+jK&dGQ3v#+0XC|eJkRY3Z2ZvX5ftfNzU_ef zl!Es?)WFm0YZ@AK3@V*|8ZiaYV)(B|=)H1L@EwMsqKB$+baK(AA^2Z8AZ(1^RF!my-J1# zv|@g_J{WHP9T;}_11@!>q((qd2Ltg2A01^#s8SUw1rv(J5{PFUpx<4dfiF`4|L-V6 z4keSlYt656$SHK(uQAC0$!;=x9RcSlJm~%pvaj&DHa8l+Hc#L|A?OHPP({< zkf-<0E92Xnuc5c;6ZG0FTJ1|W4Z|sB{x+BXY-!%WJE?H|`E9%16`?ppF7+tfph8{u zaKV9GJ4TN`dS4wGwj1<&>9uL5|+P&`t#;MD22v+uF91ZEE! z45WO5IZMlVVwb|2QNivEnD=$vuap0ka{wj+EiJ9a&2`kn{jFTqO?a+WC~9QWdD@fg zJV6NDM6w9gbOYesK|a8!xj?A{RgAlcmVnkGn7qY@^w=8XDr84Mkl+)Ri?J&%hs)0V zmkjUHZOueJVP53lgGe9Hde}$?kMvoiq1&(Nt-vTJ2{)oDWh*d|NYa!u4o5|zVxkyG znG%$!JQDe%Y)MESj6gf+Qg!#u+)DJf{+#dQRrMT{}mV(VI3{`jJPzWw^?)VX!n z{Vqyn2d2e;bpIA=Xh;l;%IV(9VN_VWb0x>D?*VS|+Wjy)MuRDyHDlB8`3{2AqePIN z`N|Qjs9nyTHeVwT6c4}LABi@PjvhGmzR*B+pI6u1yCSxG*Ed6@ywFt{z9JJEy-Wd{ z=Yz3?Cgu)rz9iEJ*f@M58#E?}ouy4JJ*|4@g?HU1+A)kCTWt#3M9iol5r{iUtXMT2 zEFz+F-^agm#6nxYRtae_pWkikUWAN~qeaUE9^&vY4YtPH*@)mdEatJf ztc=ynCcAwcH0ZkL4wSn5NCLB!)uS?Zh%c|BQ#Fs~j95<=TNurwo^PEwaX4_p$5lCr zP=?I~yJ{F{{dV);qK`lq+c?_;l)0APwi%DrVipGUgC3a8^q zls+7ly}i8+4d^-U$dN^*EFF{UK?G0G_Rf%jm%;u%1yekDp!LILJJn>1De^njr;?Ib zsPN;&YBCw*V&k*Zg;tJIk~k@a>hH3DSb1w@QeWzRHoYDnKpxk$X`Mf1@2Mw2^sCyV z#eUd2)1E{tDr{z~u(=9F4-34;hm?d4SA9<r&_-#B!)@=wgx;_zz@vtuhakWZV_}^;P%sI+L6A2otpU%6TD=xm zfVc;z>oNG*F!ssHI**G2>o$lNRW@Ctaa?bq(cI!uk!+Ob{TbwWwZR4K(ioYTijAqP z)R_(vsR9GkSFvUXvxJ0s$B!Re&tXERVK@Z+Umq76*|mZNmlhU`)YNp1)Q-6dt|Bp+ zj0#@Vg>>S;QIL@v$8vJ?A6y@J)1n}%;lNEGIpDR3cxufSOS8MX(bmJlZhgSA6}w(c zo4dOWC?Z?++pf>AW6?&Qtmpd=qp6EG-r4y{Ht9K7VD*c_MbB=f-#E`S(J*t>IS`%} znt4QI!!wSltvv9&6Z;iXwbPfC3sfyXIStuK%s0`8$Wo~UlE}S;_G~q*XY;u-h-wtW z=%vjBrrceg7Vx0>>?a)JlPa^(-=!rIHZz z|M>A`hD);hOGNK2J)>kLe1s(A@IxX}msW_1`TWnAr_{uhPka!V7v}nTxVVz~$XH>4 zo&pF8@N89aS%BrNe7tXy1!xL+X840NCkRTS+;A-`TnGo(<6;-PL24jX54>I~ANO&! zphj<7`F+kqwNjZhlsKPMEAA8}9JfrG5;C~;75Qo7NpWQ@&YO;`ojdCh!wHc0>eh_^ z;^%zd3-7$Fqm(Xj)Q_3iM0F?@@7a9SiGlkc^^Algrg@V1qY)n@9m$A*)@!{gc9hMHM$t=OS)21R=j zA@WWxjf-Rjp`SuYGI{)OnsXn%m(c8T3u>)pTGLbvJZG!d3Lg+F#QSef5E=si3IB}w z7-=-7Z`VS?s2>(#PcIjFt{} z8=_`RulrG3Ye^Ez1sOJ--t2Gr;_30<2T)+*G9xK*=J+2}QOOMC(3!$7Ua#HVaBUt= zVkZiFXTPk68KbNgiFwJmVKLz_lksZ)R{A8>#=!AQDn~m_XtgjJ$+TD<$Sjq62@7wZ z3S4=2A_$(u0@;g07gv5*$d^2sN82#5S;9zx8s;jZFR%7o26n+@fcIjpl(M_{r;)Lk z#*F5q+&5o5DrE#bsjrs23Ut=(Z4Zeg3)+|@<%KZ{J2TbER3;Tg5H{jrq0@dpfy(b7g;qhwnf^9hizVlsDag3f)DI3v@VZ{7bS1-N=;?8oE(O4Ia)YnT~dsgfcn7r7iBUYp$yPz zibBT-&a>ql08#KNI*Z3(dbVHx6CG8u&}G|!=*?Il3?Dk;2Pn`=^>`r&@63V|pFTkR zm^#rN0?h0)yKjm#f!a^(1~j3mVWsR|F=MPPPd!s7>Cp7xtmC~@a|Dpl0NR1sno8f zAK?X|tY=}#8I>#Qn)mhUSmp(kjFkrXK61d4?_!KWvv3 zd|FB_Hnc>Uuyjd^I@BI6huyYvwb?c#I&L{ojwHcK(J9JYgvBY99P^dBc#@vHB8|k9 zjA{ZwC>Lz4pR@73#nLj<_() z8uw;E5sQBZ?AuwbJ1?`Izi$`76(+|$<9wz{%{{$NrFI7+vG{H;O;vsC-{3oUU1 zF0!Po?_EFk_4TrW?SGHQ)saTI;>tWK(N>$wLAY#lUwb>Jh-Qu%4#<HNx?JL;PO8{Y?LQEt6wE%y{V_h6b4Jq zLBc_fh_Rm0VRakLO)`w4UnEwvN=SJ0Z3S*vd`gMow%^mo*>w4c`{oHk($_G727Y%V zKvg1bj@!e*BFz1+bR;M?HnD`5WU($uoD~hjZej157cdsezfGAQjNfN+t)}mrsUoh5 z`B*H83 zRx(FatC{Mt8S?Fl%5#%5TmrGc)BD35DbRe1CdkU#uLnufE_5-T;m=k$$FuEa4mgv8 zVC=4LXXNBWLw<^_`QRobihAAdiYcoGjsIta@q2Mqot+DKY62Gbz_$x{@uvM2ON9J2 zK&Jzf6!<(uYSiIM-4JaF`u0?JxmX8=Cg>XCY-8iKQXTW(#w zL-f*G?S(~Ji778%sEJ(FBn5AnnXjim^Bklq(s;hgdMHBLL zp|ii<pCElR5cmLUq*!o_J{ z6JdMiGf?2sg+=+DWcR&*ikp)=w3DO~Fo`eJUSTrJvLQjVU}zCIuLSJ;M0y5B4Y5kG zm52o5l~H3f-4a%lOneC_l#|Cza&~CkF8Wk&)nx**{D~mtv-wIHS>$i$OX&8ox#46+ z59C5`!KgjXA>oW^$JsXQKZTZT`;jt{6d0KbJ*-%M-P`VEA(T*!5-J2Lx~0A=wx}KA zfmE;0&nXTcQ;d11vmu24JLse!*c5pUT_>oA^Ers*zX;u$eZ2nJb?6Z;5~YCQC4(27 zp3UJ&2=BKiQ5$9N0<#}}0xEHG0E3E4$l^j2Che@qKR>hHva%yUHitb6xHKn){A+@I zC*VAFOpzI$*Bi4a^)5*!n%yJ?n^zYX zgm%I!!kk#(&btg84JLctK!r%fj~{~w|^4SM{dJ*1v5gY-Jac+-S%`&OaA+lgu*19Liy&uz5*+{L!dACd0th(^i- zF}z!12r^05Z1QmZ2#qAy9y^nEiF=} zB04JqZP7rf6msMss~}uLyUuHfgFS`gCxq)~Ryd5C*X7CInaeB!TtvIf%k8Sh7JOGC z5~)QOy*Pr5p&0bDB=*g~J8L_N6N|+)U6#uxML1pJ_`rDQeQ@%}4f{H9CNN|=QOPNw z0s>OFJi0X%Zx{us9kU*AIz{+P(Z7xdlYzzizdbFWleYn0!4R~}Mj-W=`Jdoe`Fy4l zC?AAA9gPOsbt*muHa|d<;FR#knF>HUIs9>e zf9oYyG8r|$+upv0=fceNMq;0Xe>g*fAUposHRL_Ov$M6hX)ZjHCM!KPiD*Z=f`x-q zmfWDjnQR^qGQw0QwcNfZ>{9H1vn|ncObJ*k@MhoZd$P11WEdj(yKpbH^#N)uAGm}0 z{bMYDlYQaDIAqsaGdh0o3nVU0*_e_3 z3|l`J-vj?1{{UmJf%gZTX=6ow#MozR;jb}jG|>$foxFs${~e&@VZ3|FlO{tcoc|5l zkhsj9rxc5f7+B*Qz*521!Qt>z48oF7!otJO7EVIHsqGs|vBgOcWIr<%aZ1!B>=GTH zG99{|{Q?dje!;Lj_A7My<10cv0)r%&#cPU^ z|8yz36>k9Z7B-zeCME`#Ne8U1_AEwkbYvhjV*Gojz^BHf8+rm7O3Y)XQvAFcPE`m0 zcRCGEm=89}M9L)kyLjPQ!Y(c5qGyMqAr9&AaAFXrdu)HCCnxbDC~|(HcE*u_-%UxgxY$fHWTXY3eXp}kuV>s|H(j_g9$GhpCx5Q@Zk>KYu(u|MuLC9?!-*`s{K;eP(iY{QBWUF?v{Pcn1<=5FUtm};9c)WO%_g$2Ulxq0#N3&2?hxw)tvb$6Vs#1`0GZj8^li#sd=z=oz6UIl*c_uYRg z1(qWp&?ZWTje#s^X>ZR+-4*vu4)+kEi9^Q6dX-Pu*_EtRD>H}_Di|A#E|;^|;7$J~ zm(zl7i%=v$u!E#h((cy)`7O-FU6>+# zG8UIGOET!B2S6AMHB_Y;j1tQJq1$xaFh)``0X(H|Ixm=is7XOlj4cBYhmrVx?-2Yp z+scL@*8luQKzs)q3yXbHhv^=Oh?5ArlJ$`h!TEHI$&{cwo@@oL%T*}1pr8z|p~<~< zwe4O44i3}%LwerpKc}7V+Y~?956nvA;>I%V-cT}L*b(i;q>PP?t*vPV+L}v2&fC2o zKY?e_#Klzi%~^v;(&EB`?$@t6T6*WGnKZJQIC|fH19s{sA>hX$#3bJHDHorMYei8? z5a$k7a3b}E#*Gz^EW^1D9}f>`KXo=Y#|(!Ic*wAv?jj2pJkEG!vUG$A=eqIJVWprO zNWsn=+(ojLE0&35Z3{`#vU+aiw4Em8A=Orx$rbV!zXF-elg5qeEO}9&$ePiB^)}cP zw|cy8@gd4bPdV6s!yFnHp5d5FPqb)n3iL=K*&%go(SCA*-|oVvnT*FR%U(zpkv5R24U=Bd>GJoWYPdF zF}bg=lpaBliQx1(7-*vDI`23DkY|4Eg z810oRSxy8`MNUPsSUD2&qc|xt2|bNsVuUyOQbtzrCte{Hn)r8E%eP(D^~ZSNY!rNB z+a!A;7ZR^7c9(TcqFS_WXr{Xzo(4o5zCUAegkv4?4?qNy#xY7IJs;9(GL=3EhOCOq zytb4H-(#Li*x36B8v+}R@@<&J3b<}ZfwFOoTyRHeUcf30=rtx0GUBJjG0YU8eo{$9 zLubFmHz2(!Gb{|$s%F0K!ivbUIK;tY(ga}yjXZ`ah)YWk3+oeaeMFP%|!>D^^LRf=D%8=Msf z1hCVclIC*8{XNcmA<>hr7E$fq=#gESVx>mfg6WqxF}ZyfFU?g=gM7zM$kD8hZ=8Ab z&wt?7Uz;NS|G_kCqvH@SwYv5bOioIZRwEMw{_2Dl>a*WH*zrL`14jGfK-!GjKJjtl zfHfDq)WKxz^W&|}VI88C%->C-OcFwRU|Cr~zs-?atj`wS88RN64$P93I!HW<{#q!A zq*ke2a$_+Z6r~#i-bf}ki%&^>QeOmhy$kaTZJ%UvD^@OqfC==^-G6@=exrD(os)2_ z2xp3c4f;$CghHJxBDM(HPO6}k#TfJQ_(?fY?hvI{1#;*@I!ju7{_ubnVi%Qv0jolQ zZ`mgYlF{9Iawu}2@sp~pR5`(%P81-WL`(We7g@VRuZ?2GU10351%A_sWa?w8)?{2` zKXm6HlrcPTNI0D?k1s9J2*_wkc>CXm!jZSe#V|M}#Z5{iZ~^uV49@g_j~vcEfR+)7 zj|RgJphpLmw|ji~(AC;s0IN{v8O`f!!oO$K+xc&8zhNwZLK*8wH?tML@_|oXutzb$ zX9;81eA^1B0f7Chl$NGBo;>kvPiVZ}Yko2BY#boQ%#fSf4oM>2)>78gR1#w_^VKx? z_g?^ZjP@AH;USI(tnc#wqU_;Oqk)nf)@~W}GvO_2n{^bWsy=pKfCoB|+zPT0@Nlq> z20UHsOq^G^zttU8I{W$(T7Le_8?QymLQQY&d0d?8`}kcV*r+5y{_i>aKC0zF$x|{> zAWuH0&A|`ci3!Kk*DoN@Yc4-@j4($|`FSW{kiGMrOXpSF4nb$=F)zF1MMJfMk=D$?E7Z1;E*S(wHq;D9JwB>Fv)%1b!ALsb0g< z<2ne^`&n`YF#Yv947e&0Mq&dHY;v!?nU_ml9kQPCyc~mY*>+? zpp?Rv7HlXmyCOu^$?M-;VzgxWK$hJ9U^FiE^^=MgHWn@RQxxe{G(Ck@1wxBeyd2Vb z9y%*tGCZYy61?Ae*Co~sk?*gbbcD7IJ7*)w&+*W95QPIxSHyk+LHD zI8HrwD26JSeNNYdj(V;(j8!4)3sG5rNp=FoSoV-AfoD@{o*o>ZKbzKugAn=mGUt~4c?`IFp4$49{2;;~ukeB( zDzo8$z6)K^>1l58IZ+${R$(=B-renI6*30EXYOr&i-l(zqaBkJD6*nnp^8rrf2A0fp8$#xl8Sn~MXV6-5EO%56k<^&%u)4vEH zBF3y`?9~S@9^TQd^|Ovsh>bedKEN#8 z6J@{#2kt#f{kY({1)NlF{(!^d$JkWMTO0uO>DQ?GITGPZI(jOST*U|1_7YBar0;Ot10?+kJt7fLqo( z0y2MUAF#-J1LU1pLY{a;Mr}o9bmk1e>`LOlke-vc{bjUWnILjl$&<=G2!b~>7iD;F zoczxcx;qfzoCJiHq>lmWc1aI&$u)2{=e2I&3Cr7m7wQro+O}nepY6`+EDf$l@nOrL zs<90cqbPzSAs=?Aw8N5d(%)ACju^x{;REcuMu3n~9WVo)pW97D z@dwc?Ox;OWe*OB@09Z}~2Pn=DHHj<;3p7+HR65^96+v)z7~~)YxV|wGUnDdMhb7`)VAKu>L0shkA zCJ|tiG*O}Kgx8ZN$VGXB1$MKM79J4VA`M_+%l1pUF1vpg8% z5%L!-(jNEcCU|^)t!G9vMXG~Ac%S{MvQ@&~$sy<++*mAt{9*cVHj!g_@XybJvI(k(u~o~6qXo29S6G3N#c7Yo;9_svZx ze)&S=odc!`#9b>mT9dnV`*@bZSfkL8qZ}dvVXHlSqVfiLZNo%DtUQz5Ve@MmI1{^4 zQFJ9vz$_EIV`mL1pkv616Yb;*{~Ip1!$GkV1A&X5ikNQ*`?0iQbgLJk7bb9yRwj`J z?}xO&;|&1Wa~>u!shk(VKZpMKs;`eow->EzV4%pzTy4^S2-!6ko!c#Y(LHlW+H~HZ;dwkg&LWy+r*08g^j{ z@a+Br1ml1&Z-&S9RuoiWC>n3bEf82cN(g*EF#h+tI>^RZfjda@KCqpnkV)|j-#tbe zNaRNpB{{zUhAjfDu48antnB*_zMOD^=dzNjJp7`N5kF}Q)}NQp!_X3bqg#XmlrL7>*m!(ZY(gAwIXN{k)818c zXL$Y3L%9dfyhrg2F@~_?gbmYygQx5^LG`Sgx(4g4Z&X*`@_zsBaj&qoX594jg2M}| zbXj5l7ojsVzge+iOFin{yi>s?rf_(>(=GT=#MwOpjx=2CB0hS>Moz0jqrx31mLj8P zI!tbVc}d&EIBFBS_L4d*gr7oWsG-3DglVV|Z2j{{MmP4W+#0a zmkGjE5&3uonm(qelaUi#fwRnxyC&P1J|YL&q2zM%pO34qbp=lj<& z2nFV1yKO)EQ*O`p8_taVr`F(vWT))X-i&Cu{q>6c<&ZYZ(r?(5&lOe zr&EL|OD1p`&>#!&^PdtBSEo+ZBZX!wA=0p%GKmc+&cN{pC)WI=Of4r6AE(b_pjQw} z(3;w6Mw^u7Rx49a{es0d)GQ@_mI$Ko@=0o>I?s^dNJjs=+)_OsEW->PDI+`6babA< zOvc5RLZl=!z$RtP2}&}+kbi7Z`~i&s2QPBSKZva@syOQ#&;JY8A1|I001pnMPA2}3 zr1Nm3`uqR5?V4SCkITii_ukjI_u4`sWL#TzMmE>pBbk{=l9@_m?>#eG$Sh=(Pa^$} z@6W&Bea|_s=j-`=Je82K{CMWB3`H`xnU12F7w{SvP9Vl6ekwEMWPfSj;sx4^xrA;m zlmK@vcrzzog0KSx2OL2stw16~P#^tqMG$hJn?7mFYJyXln0!KDQfm#{U>BT72E`97R!mp(RD^ZTHli;iQ;L+l_= zKjFQ5lOj&0rm$UA`U&TK_uDeipYU9=oHXG{XwKFaUt1g9B=bCH4a7feZhMmNwS0F| zZT-sKDiGa)1}t%J+%~%E2!i@`ln}QBjF)LyM5i}+wvN2j_g$# zcrj0thj*M=H^`hgxSGHjV{UDV|Hl8x<*4?;cQ(D6%E-IiH2)3pUPY@1Zw#zn#(u<- zcUDfLn<*xACFnw_P58OeXWI>`RZjTX$R2-Sew_}M3qq64bm$_ios^UZJE0QUNK^Gf zLqh|Y|H8MW%V5P>9so!cc+j?FRHjx6tQkuVcsF{vyDttq+^^Q+Zp6BKcmEA)sI$+$ zUiPjhashn!zu<dsejjfRp^o83(;EQ#-x#N&nvR6f%2^79DG6r-7MqN?KUVENQ9N?nM;l6}ZR${Q z&dU%oo+P!n!}C8-qgVkamB1mAuWQ!ws^xXcFy1^J)0V&JEyhAk4w3~o|RLzEYZ zLN3>}Dq&!PyQWS7dPc4SI(3ttweJXk*?RAt{QVK7KDq@YG3D^zN5J*88ygYw>Hbp0 zmhj!#AE=7V8w?B#fts`e4|(Bc^Rj=1lE*DNMkgf`)I20q=7_eyx{!c>Ml&gw5(UM5 z%Aoe&_ch=D@H(?o+>DjJ$9Zq=2_;n=mQ=(Ezddl_y@MN198|?lQ-Ws?ot}dVMYIQU zKX*hFqY~XU?<$$pY#hMbo#wMm#&W&Z5jTZL01d|s?y&8EgHL$#JwPSv(S!#DgnV@R z#xB4jIN+tFQZ%KznL)fLC7Sj59{x$J8yVU|lTw==p-tu92Qy?Yp!hGz$5A2OgttJG zIW#mBLPiotzker8}OJIlT8I~h83gnzXj{K|;=Dr!4X zs(hObhf2S_6_%-@6-NVQejfJ$_*98VEQ#pjcT9|!fA4Z|W^k&6_yVaM#2MkezRc41 zONQ~IAR;+so@%r__QM2=9M1{W2o&57f4vO|2skrS{}Fj?(D&yjliNIVT}4R~}+S#=7UZ|}^F=hv>J3Hrn9X8& zfqqO_>f7@V%w(Y;+K-X3r{1*W@3sk;lm$Xp^*5{M!6>XXtM@3Bv0^_O7k{OPec6q>PoUnmjow>ec+q;d41IxtY1 zTD%=iYpRPK%}$D8w*!vWL-!n$F@sVbXfmNH>^+SJ+1O?@Dv4izR5C$I7)?2o6(TGw zT$S?Vk)SLoS2@PAQlwZ$Gif!R$?o^HVG9tL#FKO@S?N!<#G^t1OzI^Mce5{W9KbH8 z0AOGJ-_F0wqeOK|`X0KsyafQP=y*g9OL?wMJjS?KF#URt;tn1!WQ&Y^U))5QoRR^& zJ>_4u$uiO7$oefOI`0jv5A&(hCZC<15o%}67X{>ZT`!{zY51xYc8+Z;gVoetE^Ok< zDe#%ZJ#iuKIZGp~0Yhk9;fwK7T>4N-G=qkVqT;qOqo?5gza!(K_SA)#eF-PdGV$(O zXuQVEZOgnnCT?o=L-jWwbZ(~$^DA=d6FAZy2cl5&OnfDhQK>!U(65V0)4Gl*W55DfnUDku*04D!Z0AjH@dp2_LI) z^7P`kA_+8ICb)+vkvWqASyE=|x;s+MlFNkqDc8>YY{fyvv}|5@H;CV|PgI~F&N)AN zdhnFs+EawTx5gjc4O($7hkA@QZ8Dv7e6|ws@o$H>25kNV0Li_;b`%`f{H(^{m7dVWz$R1HQa=$1!fTDnUiv zH|Beu?=qywt2_0@+KDa-7N7Sn)G?%033B#jaBd~&aq{7qFdK->y7&-!)2*zZ6$YO^ zU{2I;r5cuuo_WwKdI$|FyodXZ&?ss7;#6EHO1sR3fvXtCIBunEHIp))7szfVMcrEq z8z0CPH{8VS0wLT|JPj&}t}!UA)S-9NjdkX<+Tc(Qie{^gPlQN7M*P8f-DuTH0_g&Y zWv~i%D9qC3fd)*g{uh22P}TvE@%TJUwt=(2C)k@AzRBAI!IR0kZefoWxa^^OqZuqS z%lr2P@%k9Yd3tifZ_QKvY$L0oQC&%4VS2IvRf47GW}%)1$+Nq6)pNjIHi>99{Greo zqbz;&nVZ^lr>x>C#x6f0VpK?iiZV4O^nbi zQM97S3G#f0?Fm9D69dRoPx{ug{(jWmwxB9KlvrMSHMcUWs^aDQxNt7}kvw<1d`iof zV1tZzg2U(43WFl!dS(MhmMY!gp{(5-4<$V85H|i{Ys*0Mf zQg~SC!r6cv_Dws)2P)Vroj}#T0p<~;#fqEbMOkT0) z;10Q&v+1>sgwcirT6H-C$3z>Fcc^mMX~iqFG6w3H=c*1wwW{C`a0B|anB0$&;DpoM zg!mPp=F9kSDr1mC5y7=%Vac|BsTws|VLx@E{dfPLOACA2^ZekvSnQd`55yancJ(IWQLd-p^IjAh^2 zkX>9M=N{ktjOF1-=N1)7=Qcu^Jg}#Mjhp&btZs@+u3Q#7=>p$snL0;d9BMuJ>yy+fUxXx9q#TLJx$^Y zxbFvwoLw;DFV;m9CQztf(2- zTjIPl&IVH^`hIyispK7w`p)1Xqr5`g$+eU7_j)2odHwqZLS=Kg#%g41An17Y<=;h= z`pF2djDW2_1>9=7RQXYLJHX&9*@dN>52Pp3#ZF8$SKQ&Ht;c855Iq~TJY`g)<$z%= zsX2S7v=eB1zjBhxbr74DletcVbthuo{r&{)sJ;)0A9J~}aENYiVT=!0%FSZp*oh7N zR3^&Qxf0g79|`PM;UzycX96M4`U>8gT8Y)%u_*jFg&MIyJ3aJ^B8~TR9}JxJ4H|jJ z9NCi>n)q9U64;54sR>8%QOG^ZtRsUQAkQ&c`7)z*?M;FfxHrFZXnsv`XT`RWlp2(&*_z@ANZcumMUQ>K(xmVS_MsnMYYDcNMyEa! zMB!WojxVom(Kl3%dKhlo9Je(_q}PF-vgdby_c3+-df^kXqx|LkTK5Gh=x;p%a)C6#y=Plal~NRz7{cnAT_7>`@A@3nU3U zXTVPJCRXYF%zO5}?mIXEr3L9uipPFWDx23IKlV@M?Mby8@($-+pxI&!IX zL&d=tL+(}(Dm>IVS2?sz#UxKCXUr=_;!^`F3>r2QTO(fA3v7-JYD*4_jrsg;ZM-kG z@_2FE%=4okV)8$)Da-@;{@}FFyaSJ6?y>5C@Qlv3`TbI~{bi|2XbUi0c5=(M)X@S+ zPB;pM0$XZw?7gF5fFu`TWDzux`8rG= zvkG)184u9#s2sHK=I-9hUy~I2#~Bh5>&Kq&lb1$JfkR|dW>VYH#2j$EXm8*4IiC|N zwEtD8b-GISLc?6fL9Nz#fr3d)yWu=$H+wiZ`v~5j{Lw{cLO{xP)J>+(yp@L%e}{$U zJMpq~qeZo9WZC)iTmu?19Lw6D-g;njVPxEHUDM;9z#xV@87Y(o>FFr2%|G@FW1-?FuJ`Zso?*`q64m|}+& z%%=ev`)4!MQpz)4j{+ZnW|Z9sDf9XbQg>2h+<-PZryfc5F6&m1*0F}BC{6x7RHZ3?J|g6PfB?+NMY z8K%N`gX$_`UM%#jWeb+9DEOlv=@wX{2ZJ`9$euZHTQ%zjSIg_MUz0i?+Y>z&2?DDI zZhA(qL+LNiv5+IVXN8%>5(X!$AcwB0BID=c^tm$>Bt41o+?$|dmgO*)(K=QI|DxK5 z%!v{_urxCz?8)(nz7+Fpn)?D&1<7d|09U!`Xm)SURx7J0A&sAp7F~p1E8PaWZ5DcN zRTur1Q8!l_+ToV@DlO&;#zzz3E7A&P$3ZRcoY9P%#S?uB4Jk`idh`&o2&RPi8N3*7 z9Abxs5&fM=!XY|rZs~15-4n1#;DOg7(+8b7uDu4dl*b?$zd0&U26qz&*1yb%eJ60A zNSh?A!D*B3)hTep_US4EUkB_M-HMrv^#MT>fx6_-kkWec8@Cuahi|%f$|8is8|^=L z5=TRa(yRBh`;Tk>#Kd&P#;P0+{~k4{&e=9zk(7B$mobZ+U&`TIt3bGlYT|0XaM8z| zbRa1w)24LAz(Y?eMt(bvNre10txK^*PlVp~fb-dwiJu=?zkfTvWsLK<7}4UxM;3F? z(uxYm^ZvT{ei#WS`SO1bq*dAI$|vnk_HIcQ`f#4B=#KjOJfRxm9{it@z5@@FC<|{} z^(nT$QzhiM7dKjc&Z)=4(rP*s3)R`?pd;kj7t{8RLGy1)VedjTd+k}ZIByrVHLEi^ zE>0v`ur&U4#hvx@h&4`^qdE>C%ges?3f&TofGo_Ep|hcQ#jZ}?jIa&G|F-R^yf>Co zluYNDZXC@Plt2Fb$Nci=X&AV|cc3(1R#OXIg=f3=_V!?&d5<0itlUJRmKPQVCgW6) zLfX0JBd-Kx?eTe@mg{amVel|k{Y4+j;-wkj;jUwMwE`^d7hnE8W;dJ@h#;idC7u*` z970gcE|5sg@#nxNs>6Mr--v*&K4m8GUW1dHoMjznHD}H4e~=xvug&?Opm=Xp2A_VSvR)c5 z!TOo$+{c1231mg)Xw)o;#5tCm zj;&;_VDGphc>m;9i?t}z&X!p5HONc{-J5(_JU<>8ifeiM_5m34>nT(y7M7PGZ?|6F zTB_%O;_k~gU={mwVgkQ^|2|99ev;(u_}G4k^^f)%7<@~wyL~?b2N#ZvE}HvHd{3M| z3vZZ6!`YcHXg51y7ksBO!G|`wn#*Q9xLx`kha|*t-kB&vK>P4HP(}TJI^yDTd%nMn z>YkJdE>>3c*ISjcRC=P<;L*A!MD0Y*AuXhzG8CK&FxZ*fD%l2sfq}mGJyDG2bOikf z?i!;p;`n$_BB@pYP?%Fyua+Vo*qWip7MwnrVYWp-f018abnap@WYBMXWKipzvd;%U zy~V`0U1)ugim$4jb->yv^>35Ei0AYus#2t_emU~usn%z2J@L11{QD|$<{bH;?-88x zTrXVnj!uJ;CJf>ufH^83ey~@ z1Ezf!xMS6?et*R?X%gp{efHVJM7TaC?U&LR_;Px_Q=RR6-lP6<6tnvzZ$~LINjIJx zCGtCt{|F)ozB$0K3kaAj*4*XA?LsI@Is(U{5YL=#{zOx}Fv*HYLXjZP4|7UpFMHO4 zfE&`Rm(q<*2~d16l4#B-ULJy+M*c(;}( zJ8f%wEAL_9l39#QJ@vrm$`a>p-`8KitFp2B0c=URoXr>vYY%*dV*K~WhIH!Lmogrf z36&%%@hr=+je}*uiAv}o2wJ`+CqH>pOyk5Xsh_X+`*M3YJ%pV#ZEMRVvaNJG%`|Ar z@WBOr=B$;W7h103Q)19?TD4PyNVUHhwq&Ckjq~!7;%|TG#e>xdka@_5A+KhR*kX{K z3cE?>VacDF+p@mmRqZYZ8zoTuJPF;bd zq(oooRq@BmA~Q2HIu0-`oucpB+{8CtK-yR+G6!~7d+Ld31j1tFTkWMeRJ(xCK#4l- z-)-tKl?0v(`Xd(SEfawssZCnB!Eg_Ylr__#HwTwL^`#!*bXAcmk1-xe>L=PBv?{ScI?92E zr+Uoyob}|$NT71hlS_1l3Hc` zIcHSc$f*2f{fz6?gow03_x5ntzE2>+OX^E}FDcQ`JA)8bsZ6VZuTgQ7wPQ^tN~cqg zXsqr2RVS!Ft4_3VgeZ``k>Ol2WKtZ%m1feGZct zbNig3f5?IKU$nC=SPn*&S}QM=B9 zFiI98&%9mXuQSBS(fdF*F>s_sXx3_Leb)Q}ce@xP&v)RK!R%t$Z!%o@+Lw!~A8_Ax68G1s`qoOPmej8dRXwX0+zGlPlG8^M1^iSnS4F<(^|=@#kr~p28P`HQ(kai7 zpL}sA?3efs+CBqN^iL#|2Ob&CaqSWK->iMT83U7J&-s7gB)yJETpKtaEY(|`f=mS~ zw8?QW1?&aru93>O8|_rV5@jPD5dqe2J&m>aW=VIv=Gu^@4J%R#bm>K3Ao#A+Wv`)- z*tm%SKr#ot9GvM?7lZ?y=NvR7h}Z3nU)xGaTWiqU(`D))dF<*Yk#|$~1e`^FDh{HS z^m;*J7LW_ZCR-5A*>Q^6N~XIV+FFC*m-|8};E@g;{ zCXfEnF&Yl-k@6l7$e7U1oK-}6`NZ0(DCf`YP$me3A$yWiQpj_Nk#k&6Lr^HvVp7?6 zOmSHW5}rYdN9^V zZ)uUrI0tv}{HH&^zF&6>m0!mseLlT?$f*vXR{zxhP5(OukHjF56yqjCI%oVHZ(v6G zj{_S!XpaC&TiaDVey_pu8cd73$9L$Ecxe-3wnF?ny2LJnQ+4&j(jb{o@|3i76N+19 z^Q}QZ-7+;LyU+TpgF=exr16>k7txk0*N;7+?}x#d4(Iww5)wVfC0 zJhEl<<^YxBr_4O@g5_>;nNQ^QL){|PKhlg-s!F9*!@KOTTn63G52In~{!E)2Eg{E_ z@3Qc+SN_{y>8Cd3=WEU}8KKC7Q*6TV@P_#w*&v?-NU)h5D7(=}zZSjaKLygQ6v}|S z1C^8|aBE070}=D(M$@p=vLj$MfSr`Xm+boH=_fH_yG&#ryE8N%_VjY1optQ5F%HZE z472R8q0!m*ey79E;P;DPS^0i+R^la+?yJfeHxdG~x&iSA17ls5elEPle@l;_$T{qb z)G((uT?l&2m3ERtmnc)pwoEXwmR2#-QCAR6FnSN&X0olQzac~OtO8eQFbGjZqRjlW zJ#=!=lg}L8CJH<(9%JU1Dnuesg{u?H`+AZ)jwZZ#@X_&cLcZM>@|)%4w+a=o6@GZk zO8t?1W0FaJ4@J0kR1@D$sWhb$q}B4K0JQJuHDDVr``Xv@zwc?U>}v1Y3&|Nxu}^`+ zqse2~VQ&Bs>^0yzN8U-J+u^!gBL!u&jq~4rTpj-C;o)Z6{D~GXX{n`=W;a%>uvr(N z3UzZ^JIapp;`P4R<&|7_n34{_1qTJSwFTMZ`@G})2lT{c)V>;LDd0igJ`GM~H{N8c zvM2N>wLdSAL0_;6tQV#O*HVaebCHb^-XF^JzZ4TWg86Km)v=L04xdLizRk^kUYU35 zdX@i(OH5FZ+Eq=}DXJ|lBb@W~--Ez#^nlr!4@L2fmyR*C-3V3h+~J9+Ry(cA(K7C@ z#%Ex8=Iqlvu`DR5v()lP@4=c=He#zlisCB?A$@aAGa`rz3O8uNtvj-=h79XCB9~BY(p@~(?KFWQOSk;1 zYoK61s6kyYGX~*oD#atF)|qTxlm`5|Cobt6(EN9%i)6nCZ(kl1EtxSP%YAZ)=_A3peh!JKKYlRDI^851pyl&+xex z56BL8X;r_PJccDb{6!8b=n6CeVP+nDiJ2U|1+&V{Yd`AEr7&>;Ls+Sn2lt>ar-p=b z@ZtXMuG`C(z%1rV<^ck0)^7v%1k{d`*}UI4fbGAHWV?c6;;ZXeI#|TOa`wT;<|IXN z=b=o+)>_;5o>cLxrn|<>X+;MhpALi$^l26BEWp*T%JA%b2Ggr?gUh2eV zY(k$xp47yC#g9@51KGV^2|v6!a~qI!X1C8`*C0^oyCX8r1#fXb%^CHEW?E__&aH2e zsUmCQvcqopACJgRX9YGHXie0m%oWMMKxFsV=A-sb(E)icHa^^Zu{U=!NLWx~gQ5-)6tsvZGIZ63sto+RIapGT85Jbx7n0sN-I?AoogZYz z$A@I&@k=Ox7f=)N7?iQrzmtH)iIHQKmJlc0_OZ2)uP-{Qrb1DAKeLAJw$eYhq>_xa zWcdm^d;D4CCfxxrOix5z?L=LHoy~{WK=c<6U#Ix@8zdBf?`clZR5Lgb=MxfpBU!t; zR>5a5g<*lmfpytNz*vr0ORT$hw99<%;1@39^JPU$AnL=6M)x_oru5EjqvdY@E%FX3 z)n#l7J?8|o=%D?nElj0)ASQ5i(sw=V;w@X|(o?hJK%wsftdT;N!Jx|LO%1Q6cOBoClXL$PX6GsXP(43y zfAVDeFGWX_d!LGcIWvo#d%8$`XQPk(;+VeL#maOPfVW%$f57kT%y9ejlPB>y?aA1I z@6ue5#m?s2O+yoVTvx?Q=2G3n8?xQ4-!7dfDd(?RyEDdWJKensqqYN@Mqdi&>%nbf zEax7b{C0e1Y1bUQkw@12=6pTZty7%!hh9fwY-E}80o!hJ=p2lvu-3^~Lh-kjd5dTc z*&m5+nCGxR^))Lh5sgw%&bmp)n(%>{C6^6jWyO+wgG{j!?BIyf)s)8SUfxtnfIS3l zlAU#Rpn=&8>ng>Y9Ea0C&=-G)!-6{(bT{mP3GEcDWcYi>UHq_ADN;hkkw~^~Mw5p__O*-AhZyr;8E{#e%;nyq_Y0DUL|8(ciT}eD zIE9eTib~!mT;0C4=OVbrQ{mc$*&AePJ*{t`1$bl>GWWlk7r&uOb4o6~8=y%S4=hl$ zBpHJHwJCRGLW*kbM~El`QUyacEuCnSf`|nS{SSVm+82tM^rwRdGp+!M?+l?(xv2xC z{b!i~7BLzOXp{K|h0k6#-Yg%5F5ji|^d!JPwZdOmzN=v0E$GoyKP%Jy$T?xC+>JVJ zh6S|a(RsdkYC)$cd|f_avO(C;CxOs?3X?D$Vd=7)TBrFrv>;&%63Pyy1qMZ)1-qV{ zmaP0GLcg!B@Q)nBP{Jep*-7{|1*EsA4BwUy)NGSW%{z2kEPeWvz5*&h!LXK7!*Bd} zqEnIX;p7Yxju=>A05i5qD`!UhlW8BwChr@`4hu^ml2fyD?)F-&_~T!p`Wux zc9r!vTR{ztzYVC1Z(c0K`TqI2R}QTUA>#8@9pnqI8ru)~0KIvqFcz(v2Wi&Ij26;; z2NZFU5k8B(M>mg2hq3tM&`DXW$OjciZi3MH>X+HmsRiD;IrN(n&^A3R^x3VkysYCz zyW?6U3fboGg4vYuLwrao@T$B;lu1BhXv_;Iet?7f(d)KN`tss74RTaE+8JEYCtf*F zS(nV40Z8|Nw}r+nax{DjeG||S5g8Q=Hz{eH4RAKm7MbyA8i`(mTkuADs3()zGe`-5 zFmbm?>ueeV)fpTd)G+W!Hjpvpo|>&tj$vrWX|v(Sar;aagBO+vVv}2x-Qzc&mW(4+ z@yE6H(SRxNPUBK|lj%2tQ8oymoW~ux(!uh4e&4mSO7;P4i?dRRa>m$DCd^}#4Nl5j zGPmg2I#}L^-xD^PxCi6^8@QcX%inGdFylH zb{(DVmY9fqye)f)0NFl>+R>M;&-gcIzymY+zn-QYLY;MQv>8IkuyfgQ*tvB;bK3+9n`6@KF_}fU>=e&4ZDeK=~ zn)^Rd!#^lBq`}W-1l?8AhF-qy#dfCRjzra;2v*xx(;Hah-kdEiE}HV~BO9L9)zs(? zVTk_w5~aRUwm-q(3(lX{pMuz!@&FMjk@??*t6Bh1i@rU;b+ribohg#M`3{(YhClFO zxLsCG=TF?gFA7n_n;Bs7r~m{qBmNB1Fbc``p_S#|3C~wlEQGS{(<9wGJeR~Cm>?yfzk1lz?Jh(N+#S?Wj6!Klb`Y?@EfAfU{)jiGWTxEHI^SK=;2emd@@mE z@Cky+5e*KZvN?m1rIYDfGGc125yituISdc6D)PEUR5hg+U(X^Lp4if%dzWs|n$CV; z5s-|bNcOpp6^g5hJti9Ic;)%TeF|`8H>sPk=b%>b$R0v(=}d3$M*I;@A5-v0?>3-z z$_ZY_O&<#1ZW$n=9jothWMc+yz)Iw>04=?O;4Ium@_E&Qg2R_raZl^22QEL0iTUaJ z%Yc{u!V=dnQYm$=jr#ji4v}*tyZwL{ZdlF$9bU*-a}R;o8JrPa6(&or(v;X)@h6t{ zO-Q^8qMm>^wc{~*c|d%Ac?k19fu+V0$^LA%KSF8ZkEef%iGf|+4=O5yr|R4l(-Gl`mRrp-Mr7vJ^8TfNgN7ci-G?eZ%V?JpH zX8nwwup(M>qD4kU3IR`Rep5YiHCr}spJ#N;SU#%yq_VT6seJihgXE!=;UrJeSYYU3 zwpE&>5-Lf6@vWBKS$q0~J#8Pj>rucj~f4U4q>>tAat z@h3VGof9+J905~bwzWZa@Q7?4HgrGg8uk(&{`dP`0p+ZpvlZX>C)1pnPt+nTz@NGK z8XhuKhv7^yjG99Ur@6VH7XYTvYL#$}*d2Dog&briCN-@hxE|I$6q%o3GR?s4fgP4Nn6Q>>8E7WV!ABOwl5l*v6PeB$6E&G_hp!DsD!d3uP zY~V9s%A62TdY`8mc7DFSWa=~B z-l4)F*8|7qKYUo4oh7D3CK7MC=)|(JN^uc7zA7cF7C%oYvWd@1s^&JtRO2aT%2em^ zKi`LBuc=3pP%-Mnl-LKUI#nAJhzsN?`)$Cxr#mTlFY*v3k6Qzk>W6ph1@18%gfqV) zA}caP6Yw#4iUXm`FRQ8_f6Ysp^PaBkz-Q|=4+b(~L{DfYK}bA(tM?}*DXF3_Kq!l5 zvM&PRlCp5H5c>#xd`<~}$2ou*pc4r2kHl3XCk`GX$C$+O#3+G$MF zit9(DcmumL!^TP0HAuJ_k1P%(KLriEO{AcDG`83`G&k?8yv(O`{-z5_ZoB7}7t1@! zk7E(gMcfgc_s7XBg0Sa%LD*i>KRUSb&4erkwOvzMNhp%jLT_rIl9FfBMFpg8Fo<7$ zB*&xv(0-fJWZ@Oa|dhD38b^z3{(>Z)a2jF9o#cBYHI zE2CY=nM@kO$l(c?RGlE0JegsE`5r~5C>S<&94bMR8B;$qz(V?}isrwL z$iGrZ>9n;irJ}kYr}a0;ciWjZJ@q|K><=rkDSp4=I{;fr8|U`_xu|{S@L8viOHajg zrT6^H;uBQTJ;-`>4v9%xbnWx!%J;v~BP%o@91=vdmGQPifwPPvu2(V!-RIeo+eB>Z zA59|h6>^gG1afHL6kzqTRru2vfiqp zswC8)knPv*Q$#W@F9Z2X8_D8Yu|J)^+4SCfdhfQRs&|~YQ?s_FX7*p+_?LVplP$=C z7P`<3f^12MzcBG4!vTZ?nQ7nngx1+D)Mmrui#wR`y)N(@XsZO zs|L6M$o>FIB$w58Hj48aC)o^&ZDmFu187$X6p_m|VsgEH1LPsCAZ|Z}GA=l;&!D%XA*5ko4cSc!%SzjkE;OW3lOfF>@W@JCIOwq$=$SrUgipImj6arCG>O= zyOk58*8{GN#S*lroNtP4|9h7G2u~prW!p1P9&x`Kn9kx=Z|M^Tgav7>}J#UX$)0Uw3`$tK2e!0u}DfXhcQomnspTONg`YL1ikG8k%j zh&0P}`X!BD^Ds8_Hbj26^ro2Pb2!nA;^XIxb44wd_SEma|6TnB#_vkI0mrv)8C~1> zZJnJGo&$1~uezhMvp?aGt&i%H~fm9iBGo8Il<~=1DdJayhsGFpj zLPA2I=@hLDC(2J~zyDsR8XW1S-=Uezc{TyUQlFMldW%RE#}vuFrkOyFDJtmgZKX#9 zU)C_72WYGy!teRZm*L^RaOT#S#jjG`QyJ1jPnyg4*{WL0meupT$e7RAlsn(OD;2f| zPFnw0PjFt=IRs&punr14_ju8P(CITyW@dnxAuU?g>`Ola7KQS&o&2B4})T4w5<2T${7UdWS- zK1%sYyyW2)M8_=^z}UeUiB597{)O<*=PfoLET<2dV17}cRFk&|Qf{=c7=ogb0B!20 zvY7@P>)LZDeAz$9m;{JmZ&JB#{!I&Q`ag(hAvfd zwPW2oc>jTzdIZS5|A_prBQOG(iDQMXTiK3=uRXS;oFUN#q;K%T+Ymn+OxM)C!Rn%` zt}aC}dZz$C3U6c!WSh$|$x_~sC6AOhV}ysLe$Kfr3{tIUsJ^vnt#7u}0h?ddPbYS> zT9YWL6lo6`CJ;{8uMo|fgCelmtN0LXQ_$DkqzM5p>mn+misTQuB&8DlyXEfubEUeq zENH&@V@v-K1hvQB-eEtBzcp}VyvzFXQy|HGaKkaioDd%0i}^!~S9yyfM%~L-w|`p; zspa$~Cm)lRpvyqLyuE$#PK8zucgw+4&Hv!Rt(4B#h@XGeP9uI09NKO(O)q~Xi7Jn4 zp+`(>{?AU+%(cucL8SW3s?ijfT7$v+XrC+OM4VLd8Se7ASM6WS!&f|fESnXHod2`O zfHQ?2orhfp;6h*^xf})#JWn~;Q`ucCP|gs9nj=#HGZO}qCI7QVuzmSWf+-QX1d7lV z=r5q~*tfhHmm@opKm?Nffm3XMo+!6_*t{0^pK$_d71}u>L-gUM8!dTTwNJyX9u6Cw zn7;;*n$(Tq>C!x&6IlrfM5Ku3WY(P-u-XJqI-+WgB#s4UUep4hVKItY4^X|CptX9q z9f(@0)=wxjL=)*1=t6YWw7!{^dZaN|@MiN{WneUM@M7PGHiPf{^+#*@~<+%b?_KKZ1{?wz`{#UW`vBbicK&F zM;o56qV0nC_d#o46ZdnI@`{h#_F%>Oa}+OW%ieZ3miOLDi!;}snMAjXCjct3)*E-- zry`(!j-m7?n&U09T+7yQ4lYk_i~934$}t!^eO>EEh@S+cw7c9w?8Zk~Ikmi;yG8=S zc9THTuxUG25e%64#^tH9`f1+UlK!lqIEuuP=c(C$r&9h==Gf7Tvk6`(f5bvcbXkdlLz^gPrKe{?28l_J3wSU%%8=89nR*HCxv- zwVOmpm8aN+30i4TPnA`6gPc;Er(XmyT2WP%8nOASy?@=_D%8Pf`NwIol|KKzsu0Kh zb~?`BneSvbsAAP06dT`<-Z(i87*2nVEd#lU%CO3OevmR zW&S%>m)d78C9Jj~DOI}v4S>>ibkTZ?*~W{HRm1S;_M=MivATM7`}xxUF|byWq;YFz z{aINU}bTSwX8!m@$-@oJ2NhL+R;yM!?y+Z6#yep_o zu^9^0WysVhOJ|ekRDD3Nj1ASBilY$kG%rig!>*h-bCYp3cl&|o16-6TerP2L8F^H}z4#0*6}>~tTUr)Y z4=MLdJ$T3#-@9kr@Ynj9lQFW#aY0^S+9pNZDD-g7G}+m`Mag~)To%BFV1r=U0yi(P zewIF*OD|j@GyoXc>yEY1?=N200z{mEFyuG)P*0aciC9Q%Sv_xaL_d{$v?5@Dltup8 zOXP}VKEkgj3XIKJp{~Dhym&-@&7~*`|J~0u6vOp*7uDlg2PijUoK}K;1A74Z`>6ukq(TZ<>stg?4I+MV*7E!)vZgvO>8R>en=7bJnD=JH( zN<8%#G9H;6KP~!FMByKRH!rOy;w^zy&;2eX9-p7j*g9_cHzuZH+w27}1U5WZe!se! zV=$<%N8#xyz{s#8xe=n$=f?#h*(I>d)q4;ZBk_A};aUFIbODXRO+EsC0fCIl@lL-H$YoXbiH!`A}ymR(n0P+VdQzD(^}%j z22bD6XF;BV!Nsd9P3F`?7Nq^E%&VyT3Xfjq4=ifa=9N(s2h2SS^!cH2Fz_s3M?_5Y z1wm-6mITZq1(Njp2CopbIelQXO=3^@nrm1=mnSqO zcP4j12_wsn%hk%8@D^EBNA%m$CEQx5B$*c5>eCZW%SzjQl14=Ya14;yZ2=oFEwpXj=(|nn^Gz2uDIjlQ$M8+O*BYt|md4McI zP__F(gT40Q!-oZxOd4!i#I)F6s<-|4E(H!A-i0ja%r}X-jx#YMCwT@PMw*Ex^Ae>f zNox0zUG$`2=`#~SShYR$#xrtfi0;@(X(5WoPM;fA&A*W05erSg*#Ca8nP>g(f$UQP zm{1#_ErbJu2RGh2Tf&4no<lBNGeQ{-(EaD8h;K3s z%+;u$J|GM}C4oi1`my|H)l)n;=yiS`y;-rI|NWYW=g7U|pXKUfQy(JeX80xxGO;(+rQOIyGgt*Z9m9f_DUOjedoXiPXJxZ_~_ z_E%4S5VaYuoOK#zy^K7qio$#4t1yx;Bq;g(CYC^Om6SLa9qiDOIhpCm;1w5f@`#u3*$-g&UK!sv zlVVeq@~wA=Oc37*`FyGP&|>i8_Jn+540rMy;R7-vBzEBO;T7MG?Hl_m+A;wm?|@t4 zo_y!iVfKdq_OG=^*iCDJO~q-@i2fVk0|O>E3b1CT1ZjxhrUb2 z3(irIc3!UYYWNF0e)KLRyS)FnoI({DBuM*qEnBSVMyzJcr171)z@}&7E$Tf4&Q`ie zve|sz^>q1(X{uR9GBN_gv>EnRVA0-z_h8a>CLNmAm}xNRWTyfhvw+yFe&fc*=n}Mn z@U8l_8CnsI!kpa4G_(0eEK*;$h+;?7*2s*+t^JHQ>g!&-Aifu^h_-{GIH*q{TB8xH zYe+H=z>nwT(`G=f=1`3$LnTtBDF@=L@SwIcyob$7tns?lF(ycMuL%|0bBNByGuZ%# zWK*q)YH79{<;)dITM0XohC}TfEdz?7Cn97xH8=(&F6d~&Us3BG>2dTrF<#~0@pkxD za8DOsFJvQG06a+w0%TbDb+h^l=ssPE5ihK)U<_Jsc;EYWilPcREWcD)LCnpL(1rYYm%KM zx0mBOaPoG5*09sl)7_FfK#6ks5>vX*My;;2@f&Ms8HCX`oTM{k za<&@g?EJ6ff6}^C@^sg;<30*;UsU+Ni!a74PNX?vn6c~h%6~>viZUy;*qd@>0{EnO zuVcVO6X3ZdsGl$hd1ix-{iIJPR)r1U;l{bD&vU4FREN|l5K6=noWWMVY3QID%jdGG zVXQp2jnw@%2A(%|>0R~7!%H;a|ABkK@=UQX+RW$OFGhbGoush5maka};&CryXIBJe z>q7FR<=SzYcU#s0}LJD=C1GW!mf{@V$U>Ri*SxM38Dwt>r6vQ(tQ>;@`&B4EBj<9qp}knWUjP#OfJQ#z$fy5rm2`-9(%0q5+! z_FQv5^Yfsm83j>6T@9WUjo|0QQn~OvopNHdk}2$bwCWEgOwuFSOnSIM2|6<3B`llZ zA_7{v4CsDP=sLsPPv*e;NGl|sQ?<=6RY*OjnJXh_HAzPC*~aECib6vG@9R1zzzAjo zJb-il%+0|{)%2rP>o!J}S+D~KqNwNd-ENvO2R-*!@}S4P$pWap@~R&wqhKnjNp{fF z6En?oR~4y;j)0z6N1~7^=#6`Pes6coh=MXgJ(~B6->O6upIG@Fg&=esNgqocb_<0A zv!z$O(Ff-TiUK-Vx1!O1)kjO6;hq+M_>qv}4dt-mE!-C)wHas+@G^05GlRAA7~PoptF@* z3pg(>TtsqOwY&Hn2jy$d@L4$q6KWt1$`Dd4xCng3DYEK-);&C%S z3L5`eF5A%eAHrA2@DB9Mc!M_-%{a&yIaN0#9i5VrqDj@D@jmLKKFzLhOW(^JAT?)7 z_OY3`Cy=z%*)BFj>XE-^t>Zv$=oovV!-3oc{`VGL{_Ehb#h{H@0(qAXU z*IABb%I(n4(dOaPn{n5913d?g zBfr671Y->_@e7?s?G#cZVp~O~C15hl&F3^*V$4b*1|w+*Ntlr3QPe_lDyB*7F{vud zaZGjlx2N=~eb@c~44!veov{Ui5Ec-ogaHR&a28<&a9`>||~# ziV(>@>zSF<@e667k4pq&6SJUB0#{tY)-c^Vg>(Kd3F4`Oury(sGnypMXfCaV#svZ8 zWFqt&hK66n`Y_>~iap5WTjL@REG^Kjry>0kZ_mzg@p@>u)VI$63scsdK%G{ofT0cG zx>xK1Ftf7>Nlf(l9AW9SGK&wBFCZb;?)T&+@oh(O-BR>HN20y8m3Z{kJq6@iLA`a5 zoWs8H9+_fRGTM4mkN9UMCz8SG^y2oce<0g~j)3$H%RABLAx9($GZY|#g1OU1f%IfL zv#Bd~$-WakWc0v!15#QR<{6i8w~91}-ed^6`Ns29EnvCO&pvWxIbpjV?R5tRR_ZnL zl9iADMh@gALY>w!R73b~*^rkhW^GMe8mkxlL?t`i(T;e1vNE^$M}ko6?+}AZT53*C zuoIWGl)0ZkiXRX#>J+ps?R{5jHA>RM!)XJ&O~QB>zk+Hxg<<(_e?a;Gl&YtvV2(bm zcO=xvfk>B`BEymBHDwF`4au)62K;jHya_GUZ*P`onf|MXaHbTNdAMA1GMX37n%VBsKVLFBz4 zn=awnypu#kf!IHmn(Zmea968I!! zznD=RMKC2$Y2zYQ$Ja1rS_*Ngw}pleCd0hVbjwBm6C~;Ky3!Y$oGMZfw}oLE;pjWs zmu!^1Y3F+=tM|sf`_ZdsQG?VJNca(W;gaEj~8sRl5lUQbu(BA?!n@p2IQ--Vx_sx~w>7L=5zV8Lw)!JY+^>zG(5 z{8gXz{;HUZbH{>$HMDD)4NJhydAz;|7Y9b|q2ae-VIw!EKYs|MZ7oLr2W2@zbQF)rD8aY=9EhD)JDcKjz<%rQ?&julbLn6Qtsh*2h_oo{($d*k(q7OAu&qZ@l3(O2 z7~+#4M7gkIR!Xfl%=7E}i$}*&L6zOQ{~=o|%)?R)4J#0^Wa_D6ou{=Y$`<34nF$b~ zwM?CCP@gJ)-X4m!=~sbDz`9TW$%*s&UW}0S-s0lj&`=TnW%2hrL_~V5*cjJogBH7f z4GPh!Zkvf8IRNi`h0sUwjb{!8HfW<#IKkf_B%ceE+tOd3<--HvpZh>_k)*BBz$N9a~Fm>Zy{!} z!+fyx;5t?yb-Jj(h{R{=c62!Pz%KvP9x4m|ntk|Ov40*kqRcwx2!oe(EkVp^#6vP~ zus&l2)MIkqT0^s(^$UO^wLFQ-gTK;X1KZoa1^E~>7)z!a?$1BA^we-Ftl zpt*vjyx-|G;^m`cS_hv-q@hGQ#6l$-w(TPiHMg$t^}K1W+j1ABm!=+4J)c}In{Goy zOaSJs%o2KaJ1Wj(1r*fFrJR(wrqlX*HktA&Rm~J`q}1_^y)T@^MOjmKAa!w!*0zWF zpcodzLRB3xt%wa(>JWqFx|a_jQx=Q?r@;tyd{Fl$8uutvJH3`Z@^Gi>p{oJDAhNsSSn9v;)U1?Cwh2v zLzjqrQDUs$k+O4re{V`oZUBE5s;|6<{Vl+y+bCim+70VNKW%fXuNr?*g5_Id--Mvw`G1YD7D0)l%88*u;@)OK&NjV7LZc;kz zTqCxfeH0)uCM;xccX9R9fybbI-%C`0&1KEj8#}2ZKZcVrYW#`&7FZT7Z(rk&TSvwa zN1|62^=swUx?C=nP8`{g@$VG9cCRb#j&uCFV^G?$vYYK4i+lK5{&&)Lp**IGg&cnJ z+5-$LxaxDE#1^`YSKaySHMRnRq?@45s~@8TzFB4rhxb$xQyA{E8kg%B?6PFcz^gsd z2$jNBwp1$o;@SVH`sEk#_-}cEuCY(g+n<8Gla{-ML3J_vUe?kZC5P0+54l+9s3;^N z!V;%0g;iIwgh}6}Wu3`nVDgGh6;H%tGu3(N0d=}i+lkFBRZ^B++Xw=HBU*b%#Ht5q zlCrF0lBZY*8)f;lu2I^SZIxaf^1t z$OACUI-ZX03j*M5#&Tx}!glILXp0P@Mr_o+2hBP4+UT5-4Ff;W2xAARtCZ;P>7ka& zNjCW%??4q86<`8ZpHj3&c&JnyDVSm1CONYqh}m^Y0obpxX^9`@_I!^qFL#*7! zRgnZ#xi;h&mRVVk5iw^RRXMe-rsiG?`r7~b#u+-u8Fyh3MTed4GV-sVCZ$1eb>t@Q zP}zmTp~l4#R5|v{8`G}j8Z~xCGgSIuq~sXZn}ofu574{Y+LoF$3$dOdXL< z_gw$e!Hs?;dt2%yFt#Hmaa8?yY@@#@QOt^$#gXU*G+-=s4lEesTi@3Z8&jS8od1iH(dZ?9JG6x9V%c|Rw9oSB=TRz(RKj@7m z0`2+~9HK?|9zh?NoUI>bN<@Bzrm}DY7X;W-2fk@HQtkvXk7;uEW%2Y5fLv&OACJ11 z^r)Od)ov0_Cho4^4Naiml5i?3>4c7kF?}!~`pij)aV|Kd-zRsHsbZCX4RjkAUp`E} zG#3l2noLeEdK*4iYHVt?WD2ceBmO0iLJbOY^!H3frmjkQ*jh~n2obpmzggmvVnc9{ ze`8cr{dXs`s%6~6gDJZ%=cb4;EsZSJO-~RCaoJNIO^EL+>ZQe)7a2vJIfwX3xX4H9 z$I;x$@XMd5Ho=Em1%)>R$z0JSl7)411)`;xX25oomq+(zga!w&gkUw2L5bl~6v6h6 zNCMb^jneE$lxR2gl*t&;#CXpj;MyBqvkymY30S3jW zD25f#U+7vw!bdoi^G&;ge941iYXJ5ep3=J9Q7zQ`D%KvbaeEFoS@bt@Mq@w_9U{hD|0lG^ODuOIwx~Iky8+LGF z?M0~Ld{(s6B7duAF7zU z_D`XB9;2_#{r)ly)CS7a{RPcbxwYU9c|IRzr>qo2W60rh-F$?ve^VZ1a+W7WgP@pa z(>x5@hrEmDAsqNOhV`dAIaDYb2F7?g4=mEAQ_08!ZSao0bnB5@A9388EpE2MqG<=W zZP36j=W35Ce6Il465tl@esVBo!SOx&MfketS5*6@Tayc@r4OL{W9V&E99b2xUHjdA z!W7Pw|Bp#O`R|2xmA)$=u=nA#Q>-}%ahi$AEUp)wR0Rf9JKQ&T&V6#%GZwEknO0sQ zGJl=UCHuZ?LEQrO%x_ju*Wn6LXpV4_o>a|c~9PAgX$nH9YqQRtk zaCW_9zdJ|_s*MHYZ#2cplrx3LMPG#4|KgP3k*@&M#WEMNftTlcAfhY*8EKCS@848= zf{7G$NYBzmaRO~fpP&}Vjy6I4+r_Lvhsoc{*9ONPy6nlorj$e|JNRh=b)GOA0ds(qoRgmvy&|z=3 zoJh&(#xiXRNeFp);BEn*ZOb|5fs6ybqom|8%`)e)*}v2OpdoS{v+E7|{`)Kx7dMyp zGdWhawvHK;Qyl*=o!;L9z*P%~Z&euUWT~6%uF%NrRvaxcJ05KP22Vz?MuXexTd3$*e)ch{txt3g3+U_Gj>nRIh?lPNR_lj`Bx zD^m(4=29mA)kmFr3zbpihXAUw2G39UQ3C;C*_o<-G$#mkM@!yj|FU7>;iVN)vi%p* zXO$R9ehLV{h~%$u3z4DUJ|h2AB9^8}cKO*RhD9*Vwz)r;M~An-wd~NZ_2DmtT%xVa zdV-#6?=eu(E~7s^W`GSE4It6H;AZx*8M_vbS9E|1u#d|gCRE!bia)#P4S(bx9UQSU zlejM|9ulzeiQ=KfiN|wWAJtRs5h0^_ZjXw4H~M&I?5+Q&chjeF2V z#?#Jwh(!&vclrQ7zy5Q!_X$6gJn$6_zSP0yU;a9 zvjlGnD4&>8C9Bn!L7hQr5j)E?wm}Aq?Y{!Da`4@=v9qh3`r*dxO=`(;)rYGB6&5ck zyZ2=*lOM1MJdc6LTfp<2E{>=KKMh_&Nl1XCfKKSODw9|WntF)iD>-Ey{pUT|nfMOX zX=4QHaEQ3pW`b!B#MbGf#EitC`5z3XV1ycr#GApTw-xZyn=UB(w$pDBvC1cwmzQT| z3RQ~Uy?aO2?7s{w8MK+xKyybtJ)W-(hWi2hQEX*k6X^#QkHAdl3~W~Exsf7s(|`n{ z#?=ld6ZfQ0P=O&b!IP~qgeW+Kwoyr|olHSZ!AviX-psi@0!5FCUeMih*a)Xw4E#A0 zjPz0;VMLG+=t_+dgVE9&cRaFz5dUfxok6iRh6tR8E2jy>;^rrONLrxF?S)y88x283 z^V`ICGvZK)WVLE6yBoTzeIF)++hXMQaaVMFgEz13B*=u06(zNW) zpOpK10fx4k!AE2wgyDNGPL`ItL+ih1BA|lm&1Wo@Dit3a9+5}iIf$0ex z^!QrI^_HWoY;0d_OBMRVgQ4@2V(>0JBj+0ieEjFzo;HKiPl2KHBHD zP!5&*Nz3;BG%KceB0~D#scJ=o+4A@354*eg^{%OMK}vu6WnYzVU6Y(hM=m7q$p5TC z_v6+XpjZ9JG)b)!%n06kx*HhlmPE+Pbj&tz(u_nBt;Rv<&m z1`K7diRQh6uVz3Y0V_o==GP_BrzTrs_fT|FUI!0-;Eg3q0o#S`Te@D8n94yo6iwOzvo?$5S7Ot(CFq{QRZvE z`WXL8q=aItz(8TiN$O^T!jpvx_2}Z#Ku1$|2QDa#vEKDCgd*tAgI=2WXhl23{B48Z zGv3Gt;>$3$nP76)2kq6L^sVMgN56teeT7n-2;Ofk)R!n_$hbtd^aL68FLk0p_^>y; zcw|GAVB#(?Gd$RK_k*am0%jDbzD6S<{yb%(iin*_b;z`=!D2H;k95&|J09rb0a9$= zpcqP}J6^i7=ib{z^oKn{JG;~k8qEzlB+*7)9UPN?l`)k9RpLQTIUUDMOYae70@a%^; zHAVGN;qcJN_zCsVKT;?~G7)|M)AhXnN@8)*lJV(zc>YF@eDYOjo!UX|G72-IlEu37 zrPf|tniif=^>1rzv~zIqFtIxxA+D!M=x*AUWFzaU?I$CMsJ>Qdr!dScdfh>!;7 zn;jrX?ojeb5yIU0w5$BflZAQYEj!yO;`t8&!F_rxG?y!vo9oM(%{(!Og*w2!>qwdK zJDP;NxAW;ed33S1K5M(HhaO>`iywy&aj>bP7YQa`2EOl)D{nsyibg_j;$tP^q0UPq zqkWxIvXYV+xE68}eQsU@Sq%=NumXE@e{z=?S?qJ@nYl2hNjipkPgI8$3k+ z0e2|8GF4T{YjFor&|4k|ZR4xAXz=#cILZHmk9v>+ggj}mHCzEK+Bk}opE#{=sH{tE zU_pj0pAd&YIPv7n`1$d!Me1$HyM*3B{?nH3;P`kkI+rPdl;7@5@r18@0}M6&ZI2Ic zj~$K%gXpku@Z!Z1#RPQe=JJ9_EHNdB7{oQG5s;JY2>h8gq!UfidA4XM$erk>!oM*X z3*6eM=~x`}bI)2F7QNW{Vz`w&DQP|y__C9K{vhlaT|tv^ zyb47KA6c-F`EX=`jq3x$nkPIwOv|1tUOJhe+t;RbQVx_ekT5vd`t#M1qh3r%y@y*n z{;?zl`ZErZCT|=DeH((Zq)(W!^-wDYAtA0blqwAh9v2{@(1e%jnY?r%mJ;@%v4V;O zCW9IyXcX>a`!SqmEGLpFefE5;`4LRtKm~`d%=v|abf@RI?>+k7BG6c#68Orak0Mil zrwYjhm0o{dJ4T?W(A0mr9u|-4&Er)#$#?FOM?)*MNd|L@t(>aP{Blg@nw0eb{E?Vw z!kiNRyd>E9Z*V&+H0azJVc`$r4PE+1kS|~6WjIB+yhTiEn%vZ_t?$+YJny1LdX*`O zjwHiBp5Ai>(ycuT9<8RHj0bN4nRS>Rbzo ziytSv)WO?y4HSZ*&_-JQ@46V5-w*Sc>2IVM9R;i-tTgiSN%jfQ?ByC8zg4!MgLa=U z*1}hN1#uMo>bsomV|~Ez{oeDSuPzGa8{;M>heB1$U6!Fq>Qzj*^LepS29Ie!+5KFh z_`ef@j=4c8&oJ_W`p|~rg|{|1!A~)hz%Y17HV<^dxLBX>hJJV3ug}ncV8CUdYoM7; z^ilh{Uz`ElK~>Ms&#y^uF~sxzSF_lf?~UWC&#}!XFb+`M2K(H{*!%olu*@+4TFu(y z=$ga1FF-!-c=SHE->fQ>m^sUf!zot-?dA(uH|bXZNc4WtWuNisGf58Lw^G)Y3pJJ@zXDw}QZSbSjd9%~5IPW5#%mZG@ z|DgcMLj{UZYF#F}i}eL~ngeI7m<%bx@doHIi4HfRtniHR&h?8L|v**pfxe~q0)2*2$2|^=@PZ^;wl^w3JF6!-r4vdSX)}Sf(93d*C!_&Bw zv`8eoE6wqqVJP-T6Q}fjN5x`PKXEuv;HOx^a^-9^=%Pz2nH!gTN7D^=4?v?%*!ki8yMFhMgUYP&RR_O7vOX zAaxj8y1pn+f*o)xS`1-o`=cMSH!AK6y=^02m&Z?(}fp z&*QoGBGVvAbnru0WxDVxo&@omsHJ;)_q(K|M(uwpKY6y6S8{Qoo)Ww zFM5SspTijD1{e{DHBtz_832BiO1*Ev;TX1yEq7OQDMHut|3$C)c+Z{KB_|sI^sSJU zYUdcfIeHAwC@Z?pa{h0Yn98E$vd-A@m83oTWWjy7u) z2J+FUy6GfZ`v9+QS^@{V19Lt=>vv}L){chtbn>M9pZ=fP-s_d07@8$2l+mJkymlg= z`$tGcE<*oP7TGviTR8)$|Ci(DZ-fMRJKOI^Q#oCS8YW>8wFy#Y1PJ8!`tO6<{h8H~8QP|o7;`>bYsk81p(!Q^8#In0zrgX_`;JN#xqpobzSZ7}%2D|2rADgEkj zj*eXMTEIo=|LDkA38*=o!`67l@XKi?U0c6#E&#QRa>Etm@eUF}amY_BOk%D+NA>Pk z$_dO5$ggfde2kc96=$M+XQkQ@4^~$G=f4>ZDhzTBGWwV~WpkUW@?MENC?q(#@KP+a z+3Q7v^DU01QK%2st%zX1Na?Q4k5VL)o zj*2`X#h7}SI~S)zhaASSxR;Ub==(mzi2n>~6Y7aTO8HDpT%6RU8M`D}UE_{| zvCtlG;HdeLiUNuxA+k>aR6EF-9IJI32ph<1-*TzZzRI_QNpcQ=^8vToA;1UdpneZO z^;Z479miMk>5G0dpu}D>sF;?MH5)&r1S6JbWE@$)5wGfe{sC;~IpndbF+@jLc8L$7 z$UR&$la?rTq2dIrUT&Z`ux+x~qap8uL!sn4C;-p>-2K zmGb8?F|n>;z@P75o~n(b@sdFh%9i^9v_|#vM?J$y>$SXKc`W#pQms#V?k5YokFx`! z+%EIE)qckc;H7!f(H?H=Wv#REcsHPu`mUkQQqH(mpscpFtfsM5vB=nEcPx0iWL)5> z!P)DEtZ-^4jOg zcXB3+4DF@9lK=w+gv zOzy#AKK^lqS?%yZ%fL-kz@QLv={r>;7j#{1w;At`Im}82Omoh3Q$yVk6-n%DvXnl= z+-^x3aWr1TDRv6q*!-{4c5{56ThU4XB)c=Yx`J`cbuTrY5T9E)K|6c z&;p;-2LmNnKXHW|k@lS&4)@au3UWdG}IvBUvAQL z*C!8$%SGl+V?ZC%4}L=0x&|XTDr62OL9NE^!z=P#3Hua)GvXlRu1Oaxsh|)|Q7wOp zaBbAJi{^92;m04d{5kh$yoetX;36$;K{31R{72PWhg_J}cEA zTF;$gI4%lU6E+Td4$k*Xjht{U74XDybm7PvpxaIC%cN1FH`>luC`HVb1w=%jo&b+U zJQ)kbjH>f>e54=*kC~ne!>*?mVtF=fGo(TSSL8MW8968owEcK$JaOD*p`groaY>Fi zejg|^MNu4NlN3j;0T&+7AtsvnZB2cly}n*{y0|zc?0yF%NNiVpPQ|W;Tlcl)b#-?~ z_+Qzsd|)&UR^jj=e0doVLtB@%=9XJDbaR5Sod8Xsb#_at`gr6?C**ohTcE`vK zez=i|`W^K}(jM!XYS<|q=h^N~ujS%z5fXgEoBi;O)z9>op28}Pn1W;^sd5|zc~-+? z%3>L=Of&C$&Dojx=ER`K&HSJgA0AEhkgbNnWGcEdys`fGeKeEE76TnWvVPtOEd9Ku z@UR@cHy>V0<1$|aXWeA$03}ef(?Q5-T0%p?nbwk0@XOZYo$~|w-r|(5MrsFDb8Xu2 zZu0D0Bk%jht=;5ozkA~PxNHTK9u5UCY{Z7R$S(dkJ~a%Zz2VHNqy22hDCy#HzhCld ztCR2p`OuT4X7)A*2k<^!bsQiM%6*4vno>}Te-juR@a2aNOn@wFoIq_*EDG#65aa5p z8uQzrsJ~^WP<=1YknBPi!PxTm`H0I=mqs|Jc-BJ>yuoaFd75FI17Uz2-Q z!JRtTQdFa(@Ja5DW8(3|_*rQY%ne`nv8Al@%>uQfx*;+7JaCcyF06;rMKBT24h){9 z1V-#)Ov$*U6zGaj2_{HVYk0R}I8>(`m$RJ0GQnceq>l+$1yro@&}O>p9KvWK;>g7B zGzS?P7g*;kFHTcNB+4G6z7;TK1C#y6y%f(@g3d@3eFJelT@$lr?;Ck6Hp1#ySq`* zT@P$4&%^q4Nu-eL9RKdHl1?)!kDw3h1LQg7!~B4md4-eEM&Ot~N(hk)S~V)=Uk0f< z>~W!|L9lAEe&fkac-YM?G4} z(AzZK8F(=(EBHx#sTO18igArpK zB;3(;w{{zolC~(hcT4#PC{~K})a+Ke>zw?iboJ(z7c1bb9fQI#Nn4G&f1AoE8A()` znWJ)ARIFk^GxxoY&%zk3m1vN-d2FI5;L|t*M*nOOZg!nB*xi9 z4E+UEZQ9L@{8@MXWXP+GGb2FZel)*f=n9@OW2v0Lv*r!VWXtRZG;&NQe<=^bhwhNmZlRzen}6!K6dn^V`Q%{Pm@RQy`=9g=IR$@pjVtdCJ@)(h_bE3tZD%Z&zaJik!b zeSB9^Dk=x&=DdDtYN(1(ziu8Xl0i_M-vnGgEthX)hfX}w<$iP?gsi0$U$_T$n%b1w zXst0dw_6-BL`Xb-%R!t$(2znJN2w&mcfP`2L*(S zS)eiuiUf%Tq=fa~-V4hhla^A(J4Z|em{rY0J*7Og&x7zAXuU-usSz2$;&odA) z4#1UKo1APu${O?8l|BR~#F<%~&(_*=;fEF?NESAk?d$oto(62thR0crRx?|bQtRjhr-WNSS=Ko14PTcHy%->utr=sfkCR~9c$L{;HB7Vwo=(M8D?qlnhi*ugCxi9m& z`m6i2luz@XgoYFC3gKYUE(mJ3P)X=zrN5p3r=0!XxF_{I)>A%SIqOdB`T5DUlC_9+ zG?Zu76;vLG-tU=uUF{82qoV$&Qiq8-QfL*_pX^EKzBcH|t)S*$ftE{giRb zfawVidmI7mYQ5%@@=s6Snc`#uCgcr@zY=k7mKMaSa}JKOadxYU#L_i`5EXdL&@_eo zr3*rg`DseEEjuh1^#wnOZ!G^!;X4(aO4ZnT&gRQ);ExBYFI5d(LPLJ*pQ+CK*=h>! zqgo@YeNfV=7dcU>_nunPzzIP9QBGiTikzY0jbQR6g^DH>o>s|KMsS|CP3MTSUH{?pS44{ePs4Ae53eb(Ao?D9woau^V_Wa?@`lEzc z`eDqB2;z)OnbtSeMCGv<02)C?I4W7-`t4C11@xEz6-PJ!slei35Of|kl66^GFwq_y zg_6-K{Ao)XzS%ug_9Rts7*u>WTp|s4&{Fbz*8G^g6`vVM5a!a5Ko_eCA=TBGHa$fv zQbZIto#WC{4~mnPMHH7A=s_kn{N5qVv4RVOm0U3S;or%M z;3tob(5#k-l3Vg`If0O6wtKj_&?ln}5t=&L6mn6VHnE~Gm>1e|zVC5Z!ISY>1 z*H}%?GWVLcu_^by+T%3txdqIIrQq4}W)|Jcd(`pHOQ0v)FV(hc?4BnSAdHGwScpS6 zSKC`Ft^FPQQZcn?LKvlYfwJo3J8e^42}btg^xpS$vqt(afZp0EhlB3BLYPl%Uq-j0{smol@ywY9Yp@hHvX=#(_HkuxxO`bGGO z%lNUdZVChKgC-tj?TdeBxc|w7VbCLdP;gS#yvq@pTIy>91&Gys5N47h^M>tIlP+bmU2_q{KU)|Q}F`fU8kh;!<9=&$R0^tckF%pX;bZgEmGC=s)WSyN2~S|g^q4!=H^f_oOI zAe^_A`>nz-li`RI+`@@#UYhiApypcxUMT{_WluuWx6)NEcJ)ojmcgS^49qw(cmHp6 z4v3Nbpfz%q>YH~{)HT#*;$-BK0*hZYG9aPp#fM9Rag+T`Zz_MAC;`u4~@5a|HXqwqnUn!I+e z8`X%?HzOny)p7DgrURO5o$Y3$3hb;tJNtyIehzy6HC9!)nTC zD|Qlo6v2doKU74ou1Txg>)pr4*bIIu6TL60$>kBP{;s`SH`$9gr+sYmdwiIkX=s&w zh@JVd*HYYs5*3XC;TdXNyG+u_FHyg=)?)4X`!|C2#>=djtI<1dOUjF1olif1Pcw*~ zKKy(>6!o?F+dryb+E!uJ)0c2TNH*P?Us1|b-CC5FTT@iVIo{4t-Plk|y>O6@`H5X@ zdspWdv|RO!E@!=s;3M>+LVTx~Lsf{hAStH;+#NuyoanNnyo%en3{>xJ0Tu}uY5iZG z@=I{&Vofr!2-Cs!Mk@%cqraryPXfF6td_<0P_j&%=(9)d4sOnEAFu@2ZpKqfzApLZ z{s5+PBp*nx2yKMmj?`TOpSIQ;aK_`;klCxTq&SQ<&X1+@C~W3%(Lb@7N00;@0ir1D zf__a1FSR{j_z>zl1QwxhID@*DHDFH%!G78|AL2PDsprOp)mf*INgipT;P(ci1m1jq z9nF`W$6a4!tmWIR>Aeo7)u8b6tYQq$gBgW}2F0K#n)PGA?=(w{m*+uoT|Y7XIX#EOsybQqRV=bLtMfP?HW|b4eGjFQc{W#z#c7fealmOM zkpLwtiNecLbQGI4H2IxXz>S5H*Vf8d%~{g4y^KIB=xD*$VP$btkN00`S?st}iQetn z)5@9wh{Y;v)X2+I)Ry>@C|VyraXxzQJX?1WtA095X|#s$+Ap+#C`P{9zdr?SlHmq| z?j5(A(HQXl2+C2Ya%zqnht;g|q8ClhdO534sa17#-k#wu?^3G@3$0XNpiKv2`j?B_ zuCBj>J9zsyWA?A6j#`WLbwh58*ndma+RhqErW*GGSpDO0zu8%2tL=`2YhKPEhM$_u z+LaF1I{&3&o0el9vmZ_fHE5f6t|lwF&hC%qx8)b7Y*9>z!95?5 z?^un)qL00zvezcfD3Z*%gSXw7e!1%$H=rW00X38863}teo`JvUBidq<9cdUCa6arY zc{Qlp19w0uX&N)!QiJt0*u#j^{C>{?^J9M_#;og8BrRb+SiL_GgPY(NzBZE!R)GKA zH-GGvLi9*7=-0~w*c0tHA;tkzFAsD-!541a@aytIwo)Ip| zbc&h*Ee~QEsoRa9BM#WW8jcY9AP4cpU`gB31SinN#AS zjkD9v{TWfJRbXBKQC$_U6uesFgaqml3o%_@skEy408wiB5ipc{f^$=zYjuDKlvW~ z-p#yBdAv97eW2vF^!ipsPI6FQ;NmRRBKG|b^|xw+$?Q-Gg}?LP`;~*X?qCFTVm{lo z)#GGgdB9j-tF0)lJuyP%T;P2xKDE}l1XTt4@g73>YNyySJY8{a?wKr*umI5NJ$$L=as* zKK-Cynf#}62JcggsmhVzg7BYa(gVB0#qw*ME!o%cU4p7P4kiT`2NA6ckk)pFKRt8( z>wLaHOvVeNdIc)Hwj}g?F_Xg0lG&Gfhj;U96M!q8LG?`gg(oVA(TAxmJU!n1nF>UvMuuW;fn;M`NxpfvBmdhNEA9=>eGkXC*hUjPP6e4d z2<{EPU~q?d+)~nhON|oxiZlO z-y*L+tgSNRrb4&X@8;yG4d*=vP_e=(ydv(8{!Sj4jaie#b*VCVOd<7I8Oe?%hBU)d zxMIPDlfmUQh5J*&z4Y1?aUHJbJ%I?{ZBHos)xWiung3KMIgG>@uS_I^FE&;A@_=!S zh|g-GLo@G#-F(XlSZX+WZ@_w1!s|4#+1XkZ@1J7BdS9I^%*;QI36_I&!ZG0|kE`u( zhHLHKmf^9X(-vQ|-+9{li91Vbc*&I&B{%bl->G}b$?0gA4j)#t>0KUVWbpnwQO)jv z&n>0uY%Hp>9RKn+{JQ>q<>(c>?Wq18JgcYlelM+J;uD;TM4hq1xqsManaroBZy$Hz zW-Ud{{)-y>o~}*E>SuY}536<6D--kd(D`x>5GE^q&r9ylcc2AE-h#!7oZD}H*%NYe ztey64O;a`15W2F`y0qMGaGd?im!ZGZlx_FD1u}}YLmLLS1%&KN)QHEO*caar>;_n1 z5yd9-GoP?dPB(g01drcM>U%gvCyNlW=`(G~Sztu!C?k1UGWRS1)&wET#~Sdyw8X?s zQqPJwiuf*sfKEb3e6u$x8PN*3wnb5cYzM&)|2o&AfJ;Clc9859%?}nxTbSig zz0m&e>11&?T-VJD0Ju~4-Rcq4n*gwgI&orT0i!kW!#? zQn)bGe0REVSDu>WR)(Kp`jG4Vj~M`)H(j^5kikc(9;bMPin3*Tx$%1!z{ zHk$oyD1EB(yQZCR|F-+-Iv8Sy{2%qXt*83HBK`CE*6(^tN^ZNw1`%H`xy*;_GWqFn ziSu)F1~y38EBtTaT2Nbvc^ZjS4avmb?;)H`>7RM`5o*_W?X+U%p z&yu%+myFEhuMh&+!pm9^N7ll;Qy1{HI!_nJv?Qk_)uKsmD0qk*wQ=M1vU)z)B|U&n zj5x*5KfL%92A(yRf2xcdwtL|b5^9luUu^SSN}oLhV9i?33xZ#UaoGl87~~W6+BYe{ zpBZ*vXf56mnWWSxB`)XcdVG*f%4@%>tG8t3Pqx(GznHigbdn6@eHLwH3(@cl@)x0g z`Og2!rI1ILMp73TL*dO9GQ!-5i$%QcV+kHGXDbXkjfelNG+CZ+m04!_Vt@!D1)yj7 zKHPw1fJ@aLhsR)-aWCRGcP49VJ9+O(ns-GxD@w^96l`>?A=-`Sb(iJ};iD&=lh)y) zLEt`NM|X-nQMHEOhERA)aiszkvvz>OMpNu;uZlfMft1ER#8y(dK<$R#7h(m_FbQ!R zS@T3VM>0SZvYw(FIKP_v)CuxX^wP$%xd~fz*`Vo>(s_jQ^%mLx3_rci-}j+AMYG!< z1V9HBM*uedBMNnf8ST%3{GblKh+*HUHxFv0hePRV$_ZpjXzi%$+igah*#5cIF-GJ? zy^|11R>b&tqK1c2dq3I@rA)pv(0+tv46rEIuZxTW@3&`2zC&w zG1L8dAjCWbLZX8d#!*2I16k8=nnmV!r7IjfbmA8|DhTBiwk#@D5OWz6<4E%WEKQvH zd^$0MbKuZ_E0yGOz>C!xP3jsMJGu#rBjg`HtTZ4WLzDHl829}{soEZ>yOhz9n-nAR zFqvjb3c^H=ITuhIR4mIpZ6$y%Y-K5EgyZ4Y0s|CP?`!G8&$XvmkAO@wj5}DM)v(^G zO68=>BtXN~blqsm_N8E3@qaCWT;iXXk~X zL=Z+a{Ge?r^I2LbrGTTVQ6)&E^8{3C)9MRz-$BTf|HE;!q5l)lZ1QvV%6@WZ)L7OX zhu-`EM+EZOz>h{(9^-fCcm#OZ@l!=b=C-p15c+R&YvWC>OHtcz*SrqFSm(C8{T`io z(SPqWut)CRR$W7QAzJ;{p&8FxuZ#02x0CsLv)|tV(o61|WvyMW`Frrgn>PZN`?Cd- zYS-kSD@V(eH7<%?@VLycc}FOZ)`=ll>_PlCO;a+OTG}@J{l#`adB3dI+1M+Y-+Xc2 z&2czjE;(LnjuREVxSSqBTlTs+;WtUL`S>YJI|!JAc*C`|E+ym{+3;|B_52B7U3+=ucZZxh|va2 z`^w;IxqRinO8FCO5=j_QBcsI(aF6jx))3^aOCpR^GHLN0Z+@fp5Ykds7hzy3iUD|C z?T$V~@rW$u^z}~BCF7W;@UQ+2T~f=Z{JWXX9}(Wi)y;q|5{taoXceeQO@jFcFj&@# zM&`I&gP(QhJ~azFewa-*(dkz*>7^TjPs>OriW<|5zYF2-#xQ633>ggTmy#vQlD(k* zu4W>J0R1)8!9u_%iGde>@8jeNQ=S;!JLm{WUs8FBCF-|tvCL1v)FnHcFxdzmQGTE; zYqP}BZtpLU4ZtsNxn}-_MP=CdIavpoMtcHzYG5A2*&1j|c!46sQ3u5Fp8P&4isN-? zV-pqEh!XoM9U!Is7a1pb!ncY~r1#hbiy1;H1&_AQX=#~RsZ4jk)FeTUkB<~1t6ZQ8 zDMI3FdkWeb|ICH^*E}x(d}1hs$(Ih65u? zGn>yg{M_~<%)k(yVY*-YQP=bL<0Usrp?E*61oH_@N|8tKx+^q`VioNv<9zz_{eZE3 zaDx*Aa$Sv{=uhVMw_+*mlIT1>rt6+FW%4l`s<-D7w-KGa{gOt()LP^Ep8_F{J8bfg zmB7i`zoF97PEAAARc!4tR$hy3Fs|xe-NlmOu}}9mm8G)&egH$$QK{Edt>4;zU8XHR zi~@-znX0Dz0^is;79@QUtx%U!XlKXFx<4_K+UfYWX?yt3$=W9ai`MLRL3b8W44CUV55-cs@lZlRUMT8R9QqqB<2s@X<_j{*ZIK>LpTamnv9jXKodZZQSE0BBsOsWNF^5NHDqbfjhtyWg0BGmg)%mj~* ztNo&&!2pO$0O2NvbKD%2+jkF(OGYE0_%qYkw-OD-wlgUhD#DUeM)pH2wN*XjhC7i& zT|)nPrlhDS^D4d^tc0CeWa}_WsL2!VK^Q@D^`q#e8~eaxO08x}*8pZ4EqssD%JQjW zlc$Z<5^G<5BM(WINzQFa&5#1R+6Vdvo~V-vCel@>l`mXoLtud?!bM!HCFLXybI@f> zl6dfknj-c$*xKqGwATj1g-~ED@X4xi+Hi&?2|1VUJ(5A)F+$)y4@+FEV?y zuPh->7*2)X=D1mgv@3ay5*Ei1Ud{dmMANLMiW5aqiq)guhk|2Le0q2m(jainCDx9A z?}JV8Zc*Pgo4cYB1u!ZB-u!r^Jurr;I0Z$#BaYN88>u;lim~)~?~92vN6!|W#VdfU zAeqecd5QQrQmsmxNzwtI&*RI?K%qAnw5XPiZ(~rD^~Z*NWO`D=VNGdxa2F&q78&sy ziA7k_!BGKJ92Kn^2gBqu;&_X_Zfs&yT?~o%9zav65JOQ7*oXbi@7+TxYKSQ zv8JIM2D?Ae3JEs+JNB5Pjg6*~%f5cVgobWtoUZTbN^m=&nD$}^0?CZ+Ou&lKg7N>^m45vsb+jNYIFKg*Zbsf^?;nJCVJjt-0LUy z4+xARFH2vx{1%*!exg%~+B{59lM7|=@hxvKwP~>8bTkxnoT?jLZoeE+i0x>wGBGLq zvc7L8*?Z<+FHi~dl>h&iLc;qK0nY-zTL(N!4UlK1G~~z+OOSQUuL1UezC?Bjm)jyn zcL&+MHe1yH5wLmo9r3WgGoLS%P6JwOt&{lgyvtAHBWA-9$l}*U?RX3ICjDR!xP~ZI z1+;?9cy!J(5$ZBT&2aYY$rD_z2NOWY5>ByFHK1bY#C&%F_P zJBUjOH>FDo?X1z(gqqcW4>Lh`ZH9~;<~>MvB`2BiDsOJOHDImzJgDOu@$SFfAaj|$ zR#3P6`7o|x=zWbIHojiZ)-WvSquDExvCCRbV@_Bw<7c{Dsjb!_`tSO4z1Y8@H=AA# zCrh2V3wzTJ>V}(H#*XW~iSL`S%%`8Dn2+ay|4dszM68s6#S7v;ROL@ssTi!A*8wm3%q z_L2~AvEu{2Py0YypYiPG1kuBmMQs*Lv4^>#Op~h0y1l8XsrlkaOp=BCe|&t*W$?sL z757crgN32Iu!v}auMdCOzn=WywC!{-VlDHE;*qCm88(B6Q43T(x&5&u7sm^oZXV$B zHSx%OYTo|eo+P7+3l_3+R#azE!>3(U+R>?;n?_PDUCm3-cm8PznbGv{H1PLV{^~bn z%Goq029h|g;WGcN=vxCbA$f4Lx!1F8gm`NBM4J4_ht3sV`MzZEKb z!X`V;WO0XC$AGGo6y0i+Y$1;->O>T5FZW62_t5J9I({THqg-b_g1qQ^pNW+-C|hKW zHQt;@bADf3D{=!YDMW-XdBJv=YEzo2rZ#c1=aMW4$!F}`-dCn0if?hxsce5Z^2)B{ z;Ge>NPk5%4yH-C2ahFcf#7+>}*zeVz7B1HmmXS2n6R5sEU8DmEdSx*;5fC`Mj` z$2YDOO8K}nk=iLJa*gog>djsSb~*_tU`pZyuGLmxTFdnEh=whd21r)#{s8|syoO(V z?oU>C^hQKn)fJ`wve&ZvxSj_4FK@P8i2S#kq#5kK(nNE|@1VCcmnHh9#qB2synoLg z{7St^JxjHejtTuiNV~IQW|_wkOi(lYfZRS#SCInMbu{*xA1> z1p0ohY!P|doi^2Nt+XMEFZ^IMQT(co9F})3@5{>4->Nk}o7+}YMB7avqSxxQHCC#W z+5da?6g)r~8Te?V+s*?)+cGlnUsV)iEengxtNHEH$2?luKl5J%SdVtSd#a9&jbZKf zXwLRgx$E`y{I%X%)WOtCGEzd#MQigzV@$0+JWQ}@1CHV<&T0M6%YPI<8!H8k2F@-| zYr8SXs?No1c6)GDMK0Dlf34JYUT*L7H=7I6+X#Bg|4S~8xI12t-zmieyM<)A+92N> z>`OK>Uc0lBXf2)W`ytoJRTV#S!&ErC$YCr3+sOX6NUL62ggqs!cW}yNP+r2>qC@Sv z&-j+;lmBTdg;^kKn&R)w$va$hWEy#9@7^?nqytFmx|@#*OQRitG=R6#-lt&$lKsW z?vi0Ci*LF`C{X{6;%B&;KgCtf?@RGj#Th~sf3T@RWRoBvdPObI9QP8w*_aSN_j~({f3N$;hdkK2O~j=AYif`fhh4YD8?&% zNO=O)#rq|xsw8|4M846fRu#mY@p?-vXZcEX6ttZP6fP)}k%O-D!I)9eSC41W&EpO1 zq&LCy#d6J|rC&9NC&i<<{}9du8+*+Kz36V525 zjW3jZH8+45&s+kZWS|wK+JMqVofYkwI_=_(L1wy`E(ccR#=H9obu7KQHoj&04lv3D z?4c3US?~z_Yn)DLkt-VlC2;@2%k?-QN|~nUkyGAfFiQ~NCrV9WD6S22_R{_51Kb;g zUwluQU;hGFdDY!z_oe9a6}U;)`GRwEyG~uS-V1I+9C&v{et6xFILeeF<1{D>AMg}qU zfLxZ9iw`&jUsQt8C24{QfgJqYKvm+<_n3qo!11_-^u@ibjf;L{(kuwiwe*)1x`OGF z{xYp58?0VRnJL&rys#hi#wbJ(IsSCKM&N+ytBM^NpA3fUOt8m0m}YffIw&I|M4U#~ zc&icrSP1c1`vIKK0GVsGx)+k=1^uWup`aWUQ0vwMXLf;YCY*=`V*xd5RzOYkFI{in zO?o{<5yVXi0Hn+vz%J2@^%Fz*I%CUmeKri~I^IP73L&yt%K~Q7= zNuCI|w?tCX(oVWE;cB|6--|bso>4igz_atXD3%Q+YuaFli3cvNv{;dQOTYP>0@g4S zFLw!yc~MHf4?1#jvY@(MtrHR@OqdTcCZ#O{#Ys_@W=I&Zm5HBaxd6_$LFy4M@?iap zD|w>na3!1c33GnMTUkdqMrkR&>60*_sM@Gdx#o!)$_wmj#K1J98Yd(KL@5J#sL<%n z3997qunfNUvG_fzEsaU~R0Kte`ud0w)I^&Y#5^{$x$B{bn3mKvZ4O&4w!b%epFF87 zpF^H4e?RvOg*=;c1Z9&7jwjEb{#q^Kcz(zxY+zpJM1NukbGMx2|M*PSl^x)7KX?G*%W= zmUb4bA*{z9@OgNsjE3XK-^m~@W`3`Fj}oInh{ykvxBY-W!-GY2ipHUmb;_Q7f_288 zS>B+XuRM^wR>o&k0}&;-}2NO2w+Wv+|V(4O$9G7vuO;9l4dE>Bx z(%%_)euZcgNPF}SEqkZGy9uM;>j>nk&Lc_!`X5iLx8~vHum^ttd8N;JM>Lr82mrIy zXW)x!xqc!kz~WHwydZHm#kyJHWv4MbOLUbwt~E&9x{J9X8#Y-^0;=vi78CIjtXmhV zQOpo>k0p&8R0D({a(5*ndmIjr1JsV12+ zjRi5-L<1DbF(&h9y70y`IgTZ0YGfXBvFj0BT`>R+e2O`;u8p`-TK>?T3*bA4)wehsH(J2ilx)Xib1j*J3>JaBj`)4K z6m^8?5%$I1ym(WJ#_34B?w2yt@15~Q{9)T{zfP&jFpeTXya9pkvz)iwfV3&f-)lzk z8FYomKbPN>S{+uFmab&)S7jorFhII6oSKw$@qHYt1ZdU-Jc3^9)!?$Sm7x%Gj>)30 z>*IuMKk*FK4L%GRn9-2vr=caK_)`s^B~elQvRh=uLeVF!{d#&ar0sTKZRN!v5^@`e zOBQ*XM}ypyEEbmR?KmO!llhgn#Y3}Ar-OcUt;$Wt7d?o%%j;6Xo~Z6(*XwjiVdOu6 z^qcm*J)V6b8t*ifeJcQt6?YfQgz@1ZPt#!gJ41(cmD8}x_1|l+Vo1PCHzp-_OUsDa zPj*|*si|{Y@^%&uj!AoV<9^R+Vb+z)wMN6S%lY0W3t#Jo&K?10@%#&VaJ^47cQmKC zWLHeFwriG>Fw?k~z(Oj9hOeqw$yjkR67pi=WSvr*Enujvt>5f(TRn0#{PUjI^Ovrm z*F}%uIN9{lpRGSn;O8ywPaESYG9ekq+!#Nk^WV9^$aB>&xOuD0=F%QN|IY0RWhOZ zFzFiSO>HML!{_% z4HM)Ve*oUn7pwL8CyK$3zp=Sc>A=W8c5EzotpMwD)7dwvi5bK!4VP5E^29PAH^b1*y&d6V zjet=`j4N=KH#m%e9CZx77E_ZJ78Pl9nGq5$YCs3aIS|O0YLI_4bA!v0GGO&_yw9wl z__{ASMSH50dM#Pdl|-yRoPc9-K&(d&OQBm0Qc-JKI=Emm73*#cF028oVngHP?0{qN1BKm|4 z22rTNN5}I0D^ar7l8-RM@U>$!K^k4o`DBAnP!=@$B z#&T9wbsM>3zgi>spQ%YtP`TY6a<+UT@s$dD-Wf z$D$aCK`LNsDrSk(*{RTsb5#A4d33atcloRRs)K&N)2~6;li}%51Pmr-7N#lZ3r&rM z_V=X$QvOE9!RC!zCV$iIYBFxiJExLiyzpYIIFG`4Q$E&lz_TRLcvz+i)i?GvnmKzc zKLQiA!@8!{Dv$S7(xRG}#Z3t_h_rP9g2qBR?MqI9)LYYq5@gWTV`EdZS4&?SL&t0X z82f!81p_4;*hkPvg@$16-?d-}H0@x>Ng7&$RR#@7&T9>B3bcg_PV#&xLHAD9{zRyP zWqH87Z!N**-y+Fcg)%n*r|S`fL9!S>W$ogRCmQlu7fF_u*gNh&<__VOx&|KeD>|IH zMCJqRFL2lsY!79tli_}eH~iV}%wy9xQx350sZ&kh1?*3T3szxr_Hkdlphe`TDf=90 z#{^TlKC!t-l7ys9ANrk6j|1qLJGM!#KQ^NWRz+@^T7Dgmdh2m&FgkalY6UZMR3|Ww zjMuhrvqbY0JVyJJ9)R!al zZvyaf%qG4gNeb^|slyrTqg=z1@Y*X9nNF^87y_Qg+87PlY_w(93)1 zII5`RE$ZuK`AY@|By`>9j8#J>Pj;Q#uCa4~?Gp)UIIv`FE4q-vbbT`Jg7tIugYpiZs-;B8CT^ zKSRX3z(A$VZ`Jto+MJ%f1#7q0bjz54f3qBec#ppB_l4a08v*x*y23A9@K&WK)q6Jv zBrzxkU7nRp9J&jY^$Y%?RdjR~0mi7(_r`HIZ+qF(Gk4Nn6dX6y>V8fT;1}&L&x*g} zudQ|#(bn;*C<}K+KVA*I8juKw_qnXmOYR+B9*7Vrd0+qKI~r=0l`Km|trES4i-v-~ zkwqrQmXMcfpa$A;O5A6OjV;fIeDSAhs!OxoV>ux&&wHE!C3)BM+mir>4IvT9=!uIj z>;uS65=T@rHA{pFhhq9BSy;T%cJdB)c|vblV1J^pdVk;7(7s_Rqk`?A4oVAZrb@Yq zZ@t2f7y#Dy;}s?@2@;v&P*UBx#EU=FRfiyJ=K+4m3L-}_S_|cHaamWoaE~8P^k^Om zZnMnS%%bM?Xvz+*7<2y%!3iEniotv?wM*nV22K%{I8mStL!jTuHsy*~;>79>R(kC; zuCi^Zq~Nm^F*XVggG8V9;i)~wz_;T804)HAdV@uFYnoVM10YY)exzner<{LS|M8|a zs{ij-XO;rW`WA`b(r<^Rrf#{$Psj7*rT4W$N-S^Xi|(CyTqe!`GHFsa+4$AEBTSt)s^dr zXG$qKJoj1>1Ff0@cnu&#n^}?H%FSRTCd5A|QAkzRz@Gi`?g>~?7}`SOP;Tk7@CD0h z2i!^do#HaP*(`Si&C*7d?FuX2-wtyx@t1_uR0_5@ZFN0ScDy&!+AgHy6tj}{`p(t zmPcK+m5Q??PtlJvdh}r**zB$0BZt$CALKdRN+Nz+@1!OB?{pRlaIY8IhK7CRV?`$$ zgNpt>+m{xQEY|y~VUV#T_r_(2PSd6E>7qN4c@CH8Y^y!e*-fcw9trW5>FHj@aF7Ai z0Bm-7jK|D_UK67T@65r5nMPs{73MPCn8 z6lQB6mv=b1P-Nu9clUbP3YK!a38m8N=uC;GG>4YK!m(wMe+S^C#SCDi3%(6$bp4ajxJ8a0Ei)wOjVdodN;S;^0fTJfDCUiA3X#{A zMQw=L5XuTCO=6_p8)WR(hoE;sbDka7@-s(U2RH!BX09WGKyrP!-o5< zaNcA?i?^*SLu8E@&<``9E_on%h*5A2#BnEwq69I28-s-mJlS0#;-dpFA40;W%A@aCvr0nfShe!gr?Uv%JM%AL=WTlN(~!W<2Qk-z=} zAe|6Lg(h}YqkuTDX(>$ie1he+y|W!uSc@lkRK)V}-5biZS??^eFb;T>wpOy&k}zH` z3~gQbx&1Ek;LmN2bahTQ6tM+PR?~p)1L9uO?9h^i;QS%rFeIj+rln_Qre)YIuIg)R zr+FRkHfqVWN_2hVG-N1t7WU@S$yZT{2QIGay1J_BY8Nb>yIP-wAb<0!mYC1iq2b z>I%h1xAV@CiZF10wYo0Hght+b)G_H80^K6&f=HJ<~s=tJ*-(hjg2$Vi; zwzB%G6m4{CjjQ^sM+*9SUg{=2q>A8ERps5L$UmCgtD3XGpnU$_d?}+$fs{PH|5pYc zzz>dBI#CmAoE<8voolKpH?#UO{l^EZ40yM}axCn)u>|boqiS%Lq9*F=z2>Ja3PxS- zPENKJ_4S9Vw|0t0EHn14Pj}<9+5Dd#Du$t1(y1J_Fak+{o&FD>z(>bkT5)x^ulNOW z@g#?evhp`dYA~}iqZ7dh=CDPT7|@MqA#|d!&d%`K*<$M+(UvPU zR5y=EG5gF)kA8;;ttC`Y5t7O!IvQEL4djBZB@4lQNZZ~&&~R5=f4q$>I)lvVLt2G@NALMArN&U ziwGtW+-UblW7*B_8Uz_eOlfFNii4MUsLUFQLhQu1BH|*|Rnp_6*tl)xsF1(B$x1-h zXr&tr1QxXCY;yAn*D@^?{l6z_fjMg1;7JyHIZ-nKO?aDCv!-yyBUEU0OBjFJD)4{M zV#JV+Vu`iDyOuXCNGEEt@r<=kTaHah$2Ji)0bdgbid7aY;vcbxU0Bdwa6k?shYPK| z^^Vh zeyt}zt0*|(8_bu+iYg~wY$+5q9Lb184uAvDo%3kSA+XpRG=FS;1z%r2$BhoF>7!bZ zblK>28=pM~ry=lwd>fQPw6m-Jb!zvb)ygCh6Vr@CrK4C$qxh7O`HF@7Z)4-Oj|hfk zE$7R-MTsMX2qfh$@9;4}Edsw1ax>=enaT6zYA=2L>tNU?uvK>lY#kl4W`JvYTV-dP zq1EU>@CyRkalPqKc}G@zL(1}^3C{X`#AA;RE4X2`mzFWSKxwT`-M(7L{EVU4>e6vP zUCI^h&)HcpSX;`;XWPz+i95RWdI!&bqUOB7xqL`SKs%x3i$~Dh(N$}|>U4rjhkmzw zLVBNrNl~TWZ1(%eQP|KRRyKje6Nn7RT42qHz_A26id``Vxzf|!CAZa-Zv2QId<`#=u%?3^en~Q8cgY~n4Q0>$ z1t~&Q&Dn;6-7D$0gn{7}#Hu6@;N|HFpc@KdNFUzjasMH;^#Br>dCVph7oBy-lh8+} zY|SM|G$ne4*5?C?(HuPj>LlWdj2eX{QUdtG5o16rN~zY*3p8F-PUQ_u6ccrwb!mrd zro@xBnaas$D~P`(r*QGy*la;~B!ZDTz^tV5FpoJgxXYNK_A*Fj{vLP8xM!3D=^#7b zFU~oQhS&uh%snh;Mr{_-^@$8H+@|Ub+f{W6O>si31cti1-%zQjSkhM|BT6+xzR}r+ ze62LPDUI5HRPWhy+t9|69Hz`0UAPqCmZ5A9>8Jz1ujyklF6$vo+$opnkS%hP#sT2U zirg(}U8kATE4?kT(t{zwH+JmW7{W2QFUiqCDuA)DM6Hwr`WvRR5M5hXBgZe>=yEr3 zK(4It#{025{0p$ELeUJn6WKOX`Angu*do@jd=t-iS;&w-W-7p()#%&7Y>uDh>O)g&ZQ$W77`>Pgz*wc$nrRxxr(Ca(vvvRfY~2h> zw%j}afh1flTAHYFmmR($Un2pn^JL#$7=hEXC-j$RE?_=5Wan+wQA}EBD$2-+(6+`q zT3y8>Q~z>SZztcMz{)&Uje5e4a2gh9$8EhkHg-!B7U;la`0yQ~ac)|NL_P)p%}bj>*%fRsZgKox3zy3mBfC#Oas zKdVf57?4QO8xwQ$=WMIh`p=hEd!Q4xnJ<>z)z-$RZ*|{a?vy+4Y#&%*JrWQc9-@-6 zv!fX%ne+sj+%?fxgC>rz0`&AU>F-#CyiUItH~Cp*#>_0{7=Yju$}a;$lF#`5ucbI8 zr8-6_JGq(gG0(S|-%if!hYnIp>8*^qbdK7WR+pAmmX|7Nfp)r5v(x4FCpe`kp*i78 z09Z2io!>baBVI>ubPR8%#AZ6jJFv(le(=)T6oaSG{*x%Ijle_sR3l2Nt z$=Qa^i|4~4u=Mn_54yO%7E>~d4Gn^%;`wb%+r9r%yZl=!;nTne zDx|1F?>G&jJ;M*f#ImeBU54W_J0BEenhLjo;m8AI%07Tg;|)P$t@o;tSMmo_9kYpX zWfr(*ia|XpI_yfL7xs}jOA21Qv?jId5vM;N2O@OaTgVdAPb10q!;`G0Ge(U~qdL1J zG`&KteZ=8$X`{qI)nr+<>sjR|1@Fmk23hic|L&dtwOLN$+@f)?+Q*yAXdNb7I(v|q zS%DjpV0oTr4qj1OvI_UO`p_;i&s#*UaCs*Dw6@P^M>LBDFu32d(l{>tcAmf&U>sxV z{U`agFzHL~IOj|cbFEtstl`~nPQZMoZNo!CyM}6b^~>a+f$?n=CP{>5IG5^~_SI6R zx=y?zO1Et%5pTGrh#b8OXnbetxGr?)IT~~?tLCfgxl!~4Fm}=(YF|Xw`Q~%ns!D3* zpIeIXZxYr-=TiRpJ|8{mAJ9VOpUsl?HH>u=QUne0qg1wt5*WGqm>(iqY$F9uHI zZ##oeQ}TqFRhl4olqE5GY&@&4r+yeb4IS5CI?(3z_oSs!;ZepN8#D zJ8h1?%Ty>Z$wjh^+cYgFa$8&P(4B4~wVU%;g$VKStvTN>fmbr|W=hH};aMEPeY-sw zk%wKgnD&a0f6L;T?&?^w+nlDy013P`E2lbcfM0< zFH`{N-|M@nl5|!+Hsj~}!m1be zaCHBty9VLEJ~HTcifV*(7e%`E>>R57Z)UIz+s^{5|7O5G{kpj^^u4V)UN3G}PP86Z zHOetSJ^g$`@;l}RRVn9Y;mLSNQ3=F+v?P>_U5o=1EZkU)dE?pRec;jA{~}h|$0|)d z-H|R7_9$tgD=o1o2^<5}an*Ud?@3(ck0`8ame|h{T(#{s$8jJ)K5f{?rXAZw_xby& z0EQd5Z7u6~jLMW+9hSzcpp(@z`>!hbYnc7*Xw+g*&T@DnAzf^5>$WUancbZzSi-mr zx#zEbbrpYJ5W>`qI-~JKYTf&D6A8z8Q4kzGLiGt%+%-}DROB<0i=rw7Tk~Nb9*@w5 zd-_A8vAMbTVO*^4-?x9y--?=#Ep7oB@(@5g{c9y9gvLLJ6W-Ch4~L>SB*p%o zhb&sci#H@6#uKbcM>K>LZOYw6{j?37tbD2hC7n#6M8UWit`7x`Vaqb&a9j~BTn5-$ zbu^zQ8hr2U3Rk2LlTU-a-6Jzy0e95IAMy;$CkB+f>=X7MyDIYuQW%ntB_qvM|Nifd z(sLed zt^ERk9TTudu9^hC07*uPs3u5}MiU+bbSb1%`~8E&`79xzN8)=a%EzQw6j6?*1G&k# znQ8_L*(PqIroe}WJfJ%wW$QKxH5?wLZDLZLACu_qKP%Hizl9EE3r)>F zb=k1+%@&Uw&de~VkVc^t!j~1j8i1V=4(CxPVEu!im-}WHnD8FTI7XllMC@TJr-iJ>mXE_jfj{6S?I1-@Q_fDnAO~2;-Gq%GK+nbeUdp z-!5E%|L7LqyPPxL`u!h?`J1iP#V&JgKWtZ-h+yV8xYjh)Uz)9^`8q=*?hA}fQD^#S9xP=W2M!%i(6o)INh$D zKGv{US7c|n5l3O9U}ar=f5=1Y*qm6il&V#|P=v?6RI~SYZ=loPAyNz-V(G@X@~gF^ zdXFqFS%pO`b&A=jpe{uVB}liAfi>0brDj4CCcE-)98?=Y0@4eGBsBYZ%qc}fkX9nk z0XQnNN79{#hylDo;Q8401*oSIN8qpL#65Yu4tOQG7X>8WuJ-)GAgGSJAN#Z6+nUjacPT|TF z<`DLV;4u3@N02`Nca=PV$*)jH;X6=iuF#^yuSVgxMa@~;;%Z2es{S20zsl-$0c@$U z&mn%HqJ|`@S!TK<_DEBvB}4ru@Els%r2xn#uh9QNvc0#OM=#F*&inmuQuDQ;u{QAp zDb$o=<4|DWzse9ASz7Ca$y!PKXb9RM?|pN%)PiGTo=|v&R4;k{3_<01n2-}KihF>R z;GmKRK3|vp1Fx3X%)q~d5(M-*e zfn-!l%zQ&&)_XBexB)0q=uk&##}hHn@ed&y1f}o7OZsxh$7jHxEn-DmBs(hQWmwtD z!H$KSK20q?*{HuO45GCu^h#Ob6-l>{CO*#5!5EOH(<%n)e}bn{bK>qCYU4=aOp!Ei zEHhQ@#O_0wUvbN5As!*`yWjj@GG2G-KOYNi-@jBrfBovnxtl!-Em_P(!mu|f0kt;L zXysU}jS8d0YRD{)Q$FTDZ1(BpZWM^fH7f0>XF;7O=;(Lr{SjkjzWU9jyuDOrNTycQ z1*z=mQw23UAFYK9G|nZVboZ|_0AelEHM^WUoEbE6`vSU}WA;}P{(xr?sML@4#)z8V ztxpvtUYuuEU+4Ph=BTpOR;zH6lXLnUq8qOChaw$GQ*>YzrnFtrev>3;AGJ}D`Z^ca0r28R3y?S@6$9PKYKgJTX8N|1|!Nt zQbDyjpS$Jvaa}WzD>;FwEZv!=5t=^gAh{T?Zy5`? zpT2!~n=YCXgY*P8$sORWfMk;J4Bw{wra^`ztnHBSNvAt>{(($J7eHr2dY*cK%K}&{ zcuPic=|}Zp-8>^EH8mauxIX84ZrHNfc7FSG^yWbc*wppWxZivM&}&F)Jp27cOY_d- zN_$##m2$Tyu!1o&t1n1?K^4}Mm)M1obMUh9ix~#R3$LI~WxX2`N=M0q=>F^L8K&8X z3y9JsNx*KHDzx)@-;OWKk_9H?b*#{e7>KJb0lVGsStTyfI^tx)0e5)9;J%!^hh3^Z zJTc&aZ$WXdsEq}V*!N5E!ss~dKj|?6mco&DnTuE$Rxc3N@N@h zyEM(`Qhvt`b%P8X$44qV7D9vHzhg*A7cw7!38^#<#f2z}{AfY02G`%Q%9MvogCOpG z!`!C+f&uC~@tIdTvyX{kHFZ3+{tSdyLRk@GLU(efbmE3uCMKKT*Ov5l)D4Zav~++k zqW1UN(%jlcu60Ezvwx+Jy_=GTgqf|2g4VsvBnL8!A?YT#%WOs3}IH(J?ZTx{q(wxwbOVkN{k0e!gX9Y}8myXloA96Jbk3CA%up zKj*^ow`E7S=rBgzx}YS6UWIwzluf6?PVw>)FTKOQB5yxGpn87gw!W{iva@y6;$G+O zuOh*nqKA>cR`sYNsbS3h#e4onRi((L8wuFQsE>#kWCmUCf|RD79(wIlJTjtBjNF?3 zx%W|V`&gw9Xvw~JXQ_@Zn=4`6ZNvX?Hoo3&hvsJfq*4|BPviiZTI#_w$<_Oh(OmNHr`FF;PtUaBRx@TP0ugog#Ozrd6ByD2l#{Q0Fdq`}aS)(oD)8 zB#)^I?1d=+H)EdAaOK_T_7o07Ld4w`VoBZgp>h5VOB?!9-^0{HTEb?#!G^F)&d$2K>_y-U~C&-NW zJwIHpq&Jngd4bL9aTTPyn{SvDu~4&%##%44{47y05VA7OV2Phfe@L?2(!iLDZI^bY{z$Ol^J~H&?(2p6n12lNV5HJiqG);2|zuYdK zlnx#5^!FPXgNl^c(N~!6Z+H%>golKv(`BcLz)-*63~c|Ohun{e7X$Q1yN)~gRgf_y zL6y;VvsWe!wf|4sj9k4SzZLCOfQU>=VtTXHyh@xB{hZ1BV5j)-DkEmUC?RX1=(UUp0ig%l-`m9pQokaE+saQoGvMozT~T6S6jk1D9T#E$N1xZ*gdfE!y+NPsGV z9!L}IpZ@aj=9iLN>c}Tjyd%HH1(?nm~}Kf4aY9W#y!N=Q)#PCY8J=yL$!w z(UhR6GT>qJ)n6wPqcY3>hrNb3UcRlJU4fs5OOwK*Qm(scYV@fcDdt&yZQWErS$V_2 z9?19rP()@-;%%88%MnTp3hMIPS``_eui^0QulR&51cZm_cs~h8za1U$Rx1m6T+FrF z!~2kYwlhRkLQxdrYbCh&?p9Dq-!I5nZ)lZSD7E;j-bvTIKxk6-dJt?)cW3E+g6x|) z5w~(uqbJ`s^bK9s8!fD7XVmw$JGY`$g`aIf@?zU!V0zOx5N+>zHg1M)8#LC`0C^M} zCf9dQ=XIhNiJFYaH6oAf@3usW+^G7VAr5~1PmuiyL6X8{Q0@Rfxh-r6<^#YCOw6(7 zj1b|O1*JY`~Y@H=yGa|>X>&+5ve#h2V(gYR1Vw<=WtE?#z zZCw#6<}o5F#l@{ec?@NcRq+)Y?idkgq$p`7q~DS)jt0uStA$QbL2^kuMBdNcU0Cez zK`O8n;&`eX7`e~OKt2f|5heWzkCkEn$3278^f9E|0pD2LbQxr-h|J-L6jWn0-J%*e zno_dY{6XtFSZVIq#v)Q4A-%|u$f>LAKi<_3QfS09?j^zsT$a}9}T@^{Gm4jd52qTm%iNPsd>K0p@lWAQmcALmHRK(br*w6JW8pHKtbhlwkTm zpG1lE^tv4Hc>n9K{s2%E@d{?ZO^C-4Q{*aW$=tLBxJf`H8G`Ojpk@!$>-F_mqWna}gM>63 z39(4f=lDMZQ?>kSJp@PfxR6<6uQeld(eZ*#@8eKaMg!t~Fw}$B*__Y92=i8#XW(lmVRf}#Z*xInM%>LS}--*H= zwy8z%D5yD1!zz7$In{L2)(^ip#+SVA#K+s}ey+LRPpPH~Lke%UcHBOkA93Fw<%1~| z#>MW1dFkZ}_{O#hMiKz6Ftn%e6xq>BX&S)V;R(DE z$n+2D`W%_rAY6em8Z3PS_;AKUx~`p4pI<=`V-F%xr&t}&6~+|4H}(l93Sp4i`&hKZ z<9Zc-YgHu zN;NMUA)+fgNX2bqHSwqW*xdq&+3XoSdtfpf{gDRYvlo`6q~j4VOG;BWgd<|n8Qm;M^Eqp(&rI4j+xIh*o}HEC!0Vb{*bWc_GHuT;mQmM zpmmj%Qynb3noRai=IHIQDKAge{56|Rj=wkn3 zvZ{KK@}WUf<-WD^ds>KGCfur(7o9dD@e8+w z?oU;tzmi7}wrbhBzo-!}eH|i$fDfb>4x7g{Nzm623mZ3#PEd^}=^4a3Bv1HmZUJkV z+VYpM2oyJ+I73dU}zeT{{#+dDJ~P0;ub3qPA+Ig*?yJAPx=SOd69TX0*i)b;Re+ z^47+MBzrZftPbU$e`q;Zy;bCfXNV|y2BNjOE8qnM?&IbsU9BaVWs|%BkHwxNP;V}} zrt$O_-OV=%aY5>zdwF>%9My%P*;g`nw2g%;3y?=y(a$T5XgixUAKS6*NLJK|nRJ)R zBEpL1iq^|he~1st4^vHYNmt>B1Khu(}|t>rwcNDngx!kH8LoBey^kLuK9=0 zDzNS(=EM8V9+w{(;6t!z&48*Yk&#X~N!N)(_bjLk7dJUFI(lMXzst(n{WV`K(KHR^ zNh?X8Y4+yhJSv4%LbOJ$oD|o3!b9dO5u>AwQVc1TpG_PdBQvv_P#1;YNFXl&%nngXeFlWwOTa~fA00ebkghh_?cid z^sT|{*@^2qqo=o{w6nAc97xH9S1bedrWx!o;I%EZ+_cxw%vKB?lF3Ter>V?gg+7|keGMmC!;21!?U8q6v-2Xuq{)Oc|J=c zp^78J)^jeZn{Z3x$O8<;MHgG%L~B!8wOE8J+B2A2{T5aDB{a3N>7_~V|3K?*fIUT^ zPs<);Qfe3-yEy_OGaeA@ApB{pMB}z$7PJ5GiF7sdn#4872PqWTwaXYj1By+pBFzbU zN?1t8r!$%WFkrH>1;LmDn~Uo|2!aJ5P;drRw(#yEKPju&iYM{C0Jm0)3xsn)q)TCi zf{zeS=PVqXQn+N9!Zdl^lGv8+zYT8VfuJa(>t>3Tv+KAh(f`Z>;4YZy+)C}O?)NBg z)3xr?l9Hd9M&nlKrOuFcZRZR99Mn6QLiJWTaC!NVaQ}YZDQbaBdSW*t2wBt3qcU#( zh|bu8q8lNQPLDRqLQQQdn}&it@(B$(y_M5CaL_D6u6u0AGb0lG&He4QNI*cTgv=Qr zc9-bf_xA|k_6Q+flJvM35zix{gF~tiNqLZaQq$`X}a&rza_B9O-(7C&3Ad&10%@^TnHTcI{2}RV6?QBv4r`=C`)xTk5y4f2M^Q>;Nh8P zE%Eo#|Bt1!V2iQ~w=f{mARUrJgEUA92n^lb9RkvgDBU65-Q8W1gM@U0@QHLui%On7 z=bS$PT+F=he)f9Sx|d(9?k8q0#YD4L_V&k^mx?GasHT!%X#aYnr@c}8@z!l6c+dh8 zbpF0~Zf@&(RVymL3k;C89}bg?R!1BhJ>D5=%S{3U$`VMwz2CU)+PeURZ1LmG7UI2`89} zTi3%k@_*Hs0`$YJ39Js%F9`@~V~&St+$r%chM8*7XpQ8P z@oRf&pJi@$0n;BDD6}xW-{lNop~YMc&*4)ybb=$Ywy9XwAntDndrSF{H7YH``yvbI zer&&kWZ==sFe`82e${4CVZ&l9i(yM#X2>&o$Kws=Ws5W|Vvi`PU@|OVri-n{U zV>8=tkiQfsvmtsNG$9JegEl zlVOZWYUbsFW)X%?ox_sRNuZRu%B>EZZez(z+fcbT!+%M$Dso@j6TjXy?v_z0YsOfm zM@QbFugxvxq`w6Wrp`%T%zbrj=Bg<$&-t)O8Vp6tz-Lu+C8lQLIW{cFm{~{$_l8CD zQRo2TW5x)_4*w`e!5`bvXo~Pqs#zCx;(q-f9{2hagvbW08A%tT(6OHLgpS$Zk)v%( z+6#~?))l%C{oVM+S1hZ0yfmRur^&dKgS7uM&~N!vM+s!7?bY ztLqw%U~XwiJ3G>*r&wJht1VlYR7ZD_c&9u|)g06uW+mv~{^9g+8<^!6Xg^XbH2r}% z)l`6Yi$8(S8ujJljXUXtGA9d*`xgBN4am1N9YMjKLmEwF(SN^Qt~ykZO5)Fxtw>dm#HNFq6c1a6ZUX%3%qCY7m8NtzCsTP;bmjk+*EIp2z>jpTsPLA<4#?FY})SvUhx9d zx8J~6+6>=yzJ0oS+x@{%nqSgEIGi3&W;iBiB12a8KsPu6HK1CtbdcBr1ebQ@N|BIp z7Ge*>#jl5h3tBJ&uOoR#qC~zD+CeL5p`TP3(AwVpz-FDZ_U`sXngM1wLX5$>nKSjL z93XrjmL$_>fNO=so+UD|StBrjVAcbcN;_dGA6(p*e*;KdhmIyIUXpfXtwq~RgBu}jr$LN|J?=MmyRMte-p|jjCyK!G0+SZ~u z*R82^EDJ<4HQTyg$x-125!!1(22QuzfFBH}CC)Ol#k zOuj~K2Qq1{uvo1e&Eu#gySCI+K@IL_n?sU(M-$AYrRA&k_V^RIQcBncP=6xU(?4eahNYa%ubk@(M=A$Q z3m>yRx9^!I<SQTJV68X39-z{iVuRANkwoj|E1hkRh6{`4igOsG2Nl$r#-Z zHZey>a{|_Gk<;KRc>=X)`eA6`sC!00gJT zh}IQEb;X-fmW%>U4vyNYDo9r3FwI~vi_%XnpqY=Mggr|p7DdAx@#xRX>}Pp-V2G4d z5lF`UvxN&SBh2|+UI6*~B#vTQ4FJce`QMlT)4V$9{2CwEwrs6smo6) zTn1EP^)T36+PIj1GJ=F*J>?@k{Mm4H>2JZwaA9l}OxSMfTk}@Q!5xtw$HNdsDr91P zR_o5p@#@K1r_ct_M_GxG5x!)+a*G|8zA;4Yr|~*YHOWs8CAy zNxZ=heD+IhNPS@PK_dG_ZwCRDaCfV44g@GJ`F_OvAr8A%QnFgs&bp{-D;dat)&PY8 zY+VMYz{H&octzlLLqsf-nUWLO3Tl2iWV(Z2Ni5*rXz8RKIe}#rsMfw_diyVG-C3QF zzNDDQwc)jru)_-11Q=$<|GrB^o@P$MRm&vyk;$}vHCFk^HB8LhhR~kK-avHy%ktfD zO0unEwBxwa$_-UC8V6Bh+r#IL*}1IKM!Z?jXHXqWA(Yfabz$}4H%HIsAqXFXjT48H zFtasISaHt41ucuDg(5$)44FAFMLERCcLYJUW)qc9dc`7Ml&-+K0?A?cI;gfho|U+D+!4e*nsHLxF7XHolYuOI93I&o-KJZrXt9%5P!al$~a?7Zv~mu#5-Davu~g0zu2Faa@?p7erk2k#>2A>zKe-kyz(`E;ZDEMZ^>?0GjD{gwepb&^0I zGX~`TzWC~DlvmxFDcMkIw6&DQNSRBF^&>*Ny_D-m0{O9lhZc41ZQL!@vyp<@^in(yBU{60cyzgIkX zh>;M{nK;swrmrAJtW8yT27sudApiS18oBwy)w@fzPN!I`Y^YN(db7 zb(!#&15;+RO>?W`q&ik@9_?5oCN4~Ap;5|;vblug&IvuZvue%b)*yE!bU-S+7u=?H z9gvKGB(I|$9p+jwfdmhIg!#mkMvaIa5hcM+-5buyQp`UE&M~8v)8>6?zzY`<1B`(B z-dologWTN38G3WW;!aU))CN{ zr2tfillsK$*dlCtfdrA`E#`R5f*9A zHc_D+L4R`Xcuc?E_tgL27ljIAU`ZDOw-dhm-ap23t%mJI*Efptb~nMH?kf0gzZN>1 z0j46AKlk`jwSYz~;xm;f<6ZiHWDB5Aq0DPxbO(L(&{$jB*wApfvxs+}m6grh5NTw! zG3u6YaJ@C)c!|AQx0Zs>2luC8RyGEPW4oUn%_(`}hqIKD;;&3!{Vd`9$q^79A7w$t?n|8I4)uzoPB9PNe`G^cZs2DbXIDVNJ7>4ca=`*T*y1!}f zBVyiV)fK1Y!|!>Of-{~`WPvM7At@ns4)>;6GinESa5hK#j)wXya|-d)Rn57V5ELrk zr!sBvN0s*;Fed+G`%oYuE?14It%sfq$PtYx#nhF|u>Kj3RjnJ0o&y?!Zy2sZZ537o z`3S?0)UM(oSi7(s_JlSO!|D`_kX6khXRS9#V&s?hhQaz6r5Le8zm1N0v9&>*o7Ouac1 zS&x)>eMF=7@d7zo4-e{79LbI-U%X<`Pi+R@J|C{O4-L4Femw1zje?f=?DR*MyGR>k zI5F3RYG4Pkf7^@~SHxtue|7SgcP|uPaQLfimw6ZsOq8|i-rmv^0Ons#QHa!CiIkd+ zW$%m2tL|gQ)n2!2CZaK3w|X1H;rpXM=$VLuRrPX>#_h4kiB_Je8mIGYYe7LnTbb)f zo9Nx2@-v+g39+dOjUCflztp0gCb zd;}dowRfj?4;AWk;CUH+Zo5s_Rx}P7~CO-gBVw|IOq*+o)M{Sp#(I1g+8N`u}Z0|Txf?%PPv0rVBhV=3r zI)N+>C4WV4U1M)sYe`Gsw1IM1il3KIz)FHTFmssCIUMVCvolLGL4i{O37*Nqq97|r zAc+{G5c^X17x)Q8fn_@yWw{$?)jRWzrCT0(kJ#w$GaC*3qaS@wAT}PRN1vKjqU5TR zM-XFW%JLK5X~K4}?(3oE+7L~Mb2v-nezMXSjUwv}_^Py-v0Dyr(t`yrT5eC9Kvz~< zPX#p(0iB-wFVKZofoWUv$_{FgFgsiDY5TK49uWRIm764}M>ACHqYsXE*l>$y$9`JU z?xiIw171Fj8ze9QcpprB4;i8>sF0qqjSz-|+@N$N$A2sM!9n+s3T`|zg4Y-p5GCZ4 z@X4g1nHeO+3s5$oEM3S#ul_UFXDjM-_vu>oiN4#ABp`9hACbIdu1WJEQ*fz)0*7(S zt~r=Vnh+!QhgRN5h3KaDH(jUjL$;ij9rUX=++itZT*9 z5e@}*w&lzob5|5&= z=}W0w5Bj!fQZcBk6@@B;!fQU#Eq7417)Sl~KQ?k3-vqMMF0dTt(4j>~LkxbayW9(? z95(N-qwx*61V67N>%s>#ksGi(6Au7kRT{MzH40Si$mae)He8EsaV_>dgNy|BwCx*U z7G|InW>zr3p;&LXovp?sDVt^)+96rkEj?RtU?1faZs-G^cTvw)<=fR)hzrhC0#0m0 zRjdo#_+IH8L;#OG)AggAvs#W?i2ZoE{_O3i-`~pfya1(iQo|l8Jv5UyK8xFO4{%9A zmzkLPAPo3dR6&2%+ue`~Gf(`zP2>2KaS8G&?73k|m2Apt(tT3v=;X4m#7+(N%Tqig zPbUv=)JuB{iQn!_PM*?F66Mavivz6eaa?RymG_wmk%}hhMRrfdUq)1374}=LCLgW? zL&MSO53!bye@vjel+l1&&hO##l(uyHwM_VRwxfliMGN0P2~jHS$DqS{i{rOF$C8)4 z?@nS5d3Ec2Z9tan#B06L-RG>!^H{gm=og_&cum_Y8L}=*q6C(W8$61S<3d9(981N1 ziXNdM4Q8qBNr8l0NPS-;n&=g-8|V@Op~t$q_YT_r>C2cRhnPABm*hu=3W~x?`TXwZ zn~>5{%AuC`&5`00huk{O|L2kYNTks+iV;a;Q>N?L3rz>!XHLmCruWVUDbS( zL$z2hQjat?0f*ZQJPyEKyq#2cN884O@u+}G!ZSc=xcW`%a6rNn>Ia%_ck$6*e2$DI zFA?X|H_-A6iQ3I^Pv7wQkS~W|B8a<0>EHAPke|3LB1Q_K5#t0H1s;E|uC~d?YAn>_ z6B0d@mbY+gY6Nd6GMQLB?gZ4}$vr1@S%+FNQ3tVL}PL$!6Uv zBp0)Utk5++wQnaT8x3Pq)M5uf=5i3aqh_Gvt0w62}M}lRWoolLKfy*8mM5c?F8YIUYA-p1pa^r_sJ^f)qvh;`3ngZ}c(L zChyj`eIpd$D8CxSoaQv`ttn|4t!v%Umi@Z>c=t!!`A3_;*ni{StI1zx0R+9@9x&Sj zm%h*B>t)y*iF701i_U#8lXlwVdo;cD95`8(Rn6x29Ef64%H-)(3>)uA4M{F9sc3wq9TGlkRVQgq7vzTCU^$b{LXG6H?J^v@;tok z62}@e8y{`8S#PzNY)A%G%dk==2c&8%!^o zTgyKnwHDRx=}o;4tf()3eP3BnQ_IlJ$bS@{=nCv3BuQ`KBLOdU_iuZ~-`me>Dh`CL zFZm?)4sG%bTHo)2u9Lkf(f=}y8@GUbx|Bs5$SlEDVo?GuGcXW1yc)q3BlD|!uI6UR zD0*DeoHFe30o2#8$H~Rb2L_3jP0PI{R@eP*l;e+ZX2vR!Wtg3fk(G4`V5u3N3n!-= zuP`y!{8MON^=QbV<0k=O5AN@y3Pj_G_#!eqf|V<7O6nF(k3}>TiAR@E=!yWC*9RPt zUn`;8JrWqisi~>7o9mtKVK4qj5UR{|%^Fi`{3v-zA7-ja`)KLu{S8?z%`7Pzpt0{DiKWNBFXGb+3=MUPYn? zMRKO=sS6GfqZA;rtXM@&O2PQ%M!14i#BDJ`;?3SK%n>lDlyvm!vy!JJ_AzV|ZZ*?F zN7x*Go7d2O%%u8yEjOh%T%nU?<)W|FAY+FXq+s#ya<{sv{u#G`;K!baoA268NbQ&c z3Km?I>fFW~Q01ght|j3VKZ@5U;d-YdOHSjc7?i&wj%1~a)(Vgm?0*)-sV{cM&&7$9 zC9ks9uWu6>9Ahv)GB={CyL15>{;{&Do9XG}gdHLv|exIo}-h z$Jw+RQ)=b6^;mTNcve|y*v{b|m;2gxV)VM47qw~;^4s(C#;cEMDS}B9-LYot8q8)G zN0>D0@iANTYjYXB)@=1^KeY{Yhcdvtw$k;%*%Ip8+*IYODqp!h-`vtsQ`*ST*BU4q z6Rq%)+#vhq{GUeRRIm+t{cF9|8DPIN(o<8hsOAFBdUJtKWNT&ntFp@;mTP#`Q3z|s zeXvJC66FHQ=iiSkrF!9hXarq0cfTXLF(^a&%k2Llw6|T{iW{O_&iBp zT*6=e)=c&Gn5s~mjg?Zwr(%wN<(;8rJ%NOe^PBsR1z(Uqyy)+yjg&p58W{cQeV=o0 zyvmt`MVin{j~cX1-y|C?$;du7qLP@MQzgj_2^h7i@{e$NcSBHVQ9ZL~mi^lI+7@=p z1vaK6XG-3tgh(kkX`1PR?MUr0m4+wvAb#}Y;nX{FeUi-3BB zo=)K+bZdz;tu?mT)Wy#hrK)=sB3ujjhD_SH`n1dK6=HdTSeGsK?b4}8N}-SjwOAQ) zb*#{pG;w)^6uqB^c-Um4s#qzF&9`U{MO)ixhE9!zI_e+H6x-BBjO-9Z`$ZNYCB(33 z;yEO~n>DHV3vN7ASh!ER74;wi6mfjS1x=~x@#lA@fw)h6=^_bL;>+Igw}IuL`De@{ z#MKvRBvcdBBoY>Vuyno*dWO2DKrU)GSJHsqHcIc0GgiES zF}DLqOIXTzBL4t_;ugjvb^(k&c;T~De%I>wThmE`^SX+yE4fOk{OMD@x{OgJd=QZ- zQrdU8$o&=mjiB zd?^GvCC}?-pU}*R3`6=n(RuBcY6e0gn3uK4L2HKB`|)o{`*d&IvIp0|)aLzhwbwD5 zUBOwJV(K(SAj2WEdUu3M_F*x=wQW9rf+I7|}Iz51B%^krb z)+qmnTlC!ep37)iZeQS%p}ho#%VO3j0-9Twc%gHlJSDuI`SoR#{VN} zlO#wb_L@V34L|<{rXP6!I8+1imGunJZG+(Mp%JQ&Y&P8h)t2}1R0w0snLU>)m%lOv zQAbBhCgV8K2ZB%3M17#T&%K~^y`)wCgPNOREdTU?Wm-9thapa81!jO2tc|i)mj31* znqX^?d^*4zLjRT8SN|y<{c$@18FOlFtLXYJEI7nZJ-DGkQ~urE@JUa2?%3FuD8wil zFawwWa%zA=IE!t{^N~u_&BP!FhzE%RB=l#4dzJi!u1mA-P z3F9y@w-j|2I&wSGM)9icCD=$FD4HlA`R+|Uet7+TBH8kI4jSx@&;ZV84gl>2W~0Jf z2{)#+Ib19vU^H#;>O#0iN&1WNNQI`Siq(ZUFi!Z0*~eya z%(UC9HZ1hx{l=NA8muGAKr%-mn9AR7KngJ|K_hI$!@t=j3Vkn5*t~>515ca?zj!Nd zmKjeeG1U(7>|(UI?z8NJ&xASBpjZ(Wrd-ZkTNo0&bDX^yfhR#^3(uT3TAy!ZJppGG z>H093Cj~>CfWT8^PIyT&wiaPL4=b#n%_k=O^)+-#k9N3&4bvBfyZNp*#~~bdhI#L( z7={StUXWQyujq4R;0 zvJefLT*kH~A;I8g|3gDqie$=jjuAGf++{;j7E!xW0&$vBVq1}<6$E#b zR7!qbA}0^v+@x5s&^ss8Yt1CFQsP8`g$qiW2NUfo6v^eVX zmk|PldD>C?88gd9pGKQqw`It~Vny!dbiCA^Dgb(>O3bIAs*)Q!Gj64KBI`A#;e(nQ zlTFK}8T-;Dr=REtdjncJx!flRa`ID*c>Sh4o?>!2^h0^2W?4KL?-WX-_|2dG!|&Fh zx`};3E!3-KQb<4EP`K^lUvr74fA%fy*RED_z3p=u60cun3My|2ZP=;Of7#ITzuc>; ztR!N=wF?L0TD*QP=`#-naHGKDB!@NDRcDm*F5l_ap?Q0*2atJmLFfi(pXuIzu zD4vyD015H#&lw4cNKsTr=5R;bn=fjwG!>o!uHtQZz->9;2}T@DN;0krCS103oH?;y zcXUo=3rtIRUXpN{oLJCP9MFkVEEm9EoquS9JyI#JboT%KjG)#Tk$VwMgekQ1PC5c1 zj>F>B*KcQK3H)x^*HH*k4oIUl_zyX^!e>Vz1&Fh{RAWj)FW+O>SYYg71qV)OaS_&Y z=%Ib>f?+<(I>6)Rvckyf=s=xr(QBjNDGM1v72u=7h7_xZD*Ay3jB5mY=P%445^^yh zwKA-Hj3=stmH?qK$K@?B<`>mKB9j~};8UdDAzqAcMRH5(|L)p6D8-fW>NRW~0u9dy zMz{c$Gh;G5>8K8(=?j1%Pe0G5g zGgGY3NWGnolL!Lb24#it&AN7d(46S$HOg#n@u+#ss?{KN;~HdK0XOcohYvjKN5}Rb z>gFYq^k{t;iC5$3<|PfJktQE^jlN8Fx5%dq;f_+!%RCA6cijm8EjP;kMVAVstpnF> zM!EZ`GN_-~6C``s<0jFP=GhH5i>aDfGu4N`+^_`}c4gDx{S)WaChb;E9nfUJDh95L zsVT(#ugm8kJMGNF+*koF5Oa>|j6riQbH_(jQWd8FqJY>559GGj?+yu`39!@a%*rsy zcs3xJyU(#!M&MAsx9JQzC_jZ@jdK`}``*+spQ)YvB`$;NB$*bZI6FGMudR1x<6u2B zS>?SG#{Hf$;ki==+7W-9_l3f_XwPJCTl_`FiB*a}ae?X}$bW@yC^SS2aiwOI`)Y#X z^HI@ziG+$I&cu(!KOUldH~tLGYb!RSrBm%LQ0QktyOnO^6Vg2PuBih#y^& zSkkm*sA8y{P$y=#gkw~ng`$Dzt&EOcAa=8k%Gui~MzZj<$PsdK9n9chf8#2XlfqPY z2KuS+7E56Ib7}JeH>6MjZUgtIakjw33n@lC5EJ5(!nhDg!VXQKLhKRKvHFVb!-tu` z6*|El!RQex_0EZg9o50QA$o&JdjcE%SxqGL+H)pCJBZMTQk_g;XEpWkGIA9!? z2LBY5?}XZkUo1bs!r>W`{IKEHFv93wnq0-d*RMSnwU1tCV!X^gDzy{qAKHdu71B7(HY%Xl(Jl-2 z)M2DXtwsJ=%p#w6&v-I4JH+kx|Dg52I*dM~aJ4_pM88cT;v<)+?pYDO#rBopgtAAk z&>CYNJUhFB*<-bu?wumyDdVuTj)Mk2J5={5yU}bJ?WiE%!?08tIHh=qEbV1+-<0)HC2SH zPuDv`$NUyi6R|oOw=Cg${__WrW!MESIC?G!r9Zy##Ocy|5=}JDdGb_6T1?^d9j4Ag zwC>vl^xufFBczi-vVj`ct}#XG^+Tr2D*S_blw|0xT*gc$Txe4VyKR>7qF!LM1rfiZ znmZ5VH^g7LBwr-U7!e#6xj=ew%akrEelzQA$>YPy%%~jM2oKrUC~)aeD|3YI<)<^Y z)XfvKk*FDiCB!9~9nzMHrJqI7SRsJIY=^{@<&ZvzW5?$(++%VJj_7@SE}oC$WCykz zW*L^4*ON#CxG1kEDSQ%f_F%*pMBGbr<%9xiELmYIDSFJ}5O@K6N?TOx2TDeaQ;_h2 zFSz@F;*2+{3d}g--!WkkUVdZrNJh*CQE*ueYADu!#wpXGd1XV8{oEiH-*C4!pc_Cgx7A} z1=3-RHR+;l{{m>-AD-SKT;Wa>(Z8@dAt3<3<{{i4dpiY{+O9b)DuQv3WXK0$h%c&=J;Ji;8| zF>NbXC)5{Iu`(q()Hz`GoO%L&d+JZ;5~;nsEX-&H2c}^C@jBGU7i>Zlc8VH!Pr~`! z_a;E!iDXv5-=7i9&e1ixdZD2jF|m;$S1&>hie0CEM@dj2p)nuG%kfv6al9`{NYhps zV3mZ59HH{4_+tgF-3#D2arl$MEG@Q0Vi(_6x%X zi5j;VG^`dgySmfTXIJ-2%D#MVR%(qbW4SW3OuX_ko_@BGqXdVn#dgzO0TPZ5X$+2~ zj8(UyveZJQ<_n52H$NUcNEnZ9q#S^xp^2HBn4x_&V)wnwkgLSa*57ff6z=85l8M`g zw2j^9qgk;LY{r{=Acdr|_>2?t2XiGfEr17zQBiszR3_Z8!3@#+^(-s*GMk30BFpC% zb#od7=2QtUcl(!Jhzm-f(wfDIK-|8aF)Ds>&y& zl`?j`R;w+{8@swvtQ{W!w4dMOpuypy2R!w^0sL>h%TaNEit?8>aBEc@{yEP!gtv`) zd#Czwuy8oOcN*oiEzNSv-wzFIETwr9kricpgSRl@gidnPEWN5meo!2xfH(S197eywair;;mtb2yLLmu_Ov;WW9| zwRTNbnKXAVpFEP{&0OPLp-rEj>giCCzL6b+AtdiMdNSOQ2zujxZB#$?2Zab_;4(EZ zU+hokPd{rG*ErRRCU+IdRaQq+0;%IFTr113vD$`_&cWGnNa+u``sUHR-|fZq8;=12 z%_HH%HYoorz{kc^$`k%{&>&{LyLt73ZYMnForLU*vGqa;aexW+BGN|qR(}RIV|gCsxe*9DNB_bzo;>;L#A>=f&rnVh zNz-t-$Lu0Ik!gM&g6y;UdWP$0>uQ#xUG^zLUS+9GGrd;y_A{)X^}}2;LD>Qu$^w`N zI~~JxzJ3-2QCw?k<8#81mPK*0X3=TqXi8R&#fj+Ru_%rFEof-;Q{oY3_|G(P7rQ3# z$HTn~%M%^5-gwtJ&PfJ;2W`XPoJzaP#3UG$ohA4h#I24>K4LX36J+6}+J5vr)RFH0zI))PmAXvVLWXWgz31w zgMP}6FkHapd2hk-Pyk{7tfZBJv>uxkjG(vXCJYi;o~_vUi=NbXqhPPi^Dq1HH`80+ zt*DVd)GHgMiseXJwV&H)>sx(({0IG(Ui)98A7}NebKLEK--~BYAm2KmlR}FUTk2^s z@=WcK3@J!Iuo4sm?vukCdz?CV(-!S@SjQbT9hGmtYl-_i>gm~AI2wCS=ZU_X&if_i ze$}^eGyW>3&1nOyV58IxO!vbT2?h)#*&(^|!3t?nPtIMeBPeAcJ8qpBY-k20D16ElWibdxQlEniM;sQUffl!^?{4Gl zJ*9Lh0+z4qYO(%bSTQuxJk!Wb zER$WJK%Kz+oZGnH&8g9Iflfn@atK!()7h9|a5vrbbPI`Yjs-8YbCiQ6&Wgv@ozfl3 zU+W(T!L-(LM1YcBY=Lal7tj!FWG;=HI$-R*!4NJ}QS_0NzKkwBU*toR(yHj4niZR? z)xI2fxe_Mg%vshwvy04HnDwADvW1QpJ{LuNt!pn!-%TF9?Kj( zMaD0X-NUnv6AX>w7k_);NW3T9fk%fGjPSKf(8^rkVJ!9K^&lpv7Uy6fe5&tz_~neA zc`1QH&;3mejaZyCkm$9sz}t%`RTrxGNJm(Gz=OS*rF{y`dlNQ8&uWvtE8kX!$pwN);0Vh0?8^!dI- z3HY9sbsE@jO2(iICg9J;hCf|V5xlXjgQI#Mutu?N^0CY#a=56*Dy?ruw>aqG5f|q# zzux(HXAB0n918uxbY7Ti0qg4rU~56aetCauAM@vAbtKlfD@`?r&uu+)K$>Clck6^< z4RYgiot@N0?axHH-TA)b`n>O^IM_Bnvivpk2l;q^uqxDVck+{#wplDWw-6<_V&9x~ z3q|x2(phFXOL%l6o%8ZOtx>i*)UrDJgqUM!F#iH+W^i&}5yZId>%W-G;$o4hPkk49 zv5H14?8f9rCArr;C4AOlx!2l4Oth0;R-a&hho8Pc6%H(_GD*+< zE}D25|JOIS4Ym@R4{j=~C8&`rkJ zv3Bv*-Rvhm!N?5@KP3U~48g8`{Gue5t=A*1yB@|fO6WLS}>?Eh=o4blgMgX@B ztlzi}t4+H=&g=o)@#i>7H3#R#sD#TX`TYkz6OyLi?bphXGkY26NCv5G!{Lq1}??~ z;<>1_9WVCfCVU=fztn>*I`up-lPt}BNUsHx551*zCDKgHKG$n&Zoc=L7Uv)#yzoB-@ z;T)MYdDb39uYD8%kB?jAMh|BWxQHvmLtw%N|W=~{aah^ZToN)K7LB{ zPJnNzfR&BawuV!$+iT-Un>_pF#Xjj@B9#oTsS7QPZ3pB2yxBseK-Af%=`dUtCM<&I zR!9O7lOVd;=Tw>IW_`twLA_5w<|875x?ym z>fTpWbFwO#Hh;^zX(=cuIa1qL;Z9b0^ZP_1Bs`h!!NFxu7cd5O8vKt9e{3;*{yYg_ zoa&dM*m!!<_UQkiopDF0uiwNB@Fy~nZ$10jIO{qx%boZF4j`eO26ijvFss`d2~1)( zw5RDCZb$n39d!1|THyN47x)8XNiN^tFXdDu^3jW{0N>LmGPn_t%*CkLEVWGuldcfX zECxH=f1vpJ6eK!Sz&7v*%xWBgUkNE?xp@eb=!r;`C?3Uyzo5BIm{SPRSfOgrEPX{! z58Vl&Igiw{A61{0l=q$d;kw8T_OCw@qEueT_I9e18-M)OYLn}!W2U9WH+M7T|9nzP zjuH!6WmZ9ro1q8q@%U|59@6*b4`AR9SjGvVaF4^W7CeSs9(JFyL?vUR7G$SA*#3cF zyg#sa$ynCTFt^w7(?mq6h$kJQWszbF;)DJX38jh8JT%z^V^oOo*TE1jUWKEC+Y31# zaV@!c!g!D4*%Y&|w>bUyou8pB#LqqXSBn^^j6bdKi+QivmAgWU zA%+N^j~CQW7ljd2(a2D|?y^?e$W9T{2X%dYvVbsdmre2GxzQp)8nw9oAuzDh(=#nH zM=~MRc-X#tB+H#ZVgSKxn9X>K9elb%#W|^u|KmRW_G;tIUv_o2KA;{radf7=+FIMn ztary3vjrTTE84RUDG_BQ?1p{eU?Im79&Sk=zg(lceUzWPYf78+oxcJ*_y6mLmqKtD zw$)T{`5BBJB&LA8>gQeS!~KXPRYJlPZ@GF~w}!`OzLOb3jk@_$p1&guvac@Ze>{A> zqig;5Zy3ZMFjWK{m()kV_u0fWU92!RL^{)TB#ttA6O{gRR8^HVHQ5^z!%o6Fm28ZE zenyWM{Pf{)Iha?|kObS8$1Iido*v6;I`4~lO;MFecCTG;loGJ|=DI&Ng8QM=CdDv> zf7#&uW7*fe)#ms&zDqg&ei4K_BsQELtz=AVL-0=LkA)B072q2?M?p_%qdJn<0p4_! zd581m)Sy0XtBHBj7QGCF;z0vSO@#nxWd6&{K$_t9kbXjbRtWnUJA68oYQ!nzRuTpm$%@1pqa+n2<@9Gz5X@}{5z!6;W zmf~(b2Dc131IYs^z{(U=HL%lmD^ZJuX?Yn8UD>V`v3c}$8z8Y+)>~5gnnYtnYTQ@r zQ%9`^D#7@mJ=CmtjiMy%#WFTxXRkUz@#m3#YV;-Rpg=CX9q@6qh363x^vc_fC7LC8EC)fo5iWD%v_o(wtUBdQ$W>lEg|hban4w z$?>nO-gtPlb5vKWQddi{r7bP+IjnUI8?UM-oN=i?8h_Z`1q-zt1`&hAVDpNZ>(Qxv z^w5iEbN*IHyoIt6S+7~UJiO5LTWk~Y1!UZ<5F}iE3uzyWUG+1wc={>?l{q;%$+#Ng zi)!T>XXmtxU>RfR%2uyR-SqWkE5A7BBYOV+3>Ia)R^Dt?!%Hkapy#IDX(P>KbF`NY z)kKyiS`QhDdq?IYGRY%qgcHj9>R71%bmQaw_XhKjam%4_WuRu1w&QM%&(|8J7u%@1 zUJp7}q{@^2kOEAw70FS&p^-VB`Ho)IbK$sp?>{-0T^unOqB*5NHb8{#JV`KTiZ^BxjB+bU_@O3$r=hk zep|H}9f47s+)VmMYnCFFpw1H5Fs;tv$KwzDT3yunf%p8fU1|$P8;MK|N-rS{u?Zqb zUwS*K*eQP)V23<{?15){oGlW8dys#i{{fZUgAYuT%M4KwHDLW*2#~s2h%Pa+;Pu7zl2;?xCw#u#fBAH*6rzrZ>Cexv@sXn}xZ<1I|Pgv7@St&)fdaC((0BA`wXTRGG6yfK~ibY{FIu3V&O{ocv&If;KmF*wzbDN>ZQvc;IAGjW9@^ zMR6$sa#?eaWHi@0&0aXBx$Si+h-d=_Wn_@hua=S~2?HM7J$P%>?`6~YML_220AUY< ze9t9)j4~h^+3b#|qTwp?8a>ca|3i~zs||!#qW%S*f{W-^buM0PASRzsRO4h^&5QP? z;~lU+w;Q&PKgU$b5OhUSu4D+>aG%})Z|CEcDB;@Q*q)ba3PsqHz^4XU911Jdd73E? zeK#5{Bfy4u4RE#0zv0MsMd-YxdJ=(H%_pU8H-9*3s`_T<3oKha%9@jSzIK^tDJcpo zcJJlodGPvh`Mb2e$b{bO)&I8vJ`!#YR_3;84BeC}3ML$9VS@= zdjdIEK|qRA|CC!QHu+MuWKMQMv>Z1^&B(y03+b9|3oEe%!(B$S0=G#m3p0y0#1ns! za012z)#SCAqULG<#_sLOEuzeEM_28>-rmBJ4v#7Bkw2%4roW_otVrkhcvBcr1FmOq z0+1eYU$6a~CgzcKwx<)0aiTrR6aARe6*($|v{@3hJW8AGyO7T1#xnkSJ~1s1oD9d& zB93c(t)sxK`vD$!2Kf~DCJEFHziN8=ZTj@P9HiRG0cI9{n1Wo`7@W;b{kI<#G#P(V ze>`cP_PR^aCFHxDZ#YpsPi51AgtO5`#vJYt3R>m<74NSbYOox^iB1UON^~=$C(=aD z^{y;_HUqN^B}b5d!yfAsq>2%sZxX65t*&V?F90(FqZQ)|`^^`@g|i4O5#SLVlgA>> zS!I_ccr^%Pbs+b_g^Hu@B+#5A>L7=XeMSjA=f-R?Z_c6#MP@0Z@)u>a4HlFwh!6BS z)XDhp93o-n@MUdbu}}7<*%8{D&)Ra=Hi4o~X;y?y@bjG~yRTIuI#w+(^8ug5Nl0I5 zZN{^v!U3uL7Gc2xkHQ^Gh>(a)&r(y8d~@ijPoP z)dB9EIY=D0U}82zqRuPB)@@1KC^>^yy^N)^={JD|um4A2T&2^=(nI3zr&jxcZ_aH{ z(Z*iItUD5Mud`puhKua^`!%8Rc-tIJot^9MrLwrIey}Lchdx;Wa0+m zS{NEZ)++=-Zj(6td>tw+L1hw>H zF6o;8H0!lJ5E-g^2cG`z=X;w+4%yl*iGeH!VIpAIMCH<&`xtxVjO&q*E{0EHQe%SF-lh{k?s7uMWf42HG5cCwC zTn2{;k?Xd>orCekm~=iEZv-z<$5`;Wk)#L<1g%IB`|U-8jRM8dY3(YbK^)|}=-saO zo?E^NIG7-wD6#r2U%8N!OK4eS8R*YDq4fY9Ql{Q2rv(t`F{2>zV4_YcaIHhQ7x|Jx zG6|RMRwxkbQzQwlkKDXGenudL=!FL^@^pWneWwwVY;kf3&CGyleqqrIhc7Arz!-8) zizJou!om?_M;|v`V%PayXv-Ur%JK(qzl_9AGmC5wm;Sd>*d;gwh~$tD=g2-taz8<) zOrX1P_7dYhRcePjD?7&U#&<~6u+3rMtrvDc+ydxJKUX^$X}yM%TDu z!9q;*fysZTqP+=MC{TDptxU{3Nn`8`o8yJPTDD2#j1=DrLJ3P|)5=0el1JGqcbve1 z_&pST`}V~Fkv7gAl9e8UjOn46=eT;*1!=f^|@ zYL}gv#CYzitMY$=F7xXNvbD0jNH!^|R}a@N$oJe&9v0iCG+U-RlT2F_f=|FUoS+w5 z-qT^f%%MxbqPa!bv|XJBGlkB@2EGy-&oUSr(vMz87$vKDftgU$<1d1Q6k#ISknPbE zS5$(FL;nI%5_SguS$xHOh!?KNzu;+HT8xyxG{Id`(ma6Z;0L?NmDDU(Nmb`!f}@^5 z{sN{VRH2V7y}>+vxF}* zxdj2itUQHfqxb_TX8g$~P`pss5_O4P!jhw(zyIlen_Bh>zz4#oL6z4Cn_>TVp^Oo* zp*{Y5vR~XeFd}xtt@yOV^!CH~0P6IlxKMC2k2T0^17fyRSy6O~jDrKam2tYyFfR@m zvwMo!oEsN`#NS~td_?s{m{-HZL|xHc(cVP#>TFFN;BxX#&IDH)qP|?*17a`u6b_o2 zu8EU^D0+^$`48ScuUK9Bb_>bCxjQC^J-$RUoLR~EFO}x7x}F1w&_DPE7~V!*y(*!Z zi84;hU39zjkTF%$)zzFW9g0kZhU1XWWHIe=rAxbNyeL89s200=Z=Y3-vsf+Zb+(p# z@?(oigI))`O6MhSNGz*e3P*wa$mzAdzI|rJnx{l$6=C{D{>M`|6C~NP zd|O|HqQDXv>*^YRZT>%DA`w{_+3A(OE`C*|kxa?k;Ht zhb}?7yGu$WB?Re`?gr^bLZlJt2I+3em+q48miP|eZx?I1W}bP@efGWgwU1jB6$BQH z3l$1fviwQ3^Ptal-R-Z`DQ0ILBjJCApd+;?PCduAw)@xA3gGoUw=Fjq^eulUk@;q< z?+^P{?sQEBg~ph79tVm#-x&W1N+TDD;D&yDEWkd8vDwwA>UDFpdgJk{Da~xv$M59% z(G2=fe9B)8QsM$yF8iAQeQEv|)8A+>wuBT&h4A-}^|N3HiBr_GupeIkhDdJ#ee&8f zolJp?o?JXz)aCt4VTA{je-wAG=sT5nNp0(r)vMySk5Dd4xZK_M1s_o?hM?pF3Fh4R zPO_TTMv-zo2z{o+#5{ov+JzDv&0+BJSVMo}8Yu9F84qze1L8Rd_Fh&eXzh$ly?7dN zd{Chr$=7E=c{EIvWoSO9843B{T>D5q19z38t)v?N%PVY`Y^~5nnRF*kH3nDCn+G#F zYJ{Gj(lk$qvSjUgTR>#%FHBdRMbf%zEJrVcDTqOAvb_G-uZz|Fus$ty1c~ykSrYlV{-%qkoY&i4x1ckUSQGN^}-E!@$(k~v~B+EuNSr1t^MEk zx)HTy-e0B&KRxO)vq z*DsU)_HtZ=D5MNKV(KU8TyP$uIVp0+|_tX!P=?;RD8<(Q~nONs9_9ajfqo*_fRNz3=cPD|jqf`#c=GhY; zB<#w|3UVCvo?(RxmA>Im&=)eD+!kTfwiO42>-b)Es zV!O*lt02S;Ol7g(9Wp(AWL-h=>m03}BLg{9OEQe$3GdV+G&mi>BarVStFqoXGledR zM_yASSHr)aiJF_0Zp`I2A7-AR$gt{3v|?+}vb9pD!uM30C5%L1uCVA7BCYde8J|MK zDIpU2ENCHG6iXx3v3=%`trqN(m7pKRg}qaOA6_hkEq2++Db0n97>5&E9#;GlPNL~u z#&=&WHDlw1Qv7{CUy_I;brQdLa(_`L;W(<+Bk&>kfT_D_n(@ul%(9}rCR{MWXE6db zbGTVlm2BGM%DR23o`jzv!SE&pFw(i8KvwOoqpn@DtPQa%TS1QNZrXl^n3ZfZbv!A| zdcb%}hgi~Uty8eSi|-PHWWAfyglzQ?$tap>PwqRQt|gB86kBq|#)*&RQEwO^y;g zEH7nKhS`=X*#aMc1WE>T(tHnr%)O~ zbWlV!R{eWE%{Yu{8cZ9QwFP(X4%iy7*f;}P3mf69e-4%q_B=XcYfu5_J4 zpwfX(3jM9!Qlq{1CYb`Guc4Mda7OCa)MBd9bVn0U3Ma;4{ms5;@$`F9kR5w)IsSpo zj)CjE8Gxsom2S>#WCHRQpbt5-Gz`hXDTB??{R{j8h!{p94HoJY<&$jyub=5WDGx^a zDeOlOnx^0|=>cM&f?pX}Jh$d=PP412=Vhbk+^PDWCxX`M$A9h5|8k`xo$+3_c5}_{ zXC`E6KEP$*%+wVtqEDfcjiKE=Tc+m*m<+}ixcSc*~4Z*XLh&R4*%;gBrjNjq~r z2EyQ2%^)M)^-i<|Nme0g5Xl*6mXlOx?96ihFbs8)jNH~e7X=B+IO_+x@dNu zgxdPgx!8WL+=*Vhf-%ur8B5@i{ve#y+V)TVwgS_T;D8bv5kIH-an8OV>HT=H!`WsF zfP2uXp;-_LAdhoWYS5%b^j9Lf2Xi6@_7`NM($+ynS+9KVU9&j8oFC)6SzFnZmo3I` z{ZcxoR9Dxh%RM+C3&W&vSt$O&$U1|gsG#2yNB6kz=hjBm{fzoh1btu-UtzcG9b)c0ft;=F`*w`wCyyxpy7eEL+mY&Io*8V`} z&e{jf)4}u9jlsu5``ho2W1TcC(b(|W`ex1)TMM~}v0yl|d5f^nL-QetOVMVl_Z7wG z+c@NLcvOKq9H-J~Xbo;IqZ~W&#To}gfH%tdC5~Jm?!|3=;j90;K^a_}l zjOgxwn_(hkQrL4RB2F^1W`#k7L-`&76xS+2tPmCnqPzm(+Pp zXL>;K>$EdVS=q8-!ULJhs4mVCa47FbC>bjjX6KiIly|-ix=GI3_J#20lWqTqnyp&o zQxGA&{(j=!f5y+^HIbMAYmA5@mH+qbd$vK0se;mQ{qwY{xvh;AIj8ICh)!ZC21TQ- zb)I1@WNN=IzA7Z`@cO7O*R-KZ16%Y^V`c4}%DUi3AWdK2X8)-l?6coQU?cTwR0Il| zhNGZ;GlEXR%}x@Wha+sNa6;G4%rGIn*Ed0o+e&^%Xxv;gUaVeV#+5%_wa?yG`;`~m z;}T&~fhU$biD2|6mG*%LSO~Q38`ndDMSN6{%F`2hfzZD{L5LQ+SO)blswkDWsWk;> zTVklC&)*%&6^U{>g)qLvmK59{Q)M}qTkh{(b{S6pO(*PUHWF^{%%`15%z99YI>%A{ zfguz#Yu4j4!sj*TJf@zuYCm9@0LMK}Zzx=6ACaxBgG7rGI;vFOz8SPJ7u}{z49@xO z1U_QA2<88P^}$L^eBOf*cnR6o70J_bED_dwRGblO%B!46pe`A#)xvRI=CTvhG?zD=su z8yF2iW$&mYw(u6hMVQ1<2UMs_K*}ijTBSML(&6qu9Rlfhio_d;`G4!XCx$h5?d|A{3>Aiz59H^3e^^3>ufJ}*uRaRQIypS?H zb0i1X%&ylCfWKP9pqs4fKf%!Kde_U{2@v-?rVb9e1kpP{h zfc`V7ANu z1{rCCwfMK0$xOW(^X?AVpzAcB0f5o9{l==$wh)hiH_zZMdH?d1Qxy}@P!R$i`1x1h2B}}urYz~!HkIZ$~fV6t$6La8*%F|Zq3}cSYvPi|4Qm=TC{6U!%UV~cs{@F z`q^>DKHB_dpaCLAn@9LsOMD^MMzSi-+vZm>?l^2ORL%bsB_HRHfa3Y$cEe6sa&!wfjXO|Ld^b2DXw0{L~ddfYYFSoMK)4cvJ$;j(D-Rs~{M!gX|; z{js8eEf4ClM4P9iE*!x$VFi^tC1#`T#}iC2wT|t8+VV$#Le6=GA(`aRx&z3HQ(&P) zfL^vCvlh?QLHMAgI(b;qT8Xn<*atB|2?I*2$je9E?7X+(^3e1*D^m0)B^Yb~LNyPU z`lEf$nAjE?!TtC;aLe$xjEf^%irj9!7$m^Gw?n#g2U!oIKKS^O%X1uJEK*A6V&rBn z>Q!^}$ktv}u)nr#>Pjix@|>BmcmI2IGgDq}Kl)#h-+a6jR{Q@)D89;elk3=PabYqK zNGx)K#D;Nys?pxM({kVC>fINdJzTw;)J5lhiUt5}_5c?XlUT~-cN_1>Wz*j!ZnKtQ zj*emmg_St@7VnbYmuLz2i)-6a<><8YNtJE0!S>U4ah8lM zRvG-(V<21aytgEsv?sBmSGoIgp`m(qx9pGM4jvD#onuft2>SRIJ@V)88cXB1a$g5^ z@h0o!pC_i5)D059x895_yHRQDrYzUjRn^x1Ecf+Nh~Rv zyWGV5QLE=qTr>^#7aR}ISkHTzPxHoqEd~~^#OEGE;NV_~F)2U17UuanRwkAzTp$#C zMu{35u9{j8k4lZOtPI(2f7_V6D`?f=adysgz2bFpG-vp#Wc=doIv$CIoxCqhJc4^V z;<@t;;&EVd3Qc>@>~zvof~HQ$tZwY-r}pnra1Oe#dOd6onRm+3H2pFT4e<|as%}b| zM6-fDec^EH_;MY8YO3tTe3^nXUh7+7nY+u?FowEUAvyff#yHLBB_h?uL+QXL@JCib zNrqr(QrAM5!q9#dp_==1a-pih;9VoZ)3i&6N6YfnO%bB@Fp){OZTg|fYUB#4QKLsd|GSo-}n zf@L$Okm0qzP=vB0!}r9X#m=nHnZ{~O*h(FOm5v`EdW0&-OiIw!Pz#;N52Ml;gEc8V zAZUU0e9$qPKJXj7IP#~CQy>d$0-Uk_3`uzaSKA^*ra-0A(Y3kv6tV(-QN1 zp4vXmu|^Hnn{6+3NB~`s(>a+g1duIYm%N_%5`cNJGlO~~4`9o`+MD_d@)?vO-nXm` zOA;m0kwh*hE5ZWU8I!9X6VI1ZV|@3!P-MD~iwiSznttHL4>oG1noJc8R+eQ2s`Wq9 z|7n-&p3h{UH`uZC#suJ(4!5R&Hpwwf2!TC}h|8qpfZ!Z)xl(Z#-t$O7H|W z-fqW94>j>OOJ9Bj`97S{H#^He`IrZ!?#C@zF9wK7c&P4u6WUpa|3mYBN^hs!BgYD~ zZjvtffJZZmm?OWq$&izVQcw3laro0!?)`7`{Uc$oKe%DvM?UR@eb7UQ5!~{_cz!kR zYfgnZ$4`3hirAay9)gk{PF7XIV{uUjnM@1DBhXQz?%ZTTl9S)y{yMaUUArKPf$g6+ z0Bjy8e~jv11-$E`azAYYwpXj8^s8fsdu)5UhzV+#8d_HtM%!mKHGNh-&w)>vWi))A zLjgQm87Q&a?ko*7e)Qtu5)DFyVp*I-NU^wEUx}lrk!d0BaOcvmVX(#ru|uEH=JHv0 z@ChFn)O@3a24CNy(^H=j3n15M86yfI(xfsCBw^Eeb?>#NacPceo#cb-QNG_r2~U4}wPcpzFZG7M!+pt4Q47~+3P z7ytF}t$rvOheJW@fZ;_Pi0wd;?Sy?Dx`v8ILm;+=u-FOeqa*oxSWuH-J*s$2Qp?8p zHlv`iLT^2em>ED1$rV5_78;dsxzh9)hb)%SM*p0P$9a2XHV7`Qx5cVH3f;IdzfZf+ zfiLpCx$D79G*%8-&z=~IY?WZov1<;`AOj1xC+=U#T=vtPV&DQD54(BUXf(Uo-|v#? z4@zS3=L7KQSdl-VX)0X2`WOdP$>!fDHVwUi8Cfd3{sq0Px|!lgk>s55delDa-=Hd` zQGHXBP+-PD{duy8j~8uw&vI9k@m9zM1Vt)UWXVN$HrS(SV;CR1{*3hGq(X&=qVXC6_t`+NFq@%C#md!K-0}RTvJ5f9 zidWN(ZH$|){f;3Sg{1|DUnMZnr%_rdNK@h5QyH#2q8Aj60#5HE`$`AH+E-W)N)$-^6Qb{r3}Y zTFy5ieMLq$9tM?S?U}!(HuXPZ_;I(;=^1QZoa>DUqe?{nq)wvai2gY)cL^uTQ%GUL zf>t$qRCLHL<+@CkxO`@c?^#oP@M)+{oXu%KEe=+oMM~UHtDKr`wAlNt2^|Lhv!JhY z=(*)mAK^MpYZ(zFAu`QhDz>Z8!}cH(DD`b}>upxW|!%G(b7rKa$ z7pDZ!2LEr>xi7Ay`Dv5B8rjSM@19)1^?BmubO&ECukWnXx+qAEacx|0+Y+F|B6f*( zoX154VzGCqNqAs{Q%V|#E~0FZk0Nm*+2Z@~*e*yRH)~*%Wz}XWYblW20)r*H)p}RR zuR=y4@2=PAF50(l^Jb|h-ZvRgHo#!QzcDR&i`VrdJFj9 zKu47k?MHmK6{w$qT->xD>>;*p*eKODK%9=)%5?hB2+lIL2z zneVl9=5yzWntbG6FQ_#i1t1^K_VHJPPCig)R`&asZYe){v_v@Ei*W#S(qYHFj>CQ|p)x&f;O(AGb>R|IbTZHTsQN|@P6m`Mq&zZ}zvR7^Oa8*sC+X0|9} zVq*h?S;-^$!E3waY99bx3Up{V+cd}kWMWD51Et}qO%l53RsUTf0RLJd;#8* z#4-+QQ(xiE(9mJ+UZVLCM_u)=Pu+dogk}cyc8k+FlC)PXG`pI=U5{&4eUW3xIJtS= z`eOL8TC_J%;ToZNJt+b*s=0A_9psJ|)yi$Ut=%SB`v>C`-K)a(q+sf=Lj*!HE%k4d z;NRnYJ%{i%!NA0zOhzTP{6@@|Z+vV(FJom?_GPNLh&!R-uA}jhwkRu=Ytwmq9gQpM zc`hwtDNY-K!)NBNb>^%8KHa-Jm`Dn*Awq1vlLCvss=^xkow`ASRcdOY-1FK>;5WF= zSV|lXagOvl9!k@h1a~e()ezbcn)WS8D5NtSlXl{b!Ovh~Nj@zzVHjE7J^~eY7Aa~3 zJQ!J6z|GEq_a%w$f0rvljU-$VL`y#4Vih|e=xC$=eV|af68jsqmN7;m~DZ3y9f|-C@9K={1Xa7zn z6_{JpueAOn#HP?ZEz0gwp|Ma*GH?rM2Vam6@b2dTyi{FJyW-jX zG^d%A)XhS?-o~oTeoozx5$~-Y&usf$pBLGTz1y9I6tnT|e-*xWpzv??QXq%5g68@G z3M*S6qLjXThrY7TkwwB~0lC2Uqn|CXxJZe95ibBA|a%xT(L?=eOIzD|E@O{!{IM*!SoOPw1nzR8n$~*X5PeiHyt^EI(8K{{7?g*hFt= zVavvMRXZir39Mmi|Z@OS<->P~0KNKupA<0(bm;MkLawEQTZ zOBX@?0>xnaumYqWViHFrj3i8$b_ho={#%pKL7{kMUsLvmJSYo{#li_ut4XvB5E_^o z%Doi&w+KC^hlpYR-{3}MvB`y{j3s4Jh1$`IeBgPLUy(W6#C;%?syQt1etikA1`|?1 z-9s!Tw~K>rD!(S9_%nYJB5@l~@BkxQ)m;2NH7`3a8+nV-ylmq?|6RpK3J&@5J^Jg3 z#%~F!o4CT?gh@C3bDwZg4$*Tj;fN4v&7V`_cyUY~aK2b%3|WXmAd|%9f)lAdR8L~B zALcA>V9v~maOu~|tMS>L^ORvr1X_c}CybJ;v)fSUj98;XrizEZ z>@tzq>rBXNG*pC0!Xe#hSgDf&UoWb(+usCZ{g^Zu8B6dmZi@=Rl6kJt^1?&(dFA0| zWxyO=z;(aU(ZJNYJm;6d9m&kOne|S4bFHgvVu3D&Tl`P(^Wp_gCptulYDT!{7_me# zJ{}y|IHb>$!y?zWP!PLtngO1x@YP2GPw%Uz{baC~NvnJBn3N~9<`3_6wV%wYfZ^t_ zZanFJi2m_5@JX!2=rM>9r-)l0McnrfZsB$cl%`I&CWRE?)xK%)K)(1UPc+>;<0CPcM+= z;5>w4$9dl7DzEPentrM0n=11P!&eci2V}dMOl$QDNh@XxdEZ#RyO_GA8CDm1^5;EA zQ@1y)#ne3uQb5nq4!pKGpMZZ~7tvb#m(`A$Nv>UnZfePMs*d;h?vEE5vjUdjeK=O~ zApHfXLORa!wJjjuFIvR0jH;(LOKXSPF3v1rEP!s24>nq*PXzOaO4RHOBtKS0^Z za2l7(3J9}0aQUgXfcwmmay*@uaTgJ% zuQwU_3GMC8irWcT001VspJ9-?#A9yhmT@SCEykwk??oBp@U@;Hib|iAKF4 zNc<5><7c}F_F%B3fB~ntBukX&|87aZV|3S6o-O7ydE(Tl9%nh+0@bA2(i2}lUn+<|sIN;1 zZ!I1NCzb}qZIEj$3hv#c=jv0h&Hx*tii^oX{pex?ZAGP_K%QU~4w*uff+EOAA@s4u zb(p#tQHMm&2^DU?y~F<)E90)T?STW2jk3-lWb`HhexXPMGQ)%u%VACE>GfK1Smqn~ zac`6y-%fT9R6uB%8W&IQ-Fa*$Nmme@2@&ob?X#TG2wW`cfr|e(hEz`sN>d07g&hX{ z)?Ox2RnmEV1Eb6YTyPwR%f-jG>=|NeWCSuX4C(-4Txq%#pH^6?X3J^2gK_AJbzAlIWHB|$<_b1*_U!s?wnzOI_?c3V19@DXK@ z8S~q3iuZT?kXoOO^XP$Z@c^y4?S-~_d zD~-kn85cVhdd+F-#Z(DcC*zXXT5tNJNbm)Us2^`E#k-`}%O6Zv?7cBQwo~6#r`)Wn zw!zu;RIUT204bM+Lp`6owH}YXH}J7K6CT$cCpKUHS7Sa(D&p;~ZP9EoU6 z{O%$@g1Czda0``|AICEiq_Dyx-=yZni&}$m_S*;=SY73JljvV@&R8j~Bi zHF^}zPBh|;b*EBITm}m$h;~zrgt)7Yd25|4WZk23x0Dkjbj6kButnNRd@92vuLt`U zZHM9>-Xkm>*C*;xbC7w=TUbjdiNChi`1-JRV}T(cDIx4Gw18W*y?ZL8M;w@i>`X9{ z^0x>s7FQAnem+eU5`Khjse&3_CmxKzkvzT9X@nw%4WL73{?2O6b{-KNTYQa>osj%P zKXLW5!6b?RT1pS7(2pO4#9SlHUy0kgusN8G#6&X5rEr3BWhbsklVvoBUXu;JkWg0%&*+5w0=0;ob@LB^g!r5N*78TN=Ugl$*#f2@zwExU{#j2H|=VHpqVo z=rX?dQ$Oga7K-q|5~u)pYFk{Nw%;>d9yOt?bu zvcfL>A=rQ35!14C#f}mmN8E-5y$ec9S^_ENwx_EKdLdgxKrw1PzGpu6JH6gdPe{l5 zZ}9ss>*AksZGqd5S_i8hUS}~!gB1xVy!)s3FP3UmzxyfAH|b%XDyZiTVW(q%a0m>G z$V@ZR$$+oU4;1W%gfR~@_r*{MI&S3u`QGg0tYPY7U~u%}5Cl+~lHjx&GCqejumqEd zA>DR$tbE3WZttpq6RD}B;`cSEds=C0t%FQ06o1)fgCZ-Z3)TPnUE5U9#`-uJudf)- z7AzT2Gf0o=SSX!_McbQ$=K{Ird5;A`(^Qn|@a1 z)HN|SoQV9$WcRgdC>Ji1re{sQBG@1X=MREobdWqM{r<>8-d!NDb^em~zvL#v1;%gg?@a4tE& z@~dg_XtEe?DgzTNj}(e0NdH97q<7(ndLac5|KXFY=6Gwa854(uN2bnw&WGqv>p+6= zdHjOU9H+;BoJ5SLXcdhqmH|nuxU%BVl>glu+|i8ycy}co6@n`ZIN384&}$~g*E2v5 z>+#)`h&IK)16LV$o5NnNbZ9tMHuEf;lj99xcmn;#*afi~j6#;m(;vNHe*d3hCONX` z>*Cn2QSbV{A&OIr#y$M%nXsgd2{EQZt(M)bffbV(A(*;=_7K&k}Gl76f{T{i&X1S?`jcH{#g zU7XnBI}w^W+NUiSkh6Un(r%N$tbwxxeR8TIcb}&D#d`(NC*<*+?5Jpd2gDIU<&tfm znaNNT7%Y46cjjL85}*kYhnu|7vbE|Vc}0#_L*O42hrtnf9MbIf{Pd#bgG7M5FZ8ta zhUoF(m8fomue7C(xV+`LvAn6|c`V~^;o+1vFq&^`It-#=lpzXxIyVD0^9>L{#+fef zyy_tSYInH7A}ZK{jgC|IAXs#`SM+1U_+1hsfg-2*2sxKUxU39eDna`xu%8KCMBzta z*JiGL<1hsPo|QU1-tz^gGS)J@URNyr8grohuQ>mwrCnjr+*+1xww7(U*@sP4cfcMt z^**j;z43UEH?WpYK97$%D>1U-G?mD0h$y*XI|4n@X`66R^!fdG${>+e6j?h66Ls@H zfJglS1Ys*3yJzYMZ(&u3Y9fbkj7=DBns)baT?-~=D*_5S2 z5(v=r7T%VHAQoV2>0BP(cho1C_57;P5o%YdHU z>UEQngR(|WK=GA^Hm^zAsbDU8EU}f{IMHD<5s5%3a8a5&SMiqwN$hkK9tkEem-Ij0 ztong`+Hn(W3acJn?_z;ogB=4JYR6&qMCZ)JBaXD3)d#p;nV}vi|8&p?#IaR;cNhgR zoC{M34L(4V#<8-Pgv2Z9|b0+z4@DCRgL=D33#c*#G|lHoXzvcF+^R)#!Ly@o4sHI&nX zqJ;`^`a^e=QR+`Wv40!2Cv_jcNO~vuWMx!!J_;!!XZoHk|cWt z%-Yd1uvlE0ey zuVmKH_l_|2qpKO6#{A?$vLo~OiX24#OV8|di~eDdRvtn$Vt81 z1qKl{gtq+i)Eb6raTC>BXo?Xfg`?kAn%#bYg&C+}7kx3A9vqN1eK-A@D`bQ|2y1K! z5$q0QP=ODj0!x9qI+y>rX`59^`Auhn)3FFiV+v)$KB&hn>%Z4M-cmi_=D&fx>xN{|PDSzcTdIqW*E9Og6>Dw#d%dp%B zi$^zY1GyXwM}GM@h5~wCghtBvTYVP|JpD_m>R%7r+=?-aKw@USxdkzemmMT2?$-{9 zrWKjOTu1S$yjHoySJSAu`qJp@pG??GeBwXcb;QU>J(x3^@?5Dnku6VtgA10Wi_pWMOiG%Xu zA?_R8sXsgGF6BigN2oVSXxs_zXG-M4^BUk2P|_>XtNVuxNgsXlm&jiklD46>mi--0 zEC5{^;Sh5-qzOXS$T)ahgL)$OT=aH!e0PD2a9%|m)DgiYi-S|b9%%FMkRp%mrMjBK zgCo7~!IHg29~$TU71@l)?YQtOLucQ1-^Yl^8sI0yj9&awmbSmI0>~-8e~&`+8m6rx zHc$ZKe8&CpvPg8Bjp^(cNAywq-y#UCg96g-DuM6&cAlGpgYs6B&AuyIT0+n}iaqOc zyks_O(7(%$gmJh!x#SE&p+FrS22rtN02I?8;-~3omBJ+9f;m3s{hPpb4tBqW9=-oz z3!gj0+QDb&)<=_x+B^hLaC2(~{yD%vLPabyjJIa0)W0pxyt?*^i?UcPn8#UDQ&Q+xDO1}13l89T8}qa1Ta(+}ZY<&7reSOddJkJWXe3talc5=b=RT)$B8Gn)No%R zlRNmg?AhAyO%`~81HBWO>H)xp}4LI2M>)6`;T@X??b52C;Du-M+dZHc{o)wkL+w7yrx0$g`Q%!`u^lY7d$-jHE{fVQ3W95n;4NO ziBBQg$FBc9tDI7&zMYqEic%GQ+yYj{j+>P(G|t|k-;DZTjhqG~^`zoNUfU%HFy(-4 zl=b_)lFY&mlss23`pkR%NtpT8Uebft<8{Szfjo0S3z5739Egf`GvH1t@+uu+rN@u z88}ZIRJ0%edWkQ5_IWC;JDBnPw{)@!p7qHCFdK4!a5wPZ*>(8Cz7*|=zw8#kKMFtg zaP*UN0xSk#!EHSKJDJr3=JHhsYJi+e0D_wA;LRW2&wt2yrSAW&WBcv;QUYH&077T9 z1>>YXfc^ALx`p#Q{gbPM*#piNCJLtk>T4I{-HVcsj|zU9>e7*7Nf~=8qy|C_v!lqw zTW-!mL^Afl^D^9fqN0&uRd#R5In5wvXT?%RAEh#WZ|%M}j#()Xcr4J3y^dhC4rql5 zFt?4Mmcej_D&sYf2Q5bac+U}nH{$*}C)8T!z zI5uc-L|)gwZ0w>l=MPisK~l{s5Xn72PG;o#2gaCDiXmdD8aHVv}#wK zW1AABgOpV{o4k1FO0YI(w;wxgAUX1s1>M`F-kxnXJD)UJPW5dMzXzV3WDx5c zzmF#S#U$vw2RP3U?7}42T)gzW(=+?Ok;)mEML#hQ3#25!Z>X2!-k{#oKnzWEx-4V0 zo&NULOyNWXp4Vp10lcAoK_U3%TP=0$EE<&!(<(OVK9vb+mHv7aM(L$0*^kL@(!XyJZE%Z}?UN!F@s6 zV$7O~FfRRy%9i!WRr=n}+SbO?dL^U%dDNb_RPUp{y7MV8rTTO^5+*0RtvHUAfOboV z^)6b)lt!at|Klyt{W*(c!F|aL#O2$EzoLF1)@}&qDS-s=F&$98G|6K)qL#gMV1ZkL zUxQ}k1=s@Cfm_}SDx*#}7|d9Uw*XG{OGDBF^ zB(_=jpPlJ=(J_4k-?>UQbz0o3%C5*UlGM*?aF6#*93ns9;wi-&X;LofwIcHH`GTn3 z*O6S_T;j6R59opXhMtEd)>YqW=W-{rgK?l@N_eumnUe_d`7oDaIO}l`Bnpmi7X+s4 zJxr5)vK~g7Fp=j_UbtnlHB5rcC~ifYMl2i&UMCz$-=ts%U7@aMqt91x8@P{>I6@r5 z4vX{Q6*xzPxlxqe^m8W0?krV8A&@{#b+|j(niMiosaPLW-om$dq3raxrfzZ$eN0yQ za0{cz9K-zL$l@5kCFuhc&ms|Q9E2Q)U}B5o%;hulXx-gA9HlaUUP|<`2&9>eijd(Tu{lKRbrpdwl5ED)2`0uTPHTvhEo%mk9U~J{ zS^54ub=_Spz0v0LUyAl^+Y3X#@{2xe-a|2b85SFjFBa`v8+;!Ncj)eEME^=W_t0Mh zxSXDaiqS8{mGvXLXEOMb#VTxw5)ac)kT>hYR~4!@dRqM6>|DxlBaq+9pztrM3)D88 z0Bex2mn-=C!&=2{=c~DW*=4i4(X`n;Zcy{+lrtwmUA+q#kH_qbh5Hn!zC;9`Rg7dp zwPWRZVXk|+woo=SWv4P}#I(NL4H^YzMZx4`S0)Q)K!kk5s2r2LwI!>ID4(%dtnv9I zSnI#D`h2SCW{h#E3bzfS+=I#jmcb^7y;LV+Qpvb&tvmm?^Xlg+<@^MV6dlvNpSCK z8#KOs2b(?+Q78W)d|W-u2CiHe)lb78pVWPYj%ue`R(wFai(#cvz%Zl%Z5uSfdVxFl zOM;uy_jdioJr2yyxg|f3c7Y5GM2llH38)`9hAm&QtRI1*WAEpGt8N7bNQ4CJbRXGZ zV4g4KrNlLhp87D=&bRGm7qyc5^IG{pw-yjX-ej1(*Jy13e{BFPB8@V^o&rJO&Wc6K zg;JiHaJFoi8>quW&weI$-$#|~1i0zWm5AFxuQ$mgNvsJo2HvLAX9i1obW|Wx&rH8u zgFXu53)}%W84<5j$b(r~F5EP6CPI3|zvqtuX`QA}G#IIe0I5%;YH;j-8D%;U*5VoB zoVK}WTl&eN*ju7fu%+GhOuI427WYH=m{XSl-i=Kk<-)?J7LPQnqHK=6T*9jFasFRiZgqs#X!nE1Y`NY?A%(^8=~xim&F03b z0#mt-RkKs%ZVUe<`_eKp-k;t+i*2Ib`~;VTIu@MxDGMZnYwKM(D^dtjwKUyPMh zeUirc*&MCrxa9Kuv^&-i1S<{UY!w0)7Pe+r-0B&=c0J=w7A7d;|Jh0h)!sk2DmK0h zgr|d(&~$6SfNY=4?eOO?!A^vtZcXpt!BTzMRa43&>gH$iFVlnXrCj#C}rfP@BN3G9NJcAa{gv@BDgO!eRu;Q2iseAJ$` zZ$9F2Q9;jLZ`_O#r1ad)A!L5vxcD1iUW3&cf2QK2YWBU)jLzq#Zkhqdmjnn9q)zU0 zP<*s$n_%{M@l-PT&cdNF*?pjkQ997q0^Cv0bj3(8@%7y%TfN+(2Y}woEi+Lk<(jh1 zs;S7=*?NT{bPd!3kjhwq=vAh3*+#S2Yx2l_;crqQY(SGTFY?akEU_u769Bt=2*XIr zS|EBOVun!2k5;Q7wJ(wq={gC=uqw1h?EgK-8tz1mXETvYxR@wXi3B zp|Fjnz-C7tgSX;PJ%UmHT@SyUJ%qaORB!mfy$6Y&=@TjZt&qw%fnTV!e?U0ST~_E1Mi) zDLI0J<4ADsr~dqz2;9;|M~l3z**>GEY~7wY_}li>HJ%f6MP(99PxZ!cJqF?Q< zrIA-72lveqaL69O8SXS^95ydNc$-@D4~VfweBC11JM{Sj(2b*)?wQLcj<PM%1r$6ajZLUY3#{z!6>=Kt^wYqk|x))Strpv=eyK z6Lg^|SGFJ}b zM0lJj6i*^M&?;E=V7x^8O?1+$SE)le`-d?3WQxd3m;|CS4(mYaA&WMM}_FdS@5mlNbLyf zzt8(%5k>dL!85^zh~w13;Lz?3)4EjfmR4Y}G|aLD^puzb6&ICosbj&c6*Z3~b9TQlHdni3W z3<Lluc8Nn6po5Pi=os+8#=K$MZVHs6&4s*9W9cK)AJ&F0i z+>MR%E~Wa$e2dZaWVhwVzq70Ej*Hh<%fH=hmAa@cjqy1%z5sjP!tc5a&5tQ+L4lxy zd;{d_PuTbdYv1m~c6SzTu2OXkDv#EcXjjBziI5@$BcF3T_=RoB zElk8B1al0wV?lXoc4*g~7Fipf))PdD2+W-^z_2xqw&dI$eK1pMaQE~JxMPdAfBgfN z@e&F^13U!5p}UJ8&r3|B5pL;z{~G+f0Mq@YaQ#Kz1yt5TkOxV%iEq2!g?xTzy> zFjXpa*LvTbgL;pB{-pn2$PF)TAE4i-cka*Ls-fLNt-L9qylQV*%Uk@6RkNU1PQMJI zdVnaCOJ9Eam#l5bNGq*Z1MW*=KaEinx7|jzXk@`fA8I;S%anjPC8TitEzdmr+vpT- zv{*?GSNO7I*n^Hc%?vOjW_ySUE%1saBTJc%!;gs~^)Tfz4IAjj?Mm>?w=opXk+tih zLsXUucPY!>ZXn$CpCYZ(Y+}$OP~zy-AZBR5m|t8AAPQ9hZ#-Y|2jX+w^*A9)Q_4WB zKzf+(Wb?g)4htp__N2j!Jb(9|udDKBlIlj2A4zZvw!Zbs#NhUtk_#yO=CW*rrQ!G& zln!fBfsGqvf`Md5jUOl%zAS8l zqhZz8bpD(cGg?p3nI%ycScq|E6>zK3(Q7V~z1d1seE;fmD+~?Q2hSr?4ig$l(1v^m-pSf3 z3~ch`#Hqt)ozd#!apFD(qyL@QyI&mLfn;+CI#J7k*e}6p49W%ThhR0rB8vowkQk;QWDbADV@>{lF}{RAl(wu(nuY;yFzn~cpjIfv{1yg z(DTx4LK8iGVPSui!i{9`a2GbIlr}EvcUTh!I@0eHYO&9CYVX)Hl-pgEd!uQyT<4~Y zUpd=Fo&7XeFLb$NS)5r>Pf&Pn^giATS^h>^f^fK$t7}v4QXjpva~qdICKB>;cCKP0 z2DhW|78yRizzVe)9p>Mb9)nGyJxZA$~!z+j_;c^#hnbsKn3WRzZJBLLNeZUix zkO~StNx%sW3jH|x;{;+?gfBn6cNwjJoNL73-au;%!S_-ppq9&07Zb9CJTKM*Jt=TY$@D>;b z45fqRzrO`=ihk;W*z4k#8-PXlOk|8wN8hB#UsUj>{IfMGCiK-JbL@uoDusesfPy*i zcOcV!*Ll|gZaZY)TG=QJK2As*fNu**ASz0G#+Cq*d3J+jAx#wN9t5xCjN|I8=gT5l zT8CC+qLdG8+r+-V1}D3pO4-8PKEP4Usf5E8oIQJuIrpCuX?4))n;3q0c|O)}#(T2O z!7#<@CF+h=j~=M~Om_38q*LE=;|Gvc!16H*J8dA?OF^-q1B2mDrP})^!+)FZ>gLtk zVEBZocaX^xPpgC)d~6w*dJeB3w(OONYcPktV|gPVE^lduOX|w|I);1!qC|e5>usxm zjg!BOM4%R{9#_B?Z-IvZpRVx+d1ISmFpNOW1BM#I;yWL~r5sEIdlNkcs~Z0%S)QB(KAd%>HNsvGdwaKrraaN_gzPuF#aN!fc-{qW zND&b`@dZ0_y^uYs!>yU3+}{GKFVC+!)R4}a*3({&4KuquE@p~~9;((LF`_`A(bY7d zThZ0!uxr^t3sQ=V(65qrYOJr#%dcY9RUhHeiMMsS{KtvOQhdsi|8?1?=TBwJ9vC`A zK$~A4SNURM!uy}>*Nc>#oO66$gZpEWMH+$Y3>S+QZWC)`*C*>X{~8}ER~xm|lbQ|% zQ6hohqFrMut?y}dd3M^cmllG4{B4sKL^_(17b8LjND>oIH_WAbTSFdt0!NXc2qec72BrrKKqCPT*VsrG=YrvD)5!;XA&{?`t3^^Rw;rPf8T!VfARCJtG+`+RXsnu5dZndarwxk* zzWWGE(IT}lg0-|k*i)rqteFYOHpA4EIqgZ)l@VYYTSK(J@UJyxztTf1x0s zHN9p@;{92oRKsNnpJT+>L-^+K6k9P%^>+H0 z6g{pP?+5y2C2ax`O_*zpEHmUIYLY+2`ghYiaC>aR2u;7Ar|x?lYq0>C+OUO**yWvO zC(w=xjAo|$^{x#DC)T!6?cLX}VYvkS0WfvbwoJ?KFzs;EmXJbq38a2qNu7>mgpw21 zAfRLIs`~4akWGZb^D1l#dC>&?LK|mxi&Ail?U65?FkP-Kgi`a%X%vD8R?!8|bAbDO zw9fME9b}f|IWP#~_YH~hha&k#V9EB1eyVkUgn1#&X_tIFA>_+3_o=Y4Du{35v+B44 zEQEEYjr9!c{P=scj$JDznwN#3yClWT)@qVTo1f!tn|JuE+Or0= zTed!A^8pe6%(}$A?i1lrdInZHaq@R}mMUg0e_bY#q1U=ii}re5t+|~P_a-6o+`4)? z+8Ui5U*%Y=4CB>v_E|^F;=9}!#^uul?e{9^!9B60a&=`+UCTg4GlgG_?WCmgY`Wtm z!v}+;-vBlknVPs z;pMI`+um;i(LNizZD5kxU0d^Uaacnh)vEYxd<&#a36Z0ce314v4p*%dq#FQ~bRU4` z<$8A@P3#2kdm5(0C`GH3yeD7~v{D^{1_rIKz|Ql#wM3}w zeZxFa6NxxaUID?{J71IaH#Gue+jv~4G~kvjiB0-^@-)CxxEdGz_#&}?026G z9;fBN33qVQ0~}Ct5{XDQ;~w}Z!hqIt1XMg%P>>8n>ZH2nT`>R7ZfRFdsfNVkGwZm5 zpYH&~zM#;pYo$px*qGd|@74JI6_gP~TZ#c4im^3>jRZ1k7An{m1{MN7roarz*57xplB=6=?Hl=H zr!1oMo3fd*^{9xp@&m(|t;Y{Kva~>ex^WFV4dkPPJ@@~Nm9RN{EZU1H7s!5Ygi1|* zjhJ*IfA@ufRXcoJRPkWBEuQ^8ey8ZPrE%v2B(QN?fvBkqOm4s%K>LyFQ^_9!6Z5J?qT)SKGN4g8Aj=qCG{?g@gp$l`wT|g0dGKF`afMwO$r_OIspNv zyI~ED`E^xly6N@Yk7!=TDwn#a6NmC-lCo9b z0ZVRjLIm-tm2MIF{hfub%XncSO|YawU^!qE=e2*-wkl*A4XCG_lAPo8Fnz~u`*&$= zKtnx24thU)1Z63jQ<_GyE-qNTAc;=O=^@$$>jM}K)OM{cEWC;EU5wRER||JqEQWP^ zPo6)!S}evx2152`YE43mux;!T@pSYv<#luOPo`?TCw%J$Pq|e`O3ODa8ta)9QtaLd zuDWx|XK~uZr2e}(nO5??`20IKMg-wL+doDJ6^op*kd{2r8(=;)_tjBzu}eR(NnVJC zPZB8un?FraqOMV{d?f>8EBMpugL7Re2#z1CwD%2)>mEqrOhc8?L!qbZ*)>_#J1`Kw z{~amJHCA@*s$3;s`YV*wt0XCKl6f)H1OL|^vqWjmtD8C87*Hxy%q-&z-ox$W&rpOM zl;Z_TDq29j!3}XE0r(w*7|;hVsHoNi@?ZY2!^t$E0WhzIxog|vQc;dT`k&q?w{ss5 zhQEO#GDGhR$-Padd+kbD{;RPMH(r!zk#xP}(!MMg>RB8WxotS1#i4KzWa zN@t#_NNZk0ilLXLx`HF6LhC`6Qi$PHaF$n*EtwM3!y&vhMiQG_=$1w2f9;z7+C}v9 zr_{`FvcPs8IE)~OVyLixhZK&p?Jp_byanL-Qp5>kw|G@Eg0=UG94HmYf?Mp|59?bNh$FN2M`~t3D&SMViexVpGzw*SyWH zt7e9#z7fdi{6PZj(SfMNY0-*p&4mp$T(o~B6=mgIEY?=We@^<0$~HDq`+Z|dkQkH% z5<3ttRNsEIs69r+WOyP85O)3B?UwowvI4$@k2{9!4yHS7KI<4{d7HttF6kVX%tLmC^KX>`?fG*@!lD?Z9Pwd}Whxenprc#1$3pDI%+-Q%Zy@Evga?Tlrm z-SeB8>1eFjM^}&dVtL@|7j+xtu-4tJ6nnEYy6e`AkZN0{!MJh$aO@y_buGs#_%f5$ zaHgf+y!bb`{!iEjd;pULXX_jyX6hrLvq4cV;L!1JP~>@9w-eRR4CODB z4F!;=qeL&D@D)nJXa|Q7Eq%8{4tXUk+nw81MLpPkw2-OLc^LDZp*Yac0Ie?k2hu0u1!*1$Rb0_;F^hX(|_3jYerkpif{(Z2)tN`RX40q4uBAIzYjeLCH~RhBUy z!T3GTQG7JtUJBHS3)&ZO@?wQ7edo~)i?|f_d=bIw*#W)~(kLpGyfFjSVtVvvN=W7K^B|bwXrsNK1!3>? zf54~JCQI+B{YYIHC}x_rCeLFF6>&>4`}ErthMEnw$Kj2oIw$3Ta<`bN%*YC&pEjXx zJ}+yd1WYd3FX&i@fxx zT?yET;GG;%?F?f5hfnqrrV6o{lw zI2^YNoI3u!e~BpWmVF`SiAt51E2=Im;LN|GW0iX**3yk-W|&4(mK~bSZK1!10k^X? zM2vT}cB|+=*~=HJv}q*QwuI3-%jZbkaYF&r7K=j+RQTj~B*) zX^5s!C$+CLX>TV}!As!2;Dc0jiV=lZ5nK4Jt;+3xcsqV@!q(Y=C*E7;GXN4J^t`RU zLH>hs7)9?+;aM^+5;tXMKkQIR2=f9H%UqOy;Aar|$Pg)wm}IacED6H<6ojUw)A{n` z4%ZI_+FwR08~dQT?LXjX`1vN(3s@Jr%1Yg;`z~cL5o{-FZ^^#RFE8 zqIBL%PQkyImPsFb&^Qa0t4zE;H26LpR3=V{EDhliGe78=+EOlCu7U$J8CmctV9HiL z48}J&SZlk3ioB2y=g|UxJizUOc(5ZNwqbd z`F{wg0UqT@-f$KWXCPh-N}dwq{YB*mv8taU5QZ(t4Mki+-Gn{i+S3RQGVw$~GVveW zq+Os=8JH66LXFV=M0lFQBuDY~At1RVnN;$jGab%kvu}_kr*YSrC# zqG3Kc3D-PwgxjG^xBbifWuZ+&Ci6G~IJnW!1WS{->~#74YXc-yTH58y?+UNNo-lVE zUJD$@uMCCqCH@06Y=vRF{^f!f%v(uGS*0<+*`{5bb4|M&5Cnc<#?$~C1j|NVVJ7)! zu zUN1qQXDu(KJ66r81UK+!5AZu-<@IwDx{_>ku>|7f#OdtxUG0Xhs@$pwJi*-F&Vvnlc5#Nqu?5~Q&y$+Bl z3(l7?8*RL-D0@{Q*)-yF6(-gvHzGw6!V!}Cxo)Rzz;WisI>cO8?i`#q*vo{?WvGs} zBUv@Y>~hiH;##NIay3A~WJ10hK6m|RwaZ@seFI9@1NRh4wb+U=KR`B^>wE+-){fK0 z)$=x^IB!`as~~@%7Y41yG~Xkr*qU{kH>(zF@0u$n)U*o zzN2_y@Z^4(Zm$snCJlAq6+u6~=GVcNAT?s8DaHSTpolX46}{&RzCh3Y)R5{QA)qnW z>lLL)4S`FEZCU275{VMHmDnoyjoy4b!1P)PELoZ`C1%{EfQhTIV5b@&SeTZsKj)+N z&Z7d+(1`@X>731g0~I9LA`|X3f-#&SR1D%E!hldsVD%RGt}V=&Nc!!v^bMsiQcjoY zwourz2PaC%7j1uKckT0YYRZ6Lc&L0Il49S5d`Mb74TBR$TgglLR4?y`NcYoEzCVB0 zGoqm{#LXM)+UP@w8GrHR3R=vrKg$3$$BgaNZ^)w)wuAeLdeQCNg1tg#ecKq3bj5RaN1o{QldsZ=l+LsL-e86Pnd_*j%FVTZ z4s`$1aYst8LZy|^h%@Jcgt;t5s_YKF#`rqg8myY%C$<%E-g}wLH5UT!n>{gYTPZjO z`|NBDva}w=fcWMp9{vfpaq`+g3=@lj@6Pm!>e8I@+)M^Ny~bk$`OWgS{ACl{u6~{5 zd}?3;Ju6e50SoY#{>t>VKZxA|NK<pucN-Or{AnN~IRe*5~7nB?g{(C7OW*R+`1*nKQ2@mgZR7WSMnHkbhd&nPHUy$nXh zm#A)WctX5R>6qNnm&UMA(f6@?sBznVRikE@{Maj+FRiqGh8^l!a+vk_Y%_4t0(w7+ z`|koDI~1?-QJ_FY+qaY^ax0hCRovhh*K<1ZAth=xWw75~xU5ebYsAiuqg0wN0dpo# zxGe&KBn;ZDwtiAdO z(jw+JkR6bmtJwx0L0YkyT!J>BU}NF0W3{p2#mZu@28%$Uu=;V#NPbu2JTJiH*8w0^ z4D8(W{urre2wqb;V&GhYIsv-9egXg_P`5jM8pwg}whG2jP~1^D)%o)L4+PU+ppRn7 zE=L$MQn-A#o0JiL`byfJZ5f7O_ewdxxlT+E4-zc`F#W3Xh!@F}Jb@{mbKAUgL4;H`yo|*U^nrJ3NgYbJH1;VmVVG@J6P zw5(As^N2K#;FgewJ={_5_N&|NRuWlcTRSVpp`BLO%FeA2A`AI!4V{%|jN}41>@a3H zO{>A|Sj2elh#s)%PH;@U@@!mosdz zH0rj5x{Z6K!^V0VF74{l(ox`VmpdO|?E!dEa}oiKKitNBz}2_Mp_`t*!bw&+PD2<6 zXrxx!RXNI^m`ch{)V0@zbk$Rz{fnZsc8!>kNFr+Ad7Ac}$Bi@F0e8a4t2>c;yTRKX z%LAcSp9|FNj=QSWKb=>5cB>0$B;3`!PvtzJl0q$?V3cFyUB+*~DRtFacU`-=mPX5W z&WTp84w!)E&wSl~f#Y_fluuD%i__BibGD$zt-sjt5UiC=@+fsZ#^*|iAwXRgtkjv58jsfrrPd+~mw>`$@e!upuU z9zQN?^{5hN3s0**&{)f6eF@K*oE1{-O_;G4P&-(MGgocF&EuCcxzPmBr6TT+@K1pV zsKDOE(bPlJq-J9;NaAr=L@}P z+%B1(z!kx){V+ySyn)DVS<}Yz^)1xT2OhjqXVr!TL5Wpj0t%UfO4F%hw5STfIL5s}s z`^tz(qgMB`XMk-n1TrL{7(db*XIt3eL5vzq3I9PSU3>QkfT;C{&+rnH?w-6Zz*SsP zU3JEZ$<5N3UepnnAr{*54yNEwnSzBUk+jKko|~H^V6OS8jXLf{jcCM8nHF){BWKcU za7%;OkJHG;;Bk3Qf${{a>o1K;;ju&zhHXY}6gTl1M+}q1=i~rMS&$#+vFa5u)(rX1 z)P^ah&`KP#e^3fdP)S&!V{*gN=eLgoe}#z6Q=Y*-g77Z6Ca>tDq^{VER$NAVpJm!t z+nErtOwQ1dHu`F@)E`@71tQYSQjb?WOMjJn~uNp+2F49JSHrw_-?9c-7 zx&au`W!0p7O(wE%6NkxUP(mQv1@!nHw!b^6E_zdopGCW2tfjw5)>ETD5j?M)$61U0 z##9q!xKKP{HVmIxDUYtLGuv4RU;Aq()`Hs=NioFq);P`#A+OyOFZv)U2kBQVvDS2o z{StcI8KwNVRNBDzY{y&-_TXq4G<<`LBm;I`8$3yruV|Q8ElcX3CBig*Aty(^a+f_& z65i@AdJ}5Ioi~eCN23F)c?K@}DsUQ_H@Xab0IbU!#5u2ytd++}2Fyx#z!)HgL<@sI z4*{a(3!soji44-*LaWOFHP^=Yq?{XyCj9a62e@?pw4FJhK|%YhFPE%8+b<)e6TdHk z*Hq0w;H0{DLinF8?Ik#HFg)v}exk-il^OlU`vdJ`9u`6P%=MC-TH&gw`tyI0dR-S$ z4p7h`G=tKh428u2BXHN_E^GO50!5T10bEV8LN9aU`)qk<21Z7Thkht}2zX$;fkNN; z@^m(t&NB&lh0ZH_oIjlN0{-s=y#G3mfZO!$#RuWy&FXDOp(;_dnGPMzoC( zw>ZGl%ulJs>zBcy^yTe0VL0$4c1(EA;^Q`H5Wp%P_}rI6G|!+F!uidZP4&IE3BI`P z2+C`5+fXE1vo|C&nWz!7s&g|l%AeJhHS~`@qj01Zysx7v9L|;mU6OXo5VUeldt2Kt zvyPwFE58-@#_%5Oi@X4bp@NvM^Np(2i)eSZdby)57$)xlEZWRQZu?#F;q|yRl85v8 z=C44#N5QA-55VXCI@JAaomq`;_DDEBn>1wB%zwS(n}A_}PRh8@<@xNQfe&y4IcTcm zMXlK_4XJ!@yE~X!NvkJkRtPVTlyi}NwfJ8A6NtTDBL=5Bqv=_to+L~mJIHmqao)e3 zJXr?KcIp-S9g4b29cSKW|M>TP?v`B+ays!1|E`XwFW}-fCgNHW5xPszsjk;7EFPOe z2J|Cm=V}`YDx42zNc6ohgf9?^fkL-5S zz&tKn9yK9H87lgVsw2bq(miNOWYfx*8v3lkzGSZ4H($IyVb-LG`}{UIjTgH)E;1h> z&RS?hATC<+L!R6LNhZ8*j>JTu{|@NWArUW95q~q{hj?GXK--hQr%fk98Q~#uH%Nd3 z_x2SNdm6-e4bznTfWyJ{bwU5r1zpT%MczIFqq`*#!?%XCzcHq-PP$L~kf>C6F)-|Q zL`KP%R6asYw+|jFo|t8Q*g z#6s)GaL#!_!@JKgP{+PE*eup&PV!}YNf=k-GeW#o3>_A5XuG-O9Z!RQOY`g+4$O@+ z>D1G8`rU%4ir=4>{cBNZ$te^*)Z()L462^ATb#{7>y9j{gET>3=`vlJdV$u87iZyz zzjMXH=562|(?yEA0_iVPJZ=yW-9V58Z!VprHUbht4ulg-X!~;AoQu z$z2=iiH7%yLpHa_jK}mDIA0S&s;%c4q9bIevN^aVa{=%q3Vx43MP|=34?cXi(O=iR zvO@wj&;NohZ_3J?nLM^8CCcJTRQGG#@8@>x6G7bOhWlM=+AM`~`ZeXvB}(Bf*YBuU zyjnlOwJ_>&Y$u9{hcGkYeM|-txATv$#EKUHk<&)M=%-44F{MXcJXVgsZ|n1vcS4XtN|QCdsWKr5{a9xL(6@Yu0!Ww z;@MJ*?PWsE_t4wvrTSg)s5;o&DVlWFw^tT$E~eSgGmI^$-<4DxsDD=e6I9n9J=5tG zR+eOem^QmCpTVoW^xJRaJ2(J#FdKO7?)rf9$Oi4LL7T;HqThpQRZGD3ME_P155E=V zg+SlTOhLzlISL1YTcurabn8pCzLL;?3AV<2p&R$hvy;M>?oGv=PXC7V|DDwA7pUZi z+AURAeGasQmFc`ckq1iyWavHe9+#&<2VK}(g@TJ z2qGZyfs(kbFcAb1CYV&*$)C=(83Q#GB(~^6M+#=%wf;V0uPP6U6zl2#9)JlqpT3Fs z=N0!D-u4B7OkWlA5N8iXSi!H49Xb23G&tQw9p^GivPl!UEz&4C(v4BC5w@qJ#Rgfq zUYR2s#YWQ;@BMf2#hoY^-7}cJcWfyTuB?4*Er2_Zkfg1fRxzWb>wcHj?;aQgsyR<+B0ft^$2v;H zeEp%eS>;Hm3v3~EK&3kcznNCXs3Bm`d?&Jef9l{T01CbqN-g>8pvG6I`#7JHqz$Hy zyH>K9(;+(UKDxUH$_0e-7WQDoEjxOETqkU^z(jHdRS`te1wAjpF}3PHpb=`>gR~MD zucTa;gE>)L@VDf{q67z6qF3paQrL`dPnO$%NnY=tg5SUovi7}!yYYg!S`Cf&5j;VN z3ZI!h4#+Hx+dK+B00!6AVjGbuiXu%$5-+_gm7dIje&1`fc-=T|njPhtQ#LufRh3B` zzAZn|Kzb}u<(|;34#AyeCU^ot@u~3{HT86Je4#`CfEwu43PcL+rQf8Ow$KcGw(mQ6 z5pb<2tD-Mdcad{GL*ZCS>md<10yKKp`&zfk@pTRBBWt2G-Lzt*?8kqozIEVg{wYGE z@8#OG)DIr1jr@V(wo0$z5g^YpMPAk}YYSRj@hq@68V|XxCE9oaw**>+!6Z1tqyk)l zguxKVj>{*l-f;+g262N`6R3~qtU>|~!?Df;~kcIvA|J@1;<#>M5aTh&>d(&O@(RLbyv zKvojGJvj4q+kzC9&vZ|4Hk_pJ`^**4=OdyYJqGr)5+VAkt7*Q1oU zkRqh+(6LJAUVcf`mKcu2yu?*>#ZOtfeqUd@U?2JK-F&8Z7(MFlmzHMB$*i}(3Xokj z;zctW!z5ytV&S;qD((E9H{kX}nN;qP5HbC~H{wA4p`Y>_*!Esy|%MFx?ptBA8GGLt*# ztwLDco@JXIb+{hi2;nu=aPDiy1H3&j0MbKk{!Ne2L2m`FI7d!-C=u`7Y`S(voLSm4 zjWL7?nq&pKdf58|^nL>~2r>UElKo&cK3v6&0WT}E(_D!PsEr`wFbl)-1wP^my%uOi zTClLj;Kz?im!}|4P+&zK>plA42{}dT-dF)akkS|2PUukE1}d+Z^qS8>RhAEk4!mvn z0+4962$&zz8o_8Bmt58PU`;g`5s#Fp%(0C<74*C#Ko2QaNdF4-I%U!rwyTMw>&#@l zh&^aA97!sNDa!Z%7XHNk6f<@vmf#JYzjow2Z|@cBO8mXNSy5!G1a9Mi&alI=X8zk3<nZwPv(LQDP@=?Om33dp+o2l>Lhr1(jc*h_$9yupXL6UZ)m*;Sq0E9u6-^eqdTG7w7CxHP*82e(NbF^ z^@nbu1J{Bmvi6UIv9^_Y=uu}OjmF_!Ep69kDMIcmE09y(-o~S)d-EZ+2t~K!a zDs1tc}5f;uEV`U)bBf z^Xfb(M6Hez$?R_n8De6#tmV)I`tdcq!FR6JMcT zH%&DeWLi_IRCHkKX=_cP0cz)Rsre%`J_(Zm?=cUG@+6*K@gD=1aW1f~eHx-Y0#d5x z+VbBWaN7hBg%Lrt@tM%E^Y7Zlrufc7v?!U+VIZ~!JPACzVmA$jUA|yBnx{#bx31Qi z{fP8B>3Oy5DgE^UXlCpH9_XR1fTciDNI(?95Q?G^QdV_X>cy$`!*`x_kB>j)WmUwA z6gqxzT!8=pCJ}TL1hV{Vg>Z{7>@PC!gM?GwNgBh2(|q7BX7%1e4LVK*sT}S#Qmrp* z#M{tL^DonRKv8!an>kFW4IcQ9eC6knX!5OhW)vyk96gbcLq?d_b&)b%4ML@|TiOXvJg z?Rff;YGR#^kK*6o`xAouM251u7-w(%T1;MeF_T(#6M#z!|E3KvR*rxpBqR8(lIh1f zdAf7r4X{!(K6)mWrxqem^lBTs5PN{wM6cXL@(z)G`~B_eAMllFtfA4L;`Fgto=9yr z*LHLv3W3?Yk{LMV#gnbY8@Y5&Fg5OT+_u9cWfqgBzse4kE_H;tmIk@_eT zcUefoWoOp_(2iN0Ze8(;LUlH0=o^Cj#}4h6nm!+~-Y{3*=(i=G`E8Qs52D8xG}$g| zrunv-=6)+f8)?8($P#?YQ6kmRn`5_k+Wy5kOL!Fn#54ToLtRXAUP|E~fx{inanC?+ z9^7EcX;YcWV@vGcu`gAVV4#I&g7?SML)FlhzyTa^E2#<@khfJA)OeYl_{>*<9;L)8 zPPm2QLao;_A8lbrA@+^)I4=#ZsGa3o2QM&3irkbcP5&y4y3+|4eeX8h=63u(+oUm5 z;Ud-_t1dzr|FGIr+G9rz^UdG?Uhf5v4N2Gk)Fnj9qYs;AYN!lejVt+FSY`B@vxzN< zNZX86@-30V$&jcmaY;R+px&pPJ^y?p9-=XRA|&06V0?RlG@5wM(bJMQqJjfb##-kd zW~B|(p>5DZv}|$M6qwEF2KXV+>xh7MqJd41 zRzab*zIllVE>%&>eU>*_F8%|(OE4F_<39Y5y4yWDTF&O2- z24>3SYBL#+-j(Ve@wO?%xMzSWAwPwBFu`I79d)5=CqLH1vA^3l;7OZ~k8@x~vz*BA z{Dpx38EUPG)0enFc2JI?<$}F9)EdHg+H&OuCIRFfKikKg;8qY@1)C?SU_MYUM0^EF z4sK0QOsL?}W6v=t@(@12V+JlW5x<%pgWJoQTF~jvmUn#1)R!cpxwy>4jWYlzjVC7` zjz`5OE+^RRp7CxRjrKDF95R`>V^X4}fLj${_g7TPy;%K*=sC$+4Bm!Fo>gkMnkfL( z#TtRhI8gw+^X>A>*G<~}=F~%J@)zlBz2~R^Nx?mPryDgT5fJl$Lo-gE7?vit$W%0O zvk91Jd+`TxM|;;?&~P@|F(J;uIN}`lkm<^hA{|Y9NS+aW%&Pu;J~&G1d*Ia2?y{do zKRbXp&k##%89apIY~ti+X#OyHUefuhp_8rq-~i2(G5hN9O0 zrhtrwK~_~055!%|fYqn&R~W=DziWmWf3+`GJ(38bUA155Lm-f{og>R5>6mw|XBk#ch__g&ZVflM ziRYvAlaOdlsrF{)^e6rcROv*=OrqP`%0;2_dk{$KbYqhT})%dVMJ+RiJc8F zP05rcjsRQ}W8_w{j~;1EYZP?#_zR6O>)N;U+o`o;7Jl2M#Y%0mb9jNqQ`W(U6Rc6{ za6;hR_Zp3G2TjydSr06L=JZR!)JY}OiXvg^6924sz%d_|hsEUE+#22a!Y4*Yxs;z?vcyR57G2A+lA|MlQ^8ihZO#;n}Lid6oQE(oNI0SHtkiIv@2H1K;aT`!1sI@;!TRa5`l{$N25f=A${`LdxRiI3=xxm)nNx+Jxc1Zw{GOUr!h<}s;Oyl zDXs!xM?yBo%@wX=$j`T4hZ+v{phD|qplO1cei#(eHf{JUX1BSP(K9Oe+NWM8G-Dsf+z@5KhKV!GSe_okN*zfNurx3E%GVudK0isGEMFx{ zCx}ui2a)@arWlMCqz|=Urd3e$q`G0Km_0(-wwH?9wTf|J)y#Vj#q+Z<|SPYkz7)4j8CF}akLz6l5Lbc}uh_KlD? z@8HOQH4|LGHl^&7d(;vBTdFaQvf%Pu&+4dn6+8t2cTZ2hL`=SAWGqQuA37_Wkq>_N zm%AvmE_B1gMSm9#65ckT0>_lvH&KYpjQaK*Q?Xw&|ABEd{hP*3l$&r|9L-{S*+Oth z5x<#X&iuM!r9QuLpssFmYc0*msL3}%=Vmq%A{9g3n@JS}Q4#2vM@B|G)$4`T*aYf6qW2Nx!B?jz$Xi(U6&(_lp}a=ep$4El*Hd< z%k23lhxK+(;N)<^6W70zH&-}Rq0#>Itp$BS*6$YjU3mIXbRMz;TUiyB%QN@=uI zG*vV-)|wo;9zy;WqowapC3K)hB6QwAihwqNl@hqYAjK5ksb0Qg#wggM})C9~+^CpSn z>l^)6Eip@w%aM+mQ*)TZUF#V8B3oiNvi6Fu)_T)b3PX8X!<=wrVkC>Ra%@UD(L7o@ zthF4{(!~E}@0DHXX@S0|agMY$fGe!!yR(<=^6tLxgxiV5M2px#7i7rDRVC<0v2d;( zl-ZSsIWUgAmQZSBgRMrA_#oza6O)aIPE6Ou3%4s#Gndv4Mjb2lnIF>?eF+>DM^`XY zm;_vOBM@vS1N|Al>U56VZOT@@X1d$C$p3PfEB&=w-{n8$xxi!@RWA%*`g?`IrYBth zZSlX4f;!kEv#FPwxi(@6pC`iKho3vb?ZwK=G>19rOk1whTS3n|sv}#1wn_3y45#Sk z02ARt2W^i9d#KegaCh^<1BGZ!I!xmhB|r+4dok&$hapPisr-^7q^~NGQm)p!WyU}ba|VEiVWf&alBh^t4dJPt*#K=Th=)_>l= zF3-SeJ=lhKCfB1TaAi~c^tzj>`tZa|Xa+?j|FZ;Q`3z;|BNorv@19F%o*K5~$40Ts z5BTG%A5EVg+|qd}Hr9Vr_tFI~?DbK{|F`Iy`B50*=_4$Wl_U?^{7hk_n?+bg{;~;@ z4=Sn~r6d3(0R{akdgT-qpLxC7_q&Tyt(uC|w=c|w<|rRD<`V%z;l@xe8;yv&^YN0= zWxun=^qW5D^7H}embGH+#UnIc4&BdL^tOy6cxI8#fIF}gIW%GoHpL{f@^sxah$d?} zqJrMZP+#v9MK3_L|LpKM8ZJI-yL(0>;=!?ug!XtNZ;m$^`0b?@_kZ=2)K-gpE^1(o zw*k>PT#Ho{v-C!(U(032CYDw%rap4IR|!_}w=3Un8|?(_J9h`>Z8YB-ip~tg2HLL) zM6cSJg({8}n^)D>=W%Hj%gUKhfc4cnz4>3lukRt|k&tYDka7F)m-ZQlx|`$`i>_cR zDKtc>!&s}&&8L|3iyT|_7sniZaR#N6AXxA~1#*dA1zp+3Whp1W{cql%i|bxoc%Ook zC7UiH7^{>gDj|X9>jHn8d)qR#x&b|B3H9TNc&EN#Ykfl8G>-GUBu8SUcoRM#w}ET2 zTPEdU{$?MUCmY>xu+m$tOnGfcqd_LFj+87K0cHG*o>258={4u@>qAyMOxzh53*Ve# z`AUxA{uxZ78x00T^Y*^k5mff`AHf3%O6CseZVd<@dY$p z^{OeCT+<|d6Im#gh#yoz!MguikFNmJV0HX0foySKGlt3<~9_M2w z6mYP5hym1?)X$f0uNNTS2a8~O^tae4U}bK@5XJov38e>0!1-a7Px$5WDr1s=l@BLT zHy4^=va7T!jDe}fN0t{2lG&g{6tC5edRt6izoO95K-b>|av07`ddP#eHXL@)tT<3L z8j6Tng71HYi6}DA{S_kAew#@*$nXdTgr-q(&$m^E#no47oK{#qDVsxpctk!jrM*?0 z{)HCXM0O}N_FYVP*UV`>dF$y(pZjkmNdT{g;Z85fM{Iu z*R?&8RU55Jy)LW&&=Z-SI=`|^Dx`DYfZJE23gK8EwG?>xW@p&%VHW}st~%@!y*8Bi zJO3uY1B6G<}lPm2hYvhs4TnZTNc?;<^IzF_=VaZPB1}Ig z*`l11YUX>HvdZd8E?v+P!#sh5yEuPF$1+apdO#~3_3mb2)nWbXaiwAxukK2k&4MNx z>5Ti>Qf{HSf%I`lZbDKL4=4z=Tb!vV-ioL_oV`6+uS`Z#Si5C^jM@Zpxl@C1v;OI? z?Xn?+s;CPfYh5#h6Y#0qJHK+n#p-C{Y*D@J01zleVDwFtxAp~A47Q;!YDMxFn#Jcb zbWnIc%{6GS+61U>RRnVl8pBS_TWXWI%Dnh96Pdmmm9%OIpy688Ho}<-gezsJX$Ywe zoDa2ll%NEPkPq7(o&|TC%krjjbZYS<_1hM}E$fipgY->F@a6k5TBKfW!u9hnt{pYY z6J;_}q!jEkdat!w)sZqRPKWStgMXTNlT3mRS#@{&U-HqeXC!xEaE^bi7zYC--z%E? zqFlI;(I`h^i!iE4YZrvqEZ|8ghMkc84JFUO^k54jJMXm`!bG_$9*`r^KyM%cmBo(I z;dx~XL4#1=sDlba)s^_%fR!O}4a;mv3y3nN1n;m#eZD+3`FTykevkXkCmow}fWA6V zH>Ff^Hkd6wiwAPta>yaBN*)h5TC_@U>GJf@+lPn|iZxlV!XG#WSWkz4T^|dO<>6jbC_HsBF~H3s`m2~n z9p$~yY~GGbSp6vz5udYqBX67SGQ@mTtGcqq)iiZ93>I>86rwM) z7h0&F)b@YCFD8wGKykk1X)7E;%-xSinY!c~_@vE-CHw;DmbF6y&#{Bt{tnPb~}F zMfPD5o}f{LDDFEC79MO*>n zy#Zk8pbW^;X6~#heyvj;S35;g$1Siz)!(N3Kz<(wQ1A_B(R^AMx2 z!%k@^Ph0gI5DS#=qeUjA8fm1q&_#&TT8%YwCR>knx-0hC2K`f-c+c0m%vryvU{Pn$ zgI?8lsq!93Jh;2qq-}#0fS7w-mMn9P^6GUt=R0}j@AsO^P?!+^J_+Xv`tChgSmrQ1 z53ilyY$o-EG8S#S;NzfcHJ!)9%;C<^v4)?g`@nLEPZH4M;r)UYJQ2?|gK3~22u-l8 z;2*(VN%(6f3BzlM@cHU(mr{;0y8?F34iU(%+p5=baa#OmDLTS{Z1B~Spvo#9&F&Ly z+tlxHWdr34Khd)6AL3PWE3y}d!gM}|2@7rG3n90O@68vF?e*hG zze5Z&zv8oz;-^ldhjEUw&MQHAAW+p!ggS$9(GGa&QzXl}1=-`{?<2ZmLM&v$tF`o^ zsjP}qzeU!lDY7XCAygVs6k|oxcJtbEH8-4WU-HO!IIUOfy-w1j-rsO5r4H)p$jRM+ zSeTm}1Br!apiXVA-wOB>ys8i6j7n%hP%?9qIcOqKVg zm8_>)=2J7d)JMQy&}((UN?7`ave;-d1hQa)ck6v%2ZEI}(DCR($XsmpEx)DrTIVoA zM;ou679#crxQ!bc>&LSm9|k_Y_F$_e zsWGmDIpg!vSXBq`3FtIgmy}e}jsV4Xl4@cSrb(b;V}3Kaj;gMfw)&4J%djgt3u{XT zT3R9&rv(sCYBt;{eLVB{I+a^sQZUz&ygBcGqSrQe%wuXEqn~9{5n+fg2(DmDPWS_0 z;fSzB^?{JBJfCZd)_G;2z;>Cs!L z{s|IzCqu6OpLCeAGd+wu3b%G)^zm-NVkyWJYpb2l7f3ITjZqMmgs_nj7wMjrksy1ILROkUY(-tM!M3k-a#~I1Z~*&BNh^~FJYL0D42yLa>b)CjYtfG-)J(ATz@oL zt8Q_}V&FHWZiufI*6jp_4z819!=l^WK0wQuN*am^%S}Z}YyEUeS$`aKMsO8o&nL!D;bw}M6U=@kwtj#$N8T8gLK2Qvs zJ5@x-xxTZdBODb0@5trbe=JnFwb^O@VcEqQ1Chrh461jSC z*5R=EyE;8x`V)%w=4|ck7whlYKiWUu>3rMyj{WihIxI?lqXYH|uq8yUwp~6_W%mwN zt*NW4-yAMV47Iu6JVvC@FV#9*xjjhC>JE`S4d}nnFwh+UvUkx$)=geoZ@I_)G3)QH z^GzB2-1>hfYZc$mY;m?QDxIXPl!sWA zhLC2#+?b-ocD261<6mXlnSd~I7vK+Ht)^yJ*&Z(y7&(hs?4^&Um&T`u$A@qKOW{#d zQ`JaLN--H@fxX?=jHPktC{)Pm1peaA+oiv7MDFG@!3=3o{g=6$!JW@-F@(J3xuggP zBO;GbC1qs_FSVR1kGU&5wsT7^`eW8Zpk-jvVr81r{Ym7r>oLm3F!zEXZRo*H z`IhXQ2I+dj`i1^jQ{3pqmR7j50ss-iX!UKPpmig1NbyArCzOkB)R<{_g_b|&3E zuQQM#v#-Mwg}9xdnZ+6rI#;Q~L0=n#m-2bI(FWD56nij)nk^>kj*kzuyOkMLaREo* zQ?N+nbs!h90oglDj*+-N&@|tJXQMcdictWayZ&Y02-TrGhYvhuH+10%r=nPq96_jR z39>b!&8)R(H`K^?DniNuc`*6f6UM<2jP8`|WY5|tsJ25EYLSFt{;X-N_kNy`RGSx6WUKn^nvwg&2+gL_iRRv+o9vJ23lovzGVqI#D<1uJ3Nm)BFs1p(F|eKsphoU=S6 zEUN-oXYPT#c*8bG1I&#~{Wmp?`gn*t{*9&vbF!8XTo>DiUK{I>m>XC%b(FPLm6Wt~ zH^=$!y`&(O6Q6K$ZI0%b*vmL=*Tl`FDL;u!0J_DsP$IID|8VNZml&99o8@YUtj9j+ z=!SeY1QN4R@zb-}k}EK~75DPf(> zY-^4d!$s9j-h*|gN4~|`*=ECm(c0Qe6Pc9D^T@Or9;b4*>z+qofYMY_pDl0{3mJ{K z%^KrXPjV`!si0*#N%XAC(}-vs4VSfW&=!K z=wg2kFHKk00%;l>9feq7@||%L;32+s^rU|t2k*Tt3P5OLe@n6=JnmrN$m6m3B#U_WdujTQK7cy8(VL&~_o)F=-fD?gIh*Hn5=w zt$0Hcx??&T3>nj79C!jlro4{ojgX<#!Xokvqx0O7U(JJ&(;aU+@lnB%X)R3Vs?urx zy>`$lID}EMj1RnA1o)F!5ftG+{IP|}M(TcdnfKH#N?~p>Y^XP@8JzDOcvy7o)6+*S z8cp*yhuBVjChvef$Ta5LL_-|z0St+FqroML!uuVY;By(#IAW9LX9~L$Q3uL4QbJ8j zGDK*uuXf*%X##Z?Bo$Qb>xlP#-I2q7t0uZU;0=Uvn1Hko6i^>M3H8wi`p%>=lejfO zhdTv^Xzc-x(LQM`>W?r>0$d*VxOX{xc3g%k_9#UpOjFVjc_4?0hs%!j?>Eh_EZ&qK zqFP7vvQp#5O9SXGY3w_H)94M+l<+x8Hzxd}8XE&AE)r;XtXN=3#tC44=h;`O`x@q6 zfMV_x3|Dm9Y3mp^N(z*yL+4QSFxfby2tM4n5?3s1R?0$j%)h|EO2%jY;B5?+_my&B zU>9TVaD5Fl4GlVBQH_C$z814Hc8kLGlC)pWnJNHPp=6=O6L@UV> zG{Rm~@vgf}6u@u*4?)}q1*~q8U=Om7Yw4atXmXi;o3=WithT5Cd(Xza%`)3vRhPio zBEXYYIa)5hKzrOCEO*qFmNRH9EKLU&H8gzsCaWVX)5xr&HPu3{lV&ByLOu!W;Nd2g zMuuSxWF#026ay4?9nZJG(b(*K1azfe=IYF1`2S@#c;46UWqVl<-7>7SeLtMesV%Lo zHj6>Y;z|5o%2-uC>b$S1tGueLzdBuFq@?C-Ff?IO0eeGG+IH6Vn@V(1@8936d0sp7 zM;V#1@77gEvn`*ISgiYfgM)b%dG0r4F0)Ld)YRAyzNcedpUn95-h~wmV3~do50BZf z0||JBP|V~iRES&)02sj|S81kMe;4lYU4bw$KQJZm6icy0aSk+WP>{EW%}ewCaW8%` z?AVT%F(%3i|EG~;^!ofS1)oC2Z7|O7itgTr(jL1poT^11ya#(Lw_kOss+rgX_#rv=%7m6>7Ul?yEqJ#^7d@>q* zW6=RNnmfk(E1RrNn0g=V+B(k|w{BG4U9*e2UXP*l{w z+u48YJ8^xw7<$VBw({EzQq$5=)veINp&=b4e-D!23B=_fh0LPLb0IZsq;b!r>8H0F ziythW6mMO00!{S`5h8-Hr92v?R5f;X7I)14RH*&KYcPkjNLt^}EJ&Z|=V3Rx3&;KR z&R;Uh9tr;wsu6Rb9G>kCRVg8%%GXrXd@I+b{@>W2AAS2_ZJDGY)-Cy z@F_!(#L~#`&@U)+U!3in$k3soMXc{xKx1ELS zoIW}448S@`to?fB68X=mS*{`%iQybvt&)@60_-L+DFlUwDY{A*71!Eb#sP%aW%iF0 z`+!{3Y6jA~4}|s)2WHo2g57i;j;tRkT;kHCABRfyTax`BT7&=XcI{mg6niS_tM@3o zT3J=*=a)a)Vg+%&Rf+%{zURW7 zcd?{ON%zy0D)-sSJ`mSZ)#wV)sTI@OZED0!Oj5I3Zp`D-;qYz>^Lj+4r(wkUuz%nN zxcp>yMb^T)B!5=bAirtlbEJ*&)<}~@jpj@z(2~*&?Y|7SU`scv4|rs7vc_EK+p2#~ z;l%n@r5k#gh(x|jivvOciEe5;U~0QBxGj1)zDYtJZb;7cHEih#071~9TUW4Jz&hEV zQi=6k5odujwwj{cC@xM3HA!s)kbgpz1c2;DSI+M+C*b0p>0h}NprkWA?1n$>ENi{ zb7tE5UL*3@zLWiZ;iuu?(&*F_Hag1;Q`mh$C#77qmejjEJM9-cT*7A0R6rfY>80|j-<{Bm818HpSF!Wchrht165 z30~H*kK{p#fcbSllKZ~^+knet^TeATZ6R^Uy4zZ&ZtNc*f{6yf7@9$`p!><1Pbg6y z%06OMj~FObm7nS)={$jzB^Awq(0?k+QtNzYMDP8x@Z`|1XeP}ejx6SfQ0 z2H;fFDuo@vZt_`)KW!oHm{S(s0(Xr>_HIdLBT%^xtIH8bQ;SF5`>v)}>%s;lh%flE%i$ znjDj@LWZMxo5jYJf>rgl4w66G3-h$?bdA1+o8ncN1B(L`ljLZHh4FZAZmJ3B9JYtNNz zHdbRh5zSwXDO)xIn1T)EkMWEk2y)S3G8+B{ZGd|Z|NhSa`2IYWH>Q?y&eRSKW@}ub zwI@KO)IV1FJX_f+(fsEBr^|Gzs>Z==o`lKZ9JkAt*P&8Bi*r^k8;WkCB19|)5k5us z6Lh$`x2iSe;8cEH6uT?oMEesCYGdg|sEK3N*~52Zdvjn_1`m;0xYY0wilBV0^|FC! z(ugma=|zqkl0yid$l~Q?ky#H^T+W+{?^4{kT%<9K0Vw%rIR;%p|Ux zO0zl4;db|d(2%(*%e5vlP6z;PSIzxJSjJkEt1RmFy^vW6T9=%b1SL22^duQf5L7qW zNIId!FREzGrV4IW3VL=%)ahY_Y*0au_086yAENw*0&2J5hJ;!a5lMm@cV`iCDv{yb zi$L|&6>wl|TMsDtN#*$lCliF)fIDg*Uh-?<*f-Ez8*mvf4*$?pY+=%+KR#{#Ouy%LFdLd3nN_vW#+1_f3GKD|$i>vFK zRRdk|sEg^37D|kM$8V1Q9P?b<)U~Q4(b;5daw$Gw@wi>Z!rF0P{PME-9feLM5sXBh z<@ru$0MzYi;$PSGZu`IVbX=bA<*)odJ-STF&p4-H@E+2bihz%-yq@< zT>kVEQQ*0lNy5symO2%-kh&P^ihTg{{84Oj-`#uQC>mB-9Z32`$nQQpb{W)vs4dFk z|5c~U+pB#~%5z@a#bw-Ij*(KO2R_YS^xLeAZUe8$Wj#6d&ke&RUJ0NE z1p(%7?P#L``agFJGte_a76x#FyQO>sjp2jfka6rsX^MXR;K!RPy9Wi#J1|dKGQ8X# z0q0q6%GZV`&|MM)52YQgG}2NsZgClS1f{qK8%)$?Nci3Lz}TM%TZ4dcETLyWP?kck zb(wYMN#$+v4%!q+i=Xw`l%X(fj)A~=RtdN2Edh$gvLp9Q_vJo(a35SVGQkBDC;{HM ztnNFT28hKzmH`BLApt{E_6=G~m(>+5{Phi^pWGs$bA!=DG!dmLEPPse#0w>U)r*mn zXPaoK7n9CzXE^yMJk^SHd`@8YG5e4@2Yu<;&gys^E zATAGH>o`np!Dk|c68O)W-Y1EYG=kg0| zYkaFes9lk8&~^Z6YS;a^-Sx9}CXno?)t9NgVcFShy=DYsDd#_v+07)gf?4DCj681? z!q=Cl`?qmEK)_Fd-Q6t3Nylf`=}t`b-_s|hv}MxaGCGJXHzP!elmbkpRaUyS=Fj0f zR!z1gbc~D)jEtpKRm(O_4j{XtwaMN16>8T<(|nA=fJx}?e1t07{x1Lyd|^sSp%Uf= zd|xnGXXk7HgkTH+Z$YJ>V;`aSu@r`K7zGr^!?h+286Df@`ICoW;Ie<&)v*OyTfMyr zJt}!zR%7$7@X}sg;R?ElFJ(&F+WM(BmuY}sNXMNC0r3^uSM zOe$CQXZp{kr=QA-tM_*^s$Mrfyc(^xH;vNO0gB9F<|3T&l4VufslSa5rwq$Z!3oiF zbwR-=so4Q7lB|+7r3@>J85v-VV$^DMk6Fy-I;~guzW?_*MDStpZ%Y-@#RNeqhutEV z>;BIYR`JLM6G=U<%dx4J`P^N~KP2}T#V!Oarq_XaF?@cz@!@*m;ejTHo#0sp^;*sl zYX3cgbPp=7)Sh%y?prt;+;1vgB`XA7)UCkbip#uD`4u`%^5-qN(mzG%^@3$T=X21o zC^IvQ;kF)cd5;=y%k>Ju{`?jM{@YSlIdJLo z{KsdGyX3#Oq05^#&0%ZslPA!yW&YHiQuHxu!R*FM{4@7@MJ7i`>We9T(XBtNOxAP;o-)KPUYzw||laqu37xM&YaA*IGSv@J4*3`a)g#`>PlzB*2n~fT$`fRQKmZ zbKOg`oKS#+xvc{&5pb&@NPK&7Azgy0BZ3hv3GE$*A(DfKH~Bg*?8Fx^^0! zb#a-^w42k(Y+Gq1~IuO~vHQ3$Ws{%0bt;(``;TCr)CXek#*_M8?ZIofz-?i4j{n89im&2lWA z&~7{u52^+`rDc`j-#+_KHt}ZZL4W;Xv`rj}22Jo;0a5WA(AVf|8GC-S7JdO$X!$#z zry-w75M+&>j{6I2%&jmyu5c7oY#*p56Wo{TAi}&Haxo@Ic}KV2I+;fIwI*-U zxmxgr93Dz#6x&Dwayw|lp5A$9$ z)xxnMmPjwQ&SVzHj4`Y#?H1D)-ZMMRvm~;6i^T8P%5Sk7qG#%Z z#*?u*Hu7ZY?K9+8nYG=a)b~3HEtoGy@m=r8rzUC!2^yB$JNkbsdpMo-!c^#|Osv$q zUr3BmgA>k7BQ;9<`;W7^vLRo;=P~I7B7-p>1;LwRV03w0vZ}i3`k0eeM+sa@X;x*w zv1UypW|~KhBLJHOw&MLw#g0i$Mn4XQ{OAw=khe_XpNCUT7XE7_}8M|SV$NW=7H73R?tlKr+iZ6xEU(399C35h(kmPP{{MGqjl{ir#-EKLHN@gn z`c(Vh24E`UBPxTE{Wy^ZG~WM6sD((!sE$yvxVr5=POn#*Z_6EEMPp1^UsFuu>-HoF zU6_Atr!wd+G+qU89{_;C^vV?wJ7hBnb1;L^tc1@IvVNZv|6O1-(9=-u;bLouNw4+# z;#y{*9tjLFs-Do#LS5oMF$|4}8E@8*v2GZ6r0$|AR71+_7l!@E=Xzcwa8uHU!ix<1 z3{tf(15DmIhg&H&kUS)b|1p2<28(%Sw@c%sVEoLr`-$(>G=4k?Rr%VnZ-^kfYw$BW zP~A5*Sb&A<`4z%O#AUx8M)ji@34tFnP4zv@S77=8zK@qHkkRZpV%fmW0*?V|?UMG} z82d>1eyKOXZaRq^Le}_F2k5S+jx_1vi>eB=30->RRHF$&7ns9%QkN~Wi`NZI5J*>m25AqKf=3(6EanJ$vQ@OLQY zZV??7CnUmeP#?*+yDwnY^K}T($5fW(-12Gj3=vZiv!p^LEM4=NU;A3Jh<<7B(`Ul> zAN<^cbcO06`Z#n9fD>CBXs4kGg_O?{a8qbE>B%#hlpDs@H4PVli&UzgiLp^3DKp>XEWYx;et{jPN_LEtmrA(> zJN7Ps5-gw)dx!zHpe(iWZ>7i_27D8qetF)ciV=9Wv@jW``mlJmpNG=4o>X*dTluAs1hqIUZ(8R1wfY~? zx;yqCGRl~1WBZxafu&3e415u~( z4n|Hre7aixOc>FxJ-)pDdF=52ljIy^aLR6_o&iRCd^S3#o7XRv2KqKCjw(uo^E(5u zJFs?)y4sr4TR#I7PSxj*x_ln;_VisFnY;3H>z(yZZo^$*;RtG8*C9L7ucmX04oRyt zA>cK2IlY>%Vgq8ho~n(eV~RN(H1ZHjs(tIPXCgc{vY}r~DMBO3U_}Wr6T#t9(6Jrs zNOhX{tZJCA?S&vYF)cwkJ~C1JLw?&6#L;d6fj;wvV$w&b4Q=&pp|16oTo4348*PDO5iSmgv4*W=jn zXgP4a_tG{KX4&^5Jf3y=Y&XAgf&g^Lh@EB{zv91=>f(LU+DN({qd z3)c*>4NY=N(Q{b@pQY&EkZ|~KzV7b_(-f+REB=~93KYZOopS+xy}9kcl7Z0ff;xkm znBXc^D>GO*I~c?cFW_aVvbYEkiOE*zwKuY#Iv*S8jFAymoPNzAc>WrlI_idL`spVu z1f%X$eTuy2gY#1V*Sr_IP7#U}LJm3TrO;KhFt6buuHnXc6Acb6_x7@w&A~fXj6%dz zOC3ik-;Pv^$7x0!E)X{os=r6&9h~IDeroZD^(j_GJV|6Do?(*lY2jZ+vg)6z|3p^< zJp8El0m^&4ss5vg3wb&T3%O5OEDw#)(!9@bf_Hw!tW%g2Rpy>RvEWDqV?ggi=d0IK zf=LmYP@;A;JvwhABYkCc)P#v$l*{TxU&CX!p(7*U>Lb!fldwzb0CqfT{=YKa{D+tW zof_-psd6dc#C6=;dJ>aYPp7(uo_tXL;z4#JpC*MKXJzp=;)BKkm_jaAdxL6a*E&lc zN<_+9B5|BgttRb%Y_4BZ7}Xk_$Cn$e*J`}}0RLAA=qY;l1v_W)YD9rA$nI|aATc-T z*xuaWW0_ADAFIQ@UWgEGK1hxlsJ6!NEcOI87Dzc!SGjaH;D4d^`OG z;OxpwnSifg@igMgORw5c87f!R z{v^H_Bl9E8%JMd{6FP7II(Q_?9o+P}SeR6;2p%1i3A1H-a$Nt?0F&b)joqd&|JJ{- z9rRZtS`eI0I8V~wNq5~)1;Ie{%=g3u&}pid&RjeCekqE~HF#m&J@k@Z+$ajM2ny42 zupL9Xl%z{Wu|c?DJkTl-vZzH~NnTc}wy->+lI7;ch}_?0Zk2>-G$(>2z7ErS;aGh1 z!_Xu8k55Nadhb{CwU?(C4-P5Y_3XQM>%qTJCySD116pzbs_U}>n!G&+h$!)cTB2Ti zmyz@Y_^RhrUQYo3RuB%n1#b~Oz*s1a0w*fn7ciD%PN@KM7gFy5WrS}>6-|SjNz~Yz z%o~u(=hyJ5%)sIU$getangl}l4Gb9mpyMe3xRd~P*vwl)<_P*SZy=O3skF={?*8)g zYV>U&yHv)@;RcD+H#F@{2y>{&EGC~(YnW^^SiKXuu0x6>;`2C}t19V^GpP4#pSJ`| zx*G_9_!JL3Gv^)nGryHSS_Nh(d3mM=3)-rwsbL~{7`0fKhwAdc%Zx(2pw;sTTVQ@Q zl#V@shROH+8Q6mu)p-E$!X{(``}n4YhSY!MZC&K^Qy>j~ zv4Yxz>cBgUsp1FKXRv!<&<)X1am>Pq!+r?lV4JW0Su4kVl-M667RBzYBQu70nT`Y; znl)cvJcuf*%Iwx_oEG9ddSJ6(pZ1t=*ex+%>Ji5+a5xTKM+2L1%-IM}I2Z`(JvP(Q zF76`k#Tz^fUlfREa>e+kpUi$QiCX=sX#8HvqsHKNwqlm;UD!(boSetLV?9R4JWUic zZl#(Mjmw@}-d^8WXt5W4C>DYJ#bwbB;66_t9+vbw+CZ_}sI2utPi!DcY+xL~AYtz_ zbyYQvI%hStrwesbUJmq9RjnxHq-DmWN2QZ~-!#k-@Hijvem$?w>ASqboe+Hd#e3T3 zGju!1xZ?5pX-v7Efl~gk&5`x`DZXU;RxQ$&uv{mIeXgI1EsCXUewOOWLxg;fH z&ChQ)+02}V_L)T!@XKk^^qyN=$}{2Y?KM1k)pVRI`1*{XlPl|B|D_p!6I)!+Nuen1 z=1Y!8eoojKxh@(saH@}udpKchnafK&RN_f6A=l*|L$&W7#+^<;986qzM@Xh3Gs8@R zvNuT^bauMpUpIyS-gqAs<^ty{8*!)!XZrE|uyRFb{Sl@UDGv$_egOiwud#)d!t#4M zeNI?M{VS>9Jra%TRhwwiJ;j(rMUn}SpjgH})s=;jld>x1H z!VUn2GH4Ba7iPjxzSYuCf7(X<&oaEdn_%E&nIACc`)tWiLbqraH=y&y{OFDWU7 zm}KA5Gc&>c({_>-ZLlp>QJZSA`$Ff>B0p-+gcr90e!!=mpv*ye1i~bOU;;srhcob= zf;cPB-UubA>niJvI2Ft~LBg61bdd5eLyegBx1Jo2KZQHGX1F`8!&x#1VrkY)Df*`S zvY@F3OH##QHmdaDriq1Pn=z`P;!&j26V%mikyH>w9{dUn`9y#o0&b$eC$W_y;`Po6 zr##ri;G#fg!|c~h*kC^y-gwY9TcWo02903RMyZtI9H5Ho!4bo2Kx@C3?1x_md)MwK%F*`*>_6c9L zlfLgyx7aBeJTTUG8&?TgP5f4AAAH|B){aQtFTEr;H{mpkiYcC9WRS4C39OULYr@s=CIX-5m`&6_*ohTmkD@KREoU zrhnC~OO%-eG?8*+37rIWA77--H8M87z#395%l9gIyS)jPz&Z=)3%QXE*-~;KWDzUr z_n>H|i+@o#i>JGs_BIdTe)Il0r2D+FFvBV4!YYa_@Bp>+AMxwERWfGsFkXR`42Qu< z@33h&3>ZS^;Q=bxdqHXb&{x71s#JMtQ}u^qDCB37K7AaxAJAcX!`EB7pF}Zk!XqQ! z`O(A%_d;uzPx5MkCfb^U*P#j+KS_v~-Gm(WFl1Y>af;y$A^U4Wb@nD7WeU+Ik%$DB z55EYt>okWOgPDd7V3z=94C?4ls)(1=kloaMM>MF`gRQ|2%+z@zI?};V(LApGo~N@U zpZ*?MS5rF)nau` ze4?izsk=XQSjG}8MkC&IFdec3Yz1E~rgbveyi!QbY%p9XfA371IRmm5rD3QqNt!Ut zumePF4O&nLMiZtti4!Ck#n8evtt_QV%NSw{zHhW9}y%g(0@IUf3~ z5(Ql3JmvKAJCa+zBz?irI3lArf1Wq?0L>U~Y~JN;@q6|G;6QF|pWv-|y`E^@@Nza( zSa;Nscp-;Q(9qT%PGGL8xY7n_HnJUcz7sm{PNWFs@dQ&W5@J*6T!s4T$zO= zZ@D9&v_V0z#O+N2;pjJy9NubNdi| zCm7nY0tMouJ&;j=Buw&5uOF??fGAs`E1OK?Tsrz*6oWxP5N6Bjh}W!=1UDu^{PRjY z=q^Bm7YG^I-hRWd)49}v+rQtM78}BhY8#mx8()e{!I+A%paATpk@mB6{VE0-`yg%Qu;K0RaR=Bb6dzgYXdh@E>LxQzDob1q$MyM~2M|%0Fpv`T@|1sudsbAo3T^HR?!u(gCY0eZ zPPJz15lp}FLF^IaVx1(rsg0{Ik66>=^SH&so3E%cSEJ1M&jfyx8FA1?IuXP`DqBj< zJN_jD{EG2hg%}{i{eVAP)oCE%Il|E~lq4OSTPSWZnWL;eSK^T|DxVv0 zUVC}Xc^DX;`Da#L z3XU{Ue*Eq(0-MACo$w~JYoCf{YVmn}QAM1HMcKX6bK!9{E}W+hsh$$`l3FYlNa0bZIWE2m4S;5n;XnBO z&> zoEn=c0V2;yzuol$3{;3XzM(yXEZZPk9-DBv5qz*aytxc#aE3n#lZ8bPB{K3y3x4H6 z%*0(N#G{a29wE3U-)197ROh>2GY|)3(;DHJRW@z>RW?> zsWKUzIz3T@fA{38+Av?01?28WY|PG=!M8*Y?w3Rja@GS`j8;gmPee@nOH&|1>~%HH z?Q_@1zA0z^fsp0v@j_fy>CzugTa`-tua5dlz7vhL}d&` z?Q7`fUp7P}NVlxlpz?^BINK~aYc?4SSve+yaQkgU*JYLg+0ZH=T7pfzg1N0&X_=L3 z9ho>vrgwM#B_f^X$86Y=GWGIh=Q&J^waR5G1%WP*a6B|apt({`B=$Ip@u7VxOD2w! zJ~j*K0aZy1DJ^yXrW8#~k}{_JTrz%(je+7>$_%?!CAd71yF0+g>lDexjSL_{GtembfMGv3_j{(zQVt^tjzO`XG=B~dpr`AZv zlQm=%AXe>Fq@t)@$s{5BIObFi?ea1IK-<-SJG9$O-vW}at|QSmg3l2Cdc)Ze9)==m zGckU$=2BAa^ZOoqT)e&lF0LAC;!h?L1`lW`KW1@zV~vau$)$gM+BWZ}&8!;8CUW|g z9;hxJ5D8b$=7+qq;kQGaZX0Z9A(Z)3*g}0F0_WW)*;6#F)OSSvCX~E4N z|4wtzjp@Vl7%34`!5jFZT|&tT6u(_YAUd3T!v9S|zZC)6zkx+j-q~`Kou~W9|6Y1% zfBk{FE)@dLV$RiJp+v3^1U$3f$O`$OmIe(EerNIi1GQlvAfJ-T$uJyX&%#RfMKFx7 zxig=O4tHk9plQ~^WD73Fwd|jUaeRQO*7hY4QfNhC5pqHjdq-&*^-Vx42d`)Y+vUF~ z8t?@C+`w(fkc8U3jzNc&HyawgGyf+SP8v004shr|Ov8CJk;eMdO7tVxRD1#yWf*lx zBE$^&{{}=vyuw?bFzIh9=*H-@vDov!8!JoBNc65JI9qWtXtkTpgz#QnO0UGk?G==k zkpKEK!W(yJ6;Ap38S)C}RE54pI730EwJz3@ng@Zj76e`%38xC@Q22`sjzaoJ52tK+Q%dJxr=I$c(h_s_s;2)?9)`$lVr^ z-9r0)ABW9!wkICDdo#0z`I5FaB|irnJC#l%@r|?FxSUv01<&`x1$IF}G1Z556@y0p zj7iRs;l2>-QUlMBFIiLy256)V^J8d%;vH3keU_O@eVX@<^LP zQ8^HauBI;J!}$$Dl6&~B3|icrFVD8feQ{G!0uQv2IJq3KsKbxZLTtbG5RDT#5s@!g z$z@fUyTAQJn0Vk3-x5O9qMvqmI2+a9mE&UF9 znxkTbQNcdUMI@9w=EPH}r)VA6UijP5K32k?vk$%De-42awt##Zl@RBmTx;hg#$W4 zB8v9;zo4%ZncQy(h&kiLuyK?yfh(7XckIFc1w3%r=&04xmXt_!Nd~84iqPwISoTd* zSe1Tf$HD?~gg^zJL0mi;X(aq#;1_mqo-DY&HO}UuuzgXmhwIdD``NLf+eP zK3?eje%7g$)oQ)=V|8B_9Mgcr&frQf1DcwN#3CW@i%S-hG@A3;+v~X%ZdK+#vU4WS z{@I}uF6Ftk`BT|J_N8Qq;(e4wOGJdU&E;lqZ`jt*Ego}oWvAQDCDz!gPW{)3W4PCA zb0dQuw~x9&+EA|rc+#_d|H^f4Y|Cl~QL--Qt}auPw6DWS+fdUYjo z%i&}(Tn2Zs7CR;tJQ0J0v2M&_1k!lPT2mfy)t_jY|ku%wW&|>aSZoP^7OorH`BibVgRNI)gVMhNBMrX zM1`q&9g2;T$JP6$?91ZzXMF?4o1ZC8%zi!d^fL$pauT^P+!Mqn0mmsN*4%g>bTCfD zM^QrrrHk}p|9elol!xt5%IorFz)3ce#FCjvoN6B}Rx*mK+Z;=Pyti0jMRA%tSm;{h z_qj;DaCtzC03}bTGanC&oB?J?H62edF@X%B7Vcb_Qjw(nxnyzDLDeKH5{i5WO*!wB5tYswJQK z0qyN==8l>}!0V!_WA({EX_m8)86#DUF{j@`3Yo7Zt&qXlxY#ea(KVRi{8J#k_Aor{ zoh$jZT`C;mo1@$MzUPDYWSIt&a_aehUd)nv579aXF|%y_m48e1lAizZD3kep0mgM{ zjau0}gHG#2iFWLlL;G(mCalw(R%%+wAF2t$SxgPgc~+qIlVz7WdW7|CwB5Z~WrW=Z z|1$%e3%7H4RJi{BSN3D6*Vm6*Y48yp3|Y+X}axu)dtx+6x_c)fLI(fFee>bxa$O& z;E_n|+;BiQzS4?ZUT&?Sv8Pfu4~vO?mKl$W@yqdijpfy$iQO-E_r==#Io_EFBEFJ>99^-dL>OEvEN_C+ zhiJmKv%nG7zZZ;;Js zqI4C<%lb+UJ2ruc`(4)zIUo7dlrkxUqN*UU{t*|>kO#iPo_Um%04Gd29Uj`i-0F&( zp_tQhmfA~;MPR=bKt9|_Ibe0XJY`9gkUl5N*C+O{>hp$K24jYxMm`NA0EJTcbL2aI zs&efHL<$zUSnB^=;)=z{m_)I6ZD2?kAEaVdP+g5%hI9qHF;`t;xtx_NM=aTu zU0F&KaH5hY9B^Uz&qG(~MF`*5!0vZrG!==eE9&EkFl(p&913(qB@5L$*N$yAzU~($ z4Q<&skj=NR4(f?r;~F9(AD||(%s~3Ug^Hu*U#$cmB(sI(aT8wPS8t3>S1L8bY5Nx- z9+>_DBDrXW2k>qD072tn<_|WI2T!P`0ATO{QVQQw*blK^0BZ)zPe2_aK{p#AxU%)I z6y&&9a^^}@iokJa2w>T_@Hd;(6tHG7qoWiu$<#aGC8md%XBI~jPHS8)^xH)}gc2q# z!q-u#8lCE*__qs6e<0-sTb<@OcMSyzCh!+-MI7nhPMagOWnzXD|M`xUT70+&;C9QxY+VM_VT zw=UpNcBnfj6DBk2{U1kX6;;)?fMHs?yFr?2vH z);-ww*{oIl%xQ^`NGcq1&5`_N9eHv76W5yCSW;JS;G4qx>X}BeLT96Kr%W;WYn!VR zlZQjGNvzv1@Ph{Y3JehAlUSlTeqrw5ySMFR4s>&1Hk5D**B(Dy_!|tJFgbhR8vHS) zj>ez}0+fIs*_^P?V8^t`_kgJWC*eoUytjM1AsI<%INwmB)O;ssmB`P2e&a*GS_BpN zfHmtZqGp>t^p=}r$=2f?kK|apJ3>NMD_dJh``{#{j zXuXa3m_vb$I2R>3Zzz^n%PVO6gTSD)fb|rNAjkLhsrmk4%Opz56k9QLoaYq8#`!nP za}$CBi(%Mkhd$*3FbIQsl(k4WK2doY3#?l6v1P)PH%Q~Gd|b)+#)?FQ1?9H9!WW!; zGLo3xW5q}%;+gy(yliGE#a!eTebc>#qns-ZVSXK$6qt=r_uCVG=*opS5rDwa!o#3E zJX|J8th!XQ)C~k3(zna%{Kf&7BM*B#J2NSzk04!bswZSXNfr$YPvc7n7&8_73aTH zbvJ8Pk)guYf}QIb%(`Wt%SGOFJidP;Og)YK+o_(J8Bo=iIz1jaFmK&aaM!uUcy_a0 z!6LJo&+r9S6iftO?iu_ZG(E}k;+hca!wVcY2}TOh3(l0=%`aM$|HZiRuY7Q%9Qg0!d@HUqAI0RKlLH3R^^H^^nq`SK&Zy5CZIxA{!4KVY`LC#o^A0Va%syCvI*P*e=mGwC*IkQh#VtDJCVZV*6R1fOUYxr-1{?*p+I z{81*+47c;~(FvkX!QgUdh5Fdz(XNB>kZ)~YO#4g(BybFfyx>O5I**rgdiaLF?^$%v z?>)_4<%`=kzEJ4i7l_0VVf6lMfb;{~JNgD@wGaKDAyEa7Ymkz4-R%gU4HrFO`^duY)b#sZ#S96{;@<9m;fB1(Zhe|71>7=&YBRd zKd714vEvvGKz2slzJH?i#&Jtoi~Ah;tNGpYiLt)jQ)#TBvLOHI$vla6fLyQyGxLVQ zMV);zh0*fX{NiT6dcV}KGAO@(SHYnOVx651@QVS4%fY3Ew?b6UqRBu(FOm%h3P(CW z_UH$E#NclvA}l;jPm50F2~5_3Oh1)n$G1b4h4ghrekVwL%>2y17W0EJ(q|9o{^=4D z;AfQ|y{nLnRspWDz44j?BJbj1pMZbpt_H8>2XF}WT0Am`MY#FdYw2Na&5ZO;KgGm? z(b3+qp|*`?V!i!%wVlgYOF?0Q*(CiCf+WmfVlqHV089JzreFX2nq~TT>-Bl7RNY-H zO2%RC{2eK+$;x1%u>WYAY=FdW|M{}>QjHhW3K-95F#hJJdyC$Tc@dy#iOfC8>Al%l zy&&U#ysqLkZg*1dNOr0aH~H1+=Te*DA4v=W`>7)&o!QN>GijRMgtqZJx2RQ=S6o}9 zZ^208)x?}v5NIYae@#HZWgDfN6qhXBR>Si=iLRu&t!SjQSK{A4ztn^GP{2`jG8{sQ>{GM39V7ByR_|`0)y= zx+DArueSt&A^cDx53uwRIxlTo=%AO(9&{P+UHM5alRlT9FBW9O_@x=-ku5wfhxKJi z4&Fp4gz}tlUQkV^WU}ZVbAw(95aMQd?$&o8H<=2bmJ(G$ zkI_bSIi1CfYJy(mML{6%clGb?g)v)gkp3{P-+V}esJfdVuc9EAOm){xeL=nu+xi}L zTe6kPYIPTis5S~pL~CgWN3Lw#^*3qmMK%?*C8C(jTS`RY8!dSCW~k31#L4{()~-o@ zBaaaOYx?C!9$y+86KTEBcjbz(ot-ml`wS2YSm$J%5DMS>qEp zBSm8msj=g)3#t?dX5bA)p_PSGK?8f~4AMn8`cUZDSn_ytPFt82+^FHZIGa*qn2V@V z!j_;dM+y@gT!+;sxLt>86%_j3%a0HGT2KGcA+_2aTfBW%9rl>tD0MDHB(vD-l$RyU zEiX<}AUk`SRgmG8JjEKW(~?^NGuxtT+W8A_o#8jIpa1gqx7SH}ei_{Npp=Tb#{PLt z{%4}VDc7Tg&!$Bp!pQN+-e;Rjn_5rfL&+eqRR0A4tUlMEgM$>IfW58uAv$;sH8_3a z{rmSA_P5mGp__zE0DHAw+2>l+52Glhu7nLK^rdarTDTXEsq%xiKwbM?Cpf)}C- zcB3#kJ|K35ge%}8%ZBEWpv^`vroNoTtfp9yH3d8-x&%n#`+)a_^$eh6c76M%@&ka+ z(}Tfl?30qyY^$$#(dmFDMRdwOmI+(h%Cx{?zI+n;*C7Y4nZ5aZHBv8Z^UD5S@NHHlM?dZVF;N$dzKp&)0a zcvFp*a?Fj7{iYZ;85Kve!*@zKI%0sk{35)BkXFzxKQNJKh_I9}@|KYzz(VlF_CfQ4 zCgst0G2?my5ZRYS9M2g*nxptPNkIAS?)&Xwp@m3Q@k ze21eT$zge#3IJLJ;UY)ujC&4N+5Q1<3xJ2x4q-%BYmR}r$lvS*(-UvpQa*q^mkr<* zQT*5U8nj*t=Qtb@)j;Zum`1M(#Oe~RupG9vq_2MfVuPn?&hZz>xv!6x16u6@P*VCz zZ8qA;CZ54U(aLa5P0~Z(&AcMmLB&C-H>l`48FNZZytIkBI$0`RGZtMe!$#+)`K_d~ zUAt*Fp)SZ%&I>cfYiK(;)LjG1zovt{l0*H{MhHXb!5KSSp=#D@VLEAF#vv$GRg~59 z`U0R+!+(E%`+R?3e>(qJ54>Fn2r@PVYbv{+5ZdKL!O8#l=QkS`MQ_=R)eIu_+yQMxVZt# zL}NvXNML4z?w4Qr@+05=bSWZTJzcX`iVo#f5Ts{@$HURn$Gj0Auc%AuA|wzo$0FXu zB_HR94DB`xCZmMZglWTHHKGm!Yp=(_|qQajd{N5S@JOg>LASHmDq{gJ<6SG9E8 zY{lA;fsD$(hQN$rjAMLuRaSpO&QMqXVxj0|5$_r>%sw(_=$XHzjO(lr_*2F(VALEB z8#O3!3zL9wZJRiV87ebYR{x(HfXPBaot)*@6B*1deZtS$&S9jYtD{EL5+|RP-JIsUc^R7U?PY?#EsQF|@lBKK15{iN z`b}(EHkA`;^g}j`64KilGeRHK&`$9(3dsS?ezktJNe={0_&uIv6?6%09N0QyT|{Y< z`8c><_(v>%LEF~x?OSM}S1Cp4ICH$f@!8C}i*TyH1`ddykYv{4sosiWrZXj-6(DL} ztQ-om>KvsK?HZKB zw9tdxM)j44RUoo8tXstE{MMsKGoOnkvdMhOJ11>{xr3Aho}%CwN-0`OH9@5g-Z?Hv zz8J&?5NE@uMzv&N{=2e0J&LAhg-%$vIM00ts!0(>^vK{+_jA!m)+SOb=&`otB;0}) z5w-X1(=HclT$jtwE&cG?yv4 zyE6C0Ggf0G3s?KUZ(D$b7?A$RnvYYQ{6^%_-yt=aE}%{^CEr@9J-#8e=gXx0PUk4hi^@dCrmK&7lWMUixIuxP$g5*?a*80_hQCV$23E6rd zEOh(9{*Go^Dv^bjV7RV84z=o<-H}@vwuqnr;sK>+)EpHq5eE~Vj<$C7 zsK{lkst;UT;nwTReYRpeC$kW#%Jzjz&~=^$m12?4ZY+SoOh%bL&S!O`F6kP%McxpD z@X}g@CmH4=A)2@l(lHj=EOaXuXEds?aA{UyeBb)PaDX{gy1$m zp!KLHS4MofBSpr_Ct}*Ev7q=ayTJWfksRKxf24( zGlikBsc~F>a-}7v_;(Kwhk*Ik0<#ZN{FT2zL(#@VTc`bbF8Fo$++yhjj|tD=2Ao>T z48O90xwc#2(+wOtZB+Krjnm(#FQ#f67no=dw&;E_i6(WA$uG7ozK%jWJ*$?b2uz2; zr;e)!$Ie7T&IzX4243gQ7^*b47Gjsap79US=F-zURymV1*%%<|GL_AF8HMg#@U1*K z`m1xsf3Qy>B7x(UABo|PeVlE5PV4_J>UFwD1{#}`^fD?GeY8tY%Ju1Ks@6d`U#^#Z zeSuxdp{v*b`qHL*xas+u3^aFSHrosj1MdnJ+npY19;%VOIOT&S`zS@fl$VI~HSm7X zmOfP}z|E~+_!=M6AQ(;dUpBtXmnZR-#B^LIQ(6wRWt@AN{;$B2Ex%_l<0ivNytQCGj*m= z$k+WyhS_)4NfLX2`?KL$>#FpHIdPO2{V;r}re@?o1K4+P0=aYu_8N#PRthtP!qz9@ z=z_MusHS-YpuDC6NBrk-SnVObfKNkA`%Qzf{r-WqLxJYM?7)G49 zNF%1>=qLjoPB^ohIk=+!BYJ=3K@N{NRV`VtYGeY|id1NGRdQLtBSluAVQ9fE_iarQ)+o z0arP@Wh9H@#yRpg4wkRt`1xOSP z^I-4+pa^rABh)?GIul1(f%yCjL?Yy7A-N+kFv9=$7tr~6bh;&@(V4m?CT{$TvyAT? zpnh7XezfQos7`JbmFS<#!Sn32#PIL^;qexGk}hzo;X z{z7U3jU^b`KWVMPA*T7(%lQ@<$g18G1lwNLsMyCIAUh4d);!9c?-hnvw59I>f%A5qFEOb^AUpJXNRBY{4Mid?=zy4so#9Wf}`jI(p zEU28z6SSB;@b~XhdpvRNTu!lAHNmUh#44vII6Q)6)XRj&_ zFe%w+q-Ag`A10g6X|s%|k2^49q`#8p=#CFM(6mvZ%tm8yyJ0R5jFlxM_a7uUR;P<5gh zNarQvIuqRMdB_NzHh6m~2VbWR3dXZ5Ywa3LC zlB5W30xp@t@_}ApJ7GoR_&p+N>lEKyi8U^fpHn&u#{m~wcE)i=5(B1A^lbim&dO`E z>m?#4tkrS(nlX(%V>K*=+-`{MHYXg_c)M=R_D%+1}pIm*@vex`s-QX%)p zJ77kXKG<$GSnA6^uEtfcFev2%EwMn*Dpae{?s~bl;qfO8hG>`FLVJVpd*y6?@9pAW zKYYDz(cVum;j;P0r8dv&+^EC!FLAw$)ZEak-731x!JagVNdBB~lP5OIm zEz2Nr;gPfCUp@ZhL3_|YyS~=eZ&g+?vD#^;m>Ovs8XIb^)RdmL*Dui*_^dB}|F^Qp zv))X&dv}ki0m<$n_ucpWY4a4#q*S10w#LfFPC3#VaTrS^p|9@<_@=a)_$mHe*mb)f zO#b+26^z5UImX;}_(Q)Jpx(F(Nl-$L8Nahv?D(ykSw|JQHuV@H@+ebnC8siW2vCmh z^#eFTzzRZs0@rB_LlSnq5+0Q7q&~*VXx0H7{nevXexAys-zmM!LOzY^kC^mnHHvSy zKo?&;Dh>xLki!OE0mnRy%1TTH?nTg34FAJb>@c6(u2hRq7g;YLo&jjAx z0>$5X`Cqq!zSX{U149d`t~>ibd^|!A%Ck#H1V|ma&~-wg$1xWokfzdqghO%GhXhSE z%V3wPkXAvFLqG4cfVM}hMvE1h$ndO`6G!qsCc+MzeKt%?S-47f|26{*xx7)U?cB*y zZGmt@J%A1k{|Ce=k{16 zVD+FMNVkzZEtXyoP4%H%0{6S-jPXyBvm0#+WF`o#1^I(NGd$)8*JFTEkw;5? zoqq2!G@B@rK6l8Y1XtK5!U3DR>3diJ-kyFDnBA_}On33t*m(J3f5FMM5HaB471CT) zmnE|fWr?Qc$ePx&fO)ktXO~Ow&ZM*c1X5d|-ko!#he+>s?<_nqF|T?%4wquY7SJJd zofpR&$W_@|?zwQF{J#D3*Bynpw6CWp4nB3IgPGN5tDMh>g{zyLWquF><`mJJEVsO%ro*b4%D)K0JcYD_RPQixf`-RM?K6CY4z0hYi2A zlX;)l01~RrS%^wO4JOzyXwE&kVX{MRW(nUxX3@9O(usZ}hOgtM$T*>D3UkH&j7IU~ z1s7wrP-e5VUD7kj95+lIZ&&ytrt~Q0AZ{-1rf)ZLr2f0h^FJy!Gl`=uSZ~%I&^)1- z&vZTxViAY?95bz=lPYf5sVdRrzwx2SGOkz($whO7#R_JH&a*-8k+)kmWYr`is@*EM zQYv>=_CteS^4lQs=$+WQV+r=KS5H0D;;OWNG?x6CY*0t<;TG2tmJOj&8nDlQ7WvDn~J(0dEW!&1?xR{Ue`@D_y5 zO%uy7dh9rt18Ayr5nfYBZZb_4sdHkvk>nzD61ia>aCo;u?!k zn3=5InrUHR#bi)4b?>wIq9iIBjq5{v%hhYY!%>o(9YIxNQ1sI;b29uGd^4*cdNa(O z0FS#6g=_UFjv;{)LMH?Ja)8y(fiLyspg+tSGKQ!vG|;~xf(Vl^Dh0=a;Rn_7c^#VP zMvk^r{K!QxMrHOWoN~beZ0GoOkYDgFuFXv68M# zG#H_YwQMi$YEJ6?iu3a*UoTYx@L49ng>FS-x3aqfY%}9-L3Z58o)khMw`Pif#$CR? zzlmWR^MEi2{(+h1w6GC3dU+6lL& z1Jn-b;NyxcCbVGSJpAAK8J zx|}T6pMr)9+1S!IjmMfg$B*FUS3M=A#V^o37H?#=M4fbU;;;qGS#Wd2n~7__*{{r9 zH%1oy2>s3p98)uj+jnx8PECDpZ$W1*7wuG(g~?8BKqZ@BMr3^Q3o{#5+TY_-`s!ZB z`r040UnU)X);N7uF`k?>(Dx3_c{0tWPP8cZ{31ou4EE=)jQy5pt&~Zv@YKbyu%#G{(#d$`Dh)-jf5#7Wn^z;CQ+0+v z=G&CNPe^t8)lD?Ss97ne^j{Xg;+U?nS4LfEcw(Y2LtUZ@p)_BzAjczAAu*JONy^+f zbt-Pg@-QkuSHBhh4tC+n57wRh_SVculstEf(N2X9%3&QZ`67*FXr**InhJpa(J=Y8 zv>PbhMsPWdSZYwrR$^;>K=TIyrf56xax8g-qR`hicHeY6#@hzl(kJ(Qufo%CbI`$$ zM|mW1JF4a;$g1Q3TM6p!JnExU)6JfPRLc{C58#X2fY%bHCz@Me6yg7Oy3=vlI5L

WQv%5@A$3C~T@RF`WU5$x zN->oppRh=@J!RfR9Ei1$uK$6wPXEAD;W1S=4DEX1{;<5@}=EsEcB_blS{~9?QIkckwFdO;y8(#ahNq_U8 zY3~riH;&(tYrQ0-hQmcThDj(lv4_RzWs_HNlX)&m4Z?m0i4!#3$z&o zqO*=@EE1Vg2SA4MI$HEeoXVmrkR9^zN>D0&0ACh8 z1m6ibNs4cy&*NM=2Tfk~K~@L2;((`(L80%g)l&RG9%#v}JmUwY~mIP+i)UeTx#D#xYQ$(yzq?RHf$<4rpML=a4XU`E0 z4hlf&(k=ScpbaVYf<#s!ZZnaN?xw((Gw9@C-xhNn1vlY5YDWgl+ z_-wq9bQRHta(g!@i$Zaa{kH!F%RF_YJP%NZf7Jgxrj?CX9EdRCbt#z^3qz!Wp$3#kES>s-n!C$_#jXoOZlCj3G-z*n#wcTNSh43Qh^N+_J)d^dm=u$ZJN^Y_j z64lr2ve_bK$V89kpfnkV*gkk4&yV!B;n6Oe#b5_pJ=iwIoqfQFo~D$7L+j^wSP&X7 z?}jigz)CPb)}rOQb(S$ND0Fm^gsKnI<Zc*11DNSh6c*66z0Fa|?}a-LV+b5G#P~n-eR?TscDSwzp)N9= zHETyn5UT?TL#JGm(?2KoT+qNkpd!1nf>lAO+){$J7p$@TTP?--;Z@aR(``mx$5m*Q zEm9|z)0k=r9mO*@j|08SZ@k-|B*GN{1><2?QTB6zWRviX{Y0;Rg+-1J6rD-!n2&>*jBFa918~J>hEC!qVp5Zfyb8TE4UD|E+3X7Kx8hQ2e z^GnnxAgb3)|4!&e+<;G8bN>ZQ z9h6IUg#ZBH>-b-t0V!f8Oi(;$RuN9l>`x-(vKlX!PfHTIlA}7Q)7GoX2hjox8VJGO zz7jNpJ|X_A(!8Vhf@|a#1rKQ7!w5Sl3H0@V-DgK{UJa4V>Z->4@awD2T98c){O37a z9139S%4jOq86O}2CNgT?LGMb9*mu^I@X-Aj&Q-8%ssv3uZS0;tPkF!v_q#jk^}UXo z;H{5FCt5C(Wsmf7QwLL`*Dl@1nSj&P?x*Y27g`X7X8B`#y{o|8)m&W>VRFX7)_zJe z3>PoM>ueTGWY?4qdfqo;rsMkb!|cB!P|D^|&$-AmGp?aoQzIB|DdsmL@a zLh<{hU?P$9ugG-BD+InH+Q_1Gc520o5yx>OAyn{=x88B1QjW6>@0}D=F}nxmr&>YN zfjtVYGwE>3gc0Z>H4Xaol>@;kSx3QLkg3@C3lb75n{N7e5M0{ zNsX<>J`4|zU(7&t`&<^bK>9Wb`prxsbE$HaHQT4@x1K7Qb1@$Il-{Tu%W)yD&3H}7 zTx9!AXmpjDQ}w6dRUiTy^@Gy*i&gr9`MJ1{Z!WTM@AwQ-t=ZZQpvB;#IgFyY7H30~ zp^Ckw3 z!pPFNe|>WDai4%k!AscR>wK*?&$6|X^GjV_X-Ti|X=VYLpl802?+Mi#iqWZqu&Af> zogC804;FZnia1Y)GkIlE0FPPA0N?=P+`uoq1NL^z5}1ha{7K=`sH`XGJg7!1_qpay zS=kGIjk%_hpqxEh&O-S(dQgG+z1PWRm-Zu+NN1$9Ji>lku~#iGScy1auODl!py1ey zg9PQAHomslPoOyC=AnMU9^S^|ki>F;X#dF7huY*kPqoQC+t-)^FkkzN{-6X|B;GzVh`hLRGq88 zMDo?R;H+<~k9S82$uy&scYY9%TZN&BI?7fgef~k6`d4bm2QEkBcn;GqKy5eS_2Kfj zwT$dLE;whO1_yVxWM8;ufkR9t@jPl55J-ys&)Zh#i^&hyV?F-`Wj=WZFlDPzX{JIu ze8D3w&!CeY9WiI|-f|Q*U{lr@S)eF>DlW3DUdp9piGnTc1`tXPK>C(aIFfbeX_knY z@bgG=@RMbhfgq`CKXih-L%cTnqfrqhQDROucWA{BaBcWqi$B48o~>fd6!W0WvMQup zl+RJlG7*;*b$3T|`6KjiNhYZZ!4NVtAc&FnlTIt@OjvG1tHS(3yyqIW&EI5z?lcgz zwfvY;N@H+CW@$i{)0!S|Vts^4zJT~~2t zhYpuve9E2loM;-+BhESMej~S^j>$&Wu}eY#(zg~>dkoL#;ElE$&)!V!?aY$zWYLg7 z)r|*@pJlAaYTUIr&}a1>dtrn;?0WjWYUru=OBuzp?fH7!rnPARkTMDIV(cn}yskTe zv8~P8`Ev{wHNoryf%bWlB3tKhIyl}a$4c4^`_zPP9`xPTyOfw0_&owsyn(UCRb0+V z(QF(#03^=?0bl_48nP;j$IL<-BYigieTJEhk#)T{&_TKu=q3iY#~Wo%-UwMS_L@tENZ!Z;9_6 zeyh_$iRG9N0o}h@?YkB84q3C4o0B!0vsE{UR%E^GfczfC4a7*De}dzv;liKZc(D%# z&Osl_GK2wE77XB;cQ%!d0<1!%lGG4VW(MMHepZkx`@f&}>4G&5?e|A>URR4)zekhn z>Nh$qZ659T;jWl#wOdA{@t*%B@&6reG0^thPF$^om~pTW6I{-`RFg$!PoC6y)S2lK zg#^SBrg|WYo4R3`o}lK^B{d&mH`Xy8qM6@a_Hz8o{(k)pbO0*!gYXI&<@Pn@kfo8R z^}Wgz*3sUD!K3DPu2eRO8*8VR>c0#V~Ubv?O;v-jd1o$V+?HGf=kJJ zWlcNX+!rG!kDx7)XI0VXo8~yJ6ry>U_l&fK2cuz6g9qIo+Qy?v_@=?2=1AN=c<1R_ z0mQS{P!z^__D6!gkM}?CHv|6&qoLgjar@njtCvMPtv#BnH%ZHja!SA?HWbE^R5;wtMooC9tfmYCK9k1u3|OhJ+Jw- z+|{gwX7zsj^1ZhsBfA5i*VO>`ooH#DmiAaghwd4xxQO2ae{D)tZ@p{cnJSzpOLb9A}mV zd7Eb@7B$Mo9ySBn1Jy%BVP_{fv@;#GW!A6)#dp3*I=dx3v{@2R-wZ}zPPRq;J_i() z(2qfwKadMt|LvjzpLNLC2Ut2@z-WhLZB?gxC~aUAZsVj>efJk3rSCC;^;xl*J#Pu& zPl`_Uu@7)>Wr&!&=6Fv(ce7c+5b=~Bo%$?7V`*i}2H$V)Rjr1t3#X583mp_YgYRU0(+OMDeCvd)A%O z#Y4nGlB4sJG=B+aDzhuB07f*Gz?Z1+b6oLCa&ebNytIKSh{b%uf;ymKOY!vO^^yIJ zC{|KH7ZPlgrpS$cyCac8(%_Eq% zsdM|13U_qp5z;Bu8NkOm0B9n)rhgy|mJ1J_*CT+7-{6FlnjnLdJV;o`=pLY@8wNQa zp6F&lTH@Xe?7Md6LtZh$&Re}LlF{DJkN5vA_gES~PlK(uu$wNK#|-e_=F-6{rw#8E z2UFFYu4L_PK|zls-uxod6cc#PHy@Vb@Ys8A0>H?WOcLp@cBg+%8+;!BxK;anPJi6@ zT+C12Nxg;&k0z1*Y|-Vrb+Sy;Zq$Qcn`z3bo^q&JD4GP*Zw|F_3g~5p{7h`IwFcD{ zEUb)0Ja+CgCO!B)Ee}^Y4<=t!Z&-~E!7JYV+j3J94tg-PEl-d2c6lIS;lEddv z1vb&rP)3Qfi*JXEoi1{|9sZF>@#+QzD_h-4+dG6IpwC;w8}{yvZ8>ii)wjXOjXA)_ z3!&GpSeLWn#R%M!8s}#@E_3NxF3X3%@o+4|F>|)c&phmdy@Aq)(jLMSqZp4$$he}G zMj(v*%nd`EE*Y}}xL>)Ru_RN#(ews`7>a0~l~5_U9_UCJF+;LBpB5-SWf9UUM|@MG zW91gcaFRlMP|u&g82CKVOt z+94Ba!Uxd#?*nHZ{JFWKgA)aNtU3O@Bb7K2aq}2taS}270 zdVVR2^1s17vohj09(6ECH*>FvF_|X3i}M?3!?E(Lw9pH!9Qj|g!=xOclGStdJXuk{ zq7Y(+Mu&UK#f}AE%#J!3<^?RS;WUke z2!|AN2q`W5dG>!xGXeq;{)#??8Z0>YGmip<^LXxx(P~!yCtGIZDg8AmB8zfjb7sGv)(<|7dMCrMD;*- z#?exfX5M<&`SkNayUUp4R=d|r zSSLOh3#n;tK98nwwzaK$U7%6j3|xWz!)~arwaMcn*9S(pwY>hT0_puk8Zx3=uee(c zg{9@ioTWC0`?#xReKX{c?yy0GzXp&TK4e9HMF7(>JV17XprhefYaGr*t)yGwr#gn?#vJY?I=WZ9*U9lc!EDwi0tSyfwdMu`%>jlque zsVX_a;^@{g=0**vX{`Sb(oR)o^jTBI{YM+@&)-d-4hWa2+>T~T_(^uD^^*mjLi+9A z&NLH5h^_%$I33tTYEXU=tLYG+9VD zqV0QO^BNM^{|gp6=r@wAjJE5i=~n4rAoptJAWG{CBV6~;@q`f~MkY?-d_Z~gAWY%$ zoSl6deiWTfnmsK*S_@|$78J7If-k6|rijUjIUa)}!ly_-Zeiy-BuZ(QQ_sZ*BSN1f z`g;VM8P6smi7JppHeO7d5sD=yQ-OcjkVAAf4gG(I!fYFtQ(dOoCx%XJOKO3 z>U*M9b}g%Cgv2#21E~MGv(RZk!)FsYN($R+_A{XFd)bn=&%z1kUI-nVlMxqO&~w2J zM<(8cVub=YddVE3D0+FhvTO=<_PwhZQHJRgBIX`#*3-wpz&LaD2+?*ueF|+pzM&g% z!!dm=tY=nqu>V?nNODrUG-F+n;j3H`3BNDlwbF32Q$J@pdIl_8XCqvWNtn5uBH;lZ z9$s8L{C9ls8VviGdL(pHbd9vy0ciw{M5Oz<9l%-th)-@-I{ke>D*JbLu4$rfp!>D9 zoG0+Pk@Gol`@^k;q_H1uMc}_A<8L>6)be393MJi7i#x%SD_>P#!Cs2N`i9H5-=9EW zqyFps*Pvk<_&ovE_)Sv@&cdw|JJ_|j#PuDQnr@NFS%R*3E2ws!{rqbG z2%Q#JTIL6$ZyFYmGeu?_)VJ2Bsf6SuK^9lid$bm+SGbN)NOp(swVrCKBX z!c-AOz%(s}$U||lr;YM^s&By|{FGRf?Jm}6lx;-rUsEW~qd`Shz|KewcZD!cLI{2r zfFBFS{$sdolErD`B52eueG7)4QS~(<-ibTw@&S(zV0&%Td?LPTyQai=QInN@&ZE+o zmzcANEa|pHE?~5Kf9&u*?CY}?Ga(W&C!P2VHIHM7K)WE+;ZcavH_wKUe*Z;r3Qf5g zxlf{V7bFQS5yYV5$a8I4b8*w=PDEi(tM;-uPydOIr0pSMNrqb;X{rK>(SSKJ>hGom za`aJ4q-~j0xE!a9@>G3g(6*Na65_lC$?$+_(YL8m)P!F6Ql-@j+5$g=GO25By7P^% zHj5yJF&FUqZ%cG9MN$n$@@B;2IupaVat;Mn=?+7zd`lzOQ^h3V^ zQSqR5gifALkO(;!ud}t-1)ysGm%ji&dQ=AS2;^lgmm!rs5R9LT+yMmz(+*cEMjwQp z{ol~y(wSzMNa>u&@_dS{&=Yw%&0Zhfco-z zq5pp$NxrjBovzpaPOtvGZ>U{dgGgbOb3XB9x9bF9NpdVn8_a*UQf<5K^Duq)m~zxs zXS_rw6HK52IoxAf(Wg|Blt7!cORTei{VQwcBMzJ#sBJwVPamkl9dh6PD)i=q?sTOS z`~9U>w688(LKa$m)&CNXMT-xkZu8t)X5thGvqi?)HQQV^Jo*AL3I+f6-l z-U}@4GbilfMxxL~g~-m&4VUQ)pmAa>#LQMYrk*3*FtS^1phBZ}?$H{4C%Xx460jU+ zIgnyo2;1Z&%9m6?Z$wV;o}n7{7m4C-OZndNZAOt5jd3P`j3>oCqIEoan(%4IoO(tO zHbhqP=>s)PFBd(QM6jJO!sF@r@3!S9A zHt#{{F=dDG6e`iD9SrR%TTG7-6({3c(5P|lzC_49Svf{ld5DkUxlHFe3?F)rRvcvyXiZrsRa>0@?X4UGvKE2PZ31_!4kH! zcsQoL-#aQ?Ce3J zbGX#$vx1{-tJBBxRg>qJdF>UWz#;JPwObx$&R-4oKKmt*@oCJ7;hfS9&E^k2EL8T= zZAo|@%~p3SX%o=;>>B-I3S7(*)uvzb*AQL`7XABO)w$!P5@d~;vW{079r&&KLxQ}M zWzoU(745xy!EqB$)1O_ekJ+u%zKrOnr{$-uzxmB4TGcJb&}tnuyN)GCO#O1``x?bl zs5Q0FD7bDx9q(w#L(N>=086NuB(yq*0JyBk6lK^Ebc40~J73c1x}R>r0_7txzP(ZX zaSg-d8`pc9(rz{RKMd@vQ{%J&|JVa#c3qm&8t?@n+qZjdAAaP@MKV@?EYf)77(b&R zf|g5KMJE^X0pU*wP?bzNB9NM1<^*dOl6wJJ>u%e*QhuK)>UDt#n{pM@wh}^p1Eo@m zJcS}7oO>;rx*=#jUKmNvk#@K!N~BN3t#c(I`V3g(8E$avC*(A4mPxR?wmVefD)N}$ z(&|VLUeN}37#NX+5a8&z;(3`cSTBy0cJ&;Ft)>$qL*59Ii(dsD$k)XnDhoxuJf<)5 zDUc?}I{C;Kd7$p+qe`f1##~grJBj)X=T_4hGK!lsmkS6umIGmb!71#^qr5~oM!SI+ zGW`l)ImS1b9ITl(tye z8uJ)NmD059)fQH=KC%rlo8P;zAH;#fG8F?0QxkIc5C5%)Q9c#HW4NTjeXwrWakuVJ z}Yrj1sVb=o>JJByrzEY#A;Z9i4})qU|bH?Cu>rm@9i zb#YB42|vnQuh(gjLP$8fsHeLE9w#1-!Yf|M2MFh=CI;V)>CDW*XAuN~Kj;{EY`^^X z@_hX6>rIGm6>iYpo)+@QkMl9)q74APCXgj&Jq3VL$75w!_0&<6I%--B&r06rnmWj( z96Lo{K%<{!`|D6Jm81_p&(g)3zHaK@zaPvszZbAE(S#{w`QCxm)M`biWU^R;m6YcZ zXfa~-4_Cs?%JjTJoDX-ec5?-b`))Ayf2cl@pdSb+oZ%A!-OgiJtxTy!(cWXOE#-1FlD7#W|s_sHuY=` zF+=P_>Q&C1r=A%j3rGxf<9h!s9eo2ax?!A=7DfrPa5e(>f(y73h+J^P>1HqxdChbS z;bdIll9%J!pgF5FLq3Ik4$km|@vIWz&iK_V16wXlN-oztdX;uZ#T3erlz^3U4hz?m zxHP*XjsQA^XR=QuV!ppYm~&9vR_F|Bz7TG;&gBI(Cn`Q}Lj1<398VXCB~9N?J!+62 zIfQ_PgFp+dEd>4WRy@quOy?OS~6 z{pU>CiNz+4R6v2_-p4~0*E`Q8N&4Fd!m2!U1&;$gmb%*wpFE4ScLK{G1#lYMk_rXe zb^iOH1?9T^14Hj=DyM^D1r!f$Hd?txINNqZvj8Dw3)oK}A{BW+Q*Z%{?jt}g_x5%42dY*`4pxrORI1W!$d#ps_*^{^ajL33oUB6;vb7r<* z?ELAU1PDsTdNa2X?Dub9%$Xt>C+vZUMSImiM?M1@t!cJzFPZ$2d2>T1R>pS}gX0lo zE?T`8*T8&?Ps|ZZ(e^6omB6-8{x)nRd+GgSnI3BCYUt7Dpj4bz>ZO8mLCZgT1sYVW zlBlE$_PH-ZcPFdm?N&a1MxR66%HY%w=Ta5_%kqA{d%>8RR_y*Blr=k|s&^R@M=G{N z7tV<5vFbF@0f2WP)D!|J9HV`G1Y$PgYqhIZ_^s${I~N;Zp&cuDMCbz*n5Qd0PGJ zlQkH46AfgZ9W49_`-mI7IBWezms4k#y56AU8a`UR>(DN}%t7P~wj`nK8v|MdIzqwe zcK1JEe?7F|9`Ip2&Am!S%1rJ0w}rwXk|svgWd8>;d76Y)6l_aaAm?$|(%DUa-k!9p z^hQa50hze5i5zPfJ1k0s8om1ZK>PPclDMGYTyrP%)=ifJ$IX(&4@ZfxNZRZaZsL4SZWA-ZbEf>}ALpOsx)So# zW}Vx8c(e|}RJ=Y>EXZ@y{-y8YK5a~xPXSRXsLGr5-BCR6gaHF_Q88{oHUx+@!S?)V zefuwDMJ*_rRPYuM*e({z=RvKi66EZI$CZ)iWU#Q5mzV)) zuxHSDZ1%pl^9_2-F`KJiCHyk+wm4ITO!&sn@1-W_{rwoc@7C9^gU!0z567}5v^AaD znqgDLe^hfT$nj+@SGQ}xi*oRN?$TinK+mS*mr*VbuWFQ-DGv5Ah`jr>lL!5R;IQ6x z2@XMjFq!{yS#`QnKX!&_+~^rAnXIHMd?`6`Fux( zO(*v-wNMk0G^F%hs6bg*Y$G3T)U1SOE1b(t0%PMJ&i;@R7I!^U-Jq&WG`2N|Z__mw zv&3I2L}62AQX>BfC-)4OUp0_Qipl!b##2() zmJNaLy5^i2`@ic8*PPQvCOunagaOM)y8qyLiWlYLY>_fG^if6jRC$VqKY7{^zCaN| z;f!olyqPlROB5pVBHlXyyLf_|qs|M_nIjkkM@>nZr0SggPhbu8^?4ud)v(~DUpdBi zIz7C+wD1~Ll_mGn^5y9*f6V#$oJJf(RaJ5TaylDmAX(_V`*jdcw@d`|O&-99?*Y8l z_1oRbLv%t`Oi2HLC3EZCN(H^g`BIERJoNx%6KLx92(CXc+q}1Kkc#4*QINQW;x~8_ zSdb@pu9Ad`z@SgnduO&@A|4P&6-RrEr;l%Rt%j!t1?^3SgQZqlQ8Bh@I{a{l6g^b3 zc2}F<1~#UJG8imu`+|p6Iaxo(m-O_0RCZBzHq)Tkb4pf&|fXJz{?zoaQj9H%k%f?$nmZ?J~j;v1!+zT&;zg zS3vclP592OQ0n2QKa5#u%G!xOc6OEtoGr|5V}{zS>D@EU%Jm~25V#Dq0gVkQnswz} z`IqYe{CdjSM;}JkMELV$$_XYG4zY{tZ$Ln7X>wJu_1&MhdBKRsQ6nv9Ei*KMM&_sR z{Ygbd4c*{rp~!=#$7CKYnE~NdNE{|OuMjt>jdg22Jih9*#YS(fEATvqU7iGr_&h=i zrSWxqNnHl8z*4b(`cm`@*%$rB;EpC3+oW)5O8xXh-_P5L611`LWyEUMBg*NejMMDp ze2tqd(9$J;UT?9$8j=wk$7bu{+v}*r)1MCWmJp;PQ!@p zh|wmP=pn#jN-4m!@gi4>?geCZp(8fKVxX$ipJB&6RTYZ-y7%fSoUKELClde2$hjK{ zr9nL%Dv&OhNhb6&xY=YXG9_6*bZ@RfH&WMT0CzDH0 zW%MrIpy%N_z<-Ki0!gG&LO?3AWk4&aly>Y>-7n|$2R4+W$ta4*!&JsoC8-RH3;+6I z#_qvVan1vwaem+5a{ROW$DLFvb%}-j;+kZHj6^DiPbYc_oY2q^#$A`CQ5bqA_!-*C z&*MMVRpTj}#;l4@#;`m3nbs-2MjsFH*uFOR%vnexVT<`xOOud^*WjrK%}f@GK_qfl za~5$s(wN8#F+NSTiQ+EtlW|XulA9-YslbTYWMt^=CQXI5ui344wziHK`-5`CKagT0 zWM)(DW{w$skf9C-G+LP?4Opj zKwC%7xxWLFJ|!mq#1t~B4d+!)oYtBSGpwzQybdX5g#QSCsU{UO>sfIr)Z0|cHU7IB z!%7c4Gvt+P|3&1e{Q3}nR`(-6-{tNE4A7&?ogG>qGT(u)QMWJ1TTGghIp;+)7Js#} z^3Fk$B%JqB8W+sS?tU|1H7kXrco|E!PUgMxY7Hr#tvRa>k)Djiew?;()!c92K382uS>rWUd=na#L&wvZD?R<&*X`+80 zhDMD9={!?m-^>^7CqOV^EF|I`#BX+_&DjQ+3G7@yyf3^JLw^Tk!*HwS{*FFCy9P82 z?F0H28!WLjP9an=U-XL);&<`w0r9hgCoWy+T!DSQE-1enAAaloZm&R_kN-p35M{qbk06tu^&pYAH%trHXH#69 znkitV5&*jP)_X|Sn`-$fSW|guV=S71`uB>^jdkt;&{Mc&BT!*^5+5~GOxH3)Q0cp< zf_gAZXHE3_va)0vJta{AwbSbK6OBc>II`+-C)p8{E7yUCojtVv^{C<-TlG0^3lwNG zME+`79-sG&^SAL5AMNbVx$@-w9+2h>`tIH*c(RT-Z`9MgBfQ^fO&d!*PA<^SCl-L3E&x>2(1gZmZYV+oW7A$GSegPB5{+Bi--; z=qyDPW_aX@+;{&#v^O1?bHNzSEAD&(?-%JUAojR{@apJk2G17SNNeAXFIcSl{q)&> zdjlLqy{-e{SZ+9kw6~2K^n{-iqLREVuQuAK!$NP7-e|!iI?z3PQJ%r-O9q{v%HtXmRDum7mt@ilsrD;$pp4*Hj$`2H89jraXVey|7h|N$rD48gfZ2nefBa ze3BSk#6+|Gl49sxlT5t(Jujeag6AO)hR{jC0~s?IO9zdDogz4!RljVza}Xb@Z2vW) zS0>+VHpH`Rq@W&OV(}{j%uo$zqqR0kXFFHL0TR)|exDh0@L=b5J6Uox_g;IIcZ0XY0MB!*5Qwjp&qtVrZG_4j?rOv|rX#Z0B4Ue-SfnR?*j zu=ak{v_lA+5?HV10k}UIJ5ooZMUsUp$0ATy7ICFpNjG^Fs$jc#Ii80 zw^U41PqWiMh6su>USM6L>86`Gxxpx5z$#DQD{HYpeaFa?U!Z=v7GhLh#_)AD7D}BM z6cH$zH9MBQs>!~>ezKLny*;!0;<%YAb|^_>KbiN+i#U5%#9d&&>|~wovh;ZDSJJ8d z6d&XGC(7jc0wmb>xvtQTrhp{WdsXVSAV%iB9|OqFFZaK*!C3}2Q0yet;oRyOuUgpG z7xD8c7QgGDpkLQ*N-d+rURepAqu9wgv87a*>-#6}RfQkptMJ)B*ert&$ZU#i@AS=~<>}^D6VglWZAt5I)n#-jXxN4E`2r~3uXwir51%rxPbEA3`%AZ>()%`sBn-dV7) zU#4CNrY_;Of0US6IJWL~j~H@&pGrt5JP%WJQ#fLjJDxBu_$<#>_7aTBHI2qFx~y(@Q9H6=Yn8IbPWYeS95=3D(mZeGc7>C z>|P}Y@lc*xr`iBdp3ra|!FnnhUn=j2H|>Cc=d+xx{@>P{!u|6*;V)VQX*_AEcwlkQ zxB8*E!KgCw;rP3&e;T?u3Gv+bNqiu#`^NaPnT;D0v2OfZZg<}}2$ojw;d>CrK4Bf3|PqvR$6z8K8sOvc?qPjXq5%^07gg6n6g zzac%H^q=>s;C6`qzreMl&d{38 zb>J1I_Cuzf=E~KLHz{akWoF&%l6Hv~3847CVW{IV6``ZbiVA|dS2sG^KXB1Jk@We-aM?YV2G;UTREMlpu2IR?~GVL8c zIjIL8^Ado7CZt00%UIau-7?bOwcc-GsKh+s3LM?s=feL$!RM-jV_IO(Yo}6SlQ)Q}A4`6EKfD1KDYAqCRy(LIb#ng46K@nC;KAUk``^ z0;r`n$on(6Ky}Xuk|C*@0EAthY{}y~BNXRk8&?{Uon{A%TD}jxf=>cN*#8N5mgQmLifbkNd;-7#Q8C*xVEgak==uSbYawW!1ojO z1g&#&NOEd%tyw{`aa7dYPsy2J2>EV=80h;?n9WJP!oEkxLhkxtxj`c*_U%V9Z&V}4 z{Yv9lNrEx(6^`x7KxZbdo$U3kJpOS*a~m-A!!#jo6OCzl2X%30nnVEP=%3l1B&{3 zYG8hJ+g*O!h)d=eEPx+~9Ds`bYxP48f#M0lukOA~vVHF;l*B3i3VfB=>t6>b|U5ck2G~2a;oXNJl2zO#asCddBnx;3*O~g|Z{VZu@L22X=*x#>qYZLejax11z z*?!(-=KAQXn`;`oS1!@5L#{@qD+NrCPGO(WoVB;;d;-<#7Fi?`zdsI6D!=LY>g&nj zn|$rUA>nZU%0GDZE13I?qjS0XoYY6~s@_}WWUQt0V*s^G`%%l*UC`-}Y224^g ziHA$RwnrJknQixuu-Sa~e%3RYSZTTCMg-gXn^#dN8f!jS)c-FbK9WGA9;$G(1&Z3B znUANF%*E9z-9EdF#KJkC{8YG=)^$hM0!NC;_`Rn4uXm}U3Xwj?`ZwE_tXT5&*lP4> zbVIrS2rH;VmzR%@5=msad-Ts|af9MB4m|_@vyn5Q4joSIc+Z0ag&Nw{rA`JXXc0h_ z*B?v@&sAxwXzeFSIkJPtC@!|xV8EaRJ3`9L88BZZOpyu0XvH%k5(>%ZEOfhGp7tsM zrn^`A19%%`X|A}j>GB@)c0C?lv}|Q|)A;-|mf>p>{gdk4B&8N%L*|{9R;;?95sG`P z4}JskuMcBxxK>-HiAw2^(=WsFH{ownvN3akFlKOTPde(A(LomyvGLtDQK#DdA*GTt z3=yYPIm-iBcu-0BE-qWPbxy@VJ62|&kWby7I-0k*$Uv(73y~=3{(%3NBgY1S-d5^V zH=KAN69>viGVRjgOz!opWx_Yda(<$Pf};*Js(@?HNc`p*9l|NPQ1aI4q_T2;+lxN@ zh%xX-s1hZ_XD;bk$Vz_zJ7nv=nX@BD*$Y0?~v1jRYXbQeyP z;v7W{j`vAagRVqml0nYjUN{k7^%C!QUr)e)t});+TG9hSU4ZP6N^;d%^%-SG)qn_PDAv^ zm;m`d?&r)J)OadeQWh<%4<4fCbAt38?7V2G8_~wlD^WRmAJ=8jg)0bw9#~u(ffLi& zfm3s&AYcDU#wCD?>!|_Cd!y@Vv9`ioj%$4K6g*z?yOWLpV!+aTsP%AI=1?r}TXkE0 z%EIZy5*G@kIO^QiBot8q)fy`y*;F(tI;^|q@M=Q7fD zxb{)qKT$OS*$Hu1Q%0mwYJK`p!f_<>HWYH`ukb^dMY8n2#5>KgT>%fY&_=C~@~seH z(!Lhzo$7rFk&`Otv(v<&e*ts@aAi_QQ2gzW$x=o|Z}64F5KEtLE$0fsITSQqhor_W zxTxFOj@2#lmhP)%E;D5GXuJQtpFW_hqoi7h`wb9P-Yc||Y#`FW= z;^+157m@=IxAX+q7{K>i#)Qxt5ND8aZQk9KCbI2BdV#lj;{BR^tr3W)LqZ3oGkBQf zCD0SS^|P&qctN}F3wQzOd<94LYn#lEw8^U6R?RF*fIjp)RTQy7tQiMGI4K_eGE&Mx zCF{_IB&N5_Z#563F((#HBAmfLC#w65cRpkhd4oT zbp39?-d?J6nRqYBPuA^_qyhQt@KkcTSIEy^Q+dLm6wN((Dod)s?`X%*rhfoFjl! zZG<^7hU`9Ck?#{%AtC9Vs>=xXWt9#BG!f?wa}d>c_ZyvpKY^u*c>RHFj-z8<>fLZQ z{ps|ml}Ud|8;gvD*!i6BY-9_WaEnT|Kz)Vg^0Kj?>sCj{rY>vQS@{*PA5Z-H^$e3Vs+^lG7_&ZMlLa(R}W|i8Fq@ z6ey^Fck)saT76_b7xmaxYwxZ0y#^pOX)p;MKrVwy$Vs^|g>)4ko-nFi&u$R#R-dw) z(yzAEG3x<`J~oTn(#-ub^(@nIkd7%jDl!YjXp-0-c$3$g&i;l>`xQ2|l6@gknEyq* ziCeGqvu~#zjBW^fhKu2_C<2DV?wp;`TFFalIHW&Iv|DLMr40~gl@*y6wD;|$KTtMu}Q;LjV* zfz#{54=Xwmbi)=021Eo0u48ez9>Ee^yfhbXdKCg|sL*&OK`V7B?YI&ePO|T=0??sf zqx&@B;WNZ|DNm!ht7L{MT^6%4NyiaWUS3!T}_db4PVP5Z!wUsk^ssnTo9m zUF`QK{oi1z)^-Uo)KmWul<)J2gqJ~K0xL@{o={Vp!gnSgJY3$r0qtp|5Of%Yp#l_I zqz_o(>5yuJW|d}Vb0L!yH*9|A-Nv2c>)oxvDYE*ndQ5|%@0ODlDMVP zrKhoIWWd+LH?iM(UsiV(bxjU|DUhf-zycShhA)JQ^ICqos%I{uY{nbadq4=wU*K&# zKV=BAf)b}x&!vQwV34-B6uOzyLcwx9n$JK`NI>uV(?X7R2 z9{UqVod(6?PegN_8iT#Li_~)=kQD(@7xqp7D9>zpmxE7dfguNxh;^-r)EtVAL|uq4Tg* z(S;_h;x$ou$F@nxts5F+Vci5yX^+~dhDO@0&%jF5a#jQso4<~yhr{r~|66x{XU&`$ zf+pqF(*4q1(o^i)DCs&j4A!fg*{ z>C<}8K2|fX%$KBNt8>{^Bu88Qr|9Ni~N zQ6CGuehn4h1_~JWJ*{?n0-sMAHTv7kUrQ`tl6;8K%=cq+P7%nvH25fwQ$#<#l;5}JX%fm0~E zGzV{AmkZF4*BP5SXt$ovTyQ^|Dv8LO=Eyw|>$ zMK*W98{$K!s2KVHEA}g6`U6m$Eg8{*O`#krf=a7^4cEjYg7wE-jp%o#m~~tq zOyyYAOz)I~WnoX?zp0{9y~V91zC|^GmV--xtK)qWMmUEskz9D)(%?xg>7bx=Q177Q zY9#trvE8luY@^su685ZW--hMUvlQ)?PjQ*%*^;W#LUZw%R^Tjte`W7i=URJo0`@P>2#o4GZ-|` z6z2qeo49|)vLUy?EJ)Lv_!o?qM#z2NoCIVEM~Mo1-`V)^rM(z?S*E%LVxWe`?^bdK zyNNr#fPm=z>3n5_atKP!T{d$nwJvdl5MC6pP>_l_I80x?;3;{+QJ^-jSg;z#`|K8m z#3>@dXhd5haV@uSNqzFQQ)-oKHPf9rKOeE-dj{JFBReY5$j^5-R*@Q#=ppqu*p85(HoC@rCKxA=lSdC?l@sM zF89-lX;`^I>esrxLw$~NHRU)dXZR_*H=hSX)v!M!kb>Gb>y~xCV5n2gDO&c$q?9_G zbH+d$=Xqk_i92$QVar2~bd+6%edB-Hb8+!=%Bh&N6%$|o{r5Eu*}+TjvZmvzAuhd^ zvjJsKp=VTJJ{uQ@?DJkA47IX7lYBlyngK8UHM~MKNJfO1P7Jb9Ll0F|(JENlTe*9O zNDebf(4X0;o4uK_SB}7M+33q(kjTJ04vC3z|F8lvItSmZO+RNc8GfN;l9dk*(kaKh z8GomDzZ4`rMwr~hjY1)UG{^wgYhD=wXLC{lEAK{6Eg#Ivti#89|8u+4u%#k#uiz>4 zEOG8a(HBT*oAj)*^b9m~)Qv~IydG@}PLq|NENZFr1?Ui+*gc&zYp54KaU?poDSodf zO>H)8ak^Y9-gdSS?v{t(CUJp14lfJd_gxv(T^B3e68||9DXNp@ZfCF{h>S$BvztSZ z(0HSh&C}$CbhgzzeGu`d#dcGEDoO!13@Y|MT(u9xSBS;%feu}zmug4k3OyMnER~kA zdxXDlik+Kzk4BFWlxo_}}*XNSq*gt6eMP`Rk(4HUrIcnIuO0 z32pX)r9|J=b5xn1chX+q(1ti~8<*!JODLgvwDClf@W(pAyN%{QHg@J(h|-OytLMB>npFvW-^Dq?*BiEU(<%5MSc5``Sy90qsj z)dL@GRAfa~iz%YQyU|g-5h`Sb7}E*yv{9C+`b84OT*AM>l8uBQai(p*_h!UTzGif% zlq}<8z$NNzoc}PA7rY=ldcE^45xpQh?A`B=ZOE#09~BbUS8jD^B-YfhDN^??f=_0; z3S)kavDE6JARGE6i&IFDYIWvh>!tBcNg$A2TrjN3*KVvf*}CfMx8*-~20evdv@G0` zc^04HnYMwW4ub-p!pH7WqbUjXr_rJ?G0EJtjN|r|l)T-F6YkHIGpSL2c`WROwlekKw&=U$RihXZf&GMG52c$@-ZE=3p!JkhbgDU z;d!a)gxp+B>~!~z^09p`veKg>XOg$~VF+;FdzS}ri)76351op0%{ni!VCjB~Jl*4LmWs&;f@KAHEq9zgoT%b&uS38y_Lwob6d zDDluY3@0YzJP^(XU7b7V7TNh)^NS^oyA4^w?EL+f)`JR6_AC<7Nwk6#u!_#%ejZDf%HU+mXRA?PY zh99+ZlxAmpvBG5kHp?fMq&Lt+W!DZ)y?ZnRoKK_W>UW2v(>C0eoepoiHJl7bzU|= z`T}}yuUJ05ZiSGJ_}O6T+h$ro`ttYK8;Ia;Z3u7@($c<>yVD4rz-A|VYZdLo2Js~q zCM9Qi!Wn?Q6+@#L{fw0hj9*X`2Fhel0wbbkL2px5_MSgB%OdQ8y-%?!PEMH?E_KbR zP;~R%)56j&djx9=gZ=W{>Ma)Xi45A==}e?pG_?UjkD^x=zh4=tSqG~XqCj*N);(dk zI0+dfT|?_bQ1>9Vx%w0_-dn=VC>e$#DK87;yihTwl{q+ioD}A0L_*ZSh>|cHPh+$( zTygz!=sNDPFit_&AQ=*!`K63WY8IFz)H2sLB|2TvZEKDYp5kp^4mF&E;_jz)5pZd^ zuG8iWu|duXGrZOI7n(psv)96deZpv}5}|l^_A$I_!YD>LMj5>FQNw#3XYzW1T2V^7 zbV{dRUpyu{Y`;@QTSb71J`1tW300Hbd=&EG$ z+yIUwHp8olLsM1MGU&9&Dk2k)NcEPm8p>&-Sdz|<_XnH9&lS!3>I>dK23wq1{K-N^ zhP>`bzf83l)T3rH6eu;he`p2?T!tR}xWF8QKIzF@*gZa>dArC=$xzyrFN3yJ z?K7;R?US6AfzIieBV@CEC^5f>y z9b{&b2)o(5^PU)4O0l#GCv!;Rj*)(|TI#_Hw|CnRIhPpO_n!9yc3?Fp$5_|y`xcN3 z1|B1nez5EN`N|(gy)(^2C#W9nS{QQ2j(ysCs9$x|E9c<5fH;AzH|JudWD#n>rMg2wOgw zO(6;RS5{Tt5)9qVh(K_H(USV^fpoO&Pbu&nSwXbSZ1S^9z83`PkjFdG$ z9@fC#c#Sn;2M8%7E?8YASS%OtlfSf&@AEv~mA>->Q@xo3a0xPNHaHjnnL}_DwSA9< z_bp$qqfRLC4KFK#$maEdS0N|ruF`k6;DPr8M5F4dObzeQ$@^`eHuflYy=0?;2mh(0 z{ce@7>gw9ZnE-U)kl$cph>wb&8Afw#hKG931TP{J=GuS}R0Y~t*2<3K(^YK=NrVtJ zJ%%R(rH1bCmTK@I&CdIvIXH(FT1ELW*1yh-6_(0%IGswT@BocRD~O9OkvAz&OitrV zcd7XsXz#-0gDN@%__iR_DPTAxIbr@*}*p2WKlAhj@LenbZYQ}z~C#p&a zdrmV}eF?Y4uM)P0%yiw`TX7c`TlEB3COl(4DO=kNSl9EVJ43y`+w1;Vt<20QlcD*N z%G&bH4Ccb8yDMfam49xkBVE@@(5bWeHGFo5DOaMQZC1kk<9vWcd zb$f1N;tl$}D6iRgB;Bk^uuriD^nLE=55bEIjGKupnbsv4>=f<02sPm$V?}4L9)smwK4DmHMc6h#2SJ+!Pj0 zO!vz*ZMXB;a(7GHCk;1$WBGcf5IMf8?S_wkg@qx@7Ah(nr>5iPSi8MAX*(E&IM9&e zb`s<^gDEi8SdPz!y+wgD^d26Ll@~fzh=-w*OTd;QD}X5#hWsuH)avBBLCtNkU0302 zy@ae=O?o#saQo>BzGe235g+UMAX}hs#;TM3wa86fR&yY~8b3IZG8-N_>UJ@zFR!Vp z6~gX^o;FyeHO`z>QTgTJV%GU&$Hl1PNlwlelTPl_xB%T$FCTcl(FDiMT1y0^V-h8Z z=GaY1XKnk3wloJ(LTy2Jf>CN2Ib5ZH$C*Hqh)^!Iz5uF-g8ZH#`E31v;@KWTe9`@? zcBvd@IEhh)=;iwXsPS$WX!?uz4KX>6+`OAbv`FK-#HWdgQ_cw8Vpv*(nk1(I?z3~4 zTSQ+0JboWa-my3|!tHIvcLA`^9(~b#NE&ka+#xA|dawkbL`>cvw8269G)(bzqs%-D z(MNCWts9uzmeKANCwOXxx-aAjqIqG&WRDksqiAur9xyc_qyUKjd=0K!oW03Fe!v~5 zma+G0R&u+Dd<3PH=-ut7r4}t(>_GkWS5w^>F7X^RXFP74saQ%tHbsp#kq5F6E}1SPOou^g|P4Y!aqL#zF`=8(lY+?AN=hSduysywZfz zCK!oASlE-(1Xk!qw^JVw;QMB)WGx$s0AHVj{-l*6&Q)4%PpSuT5L{=Q2VxmHWQE1J z{uP6Gm^yC$lB6<8E~V^**KJWMQmejG$!S&rFG>uP0pVw_Zy(6y2t8k^0MYnijDCH- zN@_uQrX?y$s!NuTo;snhXt5*m`@o1E%+M8Lv-jB9e}}w<7(T^M#?_$TNpScLk0@IN;@{sXriP^2uNo^4sZlwh%BG)55tKvs0{26!&CP!C|%-wTz@ zKJ3XI4UV+dAS}S(kP}bNA8pzUOd!qjdkT9b^75t$-Ol_)43M!i)jp+j4Sho;-XxWE zd3CL2Rge&*(`4Hv=_tow9NHbbY}0sKbNziRO4!r-)=vW?rhw>HT>jOj zT*i@3&QwB1=i}z#G&1tY{F@NA>>Cx1qQm3$HqdF{U}y3J&~S2KIMA-txkc*Wl$Eb( zDw*2nA_DriT@UuZ*QtgK1h25tXCl*v`COXD;o1xQijv>`eSJcS^%qxO+7i%vI|~mCR4#X$ASwy>461KGAe$0JqTpm! z22X*o8Yp6hD~Obn21YMqr+WZNE~7ALGnDGJ0ktZV?Y~-sW`+A-fIGIgGvf|Z9#eN{ zY8O8^y|6U5Q7|F^avEGtD?=oDu?3>t$WoHlgpSj~KRaK|ffK_D32q=D2x7==Kp8mr z%AH=_78)AI)`=fw-Gh_BE*YG24WbL5cDUu_*N8x8bbmiO(wSe{MRj%PXo1K%Tgry^ zYOabHM+RDFzSn35yESAV{u|WHhrr*j zbo|%FJ6_O2p2vw~jaV26l*Jj?n(Cm{h%%HSbf$&w^Rp|5-LjJ{=&(NdD=%*O_B;-B!( zdfWywkTNY0)o>-|B-r*65f%GKzEvaf1QPPCol+k7?a~vG1`TdtyCx{@Fn0KK#g&-^i!i7vw zuW7ujn^(*30mHk;6d)Z2=0VIe0kuTLbDuTaQosK?wqN4@{l;(y#Lrwm@Th0*x>4_1 zDO!qUz2XhA3DxAdc+;f3RaS?5cn0g&oSwR-MOmW z?=%12#_lCXZ%5@GU%sM7{dQc7hw>SdtXiF{k=kIQk7x_`N!LP9Uj_3FpY7Qpk~2zF z&ar1jZYMtUnoDX|jR_as(Om9bd7?bOh2{8|f!Hp=bF-Gr=v&b2I-lv%bWQsGSg9)< zB=#hD@QS>q@xh}dKo&PaMdHQGr*{XEw@sHwal2jhGZZx<(DGCMZIWA*U*lPk$Wh~Cx>W{SB_Iut zygwW_YHxS7*!W-BY~jP^7n2rIF}E)Xy&0z$2TFokH@$N}>e&Q$aFUc7NX-@VDfYD3k&&^`x$1L=x<*B;g{OiwmVg$nX}Yk# z)kOL(){m4(>4~S*LFx_?7jZw+r<8({=5w9y7B_iEBS$~Um!)dvh{PJBjTQ8>%?^{& zDKfB$nXmSV1I6!$({<;SIxOJrqu{X#U;hbk@vuEdwJwp5a8um zaM~#IcidkwXtrDJeEfyan%?rWYaXtDJqmx*d)?9NF}CG*LSj>My(O`tJk}%@-mN$- zKHS1Lq@-8d3+SB4>8NudGUN{m{=SYrh2GOAqgl+0z)&uv0HE4P+AUT{#M6I2Yu{^J z0r}^LIm}c5=xu-*-!eIEs4-AOXdi2=ug@=|?C$L9su!#+@6PnEFAaXof87+cumiYHTSnwD=41y5PUeyA<9?OXBo zbo_4i4jtX8FcTOVfvORau#=Q=Z%x78(=$w^&Ie64+my58!_sZ1)5S*B^GLwfAIlM* z`!5)!p|HEDsVZMgaGo8r>{8gRthVyU!+*NdS#LSI^Yh$oI|_nsOOE!AO6IhbdHDQV zZTp{M&UI>xZ+a1a*6MZH{aGUOdQ*NDIi2%KKmyg-j-KZSlGcZ!XEudynOrfMOzKkI z+L~`+ch+jk%FXKJEKF$4cqXu)(gwTCv$Xvfz6uMItDo!6$ zLZ+#AQZ?q6xKM%!8M$*W*r60c#?8W+lRD0oJ?4REM9XHGOr_Xpy+24~jAAo{C{1bL zkEoqiX?|mPp!EA9Hb<(@&RHlE>oMkWwK1t&Q`6=0KvLWNe5+`Oo2KD$+5OLL`M=jx zp6l_HbX=C*&ad2mzO}|bjQzcqzyZ6CMzTclsV5LS7e~}bkS}^~j3#;aMZ-AYnEL@Olj3U2 zrU%JiW^%>o^ma25>=53qnQU=b9qoGW%U5k0TpL zT&xFIMJ{Fr_ZE*7oeE{F7@y4eg(}!HOCbnhKz<0>W02`Ye68I*YQc9#0s+t_YL?AU zyFT_l|F>;opss#pkoCh~eLVXld{K=Y=Y8RG1GW16&i`?A&cSguTojL!#KRg%zSzCQx( zu|vJPSqAwY;lU~++xf4KH_U_SYObMpvN79MyN7dodhLJ2y7DE5TR>wLOXIz2)$y#nradw#Yz|K1T(?5arkkbembG*(Ab z)|{`vKHID}5f|sNOc~PrL*jN}tJ&-}H+pcUHmL9c;CT~C3+sI1-JtUw(xsC$mEZ_q z%VoD`+xX-Q1?g{M33Oy-qJVHOo+Pj8ZRU^i5(I<^$QPQXdtuBs!_|2oug7EBJ-e;k zMC>9_^}p!2c=Wo>b{jy)ca?7KX(*n(xBCn!yO4N!fa=^^E<9@g5$)$k%o);oSPEY=py`wA7zH#4j};(C2UL# zw<)>%k2*z&z@5E2vHELoF~MA>>8A>eVbXAPgkJD$ENrxIWl#&!OVwmPTMn z=h|LVYf{c%OHky$u~;fwtek^ZfJVeWW^(rNxNNc5S6>B=`8Po5!Y!H~*t9v<9l*bm z(=>jAWV1CnK9<$Yo_)cOZ|3DbFXs_u2^w4^e#UB>fG=Sv4I0tI(K?mNXYu&zzP|Jl zd4GkWHblYw%=0{@Hp|l;VTh1}`U1K?{YiBGrNK~VWmHTH3%%A35yl9)*14XkZ$^pY z>STJk_;7mmKpLd;xQ+seTo)jb%7cxrqI=YSBwdws`CkrEe5%4ShC@+z{O||r&j4EqBDx~Fr7gxhy2f=FF ztxl6ytsDIgU4LjKLKgG!Wq|MNce_trBpGM5RK*{PI1J1pa+z!%r}I`4|J74F6=zy4 z`-3j}O~;dnF0dieTcoi6m_{ypbj5cvEVb~A3;H__y%>Vq1VYR863sg40I9L?&Gk~8 z&ht-XbfTJ>T2(v8Od&6Ui7Ga1TH#ScjqFz88f15WdhBs zUqJ6rf!As(2*iCepb|i zaUXItGJ&AcE&xX_iuK!jSmE4ssc%^+<>03G6pM`@p3i#vs(H#2PBdHcVf4IRzRx)5 zu(}#_eY)2)gy$2&P5=?3RaQ|dBprU*rQU37CBh)_Q4S_W=iEG?lrE<7PZmP<2SEjo z!+~c4kLKK%+e~@-p>=Zi{G{WhffY(zO?U+z9~7>Y<71uY)1>E>@x}A_?g8;%!VNT} zZ&- zSe{Kh&G{mI7FSZepUIHPO-MJT!k+@3eD=G~mHTQEgovwK*~O}+spYK3CkgWze?25& z>3;&{DZO?b>J|GeZm6RczN{-17Q7s^b}i-wQvJ!!wnHpGL;mc~vBK+DHc3HN_Rud6 zGOIEijgV+Puu-Q(O2$q;K0V=}vXT}yJjhvVF=uLV%*C%@{4C0J#Lgr!KS8#)A9h-w#YQUH+Df+ zDDkpPL)7hWqTnWfY!E7JGdem@QZtt&y}+CA4TH%tm_pI04IbgZn-!4Ie_SN-;}3K z8MI#yPF^Yqqz(AYvCI8)I@k??vlmApNEsR$a*zU`vUz*MH_Tib-vhCRW|_5?LpWFr zoN|GcXynhgNI-p6P1YIc)Z{ZieM4AsoFo6-rxXAXjYo%vhh6svj2rE)XbOQx$M*ob zw#=X~V{UFz;cWCVn>(zF~{wf5aZd4errBMw|{} zeSZ4-+;YBu^1XVh$xZHQLiIGh%z%W005_teE5QoKFO8Fj_Iv-l`Vydhv+#Sg@OuZk zGaCWs3Xr*EVdhlAKs+CdOJ)9{=lf0(X6fZ?x3gQ)ytu>>v2g0@VFjA{F`iK$T+Opw z$mm%BhIT|XQ3IDwCK;s5Eki=;>d3Tf;tIW6c$IBMmeix9!YKk4UN%jMEHS zex**S3^G)6z+k^G7>!bq*#L4;u&cER(cVb5ZJ|I^J0DZW zT3H+^OF;_@H<*Nq_kzhV*6ueaHLJYSaG87!m*D~4)-#kyl$&KV7--QqK4flxxN-D# z#%kw{VltXu1l$70jZQiF9A+N?h2D9WbG6a#L7QblYAF|=q%nz>=wEZ-xURdInT~%- zL`7Oj#Us}cs%$MglTgs*m$k!hL6|mWe6A)w_aI4VeC&+rrt^S+0Xcb7LW?fMBdbN^qB4+t=)8ewO#LHWu0I5?*3;bG6Hg7A+9Q8jyxR-$S)OM z>X)*hI{t{W(V)vlOoh4Hyy?`UW@#hFJ@XG-%J@DrKW)ADw|h=>31h{z{YDxH!1GD5 zzMs-Z8`-*;}r4gPB^C8E&N;fZ8A2Sn^nAQPrYIajw!@9ept$tz? zQyjst8pm`z^NHx1BsowUI0fzWwvX{SMMioCPP_@bvY@hPCd-7pv6bbG&d$#`?_;tc za8U?PY++kW6dDvfGzbf(G=q-?gOBMj0SJ6h&iFn#VZhtw+C#<4c&I{$Nd=DN_Y9zr z_Ct4>>>ee<(B3Q^Rq*ZjF3^(P^Sy4YrU(E2 z0YEdxGNCg*^LE|w%3T8rN{N|CPQdnKHh(s%kP-!PO=lzuwT0yf|HEnz}Rc{evFo zb-v^AI2yl2#K~XMA(!3(GaRai)W-+fC2%Ytz?77nm`@G-dp?$bw6J&uI-1cp%ha1~ z1LfZzylUx)j(jq~yG&}!<$8^Wc+qCRrC6K`c*P(+N~xWwipoTpwM#*wOZY}%K&_{8 zy!=W2NbJAEuE7*sjapoEgXg$WUW=*$mGC|Tn7q<^=BizTGF81onPIj#NDyaSuxk(3 z#5AM@uL$h`D1r!=Fu+x9>IiNb6;-V)G88OYRil6><9Ewt6eyEgdYm;#h|vRZxaod6 z26LXL*rA_|+6VDInqRY&V#N|eN1XefeKZZgSw*J7G>zcoJOC`r{>{zZkpZ&j4bWF# zz2K(h0FMOTb2HcVbL7uIas*nRm6Men5$Sl$K}Gou5hwdC?MdvFy`d|Sp{~0PfP}gT zS%Y$0WM5@`(SV7T;eDpFC9;=JS6&^&&>&im{0Yu-{UL{&y1f)fAgD=&?CHvV*fX?0W+qSaoy^)=V^*`>{8^(23DOr19&HG7b`F0$BYG1D=hwdCCofuq z?%c!v1-Juzb}S^A4Oi90ikPr8Ii<`(WknSqX+8-|We+D4tQBUIV_g=xRPuZ4M$<() zG~)Q=xB@b^59J6f-RTK;= z1rUYVl5|t1`AJOGtvriPMwAuKIP`bdZiFOHj(GTBER7jciVu>hq9K%9=pz|y%uJd5 z17Lw@BCDaFl);BIb_7{Ujx=O@EMi7tHhh%u4Z;-N0kzSIK@kO{pCIKi#x_B+lR(w6 z{5&D6SQZ=VYrtz}P<*zvU2}w*08qKQ{n@9`vWi|fuBp*zrZy@)Y(JH5mZ6XP}puxFYg$pXA2zoZ)Q%*~+)Pa59Ob>uybeOWEL(PiUP6n8Qi87;$$brdJrf1HV{5H?oYy`v znbq`;o~m@luT?HEyAgdHOJ+Qzb-s(QGo3Hk1~;$Zf3jd>AAcX{aB->*ra#(qV2Sh}Mrs)e1+)M0%!d)* zkDzB<8Kv|arP2*M6ng*F47GLLi z1Onc{ZuhA9a}9^kPR&Y1o0jYc^8V(7U@g1jRD;tUW zA#B{y$QsbUAnWXZ{^YHK=1as>>HQW~B!%dTq9K+^<0;V~q!)iVKaY-ENz@2jb|rgm z`}2ED{lAxgs{#!H5t_*aZYQ)t%z+H8=GIppQ(l_MfMQZPV@Y#SAPUNfJti{3`^yrl zrMqa3{VZrhWeJ}`@!pVAAuWB5<$U1{VTNGX>%H=8S z>m|;*4J5hHYSlOXU#x}BskBL-i{)|y%b$X)ClC*p11Pf8AL^>AG?wG0!F8h%AdH?y zBlEmNPQWUfotZ0!eIPSj&C;8~$$9CW>)7OBbUWEjJDt z!rTS|cI(P$-|QF<#h_L|uz}T-o*M8N+$AQ0-u<_5|CRMvdy$zF=yO_f2w;Pm!6m_X zg&Hg%*fnkM?TZr#BmwC$$rLA}FIuyvo7|u>zfgC6>ph^g?{H;j&-SiOPpQ6*coi46 z=5`>yyh>a08n&|X7?-r;H&TdJWpBjdndXH$-aan?a_5QpXd0gT$2~YLW3i*^q&(o=!;3vCDr$GpPJUuZn27hh%Jn6~Z%^ozvBwz^2 z@7h*eU$kWX*D$RGHo(y$CA=-g>#L|Qlso}z-E(D}%M@$fjh%xnIxb^$#(eWC1CiaY z9>{A&q;Ap(n*591o8(t=rzOHU7}XBdcrgLjc!i@EJT?`$z2H;JlrkKqk)Pmw0TN2i z9Agg6;rWV8Q#@hisX zjSG6@c|`ajil9D+O=K(B>o&)|*A&{c>WzPH533lnfWk$Nrd!wAs#1MbRb73vR=L#V z-n2^Ktw|8SYR$QzGqaBvL5{(V)C)2u6G&aIjQ0$6At`Oryx_eriHl;`i9cIk3ajtt z;GhJ@fp3NE`ACsMHpx~TYr`Z5;=AZ{`C9GyP;BAZc0_R9 zrmlPAu{b>l@n`>Sp~2AC0h%mMTuj{DBbdLSVFOtA!Iid=;$uabFkg(|?C{_4_bdX9`wh%XSJG~YqHq{1yI^Pb_?KTIlyW-upOa+SyS?Q3A5m_1k*&?aEM0zY|#lQn%Z7U2JS$jZK6-nDyG|<X`cQz5YDtcusaG@jIm<=z* zttX(9?6u>{!yfhJ89JFsVVCW^^K;JkYuJ1 zuf)k{v-Tj0+@D#3CXzBOa$kNqofRs6V${b-4q5%Z>of1`>Z$8Xx`L;4V$7KA-MrlK zWL8HEV8R|z3i>wAz`)CPid(fULkYX$)*Ag`hsNfk$AT@<{+V^3!TJ@!jBrZSWnXT$sgkWQq+n_oA6??nHR-c6%%1z$j8MQ0D?vSy$>j~uOMPJLW$Tf{ zh(n=^eoKK;qkX4T$j&EID^;Qaf6WJizk3;FU18nb7Pv;SwA2-lO6Fh(F(y!^MTL*pQBL<=DM6WVUP{4ppV!r_ z$=%0OK(7mry>fqr?g)|u5v5}&>Oa;)*L4UZs_0CP+rq=^V+-_E z>(~0mTs>J<*4chj4rb8>TkT^Bfuii%DgGPJQlesxr=+~M&yE}V>*s~$wHFvTT6XF68m{W^u;_F4oqkUsI>&-308QeSp%KWsNS1iTf;bVJVOg_uw&>Obga#MYHPkgyo0~YAn>m-3mQvHwfC0L(hRN^k zaRNB-0!%8Rp+y2N|!cZy_MpfnU_>n}z za`O((j}MmCc82;qRVwtc6p<2L0vsG1TwEM%Y&!JYTa+ak4@1LeAWode?feLM%S9-( zupFclC43bL@6F@|KX2mp_A&(MR9>l&Aw=qzL&W3vhUuAH!m@wQeXAR6TxF;%NVtyH z9t9Z|nMTB4*kOSj4j4f-lsug+YX#}YUaj1me5^9zrHsu3;m#5K`ks!xCX(qp1xTja zAB_fY?8vBzp_-$%DUjWjcJ}srUDCvP$LwVD!*N9}(9BY^t?$pz&w$SjT(?S%=GoUj zJQ8^yL4p_rGgDY4k&Ud3RL2eF+akf5iMA$qtzbs9iB4|Dh@00$ZN%xbm|wy1Xr=gV zp(EA>hsx7xN=XkW4?Z*}C+>uCZRQl9V`o_8fxuk|5h-fB^6FP;Q{7r)!}f)CauqQB)K}*7vcU!FFOwH#F(O zD&033eB1B4R%TaCMuLD$2Y;{%+dhize=?u?6#dQHf2-=u#p}Ylks-n-C~6h4qq-zTE#bE2687_hv;ZreUIku>Et%$B`?%P4Z!Xe(ltiW*xC#p*sXAA+}VPl{&&IanL{ zB7TG+q?Rim!HEf{7`Ow}P?I}kBZqYpy?#n&mN3|TI~FAub8W?(m_B-E{%1AWupUj& z*j8y=Wjr`IdHQ-#UR_@3%p|Wacc^pqkvV0ZK*uUsGNJhreQVRps~j1>wzoKh=v? zY&o^7yIuwd#xxu_U%WvTsWl9HP|U5z8a0-wlq0fRQoWQag!Isr_^{y1HaJpA5!;}V zCUe`qe0_mqgMj;2OOa%3E|14w?QxW$h#dK7JIa3PediZlhB2wyz2_@DPP-l=TVw29 zxqV#Z@qW9{ZD_%K%=rq=*S`y_7K&Ryv<~q0@pwIs_dh?g0=w$e=Q*6LY!oiJhn;#A zFO>!HjBjEtmt!IkxM_w^#`DKq*;O9_3&JSV;a3~EP1*4zgK_3=Yj}Zh)$1)N2U{xb zy_X|jf4qwxH)TO~#$-Ufb`>@Wce0pByo5|*JbkV>p-eInEA0L%+yGh&e39?{!T?k= zZ>2gOw7+|Qmk2!6O5X?F@2j3b@oxR%2RBE@Z=oOt{w(hUthcICW;%NIe_XYSk-uX8 zNeFMVGMY!DpGz+pY}|^1bd$!PjS_H=!(p44k9+HP9;^QuZfoI+>&49E((!BYomeY1yKxlCo}(+D}-Z|ALzOJn;4e1nhaCaO;z1M$lvrE$uO!t zvElQ1PR{C_q9C9OzTY}eeZVLS0=<`&O&@?LO|;iN3}`hk!;&Bp{z$ek0l|ciK#K@W zfWC&f`_tF(!GAkhC?h5Q$xId6k`J$%?=#9e z+R;;v#%-%*F2Mk!6|02#zT?luqRz#mkAqKRT90_fh}_@6&xusg>iF?EJj^9@J(@x* z_}o*^!}sfMf^$WjFdY#&n3+k-y#Ja>_kO@TFa&!E8FP!ChAqpk>LuTpM#f& zBiGrEmRx&b^6ln4T2=R$*cfwX zhD8u=qg$rvg_(2}l#0OVA~qP$j}P!URND4v65 zA5n2z@>&%#$b|~X2U>L#&akxEu898&6FU6(7-ok8D;LIUkcL~8m_`ga(JqJ3Ip-z$ ze(-SO2rCG%8h{f@mp72`Pz~vE2=CqntctzA;Y5^)9w?HEN`-^>cgX0M!c_trOivCM zqN)YlUq%n`G^#spPHBN!k*!UAJnT$u-A$jH1Gr|p&EXNP6s`vZ)y~wF-iPz~eQ6HC zexetn<%giAD|ZJukN{#k>_5?SNIan^F4}GNtYLyTH-22qKFDuSb;QK|7^oRjQyWm~ z7q&kExOlzn*qA0(4X6>N5&3%wwF5MT5wmt&6o3i5e8HY7M8AY`!_^_|;_wbf@4Yxt9YhgZFyI_otAx=J3cHM=qnGMjsCuR+3T{ zy0%5zWZ8j;kr8lcq_#B98P|iYEVx$0ksU<9ulv%W|wC{M{9?c!j+j|x(E4RW%IQ>aibKL zs-ak231g_RG{1=3pD3?BYSKrg%J2CQtDBgXb)B_MwG1E!kLwd_&drC1_IEm(>Cnm7 zI=b4+o2w`_HH{_U?)%xT=Ny@B^sa=EY~7yQwo*@;158rL#-wUGCT-|)f!D{*ppidr zbG@dg?0mvnSj{E80Ip>=zbs?nZ%s=4AH|d+I8Acd+&w=$=hK5mz}mMf2Rr}n>l?u+ zN29gGh#pDF_Wm%^L&teuE$jT8D9e3?x_f;d^0P8Gf0Y#Ud^|Joiv;_1Jmr1J3e0hz zeSpK(#G-~9xG?kkeZDLD-X;M~9F*$-xj;2!+3$h$h15+D*vK#Ey%anl4V_8T#@(nv z@TFyCJ#6=Il(ouq$dFv*EX9O7GjNiD)I$!6yRhZ~rpO?}K<~}^2-f*c#OG%ZpD`E@ zL_G>>_sqjXr9LOO?>o6FlxaIqaGjNfM`uu}J{Kc+-3<7Kw^_z}x9`f*Zm>3*(8m<^e0V;>XodmR?+ z?0icVNPFs6*M#K&O89HL0Lf=Ns4SLfgj;x4 zhu(8z#@EK1OM_vxPqc4HapNg>Xp_@){8l)l^F$#tvg7~&sd`TB_)6m+NppcRK`K1Yu7ar8h7{)!ZKW*+df}#XPz{8I&)&3 z%D+r{Wqz~D^~bQQfjDr&D2JxB!dyg|2A9{|v@TJ^&*JMpZP3Y)UD|rRxtr=+zO!%l zID3t8YvX3-;NY6p7(NW2C8cx1_2O1!h)-8%3|~x5z0nOrBJkMmah?uB%H?%>uDN=e zFVFew%)QZno9*ZqMYO zaaK(-jx%GC7wFsP+fj`HY@%W13nc6)9s&`BQU=?ynq6Ti(}-3Q;$c#r@H_MM@F`zr zE;{OiymX$IUiTk*_^rd0bOA@`cI$@E&6;oygI}LrU-p($U(daHxq@Gd)t{%;pMXE) z6R`0kJ{ywzM_>6qwE>TRBoHEEqJHJ5PZ& z!IzZR~*A$_PcSkof@~ zQXA2!lED$g6b&**XFJWhsNPI-5U`RVYGZQ-R5-HG8DTWY2U#A?ND={+sOV$;#5+Ly z_e;*!3qfJy|D~;^&PR3@96X&9Dh2#Co?pLSmv6K*g1N+;6kmxCK`yN@mD znu22v5C2Z_lay9b@PjQBL^O0WG3dQkoK%`hOU+GI&zU439T5=`)r9(-BtJKC-w?lt z2!fV|#n#fwJZf77?!cZS3%wM}sRr(sV`M@^7G)Ct=rr6SgoD&J7e!k!=E`NYnV@16xHDVGh?OL?Oe0KiR_0Z1uSG65%U{NHIT>|f zZ!y_;+@+3hi|gx^AzUtSA$+yaJNSd_(LC4U1>l3_^eIBVjkI|wH*H+K|K=WVBrn|P zBXz9SZP}M*<(#c{UJp-q2Tw0bUdpqw?n1oX+`W!=bvPMx{~aIP-d0#e_Cfn~i)dzje_kSfTv}QzD=igx z7*YJJ_q$d6>JfaNH@WheLQ@oQyW%fHB*?yOz=Mb_O}JbMyT0Zb$R zdj>IWS-oyzp$qlt6X-D`PXny? zb2z%EZ%s5>m^`*I3$Y}qSPHipx!n;*)Z>(pB(OwPA2U_+v+2XAy6+oNl{=S`6cM&O zS|tf7AhT+64AO^sfIVPrJpDPh*7~|Ur~#Ld$F}FLw{kq5PZ$<1-p3_x}!(ytMyK^CghEqLljf!Fwe!qd$Wj z;oE`PdT7pw6wdA+wmDopB3yh14{i^hG#s5&Z^MGQ*lPWjMxCPaT=Q zR;WN$Gxf0LbHMuYBKdVpRC_=rbp`~)AVp@-KnckLl$q$$?hpyHGqZ7J5Iksx9NWoL zHTKFRY_-1$5XR$$4I441RWeZz^}PD80iKJiii#@J@#pRx zGK(ueLtB@M+K#5CUw`!45}tJ+H7+gTM9H#saI$;1`Vx0(a4ag1?d|}92N!__*V>yKM>aHe zivAwCZ5pZw$Mua3irPvT+WPu>(cvHE3(E^($qLqgFh~|Lvsva#;7D8kn-_`RmWOHx zqGP}`j|5+m1U-O?hGVcLktMZtqFgpocM+7K7pp)TFYLFT&dvL1tv?K{o9jZ2{F-j% z6m6O^JQq2yb~ZL`7Av_%Ez(fo$QhwFJX9XIP#ff=44~NQ#355WN_0|916OD5i` z=%##}vcKCJTb>VPt2?jnqZr?}Q-}obl9u$nU41;fe)F_-;B>sd(l*;oVZr(Is|8Og zW8Z^KYa+WIBsAr&<7}7T33o8XgCytahAD_NIS~j61aI8(-HlLg`CYDCaaSsk({#s0 zywQ$vrfO7ybnAPc^gd)Y2Mu%nB+H{ve>D8d(ZhDp`poT*J~6;0d@vY{zZBx`Vl@nx zS>aaxb}f1ZdK?`cJDkJ~p_`)OXHcL*4|a!0l%0`{-M4sd`%|YBfwV_%!OcBfNvnEg z1sniPAhy)+cx*oGY z!YeE39Zs7&ALt7S2(+2Bxq>js_}B)PmqXa1T;AAZ5yLE#dh)OEA;S$JYRKuB>FXhq z$@3s&Ve~=${G+W>A&n0#5vpd1+r~vEiE$fnqAI?}nvGf*?~*&TTUvWotZFpalEHv{ z+@H)iZ{uk&Zt3b5t^sr4oE=;%WG@R-=7LF)L2KV@iVT%}!V0r|_abmz^H~f510kDG znP`=1ad;l4bC3iJh8W6&^A4DFnJ_fPK=p00!y}oJlb6Sg^v{h?VP?GroMX{FHvDhE zp+o^bqSW+mv!(us(EB*y)7s44=BLGj`Rc~_>TN1(vOr|VZTI>0zTQE=x7T>M?Isw? zYfB@e+*)R-^gb74BW-nU%(%F?Ny79?qTiNnVyY?=(fFJvFBcU$+-~>xGewm0s*~g- zy4sz=wO1nX?i?Qojze^RN|x;W9>#CVp11^;_U!c-v*8()?=G^p z3<2$Um;Dz6KPS(UHmi_Eemqlc@LcxjC1w$1IfGfhrZ4%lwtvvUn-4Yi+o*U(C2 z*KHm8Wk=0mUGz`+&lhYDD-`o5uQBRvsS_(tn?AO-6}CDgp@NqZaxt0~7G7p;E%mLN z-WQEyZ4++fp9~FjV0rinsF+AP;3kHM!x1T_8jfeX&FGInx@1G+z$;!VhH;Z(TU}JB+V#o+nl?Y4r~bQsFCPRiQ36w0M1TRWwnGFi~Wy!70quynhT5 z+BVQmp+fKo2*8`$0~k+bm_Mk7tpiD@{70423s`?0E-!I9037rH5$uRl(=Td+))c|N zj1lTq;4z|%D~aH$)CIAlBMLvnLyHZEav?!@cUYbz$4LD{)9FrtQV~FKw*c~YENpE5 z&Gy)zed%wPfaJr`+1~yRAgViVM`^jt)niV@i0RNij2Y4qMa?jQ&3_sCCl0X_8$bR+;Wq9X&`dS0jDmEeEAQzME?aJ(TxL^`6_!-E0Vj^>ukW=#HTCj;=95`YaU8uks z6|QBsKXh0Gu;O$P>z-Z0xoMV;gEb zC_E?$2b*ezBO3};>)OCXoz2C|>kNn-t^@CEc=XVDMYZfQBO`^;wwiIuzG_phm6yAv zMF6j?$|wzLC=N+6hbdc^R5iX)Ut8Na9uTn|G_#aap(JK-X&|SN@WtvW?;yD$siJaW zkT77ToqLdQ+Y)6tP zsM|xT9F)*ogEK(LQlx1;t7?Neg_jss34R*|?(>AfF zAaJ#hFOrH!8`Zq1vAC$g@nLRn^eKV+1V-z8GkcL{&?5Ctmr$7<<{-M|#`g_jho&?p zUBVIA)r~s%&e=PI|3MAWFAX5@&i!o!>eU=CKcNAy@+h4aMriOy`4Z+-p5MTg+uwuT zEp#kI}?pfk-VuR2bo_xfNkq`MslnCl1rU{CNWv&tbZ%Cq1eir!)<9%9qS;* zl%FnBC>|<(+&nF06D#WjLO-!niWGi$FuL9M{&&8q#}XQ{)}+U;Tpc=$d5jEQ0ZI)s z;%rO>Fs8ykU0q0)g$kMR2H)jHc2HAFq%?}LnsB4y7bTS=Z6_b<81!X`0?Abi&<6V$ zboMcELhnr%hC}XMh%f$9A3|>^l<_h%zW~&y-3?cdTlW0x_%4|JjnMXr2$iMw)bf(Zl5CkS{elD`p~`6 z3H^q<`?)FKuam1QMm+jk`Aq>O& zVpc@&zJzOZ~w3Q`f?)w0jI1$;Zl@&o! z%uDYPVwUtD?hS133niR^@hporF3l!1QK9<;Gy*b7BuzJTiF|AF9>~C9eoT%|L8tQy z6O)i#rtX{|R*tu~D1X_p$uj1iIAU!cGsgfIgXdnX!$VA=yo!tK>F|Spw|bYA4>=DW zU7eUAmFV7RwF)IWBPItuBTaEC7LgS87G7At?@PTiewWP9{2a~9bn0T2bI>~iRK&i% zpjhCGNSYEJaw{q}X}i6+$vD|_&uQ&aOPq6(!G~BHB}!;;CmH6={H!8@fz9U!6$$;F zu=pCp4LED|A6;44VHZo4uoe%VB3Skfg_wzsIp_^vqkzx~WO-tYshZS9 z2FI07(&XHvO^jJmqpSu}3ujBSoyRH6Yf;ems(w(Z-=)YIyS6G=x&i`FF z%Ni>{xrgqk%CRv$w=2t8{Y3t`#_-228YA`SL6mlmW1I^dKOtY-A#m?rMO2{qraP#m zAR?!;U_yq1@7FM1`ZA50r=zjmB8QF6h27BTzuF|l-eqDY(4YHyg}8k#DZtSMs`#NcVq9JfEG7|4yxt$gp-bzf4N!9iwSTXjn-)wJe>=5@7q6(B+OH7-y+!jXs#{E>FfI@pm zsWBu>^AB1VrfXrrRhyV0uZ_Q}hO4WtP9{4hY_0ODX^r4n#DhK$49$tVJ)}F_Nx2)E zSnNxP^_{+ zfW?&za(IXecO1=l)Q-`*GP5^^bI`lc`~|S|a(mpWHOllOxxs@}%f*lMI!_IlkjN>N z%nsSRxMWLU5To@JLQc$brK%EG3hI1EoCK-h$ehq`4&nJLj+`zcZ~z3Xq$;DH33H&r zoncC6=o~WXW42W}IXQur=PNz$GnU+^%eG6ett6uK>`WJYXCuc;#jkrmWNs!%P37{1 z>uD;+dXrD&OgOxy#YKmmWSk#FzO%hWFBLv~KN`p+U6_f{`(WBXU(eJ)eF=D6!j%&g zZC2-%5*mGh&Wddg^}x$vF&3kWpHa!PAsNbwRV6j8W9Wm>gHVGJG|Ae~3g69toNv${ z?e2!ew5a>>Xx0$)$(l?d%viU$N_cZzOtYY^5YfMb&tbwXsI-tniA;`yHYMsVHnFHr zA=P^vEsy*e`QsbKe(p*?$Br;0B^M3fXBeRAF`aK_PG6gpF;U6>ePKyZty0aTcE3)| z1@(YSFq42DL}MXdyN*dP|}0LEqV;xv3+e--xln-D~6f?4>C$zjN7Q6G8L5 z#_Gzd=S~Qag=vTXZA_EzDcX5Wnm6@>vnY6=&i!^j!TQG~@!}CTRZ^{pV%4rhTieBx zz-vKJJte-yl%r6CP0JPr>OH=|;w1iPE;xf5(S;U%LQ_j_|=@>pK z1@E_mH7&2kha9~Q+n7&Ezl{4w4lx?W-vt3(Sq~TIqS~7F%;B(yJ6~c-w7GbHwN9oJ z{~QPw@l+gC%~D6p;$W_Tlv?Mib_-SG3^+6EuDN2{ z)QWw^g*)AV%?Xl|KX_C74d-Po9K$ffMdau`rZ_FJQkyq{6m`F%5*3@#)oYhHK?i0f zIfgVlu|i3o1Pb}AD}Qh7H+%(*7>tRIw>?IJrjP^z$7B+65`;@d^64E!XR~| z?DBIE$`zM{?565Q4B@`r#??kvDh!8^qy~o|A)h9e_88??zWS>O>U}IqB;a|EEhCJ3 z98yDkt_{$u4|BuguN~snGGkujWv&h!q|8Pu$q52@Z!7(BzMTZmYkV8f1bNm!^bMj5 z6X3ow;}1T5eX!YjA9QbOb_)%YB=UHk`R}+04!!`COYC(4#<`D|JU^U#p%u-KaGj(*E1lBcaRG>ll$MD6A+C|8S&t~L4dwdm>1qe?AUXVOchay z4Z{)BinfL^J|#i2F{k7XM?MTN?2WtR9ZrqSI(IsKp(eBGmTV?(0vD4~XyoHpzwo?_ z|I=VRj!aIFFPei1g)G>Cp07MM)jbl}mq5k>A$MGqD=kMzsTRTkSKhV^zkO{RRC8%L z+&@_TQ)IhwJOr%vLCXL#sN1`>yVb(mzq@h2^{f;ZRJdrY8V_1jhE$+USgWU=feNW^ zB@HWHcuv4;=0!;+WSiR)Vduk7NTN(HkBn_G7v3j2`+a@G?E;7oR?X8ztC)DizTpgG zDlq<M_U`aPr%{YY`p&uPvl9nYY!~lvAqQo}Mjib-T$O z1sjkY&PzB!Jh_R^%1nlR94D%so>eQ2ViX>+j2E>NgqSGauXz(-cJ1GFe!ltn@2U!b zO}9Q5cY9r)7XLjj27>f~PF8wFPgUefixgwvNo-;b({1A6rjlc>w+CVyl~u{z3oqfD zYEe+DH45vl`Q9Mr;=m$oGo~2hhhq_}5@sz{I7eX4f>&U}y|OQI&G5zwNf($+)#YmH zQm0E)dB#<6CiGP!ou}DW#-TFl>hrj~@NZ~$z)>s-$*chLSfP<-`(2MdBI)^_a><`( zRB_0_FV;z^X1hXC&%woo0Ocm6p9)9AMHt#;N6AyB?h=gqu*?fqS^Zqxpu zXVEfFf7eO! zl7NZg*pvTy;5RelO!yGGWse$-r+PQXddl`p(9itYp4L_kpb%+Zr-z<_C|oHG>Y_GC zgZwN<6?*Y)S%?;83!aPNTSDIN2$hDTJdK$~W+11&Tgn)LSuOvBQy(ky43h>(sLvx_Tr7Zflw0( zgX@Gt9Pc;S@t)oOSE|-McqSTCX!a<~(a;h^zfCIb#L#IfJo0T;dD+PX(5$R`uOXw3 z27lzo(}U;TP5LmV#iluTE*_KOyybLemf^y4VfUy$gKan8c5AH}k2}!;GTHaI50F8V zd!o#yKp0cE6S*=}7+6V8j01kx`G`|)?!#Mq-MX`3pMTKbB?FINEQW^0#tHh@f9*+1 zGcR$5t?SFDiC?t29pt^3R_opX~1#F^0SS zUXToO&55rL?Vv5F#SR!XtYJoSFf==*uJpbP_X5sptMDTTHR!w+8!}m0v_<3IL>fdf z6#wnZP@NvjGF&+C25K70wY4?Chw{S2%uE)6hy=IM4n~f?G*6ih39h8AqXW#<)$Q%= zqaB-$hxx16B(lOskn3DDcu4MzC0&ML5njCK+N~akLy@~iek39uD;RtB?XEWC$s}Ka zpD$3Ul)FtSCZSV z@BJyw(Qw@Yy`!T8=o(;;dkcS_&j&uW7N0-%e7&dn3K+Zt{Qxm%$yc}{4x%9#YGnvG zh!xXpu1a*?*8cuEW@|B(Tyw=Nri5kcNF3e~-b{gvI!&+)vBy^)Qn;O70O`ld>u;)A zp%*nJ-}ic&-<)^hzk&8W9Cuup)i)!Y5UT2Hi6EblwVvEUWUFw$NIIQQ{@5zwwo3!! zxEbdej#Bp}4;!JND+Y{vY%Vwc(mdKyl^X3O1(L$aH_XQ;4oHv1b)7sRR`1&ZU#w0G z)9AJo8`Yt?gf~?Md#fc!44Y-ielTbn#7M@ij^1rsu3k)v<;b)jFX+tZnS++5us_J7 zxv)g7Mjo{x4K!UkFJ@22lzUGIAn!lxjvWYk|9I4qJ`=qX4jw%ctao<$;1%;v)AFKf zK<-%_h^DxAdx9ngQy0l9!RD+Sfc;Xw0a-Jv2(m_&2+-qQrF86N9u3kO@(ROp;g|8i03to?E z869S}4f+ua*5gXe~u@Cp5OpUw~cw_}%4A;qKeFRVVh+`FXWHIVChm(j~ z--c=;$eqbsMDmd4Jk5H&GqDnr+m551e@ReE@+~q=!+|m1jyO7OHU^|Xb@XqAM}|!z z>wtz_Yxw&KL}EC0%(A706%E2?ORAv>_CxFHrL(1w__v9t1b37E)jNX6wq>`IAB{T@ z6sSb%h||&rx`y2@VVN@rilDM4yY8eKT!p<=xP3(D{gH*22U|N&+Q<5&)R%#Q(k&$tTBB(Ii!&iee=J~C2PGg`B zvDR=&3N}kf3MX2+n}&+hy5>t7bR+g|Cy6!Gf2o09(H@bKGE~~s98J{#c@OH~kI=X& z%iK1_YE^s;!r69vC9|lQP{&Lq2{*TWkorw(5i)w?O!TL(zaRWGCm-@F;~xreQVkNV zpTQ?ns|@RK>`iib!S8E?16FQgnfjX>y5kNI8lnVk(yjI{lfbeJsBDZ`;=>Qq6rZaO zJnlRLtvKL1=fj<^gV7%?z5qANtZ6FJfS9sS!NFBJ?yvX2jd0Qs61)H`4Ws`dNhHxN zO}j-uA&7d8Z#<}VDH$PGC9LoVzTA!rKP>{>ng15jCa+W3qF_Y~EO(Zgd1x32$Lw^d z9Co3EKj^HXAlZe58&x3AVa_2?RO5~OOIh4?Rr?f#(IUXZpK>Muw5g0^xz5*pgh7yw zv0o&8JzZ~4PY#sE0wlKtv96K?i$g-fQ?jy7A}8F*MRjq@6(#3x+ulxB_mA&H9TMxz zxk(OuBNSqcfX&TvgmsCLBJ^L1aP}2x_T;?gF6%;NVE_)xptikwFqe(K`BDlwi zvk{P{Ew&5-8^|nqXi^e}q1%IeJN!l)h?Qg7KcI9HV&VcQ1&2*jX2<4Pw^Z>gm0-5~W=bL_~81rXdOeg2tAQBhH< zs9TZ@XqE`Am4c(TBE|C-L2qzS@>D2l#&$`BtJfNM@t^-imVrf#%0D0{=P4_~KC#R>N3miPCLFAALG`%da}qQ(Z2Z8R>~K5l9qRM{coeu+6JIZ=go znB@u~#OMUr-VTM@092!NF!ZnRzKSSKhacsHBX(4tx3ICnA6yq7Ck5f*d{ciAQ-Uy= zd--DhI@`#sbe~3D`-u~M@8hn1`CiJpCl6@0zG2OI|Lx5guN?+vIaaP|dE1FAoRU7z zS)CZ6uVA%06UW7SyHC1i3d5HUyE06M|S6ZWtQixCqV6g4Dra59mXit9oqd+U=|bX0}J&taVV%eG!pj2Df%>$S^7 z>sILJ7d9eRIIqeacPY+^he0yMCuLlAVkTC?!47*j@^q-kN%Vwo7-)RzCZ7nSg2Yi- zpeQ1_iAVO}5OdYAFy4DhOh)9P=3j`qYR5a!u8b@!^FTbiKL}B&JNR=fvu>T)sNWq> zHFh!^n={0AGBY>T->lekDo_L;3}bom$Okw&esC1O&VWX+_@`9yX?7W~$TwnY&aZ>T z|6n?q_p0z~G=*qm`VqxGR&Vs3bN!pdh1= z@VbIwegE;}Kl;+^Wz)~3q1yCvb==QU)dfa)b8IJ3&zGb;4_iyih@m%6xVJeqA($mi zSj&Ykk#gyBd1gqc(|^QV@eUyV=H%v*B^;y>Q)25u)ED$SBnHNCn^BZk!YRbVnUct# zT!B_h_rcCev!gaQWXnd{mTwkw6LV894-=oJ{5^#3mV_163ON0}Bd}e?AItnhlIHZ`E9D(_^fF{}2XfqnGba@uTGK`q`*dQ+-Vsx|@0x=uv_Xx8cQ~ ztNXkF>iG*XN%2LUwt#MivWy(0A;izHj@-x`&scAeL~o(vTyAb5zo%{90hU#nTSHzw zyei>U&b-#%zy9QtKU6RB6f^!`-+nK#Kz$a9qpe8LNSm@vzwvq~KJB!y^k8GXhdDPXq zZ6BbVnNz--{yg~0J<@Tnxj?xnXY!tqA$^uA2(sG6+p0#pNlIFM@NVLL$`xTLwV+Ux z#$ywz!IIQ14aU81j8l9l@E`zXj3KjA@(#-tXSq45Rk!?D{hmb5GK3 z{d<$v3Nhe~iGvLL(L~ucx3?i5to*)K!fRKj2C1$r-IiD?>_EEt53{z+s!?A3qUhc1-y78v`$Ks>2}=xk zhoaPM@9$TsVjj&uO)2fDiWzV@jJw5#44HqB*_%3huG64YMbT-~f)^dc`cXtyrgy$7RG)Mbet zWB3Ub>f`pE9-*}*eiM@CaP*b`{$W2q}=CLzraIIsF(@J`*VIj>B zt{Td*OSvl-=?!Ex+MT#G=@1VWS*7<-xrI!Ehk zATxaGNK2rcdw!lfS^tY{E;N}f7S#Pm+`G4 z-(2tyZ!l)NZ`%&2NSde<(0|+p?ZU>am_QZv>9x<$Im;T+HzI$kf5io5QRp}BRhkgK z_4eaRCX5pGPU84cu|taOs}_Hgm}hI6*y_hSA9}CwQsgPi%r%;l&_8+b4hSHi3>~u2 z*f9Ux#3*;gqWi|`1>hpFmz&$$D_I&%y4_CzI_m#o(*T!-ol=~f-&}S}TuhU)t5k*& z@kurrDqw__Pf{OuSpqve(>E$qJr+?;{1ip=EJBXP{_$RWl}%7UX=}SzZk@&daHHAi zd>ZBs2VLO{Do%XnA-u{>>+U4a7eB!~Gnt$M-Y7dd<=u2!!DgjfRbt-to4Dzz4QN$3 z;$%JjZ@3c<$=l%)=V!iLCNocEb)=}{wID$kU&{gRX_vkhVpwbudkBsdraRXSYT~r# zA}hxF#1P1C2IP!ZpClUjV^+JvBZEZFr}9ANBB6z1mY!>82F0F6jWDwl;T(-_f4aSz zXl=J`?(Y|ruw4>!QeM5_MM})io)QJ9i0D%NJrns+@NBBzF`Z!L>UK93ISL`8Q3m=+ zoi<;+$F`I?w3~i?$pzoOoX+X67=Bf*+hkvwIbXJcg^{rxgIEGXfPVyGjH$#*ZK`~j zpv&Nsc~B=-H$S|Pf!Ug9?JcsgvT_OvvI`1w^0SYjet@$BJ(U+DU`B2t$5_a1wE;M{ zz?AB9xeFBbiG=(!x(ebXH`*lf`F})pcI=eXi?K!#Gpg62%ewqt0m<*49^_p@+5kL`hpW&ihY0G0P?fo<$Ij zGLfyoO8EjXp#6V;QAx=NA*$>_iLwXqo^1LXO;X}jUgke><*E(ksu|!eu$`SYbr33} zE4DW3>NtL*!G4v`Ff(q3Hs)`v8zZ^7TFE)ydP4}E1%#W!wAC4PIgyQlPP%h2=#{iJ z>Cu@JWXQ{pK^%;jXQ2>i(~|Fs2;OW#OP)>hk)rytyz>6;?rBig(PN<$Kyb*S6rI>8 zK|fJCyxQ8!E7Qz20HS!2rK^fLX#(3|oa+q+VYnQ7yWV@NVTJXidxbY!nX=}f|vq*uORW1;Q9Mu)qNfGiW!d56=rm_XgdEpHfqSPR(8ofC@!^u!6BI%cNaK&Y3z5?gvVu-_GQYZQ%IXzH5~r+3-i8k8NZ zcJ>QSY$2|1g{VaoaRGj*tkb<6B01ad8sK-nOd{ezv_%qP!3f+x_3+P@28s7RWCemS ztiB;(lVv1~c_BsYLY12Ic)|yIyxv=pLaP#ylMI0KcLTdz;I0EODq+4|SV;kjg8NDZ zTmoc2cT|J$U9&n^X_Fk(Et=AXWbJ?sSrPl;WHC1NPl{#PpaTA!!VN89y1cfqW(t+B zlF&#shUVzS$pm}N9Bw9NLrmkwn>$X=j;%jaRM^*ct{!}Y81^>4DXQFzyV^~1m8b2` znKFLo%Sp+R&Y3uNzh#e)f)Qi5qHKiSxJy@T+*Q(VaJBE)63GBb49Ibyz`RF|xl8;p zrn^|FLtOXybhgKQ)HNo=4mZw`+rD=mSzyAtE-el1m(T1EGd4A7yu=z|ArST*V!eM% zYSG>o46Nr}%l6uqM(ZiM?(yd5&-3u;+x2&H?#~(<*NV*#cblqL`@Pu&hvXnhN(nZrNt2k8xWsGkctrQ%vu&_}Gu3|-j ztwa!b6@^}O6X!Ytx7z{^@w1QJj$Qeadd71EBCedXI6uVUJ*;2)u1`*Ef?o(na1xs2$^pvmBpbR%Uwo=n{E9GOeg3r{h}m0Wfr8Aas^*D3sMY=~o43L7 zRoqs%y-h6CHcq0aj5%4<0%e1$f3X>o7sB)_unH{FdDwDj>c1PiEJ+9IV&F>65F0y& z%qk8@()-k9y(M~iL)MFQeYQ)V;w~x@JwCP~Oj1aGuh71+PI(i!wK)ZszRc3Xj#X|v zu|t6^X|s98%*XoPP7axLC`ify&Q@L$&XczR&dfXqQ=KP0ICt`nF}o?-%!j(QMP1V` zW;>2)T8SKHX{iK^LlgF$ki+&_@2wn|O3RF2a9)GgMth&-GfmAJdt1+;(5;r7o6fhA z5F#*m91aZuNrxaef1CxycPtj_Cc0_Mf`xP*wbK`?R%~n48axV29P8kK0Iuv=y-j7S z3T>jPh6YRLJxgz2Fb23SH}fZcm{Y}|dY!rW>S@7?Bxn*e^7YCs(U>BlZ+*MF)vH%8 zeQz_4EiR%rY)DI4`*(WAG!D`Dr{~m*a9Onk6TMHJ4(%tImC_zQ79LK1Zr!^nJTVbs zD!Ul;sCklXW#s)D#3s^lD@)BtN4pt+EDCiQBvlV83g|XGs_ld5XzOAk;_#{lQibGj z)Ka9|D0U3o#ERto-NYlpgFZh;)-*VlVNr;A-R?(#Ndl;!4$6=O{SQoK0U()Q(p3cS zK<_U?ul>*ILPmjtZOLha`uV{RxfgtT- zPzhs*#6C_GtDThf+I7dyLr5!Q_>*Qv*(`LVRjz#H-@m~^CSPb~$sFOF8tI3kLRcRv zIYr?=)#D)+07b1W34yq9^~uZKF@SYg)N#QV94?XKDN%)&nU;X2+1uaocd4!kxTu7`9zZfi{%Jk}2y(y-h@19j zjKIb4hc9}`4DUmR*~G@ih73RlrYZ6bV;>$KZjPiyM_Gm_s7g?0Mu!?%eq@J5RhlQx z@ic_RBbv&tI;rPyg|3S}OG--G|N3<3E@vEBKO!GE4jl8PzOLh%qp?t8ED7uyKLfG* zyk4PbPxAf^ET?DmKc8vu6<<8ljwE_-6yvmAGM4Pd(VVP5| zC<4VrRH1h7CQ5kVKhecW7`YuvQ3;QlU6CB0I5i8JhIRK>NBH&!K{Rz{xnbEWg*7gZ zvV)Ev6++6_6P-PM?s@P(AWWlkMD`KW^mpg6cZOl*SNltOx1P59@%@y&tsJ+e^*QRM zuM-=L#&3pku&424!kis53`8+88=U>D|M4|MlyvFlxY zarAavvAfR8k|+_D@d+>2`}mk*a`DKAb_ykMpEK=@Ziib^oKMw}n9B9Vi#klzK$;p? zz{|j4oF@gjbaHGP6soU|8D_o7$D*ow(4UA~I@im;S7@5xk-|EkUaMUnO;oDGD)BgXcK&}6Aog;`~M|Qsc z`^*3*Ie4`l6SV~)SFs%mX!|EByt9{YV%srC{{NfprEPPHq6HG3l`jcqm zukY$P5DNsQaIf`n)nS3Y5LY1^qZ7@DO$TJ3>e2+rq;R9xs9JFL8)oE+xHct z4B9&)cT0bW-}MQ2=tV2CYlQW^zWTk)tHofOO@Z~c+RURMBisEA7l{Eg`%)17&z|nN zo|#GK{X6inS5i!3?PjipXVs|kRzx(QSLYYJ5(C z@`aHHZo90^%|@PPOVg_aQGd#v zWl!bi0<5NC4TV2IpT?^9^hMLj_f{2S6pxD`y>r(UpfO=;x-fHICMti)chB5pAFeK( zz#Pd@Y)3eXYbj)<&m4WYmm5o_81_Vv9=q}Um~H=--8x=Xw;E`?t1f|rMX4=tY;IgQ zkgVST1>4fEw!O94aoyFF1`Xqxm#8RzwQbk#z1`s7Nr76w;^02})ydD!%FoTtE!gev z)5p-YU&o(L+*9Y-*x(ffajp6>%* z4rOFpg@WGtIc(;D61`9ewix|IYh$K7G*r>_iPN@OA09t*_4=P)qSqKsSu0?-Gy(B< zAho0j;4oGZ2VA)kHfzI5zk5@C63F3|=-zTfv_@clAcN`>?_;e$P-fLbv&d#~GGFL+ zH+Kb~?3C8CA_9@c1`uu$V{QQtJ6pVbxBPSlCG5>mgnfJ5pjhoB?33Me$sxp8^xA}F zKV>tREyF9XY>oe<>1Y6U2qO39nMxJ&B>%98!9uf+?<;tpC!laRADw?ncMDjHlg{?bS-0^!&Lo> zRrzE$hR!P%(|uRl#>p$l!D3jRJrU;3!n;SVoamYxKi7Z}H(>Xsl0oO!uhSgFKvO9+ zBx@)v=>z2=LBG4BQNXE<{}&fQYDyKXXm|{hMp^J-LBbVgV=xXNnGlqqxfUAAr9!W^ zP_3zvo}cOdo4L|8`N{@I{xiNMWxGm|!Aq!o^&%rKlOkG$n2&OQL^>ZU|DVp%%YWV7 z-*1c)M5CCq!?(hppH(acKNqx`HboEFU}>uewfap~2js zE|LIZ7FS1F&w7_=rsX|#7Pi4b?6|b->03M1ZqOf{^>tf8_D?;=3LEfjweHRs27A3$ zB(xgD$-<<*?>H;Sy`wxz)q#I}A&@EB=QzX4LPryHonB)ZIBY zih9y(zSvdntWRau8y_?^diNNyikpxLm~LCMIELiInGZxJ`lp*JNj*lTL$h1u-rkD# z8@h?|J?`$Ut=&8+_Zl`7cJ;C#Uw7%mq*)y`9{#m}EdP72UDvUB!7U_Wu2{&Lb)bF& z%w}8&6wO4g#8Fn34fVWsRALw1(CfpTd5Qktc5P9U1EOu-B_Q4lrPl};pA)65X_O7b z=I;XbPWku7QA5q5M7Y;@SXC3n_dO6qWd8LkU0Wp0YCK;@Wr@2oUxhoJ5duyvX!C8TS?+S z^8U-pXs$kDQuq7Pxf=)Csp?U#@CBPR{GGD3I~~m{`7^H>k5IgLBAQL;rwnNli)2%F zc6O6dFU%ZmHbYOy94vmy8p|yhvTf@yW6WGGZto0k!C;p8Rhfln==6$eIFwAOd5bJI zGP^7iD(bN_5Y>~zN3pAxVY{$DWn^NiQK?=z%NUzn@mNHI>Rl4i&B>|7LfEX1&dHcr z;Q{4cI8WLa7u}DeB+&RR)Ad{ff14Gnp~&-zIH&&81f>P-F-j8sZ((YK7%h|#b`&p^ zs5vLtSu=wpuddW zIOFARdb8Mhm2p~-xk8cEIXGl9n<$YFmV1I{AJA}^uO$oK!y&Efm<@c#L!(we0if|A zBBH~tvGnze@htst`?|(_ee{&HXl4VhenkQvrk3{p6`GS~Y2igy6-k0GXXvfo(0d)IjF;r#g*azZuQ9D11A4LS;ckCED6@)zRU9 z$u<;@L-26CtBtccGCHxTxBN>W2elmje<43Wae1o)$Q&6iKYLLj@hGFcnbB*TANt`k@ z14&owiIQ@CGq00@GIMq7Rad&Bm~eo}%D$ZiPm+01ywt(7f9THMq=~6yYxg!#?t`v& ztY>6lW}ac1nVw$y<-Aw$Gsxqn!|~TIXQsLRH5=`Y&b2k|ES@#(jt*{n0r!TgP1}xq zB}In=9}2$;=#nMGGB6E>r*)hkWVhn|`0)wV%O^valk4}Dk1dYU|Kks-vpD$MdhF9>Nu>fqL+OtsDTP#$Omjj9a zHVWMysKE1~8)&!xht)DE1*=GZ@ArD|iT}LbF9PXT{P3h)0<>DtN`Bq3J1YLs6&uFt zh1VPV?lDk;VX~?T4M?P!+1Vj9i=XN>fk59hG7@^J=q&?3Q1ntRocm>W0O$a6yL+MO;9il$zO~I^Vv}#9zf9ky(rn{3!1>oDN_6n1+F%R#8v_Y zcVfQ$=gs(KvWEoJtO15RoZhPE&ZOLQRU5luZt4ZFiw zKCC*yrw~f&o(DyGfY;L9(i3$2_AzD+`M}1>u6IFj^E$aDjhw2);XaIv=j`W4g#Zes zpdQV_XEPbN+}OzJ??n;j&~Pn0rQA72Bh}sSLF{zd>AD+2WNEh4=P}~|UI6a@JP&@| z?=4!uj?ush&EE&GrDB^y_zwFg1+-NPz;MGzyM49E^fKl=qOHlq2V z^;V-udL<7JPGa(Qge!3E-AMWZiJD+*&m@)JZWX$>moc}PRab#XHBgdle<1u%f9+pSHWfm`15EWPo;a?8wU8G^^4X zarVT+Vlyps)*6mOGteb6bs0I$IN5o{$%a10TKayBtn4er!|=}1l6Pr_GSNgh7(}4y z#GRp)X|Ex%V#3r^ZD1D{9KKw?KEG)8NJVcri91{sjsCmp?nTP=DoG zcQ3EjKDNGPTMt=OeYCVxn-Y5@++}^8rE^SHoH2DfbzV168g7v{=FYBON2nnrOwsRdB$yYX+nD}Vj*WK5?>&OXpIoTA=%17P^hdLBB6Qg35 z`pA6AqR^N`j~4zdC8hgDuBfb!u^oGk{&0n29U4ux;|&e|wDO~^s^|_sPt}BDp-LS9 z3&lJhk|~z3I$hAa?Eh_wrT1s3*jpcWZ`*!J^o zJ(~3rEEB{K_e~TYz!T}2nAjMh8(c%IPAFBNj8+LY#$T+AuCQ9|KUX?E){=D)nm2fz z{=I5LF6BZ=T}ZJqH9ffL{q4;8g~w%&vIO>P${*n30Yp<1l<5Yt)cSyQ$$u!S_G$%z zwn;`+Z|g`mcfkP9G8fYUDw->O=>@qTVLjrl>{@okyg69oV@&I0aZ}hB0+0}F-@SYF z*|oLv9OBJbIxxnw7+9t4%WH4xC0x^ewUvjek;qY|U9Z^+Sh9W`j{|H+Y&cZYe8D_R zQ+0O2;Us?is+R2^-jAmSI*sdjVpX__DpSjz*Uo^8^l0khVs38j^a=RT10IvnQq;?w zmA?sjv($kh9L-5us_XByvdZ0tQB1%B?*O%(7K6&T*BjZAx~hDof%g{Nd(h@qCN1jo zGl)io=$wR>I(Gk(+RT)|T^Z-k=AZB^i<95ompd)xRgzikq*4)LgOLme4*w}1tK;BpweIU3?$=Q4fx(i>|9VW25LgKiM+#r$R521j9vSyZqI1Ox1L~ZCZ*a1I4?N(rfL-n>mwXHdN?$<8r-{Yn&Y2N z36wD{KN+$uZx-aUfOhM*O^O&Ze3^9+qm5Xr%U-iuOgbpLLYu9a zwtpIzw(Q{(&kzY}PT|-O=(7B_a(Afr5H^VmoB0SVUriZ3i|jMzadq5SR54*p==UsL zlUkD?=F)PY=vQtak^!nXzFbM_ldBAK5Rj}REz|ECARHsU-w~6?U51tFw^}B0X|&3# zrU>p|i$=UWV+Fw8B_X~ZRZ}!&Id$BIHk{5qCGFUecjhzBPZPDS57L=tGeo3hGpA3$wo-kujR4-VG{h8|7^7FgaJk?;Da@C~d z!$l1FCzjKd)(5^iksY@~1^I%y1h{A2UbVyg_(mw{24>Py2h>zt4iq0{4m9Ne2T}_+ z7#zKJoffqMZV$zlr2-qq201%+z_YbH3QoN$?HO+Bq0)KF^7(;t>?4UE2wgOvn2gEM z*%?AC_@SHxJ6j z-V79Ym54tr$NK5%7Bb01Gq{ZVzfDnL+a@paU14YfO-3yxXa$^9ofhqK;+U2Yrw{kp z#jFv6gpB#nDX<&WP}nB%YCA%H+eY<%S zEQW2CRuW_EA+muQ;qK%|#13v$d*yz;%;5sN`FPAOrS~eXCdO5y)zoKhuA*>0@<$d+ zB}Zi7SL(^ObpI=zgo&12lwh*-hi&WC@5_OuAWOmR2lqxLb`!UE*eGdf)MS)rWE4$U zm?;U!)zrh#mX_3(yUEbfSOC0g@70w;&_>v~mCf+HjnA;-#8qyrKETP}UeC2*XCnZ9 z({RBTtAHo9e8FjtB4R?@3Zb^3pz(9{e66=|*I8pvaZy>nceiVO$jpm>@=2SMom!#t#P3MgDn%(m=?nVCj+jm!RVm<4yzH@yF6+kLzrC5!0f4Z2hndvgK%l_E2Q^++U$FLKH0v8O?qAVhtf!AD^B?dIw2 zZR%!i?dkONiF(7r%gQcxe`^Zioa-+mOCuxGL@bWiud9puqphi>)6=D=HG1c=RcG%3 zJ|{mF+Lyg-6+0-1`xP4~$qlO_@(o8X@$@|{^`>7H^81I$1u)?p5gQQ8Dc(7xqZLBA zIYlL`DqQn_jVUbE3ya0sA&vlG>2l5QH9*@#G&L0gg?jYB*MVy!3mKpa`9bL&PAV1z zB`2)M*!wM-)yd_WGoQ&cxOKJcc42`P_C$dVzq{@iIgxV=GLSJXk>B z-f}z^b3C-sz2`nj#R^QbN(l#nP$Ca%ge)|}O;A`k7&L*NG7eD1*4Ed>C^O|xfIO?; zK`1O3C%cvx-LJI<13>M4wX?%CF2-!h>p9LH*Rb##&rY)jhXyrSmrvvz%9`f4jmK`Y z&4WHiZXyS4$9q)mYrh%=tRyLM4IDMMk_cNXbkz~ntFeLOwR6wYU*WK3g4@gjmOBW9u5}1qV&*Ob)7euo`}IJ8y^wP^+&%-uxqo_9j7s;}@lkchtKPI@sWXE;*Og&XS?aHBxNGvOS|i?34GMpm zBV$kTrCio}&JKm44M84YtO+r|SE6fTs`NMT%CN*L(Uy6V^%=yW3AZxiB}5kIQ!$_g z)kL(5fopPf6tIj>M#|wuCpi#Uf04ddN0_p>wWQWm#t^sLR%}+w@i9Y)(h>eKYX<-0 zgY^C+>Ph#et&H|~jFx7@W!+uuLuwu$gT$UHDc_vfW7B@G&ho_Qw{;CA%L60GV^qDR z2>}QH;x|eC)8p(6AwCHS@t2ts4_^5%?jdqHC5l%QTBH)r-&-C+cdnWwRvcbr>A>zBtoGS_4^O$Hk8+BX0N6aTLdgDPVVmFEFvHE zms?>NJAa*WM5^0awJ$sN6m~Eg_I0mbX2HP1B9@@-!**>Z9l|~aF2=Dg`4C%|e*Hm= zq;sGv8kJ(~$j6ulyDV30NX2>-Qj=<{N!IOiX5+0z(AFb!H6SM|Af@0MhX&NO;e%wg zW*+$O9|c&6l~E9xZB+E{XSW*)iNYq@+qsb5(#l3hMN*311B1imJxYH& z*X`5=3fuY9lXFn#;znhtv%%gTjwev-FT|N$mcts#P@Q`nfcNX7w~m{MmaA)lqj9y0 zBk`9nvx>tXLXQ0RNLbU%6Qrj+ipCD@M|&ogv{iAjYwA8_q_xy6?L~#y;IM0F`*hk&>~VY|Af7XN%1f1CX=7a)YlYCtXZLhT3^VOT6tw_)2X9n zi5k_BzA89~qB%*NB`~Rzor;5_FZr9IF_G%Oo$hz;`CkGI;EEtpxNE_?5lkRYX=1z^ zUt9MNP&fO%omc5exC)PeSyCV1{qRRKCxeMnfTVEOLp=c3PUvgfjoqnc)6*9aw9|~L zb>43#`@07r0M8*bqhv}M>M+HmbeVX1|J}sFdN**cdE0KQg(!=Hy&i!)E-nld>Jz*` zmsM~MX|c>ffyb(yjLweMEz3YHJ%`Xb2QWB*@Lm7<4CjDs zkfmvJgmaip4tTn@wE$*>5#yZDGmsHK&?PfbZ#P%17atQL3MWS0{@-I^d|R!Z*0yqW zDdZz|Yx+GV><=IhJio8}de{5U-QC~X(=yQC+S=RN-`;%21yBs{UA_8p)#0Mu$m&v# zDd~ez##pGo#UrOhjfz#LPgbl}ii;6!$Z(PfY*%Ay%Tvli2bCIWPGHa^rAmF&&}zq? zt}21+>UA5iuSmG zIaXcYCIL;aCvA>6B&!teN}1YQ0~$4<-)XBSMe4b?+aWF`rln+4T_5?~on_-+x!~Pu zZH;Gh?JGCO;jwAHc0KJ+#beWLe72nbf&rYu0}?6$iOr^C%l`pRL9xDot1ei!;l+L- zljL(*J6|;Ajq8mx6BH}eZn>{xWUO8{6SRx2TPYTb`J5+ryk-)-BtcTO(mycJ-`_t_ zDwe#g=P)>IgJotND_=Ams|vgz=CLe)V!R?x7I(wAS76Z!m2hm@!n^HkW*c=YR{#gO z%*^rRqn8Kt*?i@sMm?sceavpe|}`R-*!yAEaKDdw6i&JJmesom_OyqlwW+i!6HW) zXarX_cbuvgX0|$kE8Wk0JLv*iW|VO5Rad)0OiZng-gQC-wEVpZUKUnf&%5dlxPexs-OrOxHobcu$rR$ z7lv>EmnMo2lwv9jjHT2=)kp%*OZbZu>h^GHF)Wg`mIuOR)`}TII?Yz~MVlfJxF6+g zxtMLyNZ$A6MDJ39+%VfTCA``*^p7T^Q)Gdeo@k&k@j zz<~o4pbG|Euh*Y?>Mx&v{<%t}PX#a-3N>5U087KPly|0PN|ingqwRMMA3%`HGc*K}^)vg)xFdNs%DnV|{D z&RAvihzJ1aDA7Xf4~~?M9Gw{%tALF(r{PUT-UH9nP(ruc4c>h7!s_Z~;3vDg^;@@Y zU%LjJlNYfwN3a@`f+6q+Qi~!4XPB=}XfEmPp+koree^w#Jo3n?Q>Wk+Jk;=xqtvAx zO=bpbEH|uhq=&_`GDE|C_ntnP%R6KSK59)Bx!P=6I1za}zNd&%ZEt z;{vc@abW{IjMWmgl_*$QAbn#MCR$xime5LqSm}zxy-rVCNq!u~>r&wU`_Dc3g_<-KCBTD zpg=6MocJZbM{g0T%@(JS21GXNhFy2Fc}$AmsiaXs8gU(LwU?8J6-#ml$iW@ir_I50Uia`M#Kp}_;i67a~$d+y};K&511HDWxC9l3?jbm3mU z*Uh&YuH)wAjqV;s4U_L0Dc}H17Wwj>Zh{+iTL#OmVl-Lb1RLXZx@m30&*s9z$0~z^ z`82frZU%H28J*Gbfwte-+HS6IZn;@^duONB-tuzx$nX%{Lmbr4iPJ9pf#aBEmRbpw z_!}*&vOs(PWw}&VOl7_3h=YQX>Zhdo?Icp7NGk1-q(yL5Xs8e20NBO&lP0m>FQf~w zrLaQVLgc9C_Y6IwVoO>%f}fgQwaW7TYS(j+iL8F)r({PaxqR``<%?IZT)J`n3ORGPZ!FB;(!Z5expQS>ObknRiuS=qhyqlBNa!k*r#j|~t`91r;;XN|`r2!+fqOUv+|dsfmCG^) z`lZVA&p-d2?|ge>kj3Ci!2 zUL&=jLLAjBg-F0IeR`u%C@^b~8SRk2E6=~z;0%ibV$`)1OGN=`4I9<#b+b8pa%%Y0 zT}LgORgMCAT~S6vSP-E+@!r?h|K9gJSt<2vwO}kXMf&Z7q`7zL7lMAi5CqbuM9TzQ z+OC{1On?-k0KK4#>f%ki zy=JG|!07C^0dmLRo0yVR-q?{z<fkKUKzTY9j0U(s$1Gq$ zpXcOVH?T4Vi(Rv7+XcsqZ8vZvK;n?RAwZp#RCm7!RFdeqRJI*Flv#E%Wh^jDf)$A( zFR{9gQ_sXvx7DMsY(AIGVQ%|-UCcyEol?0}u9iH{@o2|UPm18?@N%x>IZi2`@2m7- zg$D=63gyz^$VjDs!Z!QU&>rm1I@xY&ZQ(?EUANteawVhOkMFJStX2)v&1Oy46_Dx3 zZ6^f%rtQW+lUy!~$$@E^M3xw0L88b`E!Q$i^=4e(t(Pn5p`(L|(MZB)p2#CGUvP-mXq*v#ZQEo*471E^VppUvEUWuSp-(?WogrhMZy$;3|XT zn6A&39TH4VrpKPVJ(KqLkh-cUAc3E{sCcJmX;%RyxweLz1s-%eop!U?kT2(LZ>a~8 zSJveI*(JIBvpB!B$W|UjU0PY3pPyS?T3B9QTw7n=+1#q_Z12`~cI&&eKub70TnjD6 za>ECh68tZBVF{2^qgBI%%`!wi3Wg)o-kUO8$<~JiLJJ$sFo=N~J3Bk5IbLmecnoi+ zbVnXS;Siw?X|RP-ZV8li`=oWE*XvPcczAeXVxrUOY;0^`4LAzX5oM^z76zgA_|C3+ z3Kvl)tjDchzI^$aXP!Z`hK7dNj*N`_#&7(_;lqb1PvcaiozH#lb1%R0g6M6bNFMo& zLiE_O{IKiU&d5l4Vmy!R1)&2HNE|DTg0Q|ZTUj|Z*{zgIcK>Kn$Xj-nr~^@zTTbId zSeKSU0=RU;v#i02m1e3dJH_>_POsG|d4n0FFHF0@HsCwNlI9Bbp~K^cj!iIoeNqQ& zCqt4iUxtXGZRKv>xP9ULW#3QGY-Y+Jm89%rjy;&m7GgCxq=`dsC%8d%*aZ~4dGn@z zVp-pXN;~T4-danuse`SA!{kI!P_E<;92!4(XqrAd9Un<}BdOe|kk53ap+>E$0k zv$eUHWX$EYT9nF3V0CM06vlocUtB4*8w>!p$pj*e%QVtE^5>KGrH2+qQ@mf}pFN-p>qP5!y^J z1Q@5gOg8HR5J2Sw#I`*8XERQeB*FJu=x`_AYpP<@xAhz-oC3XxGp1$qC`s*>q{#n z-d=t`2co7vq<3|K08kAH}|20nmExhIIl6TB?P z)Yi%ugd=QK!h@Y1EO$!B7|WRi|e^CY27Rdx?o=V4x5>onSp@;pbTk- z!BNdjIgP0}z%B_KDhbfW@#Dv7b8c?#*=L_+o+nS9gcq2X_q^vlAN}Y@buAQvj;>s} z@?Zb!e_dHws+6lR7ZC${sPjIuwmrX{FIi%o`U}{(ATSftN#R4IosAZb4(}Wt%M^-b zZ)h|XMDAeQ49X=E2$_Z>@7t4G!JM$(v#iee=&)-I-M&>@+o(BC-biv8tEXNOA_yaj zqv7GcBPXWEC;ENA12aWB1oKI#15Aab?PhS{!dr_AD_Ap6K3%&fy6}_fXd;swm<)$m zK3(8vh@+Gw!P2NZsyC66t*tG1PI*|z7Mrfiz+T(Vir885m?Su3c%=X6@!5gFViYCB zU{MIxwmi?qt|EJcM`unyI6ZYx?j@I%WB`9f%ig75Ec!V@5HwIH5DqOLm|P{n;ur~Y zOT|2v2xSO*os1Q>8ud3{eeKq@OMXyCKWa@}3J62JrzY%1p&!QbAgfqEzm4k;!`|Lc zKD-iODkYf8;4(uLuho=qnmqQ%dygMIjt506i0j2V$K8wPUwQqNpA-w$@aR;bC|`xf zg2<@M3|3C!hQE3mcAwZIJftKuLy?%`#>N`fZEAY*zWYueIB)=bQ>m89rChm`t=Bi> zu;ceyq2G-|KZzm<+`tp^-ZQ|MZ=``~gqDdX6DAP?qStDiaz~3?!c}S7$K(^Gab;&Z33!XDQo9!i!`>$#cW!(+#QBm3L5eB_=y{^yhO_xxt8LA_AnaQZp-yR71(h+ zl$#pa#I&OT?-dwHzaM9VxNT;NSVB+T29L$Scc~l1q(cx6 z1?0wxOwY?&DPu8;j_DGSr6$vfquA+otRyU8`7?IMv$I*J(C)>cCC740#d5Kj2h!!T z`Es#;U}$J;bbNAhYJ6;BbaZ57baZHVWN2h$d~|YjOukDqIyO|uSKtE>wp1zDPDkEI zXF1JUVrQ^XjIpw{(O6$=bz3-^1hCRKP%RX);HOj!uH3Q%&slSX5`tZ_25KvED|w2@ zAoETJHWb=VP+uoB=`zq>BZ^pux22`LDk45r!%aw6*QAf?!g_4F?tVh@1;%hpovPV8 zcOY9(gB%p^Ci@)MO&g*}=$T+zeyYR2())gonm9&b+D1N*EQLGe%vTwND5ub~p1K)@ z*~fB^W*}UmMI;tM5724!snc#X!5koxm6he?rNx!yrPb9Hev69>+dJ~PT0&v%t!0F& zcS3rZ$=hZs^HfI}r^;qm4vF+x_R`YQhWe!K$cUW(fDlB=GeQ!(ySunOws=t86tYS? zDE0oV5f0JcsVT6_>gp;jEA0~i!It4s2BI)T8DKF4+PHrG`de?kg>xlcEE0|}NkaHa13@D)hq9&wcK5ue|aKjUm`f2)_?{kmZqhDN3TCGT@F)_GPohG_*o-wsx3U z$#$o|aO>n`=ipG)F6Euk;Y8l>0sa6C5h!%k11w%@bWCOzSFnxnzFJC0%Y}N)T&~5N z^#)>RI)D@e1hD0^Ub6=$j~-F73 zhYo%E)1UdZU;DL39)0LN{D0`&$&*JXCx%v*=X>3@I;GuZq)a)VE8uR!0K0&*4}l<- zA>Vufkm1uMHj=M>8hB!Q#)U9DRF}?Mt)S;e<;ukH$N|?YcVq5@c<>wzJR80g_-%aw|0=Ht+cqZ)yq#7jogHp^M! zF(;eB$QcB1@;M!gGro2|B3)F>1B z=JsaKu;lCY@PtJ~tni|5Uu!M8{Fi<5Sqp89{~CdKDXhzD(#53WPf6KG)hr3U)!i{9 zwoFs!>=V0tq}qg3CvT@c4@zOyK?7xqD+C(>1+dBL!VHI;Q?o$n7p_bMb#L*HAfuj2@+b?v>!c~~|5HaB$+#VX-XJP(B`6^i^w z&@#xn-l_wwOC|YSEfr}>H;hWFG4GMi*8_lH=5GKPVH0fxK0yi5*a%}A(1F*OQVAgXgeZ_+yzl~$Mec{1m;eTyJbCh0fAv=%dE^mVR#zF!R;vX}`GY_B1Jb1u_#-6{ zU~$xP!&&AV*%_m6*c+bccgzB+K`6zl`H^kZy2Jf9Pfn&|)jq3`GlvEfBP$cm1cuF+ zyG+GM(BXE*Gut&(gEe?b z!T>4o2Xk~u(qils&f|~_K8+E{R;%9ESD8I9dHBdw6#G#~{Db65=kktJzfG&-6KSr{K?|&oAvrOm>G?zH9CH;DY7ST;t7=q;#TpQhD)69fM!C%39LjS z-$TK~MrkI>B>2(5wT(t?2dr|>@w?TyWynlGne({`_GSYfQ*=Oc>5z~!`u%qhrtmV6$?a;X(XY3TPl_nkU< z?(A8Dbu>XC7<*{2Y6RU&7v9X6;XJ?+o4I?lU$1y6dl{X#BunRklLQdve@_TK^Vp)uKBXsTV;p6d6t-G}r*V~2u zYGreKZEAvtujhL5ND?k7cXm zkF7MT?JEsq&>7+#q8MDJyo?QeDR+p-dvU}~3uYE^pb@z%M2}D1Po;)0C&N`jNGmA~ z%Bb}8X^CAnWXrh~z=|r0S};d? z>UP?tQnA0kPaf6i^#Cgrl9L;j6{rxI!N3#B!wAhHX+j>ck*<2azqY>K>ji+(Tn;EB zkGFW9I8I^%AP5Oi2sohKZj)x1I zB_{~mmYdE@&WsOL)cu%!e%ecurqwCLjpail{*h6$TJ@ZvJ|kDfWLQpDM1Z&)+VVGuJgBgMB6maqhB8RZ9vVSV6|78uP;H9=V> z5@J0Rblcgf$>kMA9D=}bs0AfCsw>J`%juHJv zFj3io(b1!KopAF`(5abmfRG2h)(?LC?B(0n++t~R_HeE+V5g#PX~Ao>>Wzhku({*Q zb&u^Zs0DsK^y`7&2!m$mw*$Z3NxIF>PGb7KxYLQ6tzN6!Yv2FygJ;g1Etbm|ebfQf zYPV{aFTQ#HwU@z2lLu#qhDVy)t@X{Vh|%YqUf7MJF3wJY4+0f+H>{Xfxg8aVlF7L0 zNjiB0f??V_^&Z&b-qYuP<+Hze;-0gU(+9AI2c{+_MuvNGvv?|B|0ws@cAIo=$vJb6 zXcP`(8XT8^OwN#ao?9ps86aI?6WJv}BqKlDbF4ukR7OX*9AjGyH%5!sB&`=bn-F6ZL zU_0PjCJ0>Yi8x5P7~)u#oZ)vob*0?(vVaivYA*~Kfi%O!)Y=wBiu`vy<|Zd{#9^5p zuHLZV;I7;o6g#*roC(NmV63pd-d?!X45FUrl`?5D=q6!|sLACv2C2>vyYi@a65$ub zxF&M-K{Oo+}{_b9uqP^U|Mtg@9=^Q#`Qj8SXq#u7}HFLQvV-A7~9?uwNqp3d1+dk z%#hUuZCeh$e`8|Bc6fOBQ=j_OM?Ufq5|q(bc2-wc zzy9^FKlRj841mHmSXtIxv>e9KKa8N4z9DyfY@pib2~17wIPI$29Wq&C`}pM6^guIT zDO!C4My`SavT&J{#gYh!))eTIJH3=7?uKSDV-BWK*L8Qo#HiKEOADDGX#g)m*qNr& z)8i*k9v&Df$@enj0I`R4$ROcLyVc9*N;^CC>(}NN7FN+hR)E!kClE72O{7P?97>WI zysXz9yv0#Svy@%Rzyz2>nURsv`|i8%z3+YRxpU_LAG^D|olb|yit;QCB~?W^Q>z{! z3TF3QKePKTy<_R; zdpoKUj-QGG(z&np#P#K35ra~drzwU<$Ht3=D)NeK^?dXYgr2xrfz{v(jCUMHh&rJd zh7=edqek+bFNrI~z!HRKGQQ!nlk@^YLCbSYHxtI)o!VN^+uT@NSX^7YeC^U3ufDR~ zZdHfJW{ZC=+q zppk6es{-A?5w_|2Jy3$I4?dgl$}%zJc>O%#ren!By3{*71b=wyP7n_~ARnUg3i&dJ z2&Zz{yk*OK46)!0jVhTeu`jldMhJ9p20@ZIX;jYUs<~q1$MwDEwF%uKsi&sZ}PUnf;K1&Vd(c;cspqbqN_k8M9qYll9 z)IH9EKja)CMKuIrB6}!`w00P}1=&}q2$B;uZ_8w>cS-4lY^BIv8Qr(a_!~$ch4%L4 z+`C-L#6Lm!EqpvaDGcRx;y5|!aSuz$@Q_hK0VUmD7YSzw%gf8nW=jc}yxJEC zlFiBo-yz^NbxVp6KOji6*`zP<1TE;683rA(%K(Tus6_%f#&@D4)BU1z`q7Vm_OqXzn3$k7eUza8+u#27=Rg1Xxw$!=56Wj7MgiPJsRe?_ zQ%&jUq&GU+SIA|$@-_hkI*sD6=SM@it+O+mQ{`Q&I+7Wj$T)J(eynbP7WT;vt$R`- zstBM~Y-7Hh4gFy3@)dWZxrW*@W3cqycON@)WC~5{$(x$RIKXCkJG|wh zmHB-6_N|3C-@Mppw9BP3i~@ZzaXIV?GwF-8^r!&bKI`_@OOei@0DNE&4>a(zI`T8S@6tP&e!dVylM)vpoo0(F=5mGM(Gi0E&CM<1 z*^!~qe1T{NXDT;FwcG7Zw~Jpy!$26mA7YuQNkv>}EN^d2yWL0vbIb0iXIj7~h7st% zSY9Y$q0xS{y|I1$>YH!8_~wPzpFjWd<@0Y?Tf5k-f#I=(Lq0#D}L3{l>5STD3Zqk=K_v5{P0P zuU&clx#!bXb6{pV*WZ`N5PD_c#m??dr&%kwcx1zouS58mIADtSZ+SaV#-e>#A&>n; z0q&K2KT2Dj@UDB$e(=MeI&s$nzy;g$^4WspS?&7vPk#8^_U0BGC1RPHm;tM4-6ltQ zFHvo5M9-HOTDzW8$d@oH+MsY$UD720wR3oIi|8#S+;iP5mKa%lCr+YB zPD0=mEL*^iJa!^yDGWC9rYy?=ret$2%SswQ=(xZU`7$YXJaU43E}!*sa!o^kT^m2> zT7_(`FPk?V7yQ(37zNvt_wU;_z>_8!CSVN516a+n8rWak1@GV?w4syRNMx0S@o?TT zSezgeMZG9&6Y8;OAcTR+;k-Apv9;ang$P%*znCjzU}B+&YjJQf1$l-72oND)SXUTj zGefyj!lJX72F)uwxkqAa?~n>f_ee{)CNYhwq&`G~Re)G>j@&t@&qiRtG2%Zhj6Ihu z1u}HG{X-=5A$4g)NN4J!kSZ%AUV(iWAb5tRIHd81gv_d*kS+{SUaF|3bh}cTY*kGm z7&)eU)Fj%d6Uz7Kx_=`{gQ}uVXz^pq;xQNEY-E!781GNytq)O1AHt2XYQ3&LlP{-* z2wEgc>G|vH8x&AyI;dSJ7E2Uh7_>&3;V9JN^!4@AtlZEY$a$AL9#f72de|~9Jg&%- zx(Px1pXkVX9OS&bcP&u@vk5J;0J*q2M!$2!=^g;9t%K15Y`Mot3xL3_GXKQ~(&DEVpiKsqo5 zcbS=-84{+;Spgyl$rNKlikxC(^%AG&m@#m~OASA)F0aQo*LHpR2pp_6?mvBeVq!33 zCt(_6Rq2S~fCd?e=M}*BbGH|+UcCWJ$H&GeCZ>jmhbuw?ce690Mi5(r%vD}<%)Ok@Ziu$ z0d-Cy4+tW_)Wpn(^1h@XJUDy&|Hs~cHeHfr=Ye1-_t0_Wt5s@ITC^&3_p~I?00EG| za3E;p&}_~4ZO7JZ&Gt|52do+ABWXr4B#41*f!0-BT4hygov#*G-_YS6vCoOf%5K8; zYlG~z^1K!jxF=kR#2fec{!{m>;Qk>X$P?Ev2iQ~; z)YWOw7zjH)IUbM4VH7eGqF?F;Y;)SWG)d$6bOx4&f+%v5QxJ!EvD5DS!5{wNOP~4N z>ei`Ff7uJVMJ*|)Yciv~tc$Xk#1qw!ea_C?&PtM7A(VY3RAHsrMy3X^au!>Dr3*xA8gcvM3qr9$}9EO<}xa%8R3rj2g-eS<| z(7BfV)4(%H5<=x$+=Hm9y9!{J7$m2;33ICM@G$E&6OQY-Pzf4!FwpoG4f52hkYF7- zw&^>-GzKi%Xr9W9M#>zwtCT@ibyUr!vTG$bEm)rbWc8ptO=3kf8uL+ge1)5|qb1_# z6yM;6Nt?c#ie&+PIBMRiXv^8Cs%9XOu9{3=?6ps|+TB?+8&AerQTai~w&@rmfDc%? zKv^&ofp)=^mTiKINS`XSj}rj~GCgacKuYWHJ5U(nxA8YzT~o4l)bj*|PwzEXJcEal z{-g=~q63dLiV+Tf>uiui8>vIc!Gjm!feruwgC9xNu^xXHo+euD5!4m)NuUDk^Ozrg z9vSY*hZ=`)q)G0-&tdZlT>a#+BW?JJd-7d4+&0%Io;sLZ6Np48OSM&vKqzVG7E~)# zT}8ubD4?`#2fF9@_~hW=5UgP1v1LI6LCqNkRnv4jo6V?W1E3si40TA1SI=<7JxGLh zirBctBTBj65fw-RufQP>&DRkV4t`{*aY!5vaiBzTO_Bs2grlY4E!<9P_qoq~?w|kj zfBsMZ=|2U|Kzt;EIEe7!hadi%fAeo{-@e_ccPIfq!t2z)sr-`Qvd$!(Sc@{U)yx93(GoiB$r3G#yLzE zUSHc-U*7dDfAcq=dg|%PWO8_Th;X2>-QC?QSFVi5BhU(wn~H#Zm4aZ|`o_Z93yXeW(UdmD zi9=8|hm@irVkv+;E?s>7@}+0NI}IZd1wM7Z;_e?5g1~`~iS1}bAN&dgM7z_Tjz-(N zk4Q0^(EXA#=KHjE{A4fyqrqH4Waw8|s{r6Y=HL9*Z-4o#Uwi(g&tHD}xzBvzm9KpD ztH1rN-}y(s`CBhsx(L0BR%yC=H?TTYdERnQ8_wxaV_D{F>T)JqgBes@Ykjfm`)DzN zP_?28nV#6p(JhA#yEYCFLz;k<)8H$lJuJ%l2oyCpSjBh@LyU20u#}e9D&chc_M2~h z`0;zU?q9!h?cM7)uiU2nZ3QS-I37eN#}!A48Rx3SH6e0* zi@I}Ey@ck{V4oGxeZV|WUujmle*3q7_m98w)!&2(4Z(x_m|TmZ$xnay{lndD=-}Q$ zC+Gyz>71TXhdV&aV`>XoLc}L&rm2QWhDh+F-2zoKbN3(!@eP& zY00f;XuR2)#4@3B49kShceN_eDgzd>kYSRgvIP8TBddPL_FI0QX_IkoXhFZX>DU^w z+HSXi<_`9cKzWAp&_o2(I&J!dzoar02y9YH;MoQPG(Skc=2x54j~yO24t@yJUks!d z8c|!*zKH-wH}xZ=-@Mpd8xLHg8k^J*vw4bJB-2EIYf^w~BEZ$Jlcqul{BZQ-zrzWS z(`iy}ZkuqtLaw=~-Q$qjHD77mFFt6ZJ-Na)F`vXoNb?EGCDFqwH&KZF_zT z+6!&mt1a)lckkZ1bqid*vb=_;h=%+E`{ucTz62UTnqV|Q5Xb}|71SX@PEJnt_V!Mn zJ`E56WPr~>M}jT!Ej)!oi$LPY6^f5zz7161kVem#B)m@d}cXZ->6upQ+gY!_2n1(DC5JqySMzyTt_v#_uL|H=yOxOseo>vb4|(Y z^5sjP|NQ4qojQ#w1}7sjX!z}KfBU`n-a}QOFb!TI`cx|Qb1UNF<*l>l)@{cEA}Mmf z)0ok*4-AY9|3ZK5nWtY|TivKCf`c`4)x1rqJ-+|c{mQw2XbAFzQ6Ly027!Y+opzCD zqrqr43%SYBJfLq}+YLM~gawl2)Xre6s}-%yO%uEe%jdc0Uf9|?x45*jyu7x)x=P!H zudH2q>QdWv)go;>EU*nPJ=-m0I>`Pd+)vb!JS)o zvNVU4$(R9guj`y-81?ky2h60VSuvZZMNU&IEPw*)VzoH4A+I4~AUZ9>t5<5U+ScuQ zZkJ|(*gaatYqg<63{Ho(7`hD8k@`i));o->(FTAw6 zx(f9c&Zi(9>`Gc82nk7>WkE@UU|?GM)k^lUAHOFmydmi?Uf~cGe&TgRtsVX%059PO z53~_}2*gXxi%n#B;1D0zC*gG%Ir4v!cyn8)Ob`QCxF($XaO%%NJ~y4#vn3yhD*fXHAT zP!*L5pa5Nd^X5&&L8V)!O{Kx>sv3sTWJ21GxY}`>ff&M?z6XQ*_19m2>#er{LAJKG z@NR3)Z2ZkF8aJ-gLTU%S`^qb?z_S1S-~auK7cb(Y zco$FM#^dp;ufE#s0)lVhD|m$0kwYX%B7_nIHMFW!3z2fO>MyvfE32A8vqMW=lU1&! zx{-w)d-$cTsk@@<{pHGDAY%>C0GXoxMARiAk%j^5DyH#CRTV(`3NsUFm2~FPfU6U3 zdUtNwcOTx5%j)@;UpTe7YyespH0>Xl-q20RfSNaGSoPNJ+jsBW8x5z(9x&WsFhq&w z^H~(naXTJQK(21LyS%)ND@uoQ+4XKKXqun{C;Eg4`JpDZ2 zX;nfUfTSSAV>YYX(WmZL(*05(2uX@h1kf)!@G%1M5CVw0-!v_bBj~A?8$c-S?(E_< zUT=gf3+Xv-rRhgUhZz|SbdD!7Glwgg;9*Wjx%<#(s-YB>NV9mN zDS|)V0g%Q5j9ga>#Wt*p_7AE$j4yLz*|ydyooBHUPm|$cF&swxln9+iL~u<2=k)dUCtwj2mnDl|t7x`FAmX=7DiwCLE1GT@IQ1LUc-3&;p-2J#wr01%MxG&E8> z5&$#@1yTU|PnwqA>3Y4sNBcyef~fNc)g|xTz4^{N?;IT*;|0qGwopB8lUcp!qaPrP-d_U+i`lI-b`uown-@9!7%_hxZ?006pmxlvTju^fkU_fpyTSw3Iw#{skAo2 zv_;9IIEG@hRGYX%sXTYVvO6&Qa+x|#8TgAq0I;P)8b)FA&;IC-&Yn9zo6inVFQ_fm z07pUO1Mq=#s1YzK$WpUGBkvwFcEiu`Gz{N3_~8)Vyw%+P;-f}SHxZgZ1Uw0R5)FRT zAg+He5N`oKJPE|LaeqHE6cOoD2>q>|%sizChzv)u>R0OUpF0{nqKNdEh9c{^Cv;1B ze4JJMuiqp0IOG?ujf4M5VB_FNe6(-M906*|WkK7F6B+>KgsF`z6+!?^?C$P9c<=z6 zind=*4kewJ<@t0v16KpPBaqMu0bg2E)9ZDi1;6{<@BZKiKLA`fckUc)dVFp^pM!;< z4q>cAUqXE%KDZ01;fjz(r{WgbLr60bgz~5BV7E?v_}o)ZJ@vJ(eeECri+^q>CI2OoTZ@FppIw?QyS0U!bpoRCjRpi{`yc9n(2V4<^6s!5U;3R7g6 z>Y2uic)=ULa%Q6R^s=|4vVdl<6MN7p)pYnR>E0TJpvqLOR8a~VCQafP06y0&CQV%q zRb|S!vwg37{ocb^DldNaGYdUW5s55?ZZPBoP#px+RKs!nJQvrl-T3f>>w}XiUFR((U{aqj9LF#}RN&YuB#fX>IvX41B;|d@$ySwc-#-x^2TsrW2K5?!Wrlt6Q6!&p-bh#I$ChDe9%FF~K21>;*qd zri0^yK|a-5R;m`6W3}hSy24ef8s(!r3K=lL@g(XRDoHTMO%+zEp;o1`=qS9q<|M@= z5|dJoONB;hT%&OGq%?1$gEf9L9zn;(35V5UMmskc5BwIOK_M$37-sNFDPU#2`^MXMZ(qx^(DNM{zpf0f zF#s8e3|Nm*nrn&?kHYcEbTFMHT5cOOP7Kj4X+5#5?HrnHt264mF)Karg2mOfh2`a? z<<*tNK)^=C zhsLU7RIr=#T;98P|NZwr0EZ$@j(?))FD!tGp&G+*J{}Jd?71x{c-M7MUr4{1YVfn4 zy>ac@Re12xOP4NfZf@ccz5=)cFae0Ova$kzf`))wxF;wC4yo06*FfZcA0MQ>*q?p& z+0T9MbHDRDzw^y+esgPU3lsxkkRUwB?#|B6fA|mo;otxJe}D7lP2cx{a)3Ob-H{n2 zf@n2OgrS28p*aoO4#bc_%ii2vcYLD~VU;+V7NjyPLe|mZ3tLxCpYh!8S%a@CK*O2@ z&WA-(AL3XGRd5-t#szV84VVVyRI+9#ASP&AAceOTW|i739gjYGP|lV1%TKTMTs@MR zFiXpHQsklR;>Eli>CB$ai#OkTFP!C?t}qTMVS)uv!zI~a0;$^;t>{4o9UmX>@9zU` z42Q$PU;sJ*Uck*}v(adTE205`ank_SiK7Idj_W`E@s9yPu3WjIX%OQuw@Lvi zNAsg}lnX4U>SAMS;i+fNST>DK7qqmI&>(mjm<^vWbo-Uhe|2s3R7LCjn|1?7toWEL zpSoX7_YXP{gVy+S-l;vf!a+bm9xW^^?rc8-3g?_jS}8A0C~V(Hdxmk7(YdZ9;2<&k z-R^iaeE8@QjF;zLcmbk6%MyrWgV96)*YXxxEmz6H!9kqGmFp_iRAhx3Nh5{jWmldf zSS90`CTz|3U=$0qY1qy*t3fN&(sUg|tC*T9`A8{7wkb^umU?UfG0Dt`ReWh-&7H=(*RD@?cDAow8$H^cJUp1}4O%Slm-{xeXk?}+ zEwpWBL#G}Zl3>SGx(S4rDpiqWg2od>o&wHAfKL!vhH3e+^o3u+Ta8m6HdRy?1)_wGAC`r(ge<8VHWxo)@H9XD{OLaP$?EwY0TLEq4z zT#?r^4guUCo;Z0KO^kJ24iOBX)68dtmi8Pw@O{p7(`tc<=rk15^IL7l4^%@}gyH%2 z!O?yk<>xOx{X4(?kC{mmRHJByT7hi`@eUaorLgcyLuaTU&sN|)zpT|hde zh~`kzhzT~Su?U{h4!*z?ntD0}YAtn{O zo;ysdI4Cbjk$9%YJk7W87CmTQs8c3~kSBG~IQScfr+@EJ6M~@TML4>xlR~-bxKxnl zSAUm&)MfGu4j*qk&D@$ggksPqYY!Y44_Bm#YZHi=Nt(gTSXx?%ljPQ|+aG;IJ9RpA zx*L%WFlBLZ3CQf^WY8?f^}PW63|0Ww)hlAut5>i7_{Tp2Z^OazhUfs2Xtp#(wc?|Q z-%MXvuHEYDDlp30+S+=(&nf)p&YgSesi$77-PgbV^)G($i@)(3zX3lU;VZ~w(`ry1 z(81sT{`ddgzx#JT_`we*lSwnmgUmFAYCKIxNWBP`W?Z5UQF)xJovypO)(6aIQa4Hl zz+S-6iL(`F@cfzS^6HZA^%U+B5TITVTBDDTg0Kj{rLH#oBMd}X5YKAFSZj2H9zoQg z)R=FrX*8-M^vbUa+6LFq{k{FsjcZru(+JXmx*=(RhUS@|l94E| zVzZ4+Lp_uWDbu&efTWg=GES#cPyinKDC%7nNC$!i6aX~Y-#>r=2X+K3Ltc>-IF9C! z5r(5Fu?RtnIdyvF%-IdoGDTh$IW0y6)Sw+IUL{PeR;0F4()=!-DM3`J zaXOg}bndDhr-J^MH8^5Sm<+12+iOF2PUr;E0a_v&Jd`Sg8wddlxq!T-{U@PqSleH? zeEw;vCgb_QWTjfBv>&We&C^^p?e&#qNM74?S+16O1-YUz)nnSMC}v?a9!{YC9Lo*7 z!1V&lvO#_{dsG3)2nWi;Pa(8TP&^$TPiLbnPow#~$l`E1{_&5$8%-y`6t3woK(|WI zMU_|51kuPa6-g8&Nj{%P8UO=9{JtX%->h7yCCg(?1K|P(oiBi`EW>RB=QyxzA*3LI zfVGZ~4?p_ggPYfG6p1)G975TwtgiYkcRrt`FoiT|`fNI#!RUh76{i`rysmTL52$&t z64HRtrR%h28}gEdw3xlTymb1^snxZOPG>O)mb<+*$Lq|)SmP{c`HpMrilyo0Y(BG0 z_k|Zf_tHzxLe|4-?e}`q*?ebvCk_)q)q(Ot<fZw*`EtG=ruaK|4TWJZ=S~4{9T}?iYdnpc-i?hp&*qrdUS8?d%f1UM+a z-Q8Wh1a#Pa!4WLj^1lSwK zm9T7mWv#os+KohMmK@DG1*r@_4v#lmJD)w9x7JQ6rVn1OyS54yRSGggJfS5KOCVL^ zA&`%F0>mV!fB<|D^{4}mD8x~QC6)b&F)zUOF3tHlx6OE`cqGzTUr9bP_wMcQ}8OD3C63upxJCMJootv=bv(H;L#>; zpSoWY_YVp|h&w-V4Nntm*Au?*5SH%h>ROTKCr~y~?E3+j8;Z{J1J`%wv)N=aMr0(C z<&o<;A}>aRK{yXz{>;m*PKR1K8eRr*t3%%F+=$2H$!sKa8A>&$t-y*_ky_BAw3nvg zRGf`xSsLd|Rr;+0mbbxG%`|kYjG-(bQanX7p$bQ%q0D7qnMys8Uejf%(PC5>=&(df zP032>X3`h5?L(+l8RTr5YhldhLhtxd-&K8A%PJ1*qby?$QoLAPUV&mk<_E(eo$zMy zT89WlSCLFE6oE#VtLrQ0UU=biYu%t%Y0k;`yyJGH^n~o@YI~k9bi0~w>#YE?B~L|C z<{GaY00icyNdj{o!pZkQo1W+Rw8tzRd;u9i0|Zd3^@uF3Z2{uAb^F>6e(<-~ZhUy{ z_O%bMUAcby`n8+ajvj3TX?Tv)a@#I*b)i&6#x+$jl*x3QL;B z3M~34PNO&pqnL)Cqa+u!(*sON)L^3-f#kS}%2sG%n{EM>n@ze)d~OHeG)<% zhVoXI0RL&H&tUU7E;@7fChJ8#F$J zyISL0^{y@s5D2)=^So=~vZ%U4$qGgOkHUnBd1KM5{$8ya5VuKrqeF z46sYnFVggd0CNDZARHDEvC1bCJ5YAuo@RsgpZw$}fA(j8_U&(fduL|{Pmxa31p+mU zYDGxXJphMRKn+37Q6ZXY(q5%S8npTPMz7O#An}w!7g{bfR%9@34lb@8JbT9E3#;`~ z7phlMwqSRv4g->{CK?hXx*@2kv6_^CDYP9Dh0q4@)FTMH=V+o0B2CgJ0yJ0%$bnpC zie44AR^`krq>%5ucjf5l1jZYTF8~IxWPNazfs|;l2QStOnBnlPrr!#bgnR}GA;f^Q z>nA`!^a#xpasV6%ilOWvi)ES3v@?(p@oMs;(!rv{w-pT_%Kk#|>~rUBhl7No(5ShU zlG6d2Wtt|4^W`soV|C>e^)J?4Xh`Q%_v_*Qp?g98|2i~Uuq?y`nr^q#1%uwYeFwS? z91IBwHEG)pcr^qJna$A7q2}-k_;)-U-G6X@X?gj~>9eqwvQjfeiMAsQeQy?C`QTbO zI9jxIVHu@}({Q3DnU(8Ks%e=lXtF|9#PbSV@0jzhn+2YsId;mFVoYep@^r6PRQhZ( z&7-La4FLO4Qv^ga+B-yzq?xd25Eq99FkB*Z#Vl+7y%{!-ocj`%1MG7@xoj(7}(=UGh?9!SyN%gzCD@krg zp*;&Xgt~A%K@(3+J?;3F>%i(LO6WM+<&$%t!%ShO#VtC7)(@blAx|8aMoDU^NHYLH zLP%H$(4F1AkKX**cmM1^Ke~DK&W(?6UHka<#~{80|gRQXHdktA>VuFXK%mx z8WhrOI-SgB$HU`!JZlHtR?vnKG#VfMl#bjoR&QXBP}-9WqK(c6(i9rE zLUmY{(P_JoWk7K>eTa55v%~rP+u#1%NB18d9iF67cIm=p^6 zy?1{4>QAm+y?uOqk^oPD$#SXDF?$epMxG0UPVD1A8?+eMux9g^zz0oJpo5u_JzY0} zRCHS2Yfk4g>T^=lEOe9zcY8@fCoix_`fC|6~8VcWCquDo}{TPv;Km=w$U?fO-rNjr@e$Xnqbogerf$0i6I$Lj5BY*~bF` zL(7umxq2|vBEdC)ZQ6_sFh*vIRnZBUxvEcxqtQEWUztr4wIp)UdE>Ny36j9qsIQ_P zS|olT4$uf%AxkK!<9H|;C<8+g4pc(C=4r#KwTHN{gee3qp%E~j(J`44r8c?;eP>m07 zKm5*jzn>3|7Y&VfQlm&=8F78W&DtvU7|=1#Yz>0AkORXeGW7f2+U zJHZqH@!0^Dy2^M#9iuQyR1HnOfceT`VE_=ts;G3WqggA$@uX22YU-#K+Wai6qQY3} zvE?2!m?Je`W0hs7QVk$UnTbZcySED)pGGRUQPIp=y%H*#qHXmqzx2wf=U%jy`ValM<5n>y|7Mj#J&p!O4? z0D^mlsSF3z_Rc0_tDLV{&MLRpG(Ib<_CnWPTS*K(2DUS4jH=Xy0y>u!O%nzpR1}-` z1M!hV+aZVp2kG2YYg4nP(*q!rQ8+%_os5oAM~=mTLhf9D_x<^zopwt0EqA*6Cqb|I_hwa5_Cp4fens1wC$QrPqRu*)4P`l-{+RzHf zfDVG_%m6yPasA`hfBKW@WI8xFKG->S0&it?4GL*85AWT(^Wlf@?e07}+TXu^>(

8 z8ylP8Fxc);MVbj@SwgWM=#b6 zk?ZT@X80ryupM=Nz-Ct!gMnjE1Z1g%;YzTHjBi9Hh|~ONbmpGVzMzIN()0Z5jeH&=3I* zIfPD)<9Kgx@1u`C`tEnX3*_;i|MP!-Mo{Y{Q5nS;~lSp%ma={@4exyoc zZJHKG5n%1=T5oB&TUMD?$W&D%nqy(g!O^+Z@zc++?(#C#E0};Ntw9t3!-JVYN!TVt z7dWbZGE_i6`lmszf^Qn6NG~=uqi|(1DtGtPQHaLGfQSK66ehEhmxWHJM9bOs_TfiY z?+c-Gy)CN(e5V`0h`OwYg~1>Qq)M+H60M5~%F~HXd7j~WAQX5WByH*fxdWuGyFp=Y z5ct504Y0!_Vosu!1dZXrSMt2{Jp1hV^^L7Xgo^?tq?OG0G+=z1C5X1UarTAhUZG>2 z9@o#O?$^itPcat+u3=EfO_)Of7R$@a5AHvN96_t1)}$(qV|$JRh7O?$(hQNI(E&n$ zR~|mvjpC@)?w&h)R?*eGQVi9&@zIU%{PkbTH12z_rw^>U8O4>F8L*$2DWp>txymck zEOTiLV+RV%u?nuHRi2eFRnhnblZ9{UmR`n5G>aoeid?A*rDXUzP1=G=S99viha95g zY9V*qf-RJ=SITjfXr9jJxiLtf9nD^sw*%XwQz9XBWiGg3dKPV25QWpx@Tic5Ytz;s zFprBwRJq<=*t-0=F9utuHQT1CckN)bcc6|#Tc|)snO+rPXcUqgmJxUrBnlnDt2^8= zU_gK{pd$?+qqy9#EkF>FXN{@%q!t=M2}$W?X*UV|$;3|*KNm}t?oJaemab{?mY?fJ zPJ@x1Qjpc%Hvex4Rtl0Ym&?l~@< z`axeZ>EygTr!6ck5Dxmg)NIBVdu`u$z%dZqq=!{)HXgq5v!Cqm-qVB}4MsZ;b`p`c zyIntMfk?mxX-bPMkiP3%Wtl5KM?e4*I>eSZ% z@qhe3pMLiFbLTIdKX>lj`E$=aeNl*XG93a80HDt2;XI6?$N@Vt*oP3Vkp3zwVOf$k z0P+T+M!-*UGkU{ns9h<3lHk933>ALu>*f2y~jv`4CKc@I*$f_ zAM0Jp6(W9;EFAoeYi^-nkaF`aICvU{q0U3Ypl$ta+P4=f4cuBw08)XdXk7dKKA;Ko zA2kGYpfZ{-kpz^fRtRkgl&7Qg(pFNL) zwNz>cH0up10jPpw6azIvM_&>3sg?*!fZjCQ2cLo;U#7-RBieNUWhB>(Xk6|+Qjdp* zM}()3s4=qR^$F zb=ojUfiof4VJbZL>}O7&x~vftLsA8Zio`#4zaH*?in$>0fNQ~~;Nx0om=G47PJ4G} z8>S3!1_V?Tg^o=lzVmRFqy;yaWpS7~u+h-y?%sa@i}~!Qb=LTqT|8%<4=%`gGK}g>D;LFQlrgRRM#?>7yE#c z5R`OIJ@k56j*bssf9;29JS_nchLiohgJC#Ubw<7Xt+wsb_V#fULT_>huu{~gB0_n} zI0?a;B^?4rduJieY&H+W*kI}l&pr3A{?)&5y{>J;8n#{63R?dDKGfK~B$a@5=w#GdM)8Vz z0+N=2OX|J_$Z)hCXmG;r1VM7#5`v)-mb!=9maCiv6s9h6+Te3mx zCJ8^RTVS9j1aWHKp^g(gf@?gKUviIi|0hp=-rk>h@Bk5T3l708l5J9M9)TtCA`}ca zX}U4=JB2GWM+ABc6tpb6-(P5EAs~bp&N2Z(kktnd?*HHiKLCudYxsf}5eV0Kz%zBA zisFn$qvPY_y}iA=ckkZ3c@vo9!w)|MB6;`ScY!<_Pcy9*9wgYT=D_O^J^($qHtH4` z20>63DsDaP1ODdI4T%~@nNXX#5p>pCf1$Oq()Vf2S1L3|MN=&RLCVdo>f-bH#=5Iy zOwDPw2kZ;oF*Tek}m2@GY^*11=OS$OO2qiGs_ z>+8SkYR3J058nOo?Y+Z&=J^9i>V!_oSA4-NnTukNiG<5u7}~%YMFxqjnVK0F_DKXt z9tV8NH^<>|rOaX2(twZv0RQw!L_t*8Ovi<+0=v63Q_6Wfj>5=Pq@^lo_OKJOT(NaU zu!>Kh2bGDX9Lm&Iv{l6nqS8>Av|LqT-gqve<5|1N0^id*u~HhgJ57^F5xnJgm-`~i zPIeE%Y2x`dOyfK*9J{x5>e;iGp68}lM#555r|q>)ug=pj-aF930kBgLw3T^MOw%~a z4c}`oEtal3XIcVyAWJnX0A`H3g8y&Ja}xxI1o648F0{&(P86qd zcff~JPvo9a_Jx*BhE|+aUAN`80nrR7O;ato#--4@HRg^I0=i>(tx}$h2k#3x3(}A0pUBhHyIXXO=grixRK%zshSE7n$vm#0J zJVAsH4fqGWBk!qZGh7Zk*u3v8vVQ+tL1b9J<3Y%~oLhF84LXaZS79 zxPhI9$=c%5Z~e|c{>&G@R4=EbV}%%y=+Vx5ul{5>9)v}Hw6_mEcXTv7KAwzb;cPM= zPlltx$#6IrjfN+~BixK9lj$rR&!Xu(2I88A>Cwq3N##6@(YY5{v_k0?xZp=>QL>y}0EqsEq`<`Gcqc-&}$`q8MP zgw~uOMA5D3QMkK5**!_P)i#urTh#>8M`;D7U*@w1w~ue$xS3a3o&^9Gr9MW9i4BNg zG@6Jn(tNLahZ~6MBF_NNU4U+j_8}n{TszPTB}I9O`|5N20o3Y{Pv8id1a#yUPzw!9 zLVnVIH?Sc?$1~2J+c83GjA=_EILn3 zFPLKFsh?-6k)+0aWG{1_R;Q1P{6q+t&uD&b#dGQm5j1+ARuwFjlJ;#xONUrDGy@_& zmkPuwS@VUytOWq{rD>6&lou>XAR;o`iMkGqpfrxsC=#WxJs8mz3?5#pd&46%c+a-O zX=*#2%g=n~;-wd(S!yXQrgEm*j@x0(&E{ElG%F5fu~{$`uu9M3G}N_fscm?!3n{M) z3qSxS1uPCoC_-wMVL1>0jcA4}AO%1wfR;aibj&iHew*3W{NO}CnL0vR%q;ZmL`^c8 zTTvBzme=lBwk32eoJ?(@(!y3w)9h?!0~nMV*{x7FkPy6{lnUvOPr&0#-Bt9K%3718 zdmJuBa6FaPB~{^+gO-@kSJ#;uQTUHxG9{+-F-I4|Xc zN83OHf$KqU#7T23NZD@ppr(o z{LE)w{?eCTIeltXq%nj%H0eA{r;|BKL0TUmgSIfKo0F!MDyd#*0-9F=O#w|0SV99O zq%d$HP*9Zyokv<`X(kJSY@#G}FAOvit$s&L01cpj=vbO(P_IeBkJyGRho%+7X=t95 zZ0)G^g1r#C))NRP)41ML4Yo2gH&UiyshT(72Zfq%)w#tJ+FpfTHwcH2@~RhEASnQg zX7vgx0G?9@YGK_Ta349dE!qtU+>=38!H-Oau+a@&(B?COwl8&(z9UtGg@%EJ)4>acK6-4P2 ze2je4iWEAJ7ilA#3T5 ziBR{vf(Y=}*+(Y9Icc}sK6B>u@@iK|TKSTb2>?M=7#x5G2v=WS*?jrs&%xe6mXI3K zYgp@3_v_*Q2SAXc5WV@yW`?<|aYYRd zqR?TRi)(JDB`R4|!esz8oRWu~r~wcdr3!JafhMRqnln%fu*Qi}OO?{`{RPV}4~NC> zzMPG0RW2$Po5plR73!|aR0#>J%nOjvg36>}2?*#?Zfu-_;n)g%2)-;$OxuFVPHI8d z+N~CBGM-3ga9C!8?T7c?dgJ8g^=dxOr;~^GKRUd1BR)E2s+LLlU~exBBM<@Bdm(cG zfH+J6Xduv-q1B6&tt3uS9fin17~rT%EuobP+SXc=d0_)xDcU!__SHZB7k^R@JAg?` zopw0L-g@_qJ9lqQ$5Y_c2M=~3B`pVLIvt@0yaWMnn>3<=E9bh2A8q*x2BMN6oMb(j zhIy98fL8NKq$7J2b5P41>Qj-Gh!6K3BJ=Yoezbk?@ZrwM(aCH&A5SNP z;SkMaJekbGc^pU7J)Wf?Az=#qt6LT73Liux!bhQcnc)JWfCWKHz=-)g9E~PXm}EI# zPv-R|+%WQ?{%Y`0aM~z}`Xxy35eh+~)L^00@dG=d`9jkGw9#Z%DCPo7q)Fv zjnyM`$OQQm+W!r8+|UsLP(08wU>|B#6b}i~7!z`c;vlKj)m5MnJOSO1e}uH#ZCv;E z_WtrO|DxH=9pOMEC@pf*sJ*7^q6R(q6uBo)5f0Y~oW{Z5xaM7A-`X`Xn>e_|wYhzg z4gwob9i>*+HO7Ji$fvoaYT^0i#zsGA1vK$CPe8D;&>YR&TFx(?9eHM|WTp;fjphrp z09RV)MT1kwK0%Or4iJ5SMj_!LR9TO*foPAjMC3y#n28#HHJhjpA7*>U!m_};8K6Z4 zYpa~L%Y|@wb8q+dz3rH}EsK{e6R?>!fk(+{0EUj!gK3AlrhyMindCK%hkBlm3Pe34 z1nBM3rAxp2yTAKKfAmLR|N7TodF2({j>qGJg9E&d$n{%~X##qJD^N#(8Vw7{GT++T zICJ(C+HsyIh)e5s2}IG3AXzG1yM6i6^B2xvrt%;w746&G6!ug1>*4-kAPD%F+DXlJ zPh8WK=m!T*t#9cDtru4`U4*t;0jx0a^lUbxoh>vK!ZEPCR>xG8d>)P+M{l)Z!WE8f zabC^mM+b)wPX+^B^#I57ECZj1NfhUF2!mhRrcx#4EY`+TZ5WygD=KJy02t|-hGW@M z2_{g{si!DWE~0uip_tE#SzJU}WhzM)#`!GC=TK=d8cS8?f;Jm0R0EbX6Pn7*uqqQ; zPM|L-rjJ%#mUE-fjLJb-F9c8 z-|BZf;24=IMJx*4cdVA}!LlBVwj)^l|Yz#84+x^0`TZMlx^(b58-5#0mtIk2rO2N)1^ zRI(Rdc5+G6O}9!pZji+Yj&EVqD+dKYp}*cyu_JPNv~}POErA0w5!R zh{*(=!Egdhg5Tg|baXrz4#p=Z!{KlQkTe(!CV(1Ia{t~Apu)uq=fC-luRr(fbC)hZ zb^hFivllLQdjYT=9GHVde+7I-kV(>l7lN16JyI(Q2oQJ*>TRoJJzEis57Y?UL$h1J zFtrg4u5TJRnl?cJsA{@JkWJsMp__FB&sj&pY8sS5($yjsScp8UW5Xu0<$%*f zbYHdfO3Nq>$`AE|)ENW*5Hu01`9LjB>ngxKp$1$KPWS_u1oc7?gb>bT$Zp@0u*ZPV zLB$GfTbd#Zx|Zg<@6Y1xTldPOD9~2*)TePL>YY%~7*vh6&qsO$6?GcY67`xZv_S|B zWIjogz;B^+sDiU+&z?DR2DP)Xu@M9T@W-`l*U++D*P;B?j_5$Me+YumI1=@5A;0CN z%jehDR?seh`|)vLVw8_D1*{i^#mdU&%P)SR-(RKzQmLs1ajBF1)crcRe*g$Vc%pIC zXnx+#sfjhWxc;Jh(t3r+VfY5E7TEt}coKyn^bQb7nw3zkx+<$e*e3L-P`R)??l`8` zR-$-PWJS=HXU^sA_KBs<+5zVdT7cmwumORibKnA@ihaXVCG%pnl_(}Y%X3YM?JVlj zX4}O;&&OtwDltq?hA)-r3mD4Oc07FKb;+IMo&SBDZIvv*wd_UkO z52I-q&C-k}jhH3_D1q5VRwq~nui181Wcxcix2|2izjOcA&6^J%KD>YLE|4!2X%gjk z@9ji+0woAh3H1aDqmZNxX(bU9xnXdc#S6&Qgo7iYdVxQHR6JCz?*f1NuJb2<{J(wq z%ijRjhRqLt1O^dVvbXba|6rf%+Ra;c_V$kRLI47w>MK>MFmP$3DH_p$GEU<(jKX^7 zY&z5}oB=FNMgSp0Ad;h_las+{wDV}U)egS#wXgr~@BJRM$kwS-XU?5Fb>`H?3un)q zJ`Ho0Gj{v-o&Eg-nrcYXhSGWpLqrX)rxfdLRA>fpS<#YmohFPU#0BHlTYbR6-$0OdyA9*y zCqMbgYp=bEq=2oVH~~PK%z?5bPfA)F4TgbO!7aW8E(Hrc!6=CNN%+rQ9rAd~kQ!+} z?&N4C*@tGPajhATb+2$iK7<6?cY)n5#duPiIU0VTJqSZVR(!q#kcDdCzU za~CF(${Wgpfsj9Zg`kD15GF&S1pM%yFa|vM1PXwUQYaxp+~Y5v6Am#C5BRM+Vlt^9 zJSv9lnN^{u`E;$LUb;8|*uQ&E9Sm~nzoh+}q2vi?(u{1dya2RIAO5%Be*4y~TPT8U)0XxPkw0-%-Dr1p{Rq=CE?+*sxYPj$ zp_-6yaEGc@1{pX?IL|Jezx?70Uog2->y8F=)y4bN{kphcHUuHYrN3&^5keB74zKyC z#_|Y26hvzt!SlqAW+8=u9n|u@IEjysPSP~NE!3Gv<}IBqnZA~VQjVA-N)9{87jkGA zxyj0Qcl6TdlQU#}Yk|`pWMS`-Tw7N_xQ!*&&T|=3d z+M+bqgif8&P(DygGFS5?P%YIl25ONMc@<@9oWqzM7qJN|nX}!)qrp5m9EXo~r)ie9 zdR@oR2lJD>N{p(^!>PzZ!)0a9o*xd&X<~$tYDmQMZcD(0CQrjWEc zbh=10$!uw&DYo!xT(cu{&v4HP+jLTaTN7WpuZn8ko4EhtEu9hru4 z*jrp)-8j|l_ic|>cuuC%I0P2bi!2ArR=LcRTmyD6xf{4eI2%2@pYI>szH|Nd?VFDt zKG?ngph{C+)2C^E=WritnIIudMcRtDqS+wz?9Nis2t_G#R0i-LAP#jX(DGw62dELr z>cu$I>8R5V{~g*ojNK?jcD8MG8kYSOaxA~=8=#0L|C3IH4gXeyni0Z=-?2Nk{rz_GBf z(5+932hMQnJvrb3c04{lt~W}*hDL^`xI)PRf3hCe z2o220X^TRpXL7wYyL=|>d3f0dEJh{`6HEc*1j$H+dA!n=ly9A8EhZ^#;wtzQn$t@U zb>zK%R`-AqYT?_DwA;7KELFIpl^jd}<4KYE(Q?;*{yA-9O-pC$?d!*Jswft0D+6zp zK(aJDsz7FtDh-9!_yeD&p-S2+=?O`V`F#HH;lry}ucA&*ojQdIx^w5wfBSF$Z8Djl zE)X9T-C(uGgTfFYY5q`-oOXNu`3t9eeZL0lC=x2Jr1{9S_5hMad*+!JE?s<%rc_hm zscbbC`4ocu`nX>r1gTpiHAt{=(=uTp*DV=5gj<*tcuYOG5EtMt#HmFC#cXcD=V%FF zcFVCLQ6V>{lW80$rtN8Qyr{4Z=Gj@IDkIHFrIA}YcinQa?*h>)Roq{guB{jS#bjmi zxV3!P?`*HEjO>+(>yKS;rgf$*f5y9s+D=VNwxsUo7Asw8w3rsEOzLV*yE6JV_2a84 zucl~wPO}}jswB`{(M+P9rc#wwnJKa`MQIhn6ona=JSkW~)5s))`D>V6mH7bou#K7G z9fw&FM=)zOkx3C3XE2 zZTA+t{RP)=bvg^})`I7@^?H{^%XEqel2p|#TSDh6qNA0UZ1bGKR!zHOFh|kswCGlv z8s$5KgZq;KASz9A*0@F;>EPd5BS2A5?^?YJ77d?K4?li}(QtkNWlg(slLjd}t=5^d zXY9a_=94U%DKtzGKH9lI0{+Oe;|F^me{_8wMz&>`OtEZKg=*T|^8h{!+lHRN6@FHG z49_)OkNckOc&6=|o^RW}13mqT5JdNLZ``y3# zo4+1TC!^VXFdj_@vjMr2DUllY;{~gsi?h84gDiz_;maI+^1a&F9cGv)ODs z9=-VDi?6)$1zgwH*H3S5EiWzkLD2MMp#6h7hGBrnX#G&V&_j?3HAGQRQh z1>nFda8QHLXP)Qb-H$*1_^!8NytS-(x%zIOEutdM$^Wh1QM8hO<`Zf=|J(l=@+$`G-;UH{b90w7jd z!D66gKY3cVRPFrA=+aimVEhzN)e$IP>ss25odgXXhD$s_3vK}+2x`!OeC9DMp*2T< z7L+l75*lhD6h#4w&~M!<@7yQUW!R`x>MPW9>B`ob&F-1AgRPB8z=wysv+ZqVmO4=U zj03TwRZ;Ss(NtfcIQ*meWvD3u7Oqb#03xAYv8>sY3|V^Ng%`f{t#1WE@cQeo|IOe0 z4T=x?*EvN*(gj4I$F)prqo}irYa5#@=gyt-1EW5Lw5k0Hh!D15mS^2=|Cy&>SY19v zYpm*|P|`Y?Pa(*!kNc%Skh&St|C;yUdE!SaqL7-OC~M$>^z z0n;OL&~C#rrWFLkAzEpmmff`K3boBjl}`(6URl!R9@A+hDoI<5O-8Bfi=bV$Ij8fi zv(nVnf-{JF#$@5;o~zIq+Ayar#ntr=%psu)ML?H3QaID8Tj^$}Ti9l$B@W9BJ-0Z_ zeHBukb77lhzh`#>#+}%7OT!e*&5R(=cwAJmStVu0CqGDguw8Yh!b`id2g!~N0Za4?+>5K z=TR0xsCXjtX>^E8X;9WGqeG`Ugyn!{F3qg0#tE#H6nHPq3JB|W-+lMP58mI~-;I;l zcKF89+1}zZ)FXEsmlT7`b>3fItJthar(rm-X7k7>yQO32ta~Dl+9vHyOC!BH!zZ~~ zG7|B+RAFVKkeyD?aa}swHUqrl4%e$(fM#ZG=5x(h==4->P7WW6lWC@iVOLK@aVoJE zmG-PsZs@=qG1w$%x3U}{71Sy7G*b-Y^w~4C6*`$py6^iUhoN0L++aoFTkbecr5{*+ z%LgVMgws3Mgrh42J+ijcT~*Ib1NwXq7Fflyg!=bI1-Mj>rXW6BTwd?@mQb*j<&BNC z&4vELQJ+qG#7;!q3pMc4WJiySbbqAUQf^sy5G|rBW4sYDM_2K*P z{^W<>edE<1z4zYRH*Vhqtf-j2bM?WUyZ1yX0Fk9kn`);fQ_>{Xie^+msY6&(vYL*} zpm0EhnrRw3S1lJ@^Q*+y@}!WH1CAIXFBT93AfM?Qd^C3d86R z|L_mK{J(tZx#yk(1UY~99Ncp+JpY9+eBtS*p9Y@T-rl}`{W>U?(N=Rvmd1HV%~hn- z0Yw_*(TE7dr}Zj9(ChVpZ{B$0jlcfuzebKgfjEv40*Hhh0wO>=HVX3bm_dY+fp?udsEYXbp7Ne7RrYFfI=^!eu(``y?ytToqW zhS)wY zt6%*psQsfK{pkJo-$!Mk;1J{x;6NMjqt+0!xz%+7BDQUwKC^l1^g4sAq<$C;00S`@ zhgAYem7F?t_QLt6yX_?!NqbybuuEyw?^E|{<9;a+gxU+Wa}u~{PSk{e;b}^jR+14I zhLb@&8Y&{^Mo*;~1iGrHvMRL7qCs=oH6T+ou2b`Zy-j`5NVC=M7@U)-H9uZbOe=4v zrSQw6XG`4GbC%T>e8l~z)v5XhCVW7*Fgw4G^37pqm(N|p@Avs6=q?wUCs@}qCA2mMaf>s2e8 zW@kyXJJrgfx!B{aZrNK_R?JLa73E^;xM@dIEM1gFoNH4wF(^Qm#yXT#-%vehld&ep zu{ADFR7WXUH_LS;kCHG9rKS|aD9lslwRFSF5-mxfyoz)@ABh1?G_WeyNER}6aUQ6O zd19rVS?rASmgXG7VAo`85^l%iah2YbD3+3WKuJ7=oFaYFw=QiK~;eHxT>2_ExKXTrn8X0h9g)YN)~8pkSFnAaJ;vD zbh0}i5B4A4&!%DE2S9i~dU$m>7?PHCtcqI<;Ik;QN|=fxE44mK4lu{iD+Btd1gTQN z4USJkw{T4dX41mkn5R!&xbUri^xKW#t=CqP9}rnNjOWQc{Ux-hr{X7 z;o#n#hj;GWd-!1c-rf5TA8sEW9~~SVe)Q4D-~G<_uU@?l$P3BS>$m&;u1$kA7W5y@ zS0I&N9vtlBYU;pXw97kq1CW9CIFTg-&j`o^pbbJN1jL~1X;6dJe$wl;hqQX_$VRHA z9IfJkPHoTz^lL5g9)l0m4pl>atBBP0oW*s!zt9(%t7(bC=R&wjrYyJei|c9E%Sc8- z^qEGP*B<%+iOsqLji3*$nI`;!C-vWo-cV@|bqG(~)u;v504o%ACdx$DymV$;y zC#FN&z9@<-6Q)Vo)$*sGwU*GBC926=KjTN^hr?USPPo!*FB{U7B4Ji`>h$H6wKJ{7 zyyXGxbv)0beW%fByWVM~}Yuz3<(>f1iU%Y#aFp zS!mKtJv#@b0RG_I!W9x8#=^7DT@C^of`X}qN=Xyi+E-(A6j3RxXP^G;*)tdHW=0Vi zr9>5c4)KvPQKAm{)cs1kUkU^Pw>1U<93VOv2rURri4eM?js`n#zxKwhYwwrk$aUJ5 z=a*GRf|BNI8i3%4M;lku0xcROMp9_)kR*_FoYB4@+uL``+03iT9-l5*Lx<(DDWEp9 z1sIfQy%o1b(4{eQnFF><%Tc)ns1a*0DpX#|+PGl_opgfC8ZiF>*SVt@Rwj9t+eSMz z^$h0sxKQGvbSv2}jZSF?d1a(bD}CDxTr{h~3rg;Y-jWh@6|XJ2-D+u(FD|J4g=%$O z3l@Xk66^NOpkrCQw6cPhj|!Gqbc~0UmqwmfuA(k+tySu36f1iz#vD7feF;?o8L25@ zK?_@ire`!uoHOV)Md)g7C#<889sId}9 z5=1WY*=!OgGurIgph5aDOtZ9l_-L}X^XT68&HFpI9^SvPef#Fl_V&ZQ?dx(l9gouS zq#B>}i`>Wyoo(Rg8T zZFyxK51FFZ8$20Nndu#`XSa$ZERP3#976-=fuT87pvV=Y9ZNAOvZ0>BGOA3?)@;Fy zlr|`x_xt@*r?y~);l?&i$FXuj%NXfka{$*sD8EBf3}PEg)7O@k$LTEHAFBH&+$i;q zlWC}GwWpbdR8R73SRXZ{zy{2PBDJKf;v{MX!N&TkW@r(x9@AT`mZ59?_L6CPqv`DW ztvevMDrq~`BrcxHglEvM^<|!+{2Bm-)cvd)8uES_#X@=&Pc_<;QU{B}a)w$i$}BI^ z0(L%4h6TU|gVT0l$Uj+n3>Zc)$`0epp1;OjUsWAh0(!U7%9|Hfq0A@KtG92=rV~2Z zv_8*_1~bvFbRZf=^JYm+l1@b+Y;KxU!Sq}~9p$iMRSC9G2n@^0U2ZQfFPS=<3`bcK z%|^p$J_Yq$*D9s_*-u~n@lSpPtrN5ZgXykq;R*|t*)RkcgEFUeGPEVH>p6t@9Ftc1 zcs70r1T^woA1vWG_E*00mEZsU-}8MRBmk9Y!UGI_XirszRsHTe@BHK^KYH|FdmhdQ zgW-5gyAh7ZV*s#|0S)pT93AZJZa;i<@9w=jw{G3Idi7)cu6+36^{dz3fA77UH;Ec3 znq?WE`|M}`$?yOErAwDCUc9)uxv{pkwz9I)?RGkyHaHW4CC>|53#O=f0aJul@WOC! z#>pP{ageYgm_Y&cEY#+QM~@%Z5($2a(1<2_g&x5Vz=3Nm_b6Hu6WG-Ct+kDg=ldd~ zP10dy!P-XyU+<}>SK^M7s4z9i5~KIf#3_CJYA6D!SwjvAAwTKfTBK4i%^Rh$KDwo~ zD|9}cmR2;C#UCAKS8o=F1En39nkh3N;S3TsUiQXkFF2hAB*qkB>PBjCe1Pp7u~O(k zZ-Lt!NO5_w)$hA{U}w(Ar8t>^1#-1pnK9gYS<2+;8C*|XpJ*0%se-hKDozxkWL zX;x4JoFSjce?z4wGy&Q079`-(^1}HGr-PP9(>^3nubF3+K@0n#K!9cWXFl_}m6bJS zm^A_+*hfu>5+Sl6Be;I*e%0MC1%fmU4_B}Y6g8T9-Hd6wn^G3;-rQudTF$g8WLlI~#z35m^0X!bO- z6>-!T$3fP~(^SrrXqu)|QPR2)>LZ4+pQ&j3llg2iJsOM-M$^IJ-X1OUxO@G>TUXwg zJeUuLS(Uq4wl&Qwnas@8Eu|$2dy+EX5Zf;_z7L%o3qU2Pv7Gi97sJu`&b_-=uix0- z-i118wR_7e%cjA2rF7apbXaP@CgrQ^YepwfXPJ6$zlg@uPA<9VB=WM-aWr+TM7vcu zEb@T0VZTP2)N^rsauNisGiT3jY(O?a&>6sBr6^mjN84+PvQTKRM~J-c!jgG<-JE9P z{&pHp^sZUKWKZ)&p|vc3tjU8oPQX}}m8F?y`*BsC42Dt^XSPmv`t71BlL9m~keX5$ zv-$k`^*h(D-=vAQB=lLBm#6gHG3iXjqDT^1=!Vv**hRH;WOM zDqu*GWwR&_!#Ir6B*~LFkE48^6nUCuah@gxej-j;QSwq-FSW%=4>IZGq8;X~ai&hf z;nCq}FbYK`9Hs#Mz>p`+1jr9Dui&2~$&9vE&p<`{fqhJiDybup`sfup4UWuz1vqTB zx3_cU-FM&m=}&Nd^R3sf-M%p|lBX}62Qv8H_rLqv>p#=E&bf}vi99V~#Fn`Py2(XL6E(o~1Z zX!xD)eEa_0dzCCK*Mhdgi>Ad?4V;wZImnSD**r;R@QWf1!}(+~84d?~d%Jh;+tuO+?%cUQ{nJ1B*Z=xof90!R{rWe)@y&036MFIMU;p}NKl@o=poN8n(O`IV zbVxIBm|pi;NXs&_3=k0tjdUAAfau_WEoATKudxUjn}d*SEa*pHIvhlH$QN@-R{Q5 z#)~h$__eQn4PfqPKl|BRZ@q==QOh)pC)6X7)($iQE27Q9ayWH*{q&hFpw+xcKzgNO zFgZ;Vbf6s%Jh%6S&wsJoS%6`Iw*f(F0+VYfO{DnL{p!143Irj;tQL%5;m7EemU^Ml zz_2Laef|4`y&c;;Tv$F-%h-2Ze{o$^eBc3y0Z1o65WH=$5)BItjG9}`$~6Wj1l;x4 z#*C3@Ozqk6#H_ko()u+#Y>*DDzIJ`SLiHFCL#bCM>FhXsowCxf$ zo1wa}H5Hz6S3ph!?4Y4&z}b$Wm|CSvVG8IFSXENDa{}MFA}6IfuMAOkO@sEiK)!&) zb4DAFF#_YIQA!0O*km@P2Rp{lN+2dBWo5=RQSv-@QUNP9v&^{(ZDFB&5{7@Sm4$6p z)`G^?c*km491=3Kn6!D~2ho|Q_{(2d_+P%>ec`j_GtcYiFRSOzR~Ig*7cOWQFDi@c zMelUhT9>^=-S0^52wyQ4a@(*Vf%GbloFdhos_Ln%rKe@2mOwd@fx41Iy1Agp$Nzk;Hmc91ZtJ>2z;?0_yHRe8hk_`|V7Y$-|v$Hc%}( z+Qu#nYc6{>EA8r}%nvdY%7^I;&1Y*&N~E7?nsNHn>0Z0DySsbk!;i+(N#J_E?ZsJI zKwMg;gn2DXcWvD=jP&Gqbnm{1=Co0Vtkmh8J5FI}ags-w7z-4?xC9+c^Ma#905~Oy00fD`l(yaq)A=k8sTP1s(r_M*r(s7H8{A*f z44!3Nh*qV0XhBJ4=`2!mR3|_rji4B;0?f$K?gT9Hx^Lc~>5er_z{Si}IweRqprB|+ zc}+!2C~ed6xSHp3G7XOohI`w$@7%n*`w%&Qc71(+fA^=a{`A&^JFQ+DDgdmE#+Qn? zka&SkFhiS!wk4}V1L^_rll52t@>l<8)S$F%3u@xRnRDOz&EGtI`gE;3>HO(J7P!)s zk|N*V+x?6G`_HH2f$zJWeqh~s7D$U4%h-A_4Vft?=;3eJk2exO)7}V>UHCJj)rC~tXgZQ+G(c9 z459%THmlU6T@@EMtBr1I$b`1Iqsc%7Z_8#*SDo79WPvpvD{%rJ_=meX4w0M`G%7>Z z&`Hlr9cb87%g)sgr*|Hr!noy#LIT;^MwthEu;Cr8pSHZ7r>LDY(U_JPRuR~;S{DI*5~X$9N8-?4p6?kJ6vl^DamDU0 z_Fw*AwXH7*Z$(!&O?{nJ{b;COe}8cE@IG#e=!F1EwlDASrEA-H;0I>8T<;helh8W*W3KEt=A3e`{7LzRFjmH7SdGRSW^j z6$a2GHD=}1DM9iRzh?171;7es09J>zRs|X1G81JesyQ%S8ZB7PqHY8XBdpL5`#Kko1OD)zO@QlxW@}H=)>VMKgM(zGeq! zOlLs|KhI530w1Zl2(s+QSLV0GhW*D@X)weOGH5 z+(79z4k2I#w13)ujq!Lk+27q64vy#3Ns+~^z(aD=;o#p%Fx-vP7qx-H#A3!<5` zfcUzhI4<*i)3OblHqfK}+$=O&UAG)72wXrGKX5z`s1LTaf@pvA$N%i>-}ri~6{w}q z5JU@Y=;&1%5l|H%OG8%yA^}?^9SN_Y9@8{|3WUX8ORQSbG=i)C)pJ|BUw|M@AVT0Fdew`4pl*G~U)*G!g;o+PieO|{X#j2Ms$HDhEEe1t0)wEOt^w~7 zUm%$}Lr=a54^bY0^@lzQB(aLWRH?LrjQVs-HPab#*qP0&_urWx49XgO=9y4(VVPJ%^R+X+)rP^+t_1OO5u!nvjy;UC+1pok?%z++c%DSZ)5*kuO{jCoHRKwAz_dW~ zpx5m#FRv^tc2`$dS5{VB*F`bks@=)SiSPT!B+BuN5Cjec0g?a&0ajjFT?Pb!-5><5 z)&|W=sTw++4ihJ1K*yI}`11PNDb8UXf-uyN4#FalpBMk<YirV`GFgW=9>GN`9HSG1Kc6aV|^1#o7+%r90=Q7b}Q)RHE%T+R>)5I}UmvK!vX~Lj4 zovJiTX-P$dNivGVp{f?BZ3r5OL~ue`RLML#IzEa@aT3jksPjj=TAV((f9LMb&b{Hu zNJ;Ig?9C*P=qT>012k9Kq6}1K7TQ4(CPmajsXZRkl^Ywl7m% z8Vi-CDZV-aM)BB<8uWd71r0L=i8&66C8 z$yGHUT3M@Rc?|n8pp%d_DRQ9LT#5v$42qxT`r`YUR4OR9oK`NBc~U_0AV;yHW|flF z>wlPLni>~zHXlxnQL?1-Raq^>$$}_PxvjqL*s%<^AMD@1H=c}W?u?XUit9-kFR}bJKSx#N?9;)B`y90qAgJ299#y>#LU_c)C_Hk^6P*ioM|p#1#UE& z6?1B9{h$4>fB5`!&w#>$=6OJslkr0~v!=!&9lT6LtK`Y>csM!{Qgqq@#0t$`f*2r6 z8$X&d34dJq|4Ag-TY7re-JxPikrs;Gje)S^Ot&Ed`r@%~w$oxKO`WoqK$=RA3JAvg&L< zEUtV|%rjxRVBu1hCh)1HjJs^I(Te-49tTh`{Hmk@#B5eD?z@)acjx!-J-q#KdNiDb z*{G^S*I&@<6e~(%G`OAJor8nj+jnkn*Y5W1+t;pLd*h8a;Hfu7r3s`pVyKy+ zrVOq%O%#9?%Q8=$-a3133#sB0NLkX9B?Din)Fdk=t)TyCxd2#9u`427(}E zr1T`&UvLe&|J418xnI^m444ga@&5hWKmG9!X0vfLpNF&Y?xWkcu6_LA{)e_vtoDtC zK12rqz&y=o23I_<&&`GUw2=&)CLvVOsHh*M=3|KGdMzCIxF|B+7-{BPy8p1h`Z>G* zo0aNTIs|XZHLhp#*I)aaD-Isr>fBrMw&6oYf=a!dW?l@c1LGo~Wr=qh` zpk8Q*7lxM!iK$kmQ8}i@92KfnW738^Q6Xnao###~R~XFNtcrA5m{J%pBdN%FYV=a0 zJ5`-Zm%3*f+=k)i1%?GOaKkKenNUYKEE*NYn-pp$>_X~FEX<_TVe0u7)EifMIZ^FY zbu>pY&8(CnoSRbG9arB9eP4071O#zy&ERo&L2jMluYB45>^HhEf8KcUDe?SM)um^Z zOHYeu&czqc@=GtMXSR|~|AcpjiyKDEf#{yO(y*Z%bO1{RecDT_SxaO~Dz5O!?MJF8SAT57UWDBWBEwK25Jq06*`NAE0|T|n&ANOgdmJ2S9HF>Oymz5-_kfR9W5s}__Qj9 zRgpq`BMX|LlsOIVmH4Jeqb!PYTH~7LF&aino6O2WDMf|A>0~}0Potzzi`*-c4M5*g zx|M2XRW*wlz(*95Me6X1wz2`Trw#e37e;|`Pxgewm!O?tA=6Y44m1zK)F_@Nt&(5W zSV{W@D?nvMF*-ar+}+;WezwU4KFZd-X3SsvAZsN7s;ygFHOveW&% zwPYK1S7(7#<|^8h0{Wx4w(m(xkB*NgJ9|Y$yZMxX9khFW$99_@uGxHc@BW?F-+1+% zci;W^>eYAOefPch-h1brciw;h{p;7S&t@}_kaJEoM+A9HjV7aTz^tf?Rx3Dn?$p-S zI*cua4soR3n~E0N>#_`G87(fX|Hc=-Wtnu2Rr4xRK!S+y37MPg6G!NT=<=!iRdc_* zff!{pI{v{AzW0Cr+yC!JAAR`Y2Oqro<{MYud-d(N-?mw@vD{f(YSE$+z+P<@rH8X< zrt^Nc`;=x_1x!0)+IFn& zG}`~`|NGzW?!ETh3$2S!IT|}*3Z$Z9dAigDgp=pEwxQWN0J$OzH8*tya6tzsp;IX} zI=g?Icl$@GH=1X$Qp|hZ&42U<{+imiDB1FY$sH6$ zGQIH3%Hf5@^T4TM-zXi)9hI;IO%D`~Rl(96L$J?FXJ6B%tT1fpLcGSxWOQf@&81um zxNG=y0!}>Vx*54`|I!#q`QD zVY`3_0L)mPC*jN*#_<$-W0Kl4!G)5s>Of7$rS8lCqsmd0pA=!c(oShcJ5H)_a^kDL zLNhT>G3&vamO47L5bfP+>AJ%hkLi~?j9W-D(T61$PNbPXhMDNqSCX%2L(HR>e?qKBZS3f#ks4~X|ZLLro+hu zX7F;S|LE4;kFMQ*^kBDy<}XUxElpuu;VAq<7MxhsBRkHkbR{b{B_Ib29d&N1ah7$M z-!a_bbanz1z>KT__YwG@Z4Y#4(Y&Bd$jRcZmxGalfrN&VCyP%4K{1%LvoZmG*b>Sn za~#K}1AHN|^{Q=HXgmipJ5<aT?0ez|ypmLr^b>%;?}jAT%frSw&eM7kQimhs0@0 zo6ieLCnlEz09H`@3_t1{0+OMPR|Q_7{Ua*K1O*g?oG3(IZ}QtYwRH-afl)pf zoFs9?48U@bnzsH%wCQw`CV=2Bl;U_go=<1f`NYS)=c2GQhqm5;3!cU?+C-lQE9<$o zj5=rP#k#eGBkhlL8vWWR!v=!DHG#-2bS?a*X)Y}}3#(q306h3i%d{%zm8q2Ssm&sA zk1P$U-h&FRP~U(i^&B4hNR2b-Uky8&E4f;yQx1sIxX~0^M?*`E6a%<0)|j27!N(sC z_V-$aJ~eHbC5EiLRLsn3u;Qr~He|5mn*Oq4w-sfAiZ|VMQACPxnQEWgv~y*=Hw+F3 zun}3mt$VG$Nr(Ctwr%?X4YG{JC-qLaWs=a2L-Y9@4GC6opx9fI0r%!LLtSsgQtx`l>LR)~Kh)~T{Eni&N`0UGHtI^)$&X2}X$v<(w;C&L| z=Ru#kUlsRD8i;|ghRQJR-hKGd#~&~Dmt~=qxe-lm!)K{=+}mg`ZR&}wdDdz2uKmOTI-pbE`!DKo#w7Ieop+DuxseWeB&TI$^J z3^RcB2}$5vXEbGOdq>g_cSW@P!pp1Yf7`O2EffxesZ@tBHg+BqfAweI9dF;b++W`8 z29`6?9Z1GSS#X2TOuyh(+hX<1u7u|)hg@)Nlhekb2{#2>+#Hz0-SNH=d#zS$U~DVv zOXjKnrQ82%yYrGT0VUJ`jXy{$H}--l?0!kT)J9Px%!c~U6(e^bHp%>?b*`mlComCQ z)mu^ZetW+d93G9!%<3u&;Z&r|urfu9t&KI$SWRO-S6J?wSsVI6bu+b^kH$2E!ZW5Z z%yy;$7zk79JyvoLTAzm?U9T&G6;&)JyEkXm-o!Us-N1{|G}<+Z*j!yHdO2 ztS@bKFl(h&x9tzhl@0#VbK)CcmRqMzmNwMRGFxnwYj)Vxv>t0&Bz#XMRlXg2$Eiro zVNWqO5~r=Z5Q@63Uy6mLMkk#}*s8-VrBzy;Sy!8L!%DeD8(LRT6G~Rhb1_wnBF^XI zaB?&}8c)jk$-(x$Yj59r_rdH~)A@pG_2k>XD^hJmieIwG)MB;JibN`D5~PKk z+XnCvZIh|!EHAY?J3a?6@g?TiOrBsWGg{iuy$=N7@&T*OijG}+_Bsx0{EhSw~ z^D~bo{My6g{ayd`YIkkfHwS=>)VF+u(kZO(K(+H@I}+{fiEdF)kx)irgt_v zXY^$M<_Ei>JnLRu+*qWZJ>TebTi$ejynApo3v)m>U?rfp+CHSYF90a;1AO2XxB)2w zQXuchJtRC3Mx_Ybwq~>G+4Jj{E}!xPo~8-Zgr@ScN-Hh292jEBa{uXPpZe0)=4ns_ z#cLp4<8VuKseixVaMS!gb-#M3%xRxZaxbo%2W!LlDz6Tq!w`eUdv^^){ zY+RL=QhBtHOgc2-POntia;%b2rIEb!VvRN z0`+N}HbkGU8x`4du;4UimdLEhp?-t)jaQb}e#3B9Xt^A<0~yb!@4xfryRZMyHRE%q zJ4>sT#%aYp&G%PJ%}5MZ!Ej;>wi+Eyr)m{9Rl}?hZg7>kX4_tKm@cAdI#g3FOWpL$ zOJ6wi_5Vlr%uCk7Gp2XZ_b=LPYxhxc|4uwOgst53yr5J_y1_Wosdt>tm&Z4#gBS)B zY(;LE2KO|p&$?<}cHz8s_Po7yxwUm>@$6b~ zcA;8X$QNMKB`IiD=o-xtt@6s^y6K1oZnhNPE<9b(2G9VKv^S{$AP~9CA|;#|^D&UF zQ6#W3y-dbwoP~)*QoX{E}h1=j6nF5N1 zbO>%D@)m7fP|pd_WTj@JoE7CvR5QJ537ykgsLU`^&5_In{Y}S#=2z9wfKpamgQoJ% z_2Pu5GflJ7j2BSc;6~NaVWev*9l}x2oCD}}GWcK$)4W3HMjBI~9VEySbSt$}s!Wvt z%XyXx#a4voQcF{hwQ`{6QJK4dPRv3$9dxAWc%7zdR5XOqj7iX>R|M7ShL8!Fr}((k z^DJPjWm_D41>mn4yh5pb_Qhp|4M58~nI@US=+NM>~aZdG*X$thSp%q{PO`97=0(4@U3Je|q0|*z}vX;#S*H{peMod)6l*DjE zw%S$JdQ;jnprW}Zs7R76%`i)iEQp-7VkI;JJ^)WpJbFyZwvLCor5j{Vv1)vhLrl)* z+SMD?-Md=JVQHm+%5$j|lDjfqu@6`JbGNOxmoDi30#E@mX_Np?NCu!mr0LW&T3oXs zzNU%#V0XH(vKDw=orS_{nTN;2!=p)#DiI~kXsYo6{ecv!9X!Y#u^e7`3_&Qn)I|nV zR+earXV0D9*jTbG8n3CPE|Q>){eWY_dAhcG>N78YzSHS7bokW$db?lNbW}J^GXmcS zavly&z?!b(blO2#8J&(}k^wlfokXpC8r_CqlU5-oQT#BAvzE8%25S{fdKf1Sf>&C6^?Q2pVudW$qE?PDO zb>`EIJ#}7bkhJ#kadLD#&odg=VKjjQ!VRVlr+H7*vLzY=FbU(O&I@K%uDh|k^bNoJ zvSPFcxJX)O;#2&@stY>m6B(Y9^gcG1@7C)454vFX{lQ6;i) zU=CXeTjZKYs~jO)<9G~f&$C&}52}K;K?Z89Q~~8kJD&>(M1ee)I`#9?37REqnXa|r z7fCWcoX-yvKj`PGo=syVE@swn^Hj?X3d@xJcH4%HsZ1PiY6trZtI^hJb$P{DTj$H` z>iU-0Jd-%LdH3Q4{nCZ_{H1j3Db*3?>}Vq9fEl(zr_|DV z13UI$7CW|Yn_Y&2Lj#7IlH0Ud0bmA9erYn@=0=KC zhp1^G!ZOxX5olFEi>7KeRx{wIzRuTF3xfK@Ob)6WdY2QM7hXv0c28ENmk^u41lQRdTo<= zxnPxITV@o7X&i$K7q-^jUfcCN7zN;Erj?$hJNTLW`1oWn9)|@iYd|@Z_FkoRJ~aIU zVqlunp5vU^r9(M?QFAYQFm!Y~7E6j|olLWxL&vmEKl?PDlr3m`32s;-kuAS%=|&uf z$0xfqHkA!s+s@;9iU#3s!ewN`Gdi^gOiUOb5FA_pm~POxmr-wC1`SF5G9aFs0!$iQ zGG5WCvw)U_=V8SI3YvW~7970HY|u~B@}g&k=Qq>^Zw}21ybC6xGEwE@FD_`}s5*G4 z8w6<~kU#>(piqR=HTlVpCW`Vb4-L0~Xn6Ecf9IX-c;xDVG>sS)9ZR#ws=gVn2gl33 z$m_LRi|16A){koy8VpzimJ$GFS`k>cHIsE(+-@1WyN9DAWiS(}CZl{JN_lcZXD_1? zD%w4f__hWagfaj)kV(pC?V3Aaj>iy$cmZ6T_WQj{m(MM)^dMiTeALekF3qznF}azg z<>^!BU-`n9n^iDPQlGkCWA{seAi%aYJ3`FKrKNrp%^p2`2tIUZkvB7#QlwIf%yKol zF`z$S*+*58XYo|X0b_yZp0YfsXpYuF?GY^<=~9xg7jsoT(AB?Fl~g8cgOlp@*RGkY zU8L%GG&nvwo=%Q}wz_$`b^5FYTQo~bnjy|+hVCk&UvCKoC<9Z*AVaaB1;AwD)-4$! z)Y_SniL9t*KncC}v!4A`wY-oDwWvZgC_{1X-~I5tcmM0)@aA(*t*mbfW<$9_Z~+6L z+)O~mA}y9XwnzI|bDer?O(?vIz5u{Qo5WX^B{>a$E2A=Ww$3bH{<^#Md059e6dkO~ zQX3qFfBhHVegB;sf$yxJa@|&#o z63-M}c9`0iiJ8u&$Tib|Zq9Wr=6dK^`$2m*SWLWCpRvyLaGo9s13J}4p(-P;yoduo zSzgE&E2CvW$98NP*tzLcx;g4}v(sm+^B3)TN~9O;MT8%G~4Hh8rwW#Q~z^R#^qi0thHnHP54g z#=*Y88@7sMlvJlK`g%DTiE`=^Auk!Hb(<`&)zU3QG9zupmQZ&O<#K6#$Of?z4B??(&1?qdj zGB*udFJx{3(J39@7>SK4aTMKKQt#o=ISd1dL;DaG^9J^=k`Ns?wb zmeqFcB$?j5cPlTa4);x?Erm);)1m8W&ajh~K;IfLxP&UzXuBfdO{o?Ih(oVcIwpTg^Q=|I__mF6Ns4mut0)H&C5Ln$JX7<#U&zM^_)@rJ=|+hd%%)@imL^?%pX zxv0%hL!t>EusvA?{g;HjEAJRT{^9o9?_Rn4;QGCLcOTx_x%$yt2M6zXPW;k~tBb3t zfWewVQKRHlnpKlYIggUG2p!Xfu!9MuGqv6=&|n6)xU1?ZH!9#U-#6WsHJ8!ar7!k3 zz7}-OC{?bOk!dJtJimMU>RYe=SXab_i^}F1*nbB?z(jL7jB=GmtU0aK)as*XrD14} zVVTf9a8Qwf%LCdzGmhf>#{(5#4O;f)=b!mU|9bg_f7ROh1JnOv;Jvcg{lawEeXw)z z;Ne))EeHUh3|8-P4vH}7Xd93O_ATr<3-AoU0cLGwr+VNT%qt=hA5MH}D25JG&J;3> zLIXzWsw%9Z)Q6U*=^pFamaaiFWv*>PGt*8mRR}hanUZB;4w9v+4%MZkS;?caWiAA& z(29Y`CYhYs#}P+Q0FY_A6iZKldB< z%U`gcf6030x$6A0`uX$n*~{v)FS2vbv8~I-)?FJt~BwrdWBZrjeGXMp>AG4c` ztGlWBhE(Ue0M2p?$wUfC9~H?sOLQBc#3=HlG663X)M!PTfEF}> z!>Ql9)^IS&IUp54ied<6XlVV0Yc@-tF6{BH( zfX*r}J=6AEop!5@Zw;s8I1a&`OryQgU{;p~EhSN#d_I~D=h4Yz zGM-HGY~GXA#Y|s9npNWXEJ(8I(SeNO&e;uTb4Ag43J_(Pm99Cay}a0Ow}a#3!;|63 ze44;ODuCnSh$iwXT1Eq7EEifF-Vs0sem?WvS5$a+Oer7sB1%m#X_>I9>f4Q)PS*;MD(K@ zf~cr7{2Bq(SY&Xtm1?C`nN{&n_aenGZ{M;$c%L7hNDeOaBqUs(>uI8?*=RF3S!xXe zFAr9>toE{E7$vRJ6Dr!TW|XubLSx~D|~SO&h6U|@7??VvG-q1mLyr47^uwD_@&O> zgJ)zUtEw#8J>6YR(7+Hh1~V9t0Yr9zx0PMl$NfVqvJZGz5CIlIPxp`})!oIbvXW;; zWbg>*eyLGq`<)v#Baq#FtL>NSwDk0FzkaWon%X(v`99U7N4;6@9f;enCtR(7YQW|| z+g^ma=kuinj)7-Essl8CIS`3UP{Mi)0UHzCbchAS!BX#|=(V^0qn(3)z@b8&RS;dm zt}f61`p^IL=Rf(2y-D)*ud}V)rfyCpA7t?~P7z7^D2n5ZrhO=2L9$CkNZeM;5^WS1 zRERa+pjjeL=4Y)pQK6%+efzCH{O5e@?Ou#qmM77Xl-Gawmk-;Z<5X+=J{^w+gR z(j$Q3-HT3WWp{J2Eyqcl=CvvV?b=KG(KmTnjVIM)s~(QJBwfeJ64H8mn;-0po45Gw z+wA&{_UMK`yv<&}br=$VaWQXaHs>SFGd!c1iv+4Y)pg>CtSX#M7N-K7dAwjG`nPUJvCndE?e3yqHhAq~#C2^$DOGz~yOK!e-%os|YcKDw1g zZ7eDC1G-fPFs#@x=Ij+Mw|5>rrEo^(JN%gzou-4~csju+5z9fsh|Ux7h;T<;=n-7O z?Z6?|re_Gv;E?&Wk;G|I&-Sz7;_|ZU+u>-qeY6L%#A2xS20=awvdl`&W!Lh)H&xfu zlHkB?2ddz~g{i27<2_V`3tj7uTdRHd8XI0q5~BeaE;A;cuP&ayFsYi{Jxs@Y>$VOF zl_o~GFVo^+e|In*&F8D-?6geXun6OUPBWRLJTEA{J&`t|HT#@)3HD%s()Ti$lo=hG z$amVd$~JM|=pJ^{E8A(0@4dozaB|7gV4@mbPlOCKb{esGCzIF5?ZF5HZn0SoOm#bO z6MRz|fYDgWtI-ZTqgMkV8&IWnADh=+jeOuIoRd~cD{qy|TT#l3tMaEm)}P&%27+YE zfM)t0_Q~7Er~cw-_+opwfcP36+=$CD0F?v}olH}|M&K))_7X<(`&tDhn2BS%vzx=5m_bl@DXzP~zN{kSnTun<@-ZVQi!GOXfQzy0!7SVv?AKrJ1)!@i}h=-z4_Izd@Iieu>Z};zC3=-kG~xXvZ25*FBsuwxfS2q+5)Do ztHp8#DDPDi_kcfmX2&(vu%z)~sd@)0?&99HO}8*zR}OcxWJI<31U^N@GDBDd@uA~? zY3)M!66cH)x4k<#K7Mli1W@J!@Lk(#?V3t^-y~^U78!`RX-Bx46IUC04*WNuBRcW4 z?H0iiK!#=*AVVn~f~SJ#fdj&2y;eW}$;*%5e?FV9ykm7WU(7GNipNoT^R@i-xAP>+ zx)$DLB)m9+DvG?+-sj6h3FaI|YCWG>*`Dd}|zo@6U{CP0L8?~4iNUtKR>?`#Q# zh2Y{g9KU$+{qOzDljlFbeH6cTGtW}0>n+$QO$OGl@D9_(h{utD#T z(@(aWB5lV5lax)!fvxRG8k$;QEsN|Va^tv z3>j6bBEa5^?2~YG90Hql&f|@ViR85JW;FDqm+RkXokMTYZHnVKv$Ad8K@PB}dP*4Nr2Lpac{1{4rdCojMB)GNr+lryb@)!-=6#J!} zoB4(WTJsOA*7)-ECN3gM`X|JxX8iYH@H0ms6Kxa|i_f@r0&X2~!;jpAA?;QlOY5FJ#Jdv0d3i)m`T8WtIHgyKkChv`k z5>nZeqROrGjg+wJVVUBV!Ca*2a0{L7XN%b&OLyCWB(y3sUe zeRF@9t#$`|rr+-{fscHySEnWT1<_T$WK6>gA-apDKDDRh@Bo4}>Hr|Ck5 zCZOjj9hh6L;Oti02E0pxs+!h-j)*?&mhSp^y;UrjT?6(u!J2Y)z#D0;52s$;JR!XP z%XycLWe_nTPC`$dBKwAd&~^|U_LGI$q#u10ef(iEU#WP+gRbC4wrQPFebbHO87Ro! z6regT4-TVZOwuKwfAH+_B++`1COlmoSWG#pV7#`oW_ft6SgmHyAJ^wsTtqg4fb^LQ zqT`nlEfFA&^y>R77J{FNN78R((f{^!DhI;3n@mS#_l;LkvtiJ$okAVu}loN3NS%Uo&|QX9++I8fgfiAhiCUDkf73Ail%& z75I_J`kq!k;IG4SXLjbVE`6kO6%ADc^y`8xZL7EU`lFk0vIK4B5J$r5I1VcA0E$6G zfH^<}(SI72q#+z=4boq6s&wb7BulfT~_kPYld3wBD%r2DAN<@ zyyJ_(Xn6hGzcb#x+jmTBr=?+ibMfNwzx?C>!JN(x_t@@!U6ggKW5#o)QXLnOrn0tC z#I+zU)!W`hJ${TB)wN6!5Vv!k7V9rA7i$+G!cKSM(catd{^8L#{?l^*5BT_-+vVLO zea*UNF>_C!ol^pQ#G!N(O1xS1SnQWB__Vg}*D$MA|*8 z+#FIGk~#RetV5I^hx|B8*gvD z^R=xTcl6d?e{C<^xFNQ#v2xEHY>7KlKABjx*B7PU&Dm|aiNCkRGLnK3jD;2}68qS-_Ze{W)iN-QT z3~E)agdbRWI~ty6?DKvJ#yHaHX4x0|8@BEk0*wvUAT}V}z!WJ@Yh&`1eF8li(0d3A zwEl$+S-TbGqoM#Uk?Y1GtfcW+B~1dmHMMtDhcAXtHMlynzFVxc)_aEs4f8G|S4t<;kV0 zdv|y=-raGy3$$Cv2wb@D<1D?ld&t7c+3^ok){fJDuZ)ICUB=7p%uaH2aM_WJ#u_3rj^XS&{=R?|r{88_o$Js$EwX(l5!ELa-3Eas^SQGh`Wm}z|1 za1XX%4z|p-t=TxcpmZN9)QqMm4noB&n8s#Z8YOuUFCqScQ2t9sLTIx2h9~t){()YaMCxv9GF(@ak3PLzRr3f|$hTYDX$Tn;6WqU|8)U)1{0{c} z>NR{PMnXxcRHz=%va_@E=3963T;riBCHv0AafUNcrF@`voPFz?zj^KO7L7)4xYn1) zul@12LP5Yk=pP#I^?-@Ze5Qcb9Sx^_H@`eT?rbd+NojsUcl|&jwDXk;HQv`peM|f$ zkC~|1Sx~bq8>R6cV+prRga=&y8E40mO`HBg#VaUX&eg$Qk)`#^i`ndaLW)S1CNvl4 zXVukSk~PzDGTf=wt4pfXK*JBbD8|d?7>YTHdjwh`68O1{S}+XGQr3qgHQ)=w>_Ej{ z=T``sCy(N*;~51uZ#$5wHgSQMqb3`ylQOC++;Up?3lrAHc9JpyD+Liw_1{~eR_K%v zaHn~kvdUBt+RTj{e2}`0OwLx62>=&0l}`i$DJJfAy13KmX{n&wk#_?P#=o z?G2wF^tGLVA631f{c1aVakj1&y=xL7Q;*-Ou)(i z|4KzBc12>hLfk{t*uYXL2D`)cBz|;pwP^c^#c%z6mK-E*lqYZa^jpWz z+JEuKzxe)N-mezPc(R)h5%nT&r(ii?b3tqHD(^0Xe+fPj@xv>~;7%0am^;*GPiN-r z(wHvHV<8G3XT9%R#&kbK*9R&3*qIn{m5I@CV1RTHC?T*t%n1@yCV;1 zKmXIDT#Y97V9H$k;gZ^hsI>hR__+~_T#_qFV$JT=84%4D{TWgD5HOok?8 z+SQ}J&AUR&C?F<+D;V66huRO8%Fe=UY#7k|d|QWgCF)+T(J~HV;zTVL^MLr3Z}D`( z5P+bby_VqOA}Qq9ge%_nc{Jcr%UvFcRwK$&K^w+sqkbx|BOPs>M+WLk)V_3$5F`%ZRE z5JDHNVa;kG>pJczAJjy!Zm>yf;aRatJbJ(i;ncY|i}~q0(}PLPn!0tP0wgyq+VEm_ zym;9xX9eR6zt{_^aqv8uwuu38r}E2wgz!GlahS47Py zX-6s8$!c6w(?PQ}s&+=JqwVFLgVh_?t6PVwH?FPjU9aw4tM6W4-`bnqIhen3WA*x^ zym#ns?AfF3`t^PL+LqfXY$6=k0n8U9C4dl8>M-RU2T(>@m<=6c1s+TQlhfSeAvwV< zMRde{7Y9D)3dC%ir!`Yovt|C%UnHMCD6IemxiY32CcEf%AM*8rD>J*jf4;wSx;0F9 z@*Dcrj%Q2g8R`^UxlN5wJao+VAU=_Z%U%@I$lciC)%?X55A9_eyArUz zh&st=!90wLCWF9f9bAk#unun`Dk#Tcy@V40*tV^~LO>?pdh3mA*LNcgSqAU)o6?0n zP6Fl{yx8AA`s!D{J|1mt2gHLTbotPOkkAHFZk*~tIfyPVe=N-?i|&-=k%R>FE9*ZN;&ab0g3CBn2hYI? ztgV%1lSxtLZ@%}F+2!SovONf*;>9_S6PFgV!N^70tyWD$1K8VL18usN2`)w{3>t0= zr-s0X4N0RqNh3tQ4~u!FNe2{KmD-1|4CCd?RYfMGJ{uc z^qHCNm|L&y<%raqeWLIwa04nXk6;DmH&mbqoW&kU24b}tn^iIq9`S|1Acj(63XCkx z(?Ri?Q17mmT*zUd^wJ0d=tqD37r%J#FNcHr`b{+$G6SmPD@gMs8{yUijj&VM1%M0G z4Q?R>O+}Ps0Q_h`mBh{V=>S)4IzKZZK6v-HuD$#FEFD@KB1uUvJg_g`fBM7k{rvp+ zWH8{_aG4L+X;JHV?Rmr0nnQzeiPpp*lR!&E=sZ)*nZ8Q28WoeOGA~Xp=542vo$K3M z$zrvuvc3H~liOb%9o-x4ycUa;>sS{|Wv%6_)<92lMROE1rj3q)EQC~4pe9N=2(uQD z2@A>7EC=Rybv?gWfM+#HF=)9qb5=y%j;@Cth`}9vb_jYy`M*%DOjI}xahu@yrl2kb z3!3ky@n^26^vfUyh1Mn(uD5dD>K2R!9hoAIG&G^mrBMVHu-49{ELV`Q20S8)d6tXq zX}W)yP4}XF(vQf3_f5SF=B9ac{CFVf_|B-2(r zPWzXsO+09Y0F{oI$jEfi6##y8EaHZyF*)1^o)5(KzqOu?oBAHmA6Op54#WYdOJqA* z`(wcqcY1MAhI!)S&bHh`H=t9LPd9TB(t3z;EmR_TOgReRMl`h$BnXHy9wDEFG)a=% zW$)KIG&vZO2(Aaupdz_d)6LfNd@@$!;>tCZ=@kM~MaFMoo8H3*PmV9@b{T09WBsbm z37WncEP!gJsU-?*ph4CQ^J0*q8E^!jB`NO=yISVs;qaY1E>B`&!K$gNETK%JvKU@J zxb?%od4IWF!|c;6MK@{iL{Nif0?zBk3>=loL zK`0xB*d}>X#6Sla?MmizQMV+m>}8tfMfMhlkMke(@-H>bk|VMr7}LUC&Yh60PUL8G zz3n+0ydv{*2LMG=z@c?=26@W*?UJT(WBT# zV(cNn0?v^dXOoPLwvxPnqhz0d{-EhN2nz15TTQA(#CS8Dh6xn;dJg?9HEm(z3{=1* zPWvP=QG~A8@CMl^?UhQM)k+}-2pTG9D$(1^xxPAIU!2WiwyzXlR#(fKJUAalx9$~* zUIUBZ)RE4O;g;$?gMKLy_bN&~XaSItX1?fkhA7_9qzSsfi;ilo0hE*I@`C?Q|MLgm z|C{$8KRtQ$_|q3p9=-pQ4}SWizi|G=?!;fa9;Kj6Xfb6t#(kZ>d@(ya>j3Ks!Zd|) zh|XNnJUU~-Q&kZll|*dlfam$Ptlas+7B|2CkA~O2#X*deS4=a5H@ENq=r4cz;~&Y; zOt%pg5kEwx!E;0#o>675%`6zzW{JT6oUwhT3aaTyTgJL{m=s&-tZVO|UUZB3_)yK< zZ1VQkcYfVkn|*(Yku}?847{#HMIhB^OP>wm>{MKR0zE`#?|4k0%kWAz);A=#JqK z@goNdBN)Y55!^ZSddH=SI@9K1U3yT##IdCIyu({`ZS6XAk+r*Eypg)dY@fENsJ-Gz z77YrWC9KTs_Kw=WE_Sa)`#W}PKkOZ{gX_`ZHF*DZ8%bi|M?B0-XCo!cQ zyFnbbYS(H328!q2)7nwZ>WmV3G7G|mNZ{i{+Q8b*IScMU+1ZW?gHz@>&BM?r2%@TR zGAx2=m?=d#jN~L?Eb05G9#nE5RTe46-FeiXB6>Oa-lmQjIXR4hCJPEDh;x`eEzIV5ratSR32y+~If#19`9Klw%V^dbpKY0xb1Q=LlS z5G99GO2>A#d}DXMQ!a;ajJ>ZV;SR*S^~Vn&0mtMQ_iYq!dCKS?t!=SIA++)m@yjjP-68P{zd-=U3G)Q=4NIpx7o z2B~&Egq@U;w6^iCE6Q@b)1RDwe)25pDmc|;q;%87%Z0(QcWpSDBwgP^-^6i<6W-Dq zF*Gbhdec1G>r2FO1R2-628a`@Erbzc>o~XLZJs8BFTQwo_7YwmLsmy(dvO`&%UL;a z!%<9I!oeL4Wz}-p;3K9`1t()NiXejF<`&JRIcT2J9=*_@H0!O>Y?Nn1DZAt6XXj5R z#;+MnSq1zv)elzCc+7^mPIfn|qBxBkIs@=Y{PQJssp zZ_Vdl{NyJ;{2yLCxxc@c?j1#(GGP-DvLY>9G)v=BN5v~MplLfuK=e!xXf{eq+Tblz zgZ(@yi?eyxUoHKhnGgBa@BPvKAN(Kr^cz}VkNJ_#?g+X6{?E_;{9k^2`l8Mgy|>3{ zr4?~agh)hRTGtv$MKkRr{%PK!@0&)h^f+XB++T&OCu_Az{UBWpt12-!+Gy&N^S$9* zEhMM1E=8$zitvCi-6`cVO39@nn=C-~;YG6pTt4B|`X^Pjb>!WMJ#atqkI>9^gnZT~yxc=n%7pLcs>($AqU{rWyGc15U*_05& zJvi!Si$oE+E$OGOhDu{sbuuU(iS($mOSYel+bgY}b7^}qS+`srzG^_D7P z02drH0ZsJlzUEEuC2Mx`vp04Z+ar^1AE@a~$Rlb5?uz!z+KlAjYqQL0Gb00DB5Cas z2p+Wt8c*Xc(uD0yl8dv`;}_NWvca_y4}XBtX^04JwlIVms6WZ1TC zwT@o9d*j`&zXPnc7Nja@9eYPJHI#e`LyD5$`@KIHk9I%@sSRk-m&f0M<8Ot6yc++& z5BN?_y!jQjh;R(TfR~5E0i?>aCtm;;sL-Tn8r%1X#{~6WM^_?3*gK-hnkdt$rOHfv zCiN2?pF}Jrc>>2^vFRJnY6M^?W}FI=q#U-Btc-g|#3Gu_`qjo5my^bFufa*0dUxCM+~fqeDYSwC7r0W_wQ`v6JIoYFiHF za(&U6YPsl=%T9Xh$E#36wPOR8q-Q1jVR; zKW9y_;lW4!Y`)TY9Atq;&zJN0>U?K39ZeCy)=eD;uO(!)@0`hkC^TT8Y;OJH+jiBvWvqun z*zf(|fBxZLd=HW1`q5yzLrL{81Lx|z0K5()AAy4<2|5?Sit-K+=ebQ=+rd`Q>x|*a zS}>KtU?;f2VtrbayRW_Z4|i_;KF(u9ZB-9ZUf0X-{pFv3`oV`?Q)^|l_Jgvd7DL&A zQqq@#Hub^)5?j~PP8zry(L^a5j;1<{&(Er7r&mGgaw=tk5FS# zq-mDJreQNhPF2}iNN8Cj4Fu2*ERrg_NeNO3wgUp&w~1gGh=GopHngpYeU>YYpug@- zC0tga5MAKDzKhVjbSI=`mxN9=v~mp&3}(So%hs`*XQA*O=Jv~Yp=dc7p4ukHf|}Jq zfSsr)%HXh4sk~IhP?ZRG)?Tfy=KWlS`qn@fy6MHNcOfk@H(w{UwTjPk)quz&6!$$9 zuIj)$IuO*Z@vF)p!25)v9>N?A$QfEiB&qH`YbnEq%A5q-j|9J=lh}5So5dhMRO$TF zhlb0^8*iws-Kw`#h#r?PRzfl;HyEbX^8Ca1J{+Z~Audl3oa}xxwnL)?oIc?;bU39SI^pv{iQli|I4w_dw@tL=cy z@EQi(bJUYSZ(Ln%Z|!~K>%Wm_C8fon-~Me7`SSSnKK`~wL0(zUEB=8W;EUv_gry{~ ziYzPg#GB^H^9L_NO`1chY6SEwfu_}t&D!u-L@$$AYM8zS^m?K* zn;cRqqU1X%TkG3MP7ZeOfLlEJ;`rrLmghU3&ArR5$xhEM#*^ge#yCk@(^tXfX$HF8 zk=OYwk_ku*pv+rkdkqdDwdbNm{0qR*E>e6l-En(IJF{8)=bXBq0W$5~9 zZ?7D0j}X$k29Axm1Am6^(xQKzc2P?6$-p#35GpPK{6T!6GAEE)wDoFMgq_{#+3D5u z7xijY7;aQK@0#}NMFG&;+D(V!81#q+EM@Iz`DEfl%*0yjhBn9F6mBHU1JXx;z|MKE z5fXU<05u4^wmklP`0)OW`>_-WViulH)vVEpM?^ui4Yb!imo;vkl%6sGHi&x}2Rt6= zBO0{lxCO8f08Rw?f;bQXrKoQGTz_Y)`DcIpeb(t|S#ZB-nv>xm%~F_E8l|A2l;PULzOPP%_GoCz#qUgD~qX%_}ThuU9~dpO>D%d$lw0P@BbhEZ@=~3fBe>4fAF=h z{?Ti9zB?Ygxx5rtCoOkLU$X>6M2RS(LfmpQzCz{aXn0O)6Ljxl#nm7J4eY(A)g8-T z(*kEb+mx1=P#qFzMrO(iuA(AO3#ufZB8y{|q=*9`lTf6HVpN=yb}CV@NpHZ+DLgpZ zOfa=F^d({~RThbIbX6jI=4E4tmNr{CDf)b1bd0vKl+ts+=j#1~=;&5_?~U^M?d0%= zzHvReaYNm{mE5^kzILzNIkdNi?r7qNHN&Ud~w!vzH4q4gPkPK6r#71 zal)#;>=^CpJB%O=Xdk6^g&@_LmbrD7fJ|oV%FdTdOCv2HwYW2?Q=&Y&9uNaLLbZqy z_9|Gp>F#W8?`K))ySWU5q73tOIGIOzKK{mAU6Q0QHxGY|X}NKvr#pK%+sV`C_dj_y z9L5{;ax@1+96~UBQL+Z{53q?1Go%AS6NGw`*GsR`AJAebsGyjW%r$@&PX0s5z<3eh zCLEj=yoR_7#p}($(PnG{!~>7HVZ5Wn8dl(mg89Q)6Do?5ntmm+V>xn9p1S|`zdQZ& z?;AF_wSDatPol-*LWxiSN`2d#w(G{+cBMMoD^6}6MbrJ=bo+>l08J<3uURhuq4Ga<4+6)I06^|&# z96f~(D@D|?qfy)a{k?l{-rm`n8aNd_}cBn`Sy#?nx=^& zO=*K7Y|XA9o$Ar3C`K&Hdhqrr>LGzRqg)CckguACCV=t=k_Epi%HpS8scAe#=(xO! zQ&x=me6hIy>HO-l9}LIFXm5+z7@^sn&u6&F-K{b$8QQa2w+KL47C{vD zZ3A$lU`lf_mYOV+7@+_%pHWW>7Xc2PSe518&Nx0hJwAR}^*znsh{!G$^X1CuJW9)` z$TQ#DNYLD{ajfkd1Ek_1%Zn&Z4An*T3ToO%p-1osUEsz5N&q5&oJvSjHPhy&Wn zYGAaAH07s(Q_>)9i~tv9y(pJlb<-Q)Nss;mT^_))Aj`o(1Uvcoy-$DeXFne2$^O1q z@e5;TOf1TL5~q2br%G#D2~63>J#b&gfL%jNVG;Ih=!`8Uxt@gHRF|_x&;l5lA8c=Z z?Yq0z{z0GYYk4C|Z>QPo>&x`x_fAfpE^!WSlXTSJv@~EwkJZsU4~aM6vI8LFHy=3< z{+yE3?9o40P2KdJj~cWna|!Q2OKnk}bPEtd1T1_RN_K>Nq(CdAiz1>XQW8l8DTy~( zlw}0QZJo3c#I*8gjSo>Nl48!R2IsQa7B)d>qBH zqrF~LmuQnFeNouK&<@7-#`R`*&mUZqJ2zCk@7SnKWwRCfG^FQ=8FrL@WnwllUU54g z1y;Z-os5_Qxu%U8IdeXOmRCv>p+xAVlA(!?$~?oPu#LG`tQSoWzw0O$F$|(&9F2-J z!p{lr)qzK}xKpmtNA;37G(u*f7Uqf@t#a$-s##XFI2YtwQSmTG@k-GAA1E4ZhPX*% zEu==8>b!#nbni7I;<-@z~Tb`Q#8_`SdWK`c5D z4UY4IB@o-7&=_dE3#TWV4l_pAQ)OEkzyo4{s1PBgF%o!gkUl7!HqvXFi2{28SK-#d zy<8VSNg>BxjeH>5Q_Xe6f4UYf21tNcFg#rvee5}}Xo$ZnCZ)?BWN-mFfRyS`=hPy|y7zEMt9*=`anxJfA z8V!Wf07&97Q7#HP5%&uOLo28>A$)|ZxS=V?wv5vx&sK2yPk(lK1&{`Vq3s0F-3AX@ zxEQq5Ysyvw`cpQv>8-JGEbrXD@y1)P=~y{O^Od++Vm|mBQ&m-uM_b?d&TsAP>_;kj z6+!R^Ji=FjK~^x+dgnJyL(*6{Spt4rv^t!cKqH*}qB%(FNeCGmhJ@~Ql#rb-yP(b>X7Te{3r z)*ga=taNDm84u8sVzeW>-mR`C$1iK4JJ2B!_S)JXpFArj&2-leN4Xa1YEj2o%T(>G zw|xpU)>*@;zySaUjU7o=AVNUhAwV^?p)OP5=ACS{$R9phpI$8EXj=xB>v*xYR~Pfi zRP5{n=-pxt^`No>qO)&m@A@o`Qs6C4L+}xDM0lkMCK(khk$~5p&68v@*?E9q_V{5n zyW&;T2GMdMS4+QGb40kkt?fi;kR&Rk7BqwmbPOy6#0=!4H#GnjKeu&2zjwV+F=Cvy zAT3nt6F6I3&fQOcxccNH8$=wW0l%4@EmEct0!QO+IHC0lUDu;ClT6WaqaNH#M6m|r z1Wr+k0{CXsBs^&v8xU1M4iTjhHzPc^nJV%`6e8TKySEmLf_0aSEevy~Paod@;EPW_ zcz-SoC$LXhR>}Dbd%Nmt9-tayKgnc;?2Hd0w}ag6g`Ore?SDdcbSQhpzJG(sV04DjubX<%=s?yW_ot zV)rlV}&2|4yH({R*}{g5tQx|Fh&Cya9o5-A!P^O*$j68hAaS2 zIHv$ecthHUwD+;0I__XFG;9FELi~e139bQ0BjSNCL~c+4bRv)r6wR30`!#Lag3C2$ zJ-ZY-oSyFfuYYp>C*NCr{4~A(^;_3(-Af8)XdRs>sftQhcXe-7?sD=e5^wTiZidz`=;E z;pE_&^yRm=c7NmBzdamGK_k)Kh#jo)3CZiJ82P3xQfSsT-iexiJ)mJTfs5mG|)R;B@z*DjVRme<tw6|h#DF1|cpjEAFxok3oLES-|(;YQK&G7SKsqU-|U9d}$r5unZs1UEk7lqrv} zAZbOa^9MK5u3bL8-z_gwA_Li3-}&D-pHV z8X^fdNmE{w-VQFJ6wlG+I__`3c5rpMkG9uPHRy?p5I&4uK?8z)AVx+&NN~W> z?&nW0fAQn>XFr7ye13BE;pN%cqt72cxc~lo^`b2MWOy#p=W!`lYf;%|-Po(y%$PRL zC^5o%ABmJlfg}Fku-nx z7k@H8f6n|$v6(d&KCU9J@)RLDg&oEqQ?w3Q1q37FO!#OjTnZ4DsxPL7$NiHS(Nj?qr%N4ECa@NX z#<^LoRL_bS!JIZbft7+Ip^vE!>mcr3Sgp^~uuS8)Q)pI}`YLUVXpLjTScBa+kiSVD zx|Ax;g_YzM3=MEki^fCj>ruvQs*>gK31gHYp(~>%)#J;ZmZu%pk>j!Jb>HN)LOZrY zcTq-Qd0T6n#OQ0cwbvJucISZYT@MF0*xrHP-eKE2emXVdQKu$8n>1V7{%9vIr#v2; zL1FTw8&myrPV*jdu{S8uTO1zlzkFh03(J>9}s!jqG1k`d|E& z{eS(b`0=M^>(0^5H{P7=ZMpu0H?3w_(55GDle<=R>*+v#a(n0HTlb1BD#bGOXsTPv zD05IHXeVqH_e9MFDKVf?G_isP0XJ}uea(3a^QT^e_tNI?#Hi0LH@t^2aZ>4V>5QS`TBSK0|%Kl*%iIwJfr3GO5{as zy}LNSTFw?3kP(OXFwYLQnzV6iigqDf#VlY%6D~C%))#S_t2Be800uMZji7Y1mUj*4 ziZWHWV6xiY+bhfI{rewZzJT1n8cq_=CYLi;n|YkHJKNJCLNnqEYv7B(Y6OiQVk%-g zg8|w`d&Nf3npAo@*=(@C^rr2ZNP4ed4!1!gZoK#Yvx~(n&)X7A$-Ap73eWkZKfE!_ z2a|Tu1s^2|?GS9;8Y+ci5{Fbou!9!%@DTrysvZ13f*Z9awAy(oom^`NbuZ3y9$Ha1yH$=!W}MP;)eg zj0dOyeU#H9=|NCN$Y%8oouA_;P$*3TT!6du>vjEa{^XNC{a>E`_=k@lJ^tjwkAME* z`}aTl;OWKragwa3TPE;}-Zp|Ko2|u6)AsY_vTYl5B=F8s*%^tO>J2lN^;9&PrAa13 z9B_K!cXrCo)l7|#ZvEcgwcidbF|G!SQ!=U+)lYu#)AQ4(Nn8(0tK;^3c?AlSW?4~W zG@_R)x`?ld>o~ALmLwXT#yn0P@-&$YZ#BJLx0g}e)6(oLO0T`~weS8HyKjDDJU*CA zkM{Sj@9phHg0E&P#97;~aMuv?kq)qfh_(e%Ng|!@O_EGTITrCVoL z;oO)j+1u1dDS4sc11}0ogL0x}wnfK;PV+{{UT6mj$U;IHgu+HzC26`&tArMwbJ|BW zFo<{IconhOCYkMFqfT+Kpw9D3(<~D$HX24;o6t8<)+rZbmE&!3$_8bW7gA}XV>TGY zqj8cC`1X!H+~c>dMSIuy-Ys?OZgRBGvSKj_sxs@UZyD9t*OB4gfFMN|1xHWP4zzGk zMd?${w#+q-$+lT{P0QpOKO*olBZEmYkt(KJS|ZGu)fVKxPaO#S=rUExwk8^+c~P*n zxq5znFr22hZpb2W0=>mqWn?Nl*Xql(*ouNpKN70u6x;(+1OyN&rU@;xPjLqxJw)aJ@Ac=7SgJPyV9%H-Axm@(8_@9lf^q##e4;DOk=7Y(a{I>mKyN z_Yh`@Gh%1>^3I{Tb!}2i1|A`wE@df0442uE9&*KB0yM>b!V$1J=tkVGbu>N$uTNso zQSM^lr0oopUmUy9mR~QU$IoXcYrHSG(6PqGV8Usbw>4xNAkIPjbv?wz-Pdp2zH?(d z9vY$`xH#P@uE2t5nr=MWx_kGH*YCbb`(se-`2Q(xzdU|DkN>|<#Jpl2bWnt%p~{VU zZwv|%0O4!%8wEK74`zK{q~r09=`G}JoM_rB36V~X)^*wSRbJJ3cg|VgR!Xl&Y%Tk` z56eDPTUoXnM?)@hPADxEk2ME9&tjHP(JaJy5g%@EGk1AX@r&6hRVnagQ`_~bYFE{$ z*xnt-N#Z(lX=)3N=YpI!tIo@kC9!ttuv0OFpf)VWPf${+qrGQCSGlelX2bpI&8wG9 zxA2fzwA+QyzE7%^YwLPITfU`fVR-&JInvp1$m7mu=Tnw7t6orl+&ZnlnG$62Q;4X~7Pp?&BB&7V-tX-GhzM;HpO~ zM2Bxk0&xX=Cva10xUOfr2U(nl*~~tE*fLi3woY>3c(^)ihv^{Cp_>^LkG0e!!l6Kk z4uqkI!&G4dL6vg-p!jfR%3PosUA(Ukw%pp*ak_Z^^6}|$HJ^*|=%BN#YSxqj!sW0) z2vGI9r=e{eKQm6R<@x@_=26_*!|ovj)gok72Bx|cSB zi6~ctrpfRMrKQ3w(D#T%Aw-})T7`7c@P$f-22UBSneODn5zHmWO~tPYxPdnjD1n42xSNoV3q<;9K5B` zydLl-lZ}gNmbQaZM7mq!>XC*w#!V;!7`leV^u~5oW1=dVdy|k+=Yi`EVL2cm4tndRKnlGLv zmvg?imEOI*mO2IYcxfWjQf;;9wR>;O=VzZj_!*oW4Webf;Pk^1PbU3IzCs6=MaOC*_NE%I{JaamLlh(PWTba5u zjj{$z-F2a#we6#2^8NStzxpfl=tQ?njkbro2jioIX_)LWYv^RY4pK z1WKQbX4_eJa=CsvQ>$KPTIQNY&R}{S)nA0V;Fbo94E*$~UwiBNwf#7ieGdvk49sr; z01aNRt83S8z5BIqZcle<#0UUOB9!VQplx3szxKzkMnTA4U;RrUP00s%0WWU8ktfp6 z^gsPWc231=;BJ)S1#71wy`54%%SJ^$m|w2WFE0!tL=5yvTbnlPh3c&`ZRBJ(W1@+8 z#iH6hIek38T344#KWpXr+Ps+em$j@}IH|nguo`e@YTyA3p=bHm`bpuAeQh6>Yw+8&($ zde>h&7I{VcWpN5moBpIC}czvR;;}l~UO%%guu54rgjzPRwA8n9$Oi7uxSE z6*x1ybYTtFM}rlhV6?;)F+$OZ2oV!d9;)A3=6bR{iskf+`^zVfPol)@Xw+4Zd4t(( zJ{Y>)Lk`K_)rqAM4yu%hCy7TY&~e~SxFk2$)j+9@wv&;LBU=9xOurOrv9m|TK~J9# zUp!6`!EE#-O-A)Hon7>C>dS)BA`%^Q(Gv>M96Q32i4&1f0VxGR37Uet+RP=<<9*h)t@BG6)0~AdyluKT@y;crt3;yXEKO2HysBy1 zm6nqh5H2$?VP|@eaN2R&u|Bhnd!kZi%$*Ww&Rn+rbD`!^ZNtuB&OLyev$L1apFRG3adwsIY`%U*HGD;zrYxovwv?zzHEcwi z!K(xwe*pE)X&Bvfsu`lk5=QB!O~@NRj&WIg$@{~b*I)mgfA7|J{=I9jzx(wT`q)%C4a@~NQE2+ejB*XmBsa+q2)BI?!iom#Sm?}vy9E=mj^<66juJkI z&z+je;Zc{SOQN@K5ShsJ-7>SQFc7O@2pNkvE7oYYhFoU89gf4^b$xVGA6)bMyZ&Iu zT|02MUzfM;vBTT;+Kq7Uj(Y8GJiY1lVV5S8*Yxm)gQ8ii{45{mk!9_R^Uj&cjqCd0 z2$qIUw#;niL_-wWVi+yg=Rf($rybtZQ*94CTpodqcrXweWCZv2luHdkMdNFmB`w4+ zHh%+sC!*oB_X^$!dw?&(stxV6hrduJC~RayTY!uNiS%KcQd$v@`&Kr7Wz*Hn%7-tq zKl!Wndp~TyctPV4u+=<^@7%n5{oqK#_ZzrJp|s*zMH}eUiEC6MUcP>J`Q~d$QHE?uwTvV!fi)P{{Pp<{*=X7ZMTy zg*N_1L(5cRoj%S)o(>dGUc5M|`ieGw+)$LIuREY?qbI8*o%gKk8c5z{AJ1cc9QcDa z`P>wrdijarp9lB3>mM8aT=LI)_61|lBYBzHGhc{F{MfY*S$!E;2Jjayihb*wt7RM6 z-88*L|yL#OLWaAj}q+$UC15t#45HgQknxqnosJH}= z;-YI(=i?}C_HXF*+CG11=PLwx%i z49;O(=n&$;`$$`m(j3!$Ep`akN1d^*7lnm{a_!%lG%BXxk0LJvT4}&rtO=8=t7tj66lNExC(j~;t z)n#v~_<9(OZIXn#Hs}+nEEgSwA9|H0z9J}LSO$<9FB-r+jc1`v_<_a34m={!a1=~- ze$qU9T$vspVNJj2TDMwvKD6UWnIy{C23(|TVUYsDvfu_W=Mm|nIE5@V0p~`GB?FnI^g%`Y`i?_l z2fZzz?paz>wb@l>t8sMwE8lwa-}@)y8{e3YZyrqV?M~mmcJP%{f{WhD;$d%Ay}hJd zW)A!hG72L+V{m8K4PMZKqtkF9gi`o#N(#2GY`c=I1I^-H+F7s-2~Mfk%Fj(hyGAPm z;$_gc!lRJ_Rt~ZV8>eMRU^=ZrSdLkUX*!JeAj-5EKrK}P^2?>GVA9}QDZSY^Dl`Eb zh@-faM%Arc5jkS(0Z{}|lv1ZAjcr-jVQI%hs(LcoHQW2{+8%rDy1IQU-n${EH{9^% zWUTvrFS50RkZ7Vz!O3geEx{?>^y}YnS=k+CCVKc0c{({@L-&k${r4 zJPstqaNA4Q(HNe$(phbdCi6EmHM1#12D^+?w8fw2Qe?keN<%A) z!R67}L`5vodjS^L+0LlS#%yNCzxYCb?#g3A2m(biGWiI!LF50vTVgXUnMNS*I84zP@tZ zTBiv08Qf%PxD#m}OpR8D5Vh=zXN#V%0b;w?$~bAy7AI$yaPoasfV`ZZUYuQC#amgn zwN(y=q)G%u*#>~6_%u*yF9CojXC%0T@S(yIR%A9HI9UeR5?)5#-p=mn>E+q^Vm(i_ z+)47#bgT0-XkJ~8(>JciaZ>rPusy`agtHQUi+~hGBs~Fko1tE~GNJ$?9PN^#Shl!Y zN2*KG{@`eLeq}%X=;d-X%txLU@A&lmBviF6$A0%Zg8u-mQiNO}0TB6iBbdado;}4s zJUk!>qz;K6a2`C;Fpv<(!^LQaa^D|(-k9bH8ZpweHg9=FOZCceo#s%vka|Hy7En*K zBdv7chKb4xC_p0wRn>&(q!DpWQ|3}69wgLWZtoV`yIW9G&mTAQE1-C4=8()wq(SD zq9}zs5VX9-BKR^Z)S9-@%kLiS{WfPios-s9E+8T^uy4U1ja1ZeTfaE7dCEtrRAnp)D;hgUCj5Rj#Xil_h;{LP}c$ap%A= zVdo%aAOr}F43`nyr4cJ}BdN|akr%QoWH>z6c|*KvE^{~OY5FwHbXqS@S7&E~G|Aq) z<>Fj1B@Ft4WK!^IJQ$~mxSV~OmY2n-+uo;v94a|OBNYMgMr)4IefZylFTtG!C5XIQ zkZrXwvg_8y8;}iJ2m@x_BfcvsQbI|Z>!h_G#QvZmENBb}3RDbb!t~mlt&5+1wEMju zm>++9Y1)`ewY59K$MDE^wzj|W?(2=65&3j@ToGk1soL}^RI%vIx4!D{-HQhkO=R9} zh94O2sz;xLDr{&65oN-nR|z3RKtN5XSyY`J7N=yuhbXhU;gB~XrooBOGB7l`({`bV z+iBW)Bffat&1yh<1cKTUffGRYu4!=gx8J^Z`_7?GaGS6J(n2)W<9f6S%Aw3BU;XO0 zZd|_wuK`2aFb`@U;>G6YFOOgI<5!~~V7l;AFkW&W{EJYv8Nb-9`=GB^YyOC3<3%NU z{7#|EZDwSsXvM3A@d3^NUBL4}S~rL*vwAi!q@-<9oP^}E7Z*GAYJ1gYm6UCkQrWG} z!P6DvaTJY;WK{AjrZwyv6NmD&v@d&~A;4W(c@YorLgLOEf7%#;Ljf2!@p7@~mYnyr z^P8?ac4hoZ_BD@YQGe>%6UWY(J$BW@wtE`fOR+i?c2=?~BZ7 z&g*5&BMl^Pp}$Fw(z2%Aoh-PP&~jsb-~!H3X$deINhRmzXgrOQ1F>;0u>xosAZ}22 z3b<@nyJp5tUi2rIHH&rUX5J*$CX2n~)~Ao5Z22dFmenrJ{ogX(Z6T!0HGSX_-r zHzKzS2r9I=2Lw%LXvBu}2qp97a`gUt^#{M0efZJ+&+otY;Nj07KKOKYxu7Ajczt&H zaoZuf0L^KLt7%MKb$HM{v6+NcAmJH<9D1tEN)h_{8?S%m zKQ4COq)9>6O2iMQy{#9shoW!S)${X<_p9nLh^7){6vcUoa~a%*m*^8%lhGR&?YRK2 zak{oyh|y(zT%pg$CY#7KqDA(}om=nx!~f(vzx|(n(n8VvR7lXElrnE&qY8x5MYabEpatcfcU2E!VzlrY%Ld;WOqwcF{f+qh;FsosI98$@HB=$kjQ(f0Y_&8x%P%X?qZ_uh=|z7gNL zt8U!3hqwIx4Yqa2whqG9ZZh7L!>K4oJSm(?dJ#22)=9c4k=9wkQXvYe=mNe@IUnF6 zutORUaE?YtHilw+!gw-n!t}{;_BTJZ-~0aMgU55|5*@*KDLZRDZxfx~yt9AzojZ7} zrk8jXl7=Tu&({4qiu$aK#czIt?d@_Z8*PZw3zon)0idui0&ezdM1&9m2OjY+e`drG zz=_~=jOw~DK@&!1lQy2>4VwZj_&n{+%x$B^JW}oR7tQet-r7uLyra=C3J-l}vONCQ zx4yQ$Gm2nN&L~OA^0?Q{LKxAt_SVgNUwQkR_tiPxn~RlYRofzb>paE%MlsDjpqG-&z{^Q5fq5~cIf z@zl@)0oI1acz0kz|MIwd`lKn#t;RjqX{guf?6Lu4xOcY?ke|$=Ye_=U1{{&(go0|b zj)Igvf;Q*@6nUoc&H1yyR*DS+kBTuRH-7rri?fp!952f>6HUF2Ru>uLi@n>Y8P$Y_ z0mUFyaiS4RX#AjKWtj#l!~j+k)6g;Bl%!y)W1R@Yrdv+8*=U*;gY5IqAD^GFrYo3i z;uO7@oSmHeusk@(IF;L{>{EzhkQ*>SV_HRN(5f7*1LYdvmShx1#=9CAP4zkXvT1tX z4|23-=*-sR7xn3Ck;14z@~oL%&W!PS7MBAXWmn8X>3U*&QB2yAQ8fzBUDMVGmyo~+^}1PeNr{Jv9-6*5Jr)1zUqATtlhwlq&z?N}=;5RH9z1x^uEVe>^1M4f zf4^BT0n<5^35lAjTdu2)Zo^YWu1(1apf)WS_L~*mGSZ0X{hB+3j3kLzWakMhUc33b z_ulzko^R9cI~*tMLEB-DwmG%t*?Rr_>hiO$KTFdhj;4qKQEIb@QR20hnfHhoE|CcG zaM+wzryx8|O?hckzn1F=W-*$Mv|S6M-hTbffApVk?f;HS@9M$P{?@gv$v3B?JJ)Z# zdFS?H!!lLTLnvZzPTdk2o1$KtRq9cQb7 z(^HkKR)fnnSh1iS=Qdie+xaXE$Jy<-T`{G)aspuzWV`@c(TB$KKHRtd6dgDk^~E3z zMq;`Z?d+?)YuUl|;o-H>wY%!*raru`4z5QB*YyD{`B6KE(V$Eal~)TmCwyc;1wUW} z+*nE^!K3tmN=lrd9U^JvTE)cqym|j4|NZYLAAj1NFRysy2Kjyxb45J9)gsy3n;hMq zOb?Ihz6c)9(sAi|+!^1tE1kGzo^4Z?Lwo`-vYB0|CdlHh$FMx4@69L$_=)`GKM29P>%cyx$0jeYhsdOlM&(XsH> z(kw94=43Sf<~P4ax!{VmRAf3~LE&B*H#%0PV{gCp?w#9j|DE@#tn3l%*sq_Wej28gN`tu)u|Km@8@?!aNYdVe$EuIB*0j?z?0>P*7 zG-JSnw?+ntAzJL;nM7y9Y#0gI8T0J;WzM%u*LMBNy5{`Tr^#`bRu-3AL9y1dFgo?T zjF@cKLK#^g7Nkr;@n=RqsVIb04X{qvpyonQ>)=j-?AT?q|SX(TY8duH&KQw$$ zD{~dIo=caBI+d3yy$sm}D;60$&-^@M&qOgV)2qZk^Zbd-UPS(r<@9N^tjt!W^+|IY zx<2Kxl|3)6EcCQsb(bqQ)MzsomrO4p2ZddVX6bDYj)2ge(Q*eSO9O0TQb%xJ&BjH# z<0Hq4WqMOii}?7#YPLvKoNzk_&)InT2JkCR}!#nsF0`I)70>u3o@ z-7W{~SwG1K2iI3p>`@&_*{8{_61nv&ke*zQmGVMU!Dlb0FrciP_E?vGo>zg&mYy>D( z5(*C=r$l0iZBa8?Hoz&Tf~(D{nTUr3Pe3uMmru2^rGELmKYrwAXEf5$bmw(Do6Tw| z6Rmu2&WyS6;sPO_YKOA~eiJ0v1&3A!{-Zs?s;;LYb{h49!BXkXxmTlAhd-kgOOsl| zlT80^Ef0s~R=rwrVI?TLMN=!##cDQt_Ux0B(@(VaMFw?ldeid2b)F!Oh$M(D_LeQSBVZOQy6=3!RSAyey@w z7pGUV=m`BIva@`A+46d)VziU#-tFzL zf9>ut%UW1J<>=D7I%{hfEQoov3cvq*|KZIWx9J)*R=%M`^!=A3B3~ZA_Q$U_3PLvX zs?Ht2n@S?!2fVVn_~Kvw>;LuRpZ}OWI_6L2M@M&kUe-d@8~{v%CLWduRzmw*k=~$s zWk4a|CP<1>lgR`>KY#ITzPwVwj%&{@*FnZTzsHp?K*yltqH3?|>XLyOOn_6Bxu_N=TP7UZbOK}%%+_9; zko2rDQDJq?<4ET+PN2w(5CK>QUdIiKI5ce7O;uf<3Xfp%Bb zqM2PDHvGCTW0OF(HA^E_F08zp+y2V=E5|R4Kkm%SrdqRZm9;Hj&M&(Toitqae%{Up z*;ZbRJWI}>t(wy+Wl21kv{GGMJsMTtZ;d=hMpv;k1<5yNQ@F`%GMO^{1twR2fEtdd-~ ze)st7#qskx5{G#K5>p$TZaEuI@=;MFF*IW9T^q-UloC{o@h&S0TG^vxnzr}7O03eX z>suHm6~N^&pc#@sFG|kKvzPPP8HvB5M4Xs+t!UPo%jWt`&ib5^KY-0()sU~SLaOR7 zLuhDTBqEb0JqbLev7DfUgY2WdFJP5K(tO+G%Xuo4EC)%|R#`f#S8R55>Dh~9a2lbf z10GjLqv8@KmLOhB5i`*t0Km3sT_<`7v4v6)5IoGL<`sA$oXkkja67tuF?ew*pFDs1 z{P@}B#r)y@FXr=?Stemoi}UxMzWl*#@d<=18VT2QEUeePj4e4g9tI>Yji1rlOcEKi z3jkuJizLsZq=<9$B3eP2kh|C3{^ma_ci!P5>Fk>1i6{9?b0hdjbFrR3bN0&nYE>`O zG^E+9aWtC0h4_ZI!cAkUK}RL$T`FAyx7NNDQ255J8C(wByY`d)cXz(}_piP2AMEdZ zyWGCJv-Q>S=o{0?*UI7T(fFMZ2CMeUyDJrUX$~)yGLkWP6ZAi?@H(c%Nxy1VXY18@-}a8TAYzfyc-EW1 zNeTJ1wwyYQ9y)zV5KRwTfEi~4R~BHpqw|;j)urR1&`Gkcm$6oD_iAMf9ze8iqLVY= zp8dg3<^3<}(~H)KJ}E+05Q;TbXYouCzm1Jkd2qCI{pNKgla|UaD|DdFnjnmAM`oGl zVRiRbbMs)0CT`|7HdY7|+yr+t?-hE}Gydf-XgOgr0lD{-+6Vp@K^D=QX>ynBV{@x? z8p;hLbC)1RV6;$F>o|&Mm3(||pPn^I%HiaoMk3|6@7?_B8?Q%7bhZiJ(1@vk&~n!G zU>%du-gmzJTf@QRRdfE`fouKpr!S9R_v2ThAW(kbs@~g;RloAa;JW6;gAacG>Cf!T z z@?>$CZoT=R{)dy_`;FV*`sTH-e?9;Do%C?mX3<5rg1n4rber<45lKXm_iz`QSEeZl zy40qOg;=!=+8k;pjsQdJt~%${icg%Xtz1;qRfI@XtHSX#bcdI1x~${I#E{|;uuv<| zz^rAup*@>oM6JH(omVyz1eowQ9fO)sa@=|9Pui*h%TGZ42diebo?ppUPUU0}#ilb? z^IBG%H_}{&?n&z&wEUAb`(PQ~o3B5ytDkl24`$sLXa2Ei?u+$<#=Tr7PuimKQ<2Ob zUR<7ZwanRIV4aiA%$~-sjoS2oC1GB9~8hGdU zxfd(RptlF6cH{m2U?;mczj*SzzU%|kbCl+$E-sD{mG$;k7?fS)6Xrw`i+)oo+B-u9 z5SdR%=?lcd4ML&2wl_Izb8Eo1QfT@t2aJ|rVox4k2~ntcv-HmMt1B=hG2OR2J8?u% z*GSqqB1#g`g)6`j0>@^rx)vc%shEHZpOoMY!C6J~8<`tTicz_JwS4*ffn3f8Os<4p zN|7z+ez|J*CfB#OQ=L|A-^8k4nZX$VzWx#L%{`RaB3P1FG#x)%|+_D`h1RFjGZpZ~z4o%xEfT zL(K`hV~wi>Ff+;+;G|0)6s~E&S>pLsg9qW|$=>xYjs_A!*;SzCk;)L= zgLk+{n&F*@)-*qcKhYl3xFEeXP>m+|Ld1O{n____VZu-{3oCM z;IIGY*|U$q4e#83dwKTp)0aPPyO&u~fOJtZfe`B|^nQiY5Z~qe!?cqkPUlJ9gS%26?FIe5IUMyyhbwq7k9Yd~h= zM8?!dG+U^n%@+cn@U1c}Eh3S$QaB4ra9@>CvEe{iN`@MHc3UGWi+6KFbt{z z7z81wZ}0*NYODlt*s9A9-Ge_Y{WQIM^5en&qF%z!)6s(IR{G1S638P@p--{;X_8Sk9$W-oPdtcK@Belp+>g?j2nr>gttJUm)Yu6VK% z9ZQaZk#)D@qJuO$b?kZ9DBJHcK7`@}VAQs)1^ANhXt&bPf%fIvr4eMI%vF?&MEbP$ zS}--XfzsJ4-i!|A^!oI}C+lakAvls$Zc-S)b-gg6zJva1YGJCYrO5eE&k zpdj(4Mm|j#lu{`hQ=%|$ftA4x>)KWABF+4y+*w|VCl6PSXhtI<1EV>+m?22)O?S74 zThOL`-{HCFENbkE3W`$iTIO&zJY!|T3M7>oP@Dnn=Wlph(K^pKu}a4Edi3bQMQ6{G z0>2iLkDfm}jafO_3BxJn`FRuLBmi+>ay64(+h$oZ940=1sjUFH5Vg2?@Zgg`YG~7{ z?N&QG!*1Fy7+}p%5Hy`r`~7vJCIQT_M=fs6VYA!nu7A z4)zq$5QdN`A8rlg&`?T@Om4jU-O;_T**HU=Y{EO(Y)0~^e#xI|J(sj!; z3-D|2B$c)cAPxOMrVSp6(jzE*-FH*LVxd~IzS2|zZlc`*O9!1^Ub!|*Zr@a8Uc)x{ zOU_<2S1+x36y?uCG)KHvFeIvn*r}+GG%eGQG`JL=Gf`1Ap12754v~73{U#$d-5wuY zyVdsj%NOgb^-Pzn>&j&pKRq@d-d}$BdG*-%OL6= z7zur|ySIJo_U*mB{Z-Y0lm=EOAcHj2%MF?%?cvty?rl3MdXPnWXs~Gl=U1a3U=8$G zH%wx~DPJKuy-(6WG|ka~>l2s453oA=B%UZf0%Cw4=}X}EKzZJr+mxZrY#xDPE&4~F zbT7}n5;=>yy`#Zb-}zdeXU?tQx=KfIw5~I7Sh|?d-~7gJ?(ZGOx}a!6m->=|{GB^~ zB?j)PvyqS>v)-gRjh>v(|LkuD&Fam6_Pe9s`KIJ07kND>x+H5O`Mvw^y?^o$ zpedGhR`;>B$(qU{aR}xjZfzI3o^n)8Cs)>INtYwKAj0rCPGb=zhE?mPU(w=-TqlWR zJL5?)+!E!^HQFiyEGW~6Nu3!dSsZ9|KC+o`F;L#3bu2?@PfVivIMAl+A`UE-YFDKb zADP}PZ0*){mMVDO>Dn*ntDBTMjJpVQM+PvUsjEw7 z`^Z{eDIEr3nWoEZKN@CnRNH2LH6KFt#JW!F70uPS!sUB|Vj!fyu+54IbWj_a3v16f zyHNHy>z;=B)8pkc)6IohiRFpEe8#G)po4OqVC(Mn!`reMUp`IOb1l=>WiJvd7t3}A zY)Oi(tSx2e8fW;D@=RC^ZqW5$jsV^eWbb4PLEE@yZQ9lX=f_eNU5k&%v^+c5-7C}G z2cKOmmpy@23KKAORjn={jiUX7ILS9!kESOy0-ot8Z4E$&FpKEPRA|kNN_nz8)@c-j zg3w;O2)@p*2gO8+`1s_ks!Z@O1fHg_yY=eA$#^vy`8+KVgMh7@{d$zCdrtENVYBxv z$SU`ENGdZH!KG)SPqRev#1ez`lPze^ezEQzKSH~9nC#+m)jK;s%aUZ4mAV{&Ot+@* zXi%U+f79~1S)DjVi3t-gfZ_ajf5(J z>fV5KIjWYXSk>ic=gG&P)E|8C@cw5XfAPiVpMUzr`PpJ;ds~C)y7^-E*fi&Y>W~HW zPw(osTlc1+aUwb^2n%JEg_L?Mp-tl8LN4YqNpw0$qLdr4fE8rp{hMF^!~EzgfyH1a z5pO;3dP^M4xt^hWMONl{F#T$E8Nx-L^+~)La|^ymvP|(#L!s!QGcm72!9)G@AgO4uGFT&}9eg1I$*%!_6MYL$Mm61J9bXjJD zHFyVjsP7q7?4#w&F8Iy{OQyrao!9T&x^pMbOWI4wQ*9W^$%hp?-2qaf=GwvPwLATQ zQ?3~eY!KoSEkcwhvOziEfbUoFeltUZ1NMn0fyWGTu(^j%|{GQ7b=yursEectB*eq&J{_S-oCrLDfoehyoNh$mV>b#6l6n~@@({*zwtZU zTYK;oY6o5VRg;KBf*l2>Ul8jSsvs7ZX~Fba>t>^90^9P;pmZNJ3uLCntuJMXm$6w!Vyvs!be9Xh>Y|a7+fF1aZP!k%MYN8>CFkdiov`MMruuxHzQ2;6x#*EF zA6fSy;}3ZB(CDW&`Y4u9f;jKCpxUqI?Rjl#CZjZIx{8UVix%_ay==ahAS7gSch%Qh z!Dn4Bs@l=+XE9F(EE%&lwIS_A!JUX{`YJNkHwKsD1WZ5n}(yo!93=uAs{R6v)~UU4*n(gEpc#DuD8b-oR8t|4jx zl}{fvvonCF)={gXuB)@QT_&;G-kz3u0`x;D5*(4i#5zaV>Rpq7NF>9+BJ1r&`B`Q` z-<0Ns66v~K^T_67rIX3S`}O4+0*ujV({;|7$!hT+Nz=)6ROEPOpcS4jEmD{T)#Zcz z5j734K>~4vZkZ$gS`U&IB3O`$@$SKhxchqTpFh3QvGTNNRtY{_EugH|c@YnWuq>cB z1F;FTU0uc{B?{r38iXf)6)%J$WeclH!SEu451({(2X>NX+S=~?V%0V@7yzV46uVk3 zK706Sls=gp^n~T8qZt^g?k0)m)mrv4N(O11mck6& zS~k`E#ODXY?Oi2#Tb;o%On0_e9qXLQP;6?9;-OQnF5Ljv5yxG0plmd9gPx%;e3XVp z8~}&VVp!yFm-&sRi{AVB$SN;t*qj0(=4N#PLycnEa>7Mq`7Q14 z1~R}z(=}O^yngTA?(V*0n;rO+N@eN73Nj$bylX+KtJkls-nd=CCn%6_!a5rA3Rz!; zc6ya^fQf+62nS7t)4(wiO(3(10A-*WFlqdGqZ7#%=#^i71aHSj63Pkz+=19AN8@Fl zEiW%V{?uPKaXFscySI1u_MOhwLAEkzKm~}Ig$)tckdyJw*Wdk(vKWEcY{_HjNqFQlID4cR~b`v3T!hE-es=3DCT|E`x4 z=`u?yd7TRR+4ui^{@~+$U6%`!p0#mL)E%))1M54m3>n2GWr@I;0nJ&A7XhvaF;EjA zJAgBuB*8A%Rn@HEtKpCS*+2d6fBj$H{QW=Ne&=iUJKv1|-n;fIH}1>Tk53-9&^@hZ z9a~3hp@J4Ji9(Vv)Vpbi_c

opT5(z~5&8dE{R4f1lB<&g(z!SjX2 zg~ke9hp-2$VF@S;0ueV%*1`L(p{nf(LIA+a0=^Mz+wHB%<)yhiGl(nVflse@nZ^Z1f_f&xBqmKz$Ec30W*f z4jTdeWTK8Uoh12uzOGx=)V}X2+SD{+0hAYMs`3JX4)MW)oq%ae-O)rnyk(R9ia-ZC zf-hPLjNYOOA3XHnw+JnDM)Mb@?fa_Y%Q<)j+Jhj_o?l%G*%hTO1_+vPxWv2IdW6DC z$b@$M3Fsvf!?ceAT^dcLRb}v0Dr%vm$93V!Fa#^ARd#k_6xXir>s5bwesOaCJken| zl+y`UVlMeg2xD-4x7oZo^i?}=yM`;3q#51;CBiJaTyokRk;FG#Bv7shZ_p#O<6M$& zzY`6#P*<)x~`E>@l9iq3NlrO_qT< z8K6uERM&hI-%Ih-g$bdB+4R=HfZ{9z%JhA=vpaq5?(1ba=zF{XL*Ec*4&PJ3rM5Bq zW&7?ecT_AOx(EOXs?i|W5{>}*hfmR~G%bUlDd6J=m<3I?;di_hPYCbdFi)5UI0n6E z^BHvuNfKN)lHbe+WfQg*u4uzQ_%HtX12yHvZTc3L!$x1=o>S!r^)z*37!zkVc zDQc@F#Mo*%y30Zbo^eGD+JS~W$U%H7Wci`MVy00WOC>_4*lMBStZtI{ra@(7HxOc70O$0O-n+Q!r3n#$*>zJMc5dChk!|&> z_Tu3e^S<6yahVRfy7E`2fbn#@OomY?^eXfLLYUTe*W6hjMJ9z9mIIaGSLJLhf`t;!mB_fY0fynfs<}t{vsu!?Gb@ST6{A~X6ac@>zWjSihBQ3V)^R923 zd=SckQ4z$ebVd*2jCh$eIE{=*VG^ZgzB5bE5A?i}2?8o82qp5`CCn=?a>mj}4_D3% zg^ZbK!87LPY2S7__M;I?Q_!p$(2NLcJ=Nv|C7~!na7|<66i^}r3oV!hZRn}(k%($= zMW}Cx|N@h{Te#^PV$#EM9<3czqi#Rq$U#|1_K3#tH>GAR7&t@l| zJvsk8)srIGvAvgZ%R&DrUA$+$7!G%8D50w-lv}Elru~_V9B0x^NDL%N6zhfnM~*_o zx4JD|#w_V`=|?h7c?Nq-xMEN1a3M0C4*RP9K#C@c)7GyA16?pudGu|T`#9-!)JoYX zk%14;tjuOlL8XF-7`RT67dqBOa;sVuI%$WK^Lt;pb?5dsrT@n9@$u>DQyDdk)zBQ< zqv4x(-u#dL@qYtSGP|UqWtfW6DW&Ox%UJLeb9CeA_1EuZSF{E&%@#E*WY|&3#K(|<}i@Rk362I@BlY7 zXS%ib`rWVGxPA}4_3DiO9~6Xs`SSQXaQtc%1dbdh#)a8pcJ0RD{=qi%)O2eyoR0W> zefV%bVd}*IqP5!z@oC8~uU75D*<^|?7K;t$T6XD=>~FCMSL6Uikpw&S~Tmz-qZ%T7Fq~ zmrdnU1?j;ZOQE>UW?Yx#ihQ-=aI+#4aOWZ&MsM7{^`HGwbnO<8@*V;p!rz;d=O2Ig z-j5c?7e%Y`)Aguz5Pl*!<-m6kIcNf&YF)SxhlIvdIM-bmvpCj3I2mO+1So6veARZX zP_29Y*3obMXaD5u|L6b9z3=|k(YxO|{K_{c-}`DrF?Hi22H?jnHRJR`SOL+WhwW^zV_5E7?`j5Mg#3<<;(;+!w4t;KqnxKWct z$KKBD3i`~2@?7XoW%xL+Kdi#Xw*T3>`SGlNZ`r?J$&ZZspz$AeR}U}Ok4~fev*~lu zK6A~5lWQ5<<=odLPx3B0s}?M&4hK30$+T@9nDtp42DNFPwJ&PX4)bvs=_t)vDm&d) zs%>;rhxMXeXLy9#T{V}xyJMUnRNe8D$89$o6bN{Y;k;@*YyIvhnQY~Ki1lV%OVhws75Yr`RWIG545&?|ija2e1b`o#s2W7TeUY(zwHp>y` zrB_dtm{to8jx*j}m*d_xin}7qQk7gVADcGyUQ&ORU}S)7g}5z58^_@Dy^KSYAhhS+ zWnjx$I`FLXE?&(jL5J2Ox9}D}yEMkIauTMy!nDf>gf%2WQ`Ty4LFF6DWuc(DS(GFw zr=bsBl*lxp`euE<_PmW0h_QF3Z!6w5vZEvszpj^;=kCR`7hSu2=PNe@Thnfk)^!b7 zWz||JehPSC9>(+=c?{NqU`gWJ8ocPdgG(#QcmV+ypiSHNKh_UFSbp*8FCKjM$wwcZ zeebXT?D5l|fqC4%{Z%eO!$OZ3$3W2-I=n2wdd0Kn51hZ$F~FwoXog`k2ms)UhOtN` z1HTWk$h>ADHzILy#PGO8+^MAM63|5rCLGK%N_iKSoxe<@7@Z$z*oj3nZ$#NYa9Pe` zIPFH=5C_@JQ4#e7q0%&!c$={SabGfmT=8sgd;0zNe)6-QKA){F%dy+tdgJ%M`-gw{ zhkx&n{?UK=`+xY`pMC!E=MNs79AD*SflE;$sbe12BmL`lZ*A{RBe0&nb+k-3a2;X? z6%oxto5uCqTkOuHkCN468vKm6za`PYBvclqsG!?)g2Z@#8qJE$}E*^4I-lh)z020{V1 zL%INj$y25Xlrj~SaI`5nFarTqWJwI_2SMT4x^7mU)+7M-VrZ1rqFyZzTALfCRy|uc zq3uFf7aBTJDbOp(N=j!CR#Mqz$QtPLoDwfcAStR-n(#Prg3}y+Yw%w~J3b_c5{rJ( z^-I~h3%+{BNoqSR@Y&91uHmFyay zWMDIS->sXb!bkAPi&EqTjr4DpflKRK?`w32hT=wup{Wy6%cNi_l+c0_T3$&57?F^+ z7$|Sm@iSAeq>duz*LZyicdYw7cRPDNN!#FLvr;mz6Xd z1gqRk&~!c+JV1&XAoqP#RZ+bLv7lY@*DE)lUA1j98RWO_Y{_V4Ol#rdl*a)#Ln~>6 z=&p0t;8L(elJ&R~9OxK|e6V)7Ei4Umjp?%!@%)Kz)}Ykh*wy9L^8EZ*MD1H|zs(Wg z6}qLxT?3eC+XV&R)J=1-ZXUp*xd&08#K=JVo1}4+5q@#n&4kvh2!?o#SgjP~gO3uB z6b?zlBbrKaqGO`s5`MOsFP4&4Ao-vqG+0b~A`|gIx6mL6O^pEvHpS;@rVvae9!6qM z$O2Ez`xNpAkRf&d?B&U4pL}+H8j@u1&g=WPUfUfG4z---L-`kf`EMQ~jGMYB;OG?p z(MPb>yhv}oc58ckTL{&g&1x%ZGi?t8;sv`Nr}plSI2>A~)*S4NP#Q)`l!1C>1AiL? zq#=>bOPlcqnsQ;ktZ9N4)64jU4tmq(jr6vE`+f5|RgnSz!5PsdFb3Q#CE(fq#nbBH z6Fxn7eee1hW&r!$it%tUu^b6r`2f#otZQOYfqZK=%Bv(HDr30jM5U;clpJ0U~ziqnjVas zs*5zJG}$(Bb1IrG8Yz;~r|SRtzX{t^(tXyf{`}(P{%YBr&8n9t_fMX`IDQ%xdfSVg z7wht>H!?KZ`N&5$Zk(%>IuB+MjORgFTPlD=Lc7|AVySry#+)%A&687uH<%eP_+YvckAd`&*-fV!V~c zc^oAvI@DMQHz?>3QZI0K!f6SvMQG}2Bm9D*F>QluBg$%lpv{HcPqQw#YD009P7r3! z%yNd?So5Kk6P0f>ovnF%C1o2yOm*6hMG;G$3!Q9IL%{j)4H9{$-kL6xv`)JfPtX0` zsvL&+(ydNHXA%x6nFg_H1#Q#Yn}UZD_r4hLg*4TItxa^5sd*meEV^pk^Ugi*{jqcB zEL=r$ohEg@x)Qchp$T@mI-CrPB5l2Tem1+byCQFBdBvBG8S_pVR!7@veDmQlxj#b|{Eg4sZ+X=fJz`?_z&lR=iJw&Sx?*Ue(|rHt{Y*z8hN zl`BVlxmVal#C693Y&t=fDKdV!beCdqkA?z1S7RfR&i#gI|bsx)rC7h z>9oo{?}_28+2SgWWU_yxMx%g+b2pO83Dt68;D!_=scvQu?F}T4V4n!70yG1SqYa2W z9=To&h7?K`vwnV|n@WhNR+>tN_jTU4yvY0URv&5J)cmMx;g|B0>?0&>zre{R>4XLK1}tksyZ}ii9IEz!(gA z+E!O}`KnvjyJNRoHm#m_otg$nQJ)(9WxCegcb{$6&Xp_kHP4gz=9`jfpcznG+JzT& zhdTnz1?u*p!-Z&4YK-Q<#fU&av;f7Vo6K@4%XTZ)o6xo$sDG|@t%cBZb<@A}^5tsU z!b{d08{w7+f>7`y&9}jMQfw<^ANcQ+gSh#4kk^ao!#?uhZN56moSov^EC+7m+f840 zXFxn(`r@xrFav9}n2fX<+C3@c-PtHiU!I6(vwOdXDKHq3dBR3OVbPd7F3D0 zkf2a31_jf(OvM1q;JI_L_N-MIg?a?qkBL+#cs4k6zRU{XLmJ?swK22-00SJ66!#Me zYS0|W0cY1)DuFq@r~J86)l#2NC;r}p_dkADbj{)Q7s}Q4=*c638M_DU5C8C=KYDy$ zOP*(HYz^M^9cp^z%B7b-^U`d-u;4m2jI0XK2iGK#PO-hdn*c%ft5&go9I_zeiU$OP zfW+wCX>*nn~H0S7+EfhT%{qUm>dkaeIB#*fF>7oR|?3CGZ)T}i>HkO$yi zo>r^y;IWzR-JI?LVK^E`L7PT33>3lx$rs$b_`(;z@VT$y3uwf6$xjN$@zdA;?uVZq ze_4;834*{KgW^mllj~Qmee~hS+ig9@Qww-3AONvDAtH8C=MC65#X^hT`a*W~dVA+# zrL+B4UW(Hx9C-tV61fIs(6Ah|qip{19ri!`F=x&eDoiWBzn{PKTsfW3R6eh&#qPYE zltn%4Jgm!2PjkjP0m!&s!Kj$|EW(wJjDvLpsB=}7sA_Po8Cp~jmI7pmY^a9k^eodS zH+MhS%a3|%Pqxj_*Y5cA`0+G&ma_g=^t{c`g(x z4c85BJ1Q*hi5MQ7OexKt7kbn1#pFwW_dneG!j~nVP}m}wy|g@i^8FwG*_|gJgT~4} z?ypd0(rlRN=of{K8KWa8>TkrPqrN#b>-+1-Q zzx_K`zVb`EU-;bO<(GDEJTuwdT{rEvA6!+!W`JzsHoz-sf02Ny@(gX2QA{0ec-yzk z4kc#`tq1s>KGcjg!Q}$}FuJ^oVKT4%UP=djz1#UbX0$Xj7gYuR=sE$I0VdpUGq=rr zS216S+)kzpm?U>vmNL6)3X@Bhhpn{dF|K`_n!ME0Wy97rU=Q1`7L%Igt8Hp}Whe7y zH#-&X(PsOTXIr{%q<)FcPthno*Dth(?rYk^sFZ_2zI z+7MUMB3zvpdGF6YzI!~(xM{K}IJ*FOK!(5AEOi{R=|t@9rb!j+^%78EKHEV_eduKl z2W3r_F*GTfUcqg1V-%2uCb|jiF0E~)@jJT{z|PaBw%rtr_hnhZuWwc~R4`xY=@jlC zxMYNj5D2(DT6F`#i&~Q_BA0>g06-?73O5)4R%qKu)&Ua1)6;GT^i=xb6 z7MjMc&fy`anVFkR!Yn*~bZT<(%(Juo{nB~cv}cSDA$HymG@ciN`?YomhoA}32776qCTnxuMhW=DTd=? z_U`-Zlhf0;-ny;j>|5V{&BwDp{^NhOIy=jOXHg}pkr@5AcAAx+F#wV@V0tmsabd2hG8Zrcw|0R!#uE~3Wu(|*;NlT~T)+-8 zk>gLPNdPp)IUV}Z_!XHsf)_M0iywhB(P#!b62b{Y`|xp=%q{`+9VM{7wlFBgCV&lfMoyB@Fi>G7BP_?aMx4>mJ7#0E0?!t>8Pdi>{V3vjJ=xlRwyXT@~-#m_w9zT;_bC2w6USkHU& zaa7LmeZTl#qQoNv?%v{;Uz7`j5dp*fP3MzF<73# z9!Plc9N+ZAIPOT+1tYhd1DWD7Gu+TE%tp_rR<0!0x z-a(gjW7XgmpL_YGzw^81xfd94R?Yy*U|qV$ci;FI|76zI2kUP4csprAA*7)lEP<1B zF|7=c0qnhXOzT9c%~`=!j+-1hfCxB-MONie_tCY!(W}j8uRZ^pf9LPK_MiRlE`9aY z-LHJ9`s$a=7e1dq`^<-@r$->eS@3wWX&Pvg7~m!pj%veo!I{7r0A{J+%{a=#f|p9p zyx6kv;c(WuZpzG#-qGH~?WVBXYIQt?3sI^8v$KA`k8?g311uWIajsM;nW6EPpqFVy zqvHT?I++q)(b?F|GU2paTmGcBus6HfguqwUt-Ev(CYRlC&9$OcgI&Zyr)3?EHfCK` z&1BwAXU#0%l=|GrV=j((xU*{CZ^V65otSv1wjXcYeW#96cGA@YjJ+%;aL?gv+qDgY z@4l9$Jn-BF-T-rPOY2bje%m_kax*Qn9mA%XoEbF&shf=T^iaFSOMt`DGds~DhAiL zrr778$N><2JDC7y7#^#~_r3SM)@4RJLpSxd2EsPLR+m+toe|NewYNEJx|Ea)SSbVX zhSveMpcxbaj|qbwgiI>0y;HH@HCpT*pnuKTv8XqqZGD!(Yo_(8Z?ARtN%FY=r+jb#PEOjsWC^;rSe!lmu) zX0z>{JUzQ~>EP0(>2%KO=G29)4;!gsQ5e7&VCvvE#8Nn=Xk`~8AcRNo26l$BFr%xg zi7YA($awsC*er|4aV@)Axw^Aw=Z{``=?nY2*SfCFGg@~;Ym6zdpxm8btNSMdzs-DS z4A%yr4OC^&MnLk(4FjwY@KJE&iDfY=TAZA?g~6cllH57ocTjX1SwhtSN{2pew?GAG zKsBkdECc88Bk>^jO(|MF@!#;GDE7J-AqbZ%At8@|K9N&0+s*Z7(7)mC$4~Fx2{J8y z`?r7nw}0ogAHV*+AN}Y@eb-k-Md?S0H6-WJR{EuvU%GPjGUKxCdWs3ADI~}ltzve4 zH<#O&u7qp5R`U)zMeD@~P*5fC0)IZK5vmB_K(7G+*cjMMUvdp9H2wf}Cjc@64Z=X5 z6f*v&Z}A?lfM`)MS}YDxqYMN19>xzQAbapQ?_3oGVL`|Ys*1B9y@_JX?Mp9w{tKV~ z>ZIBoYlK@M$cBRH+`l-eJ{On!^!Q7C{7evJv_23#2EGNL5I}1B?(xG1F;mkFgqzpQ z6_cufwOnnP_iU$FfXe$J;eL>OjS+6lY+Cn??FjK>s$sNPx&;t_XQI)2LX}-@PTt+U0|d^ zxN@2zaI|;!Kv7~GNS@t|!@GTb)}U%}GxXczM~_ZVmC8-;{6m+PUCDV^a^SOT?RFy*%>m-in+LSE%*jdP9@CzD__ih?KQu<$3eeAOu0AAo!ox! zjX(M4msyye)zzx29Q+1FxWaw_k|m=(C#qNg5)_7(T5>+2%`#!4lgtzVkoK~SqNt?s zy+7Std+Ft0`#XQHc;yR#TD>m%thDp;cE9}BAG~?HUM^7ge#kmMx4fWz9}>)9xKX%Jy*X>ww=u~d)Hndl-@9*wT^XU|gxan-xg`E|g zmWYFwkykRCCQXY;8qd(GJ2ux`GjC{Bt=|qPpx>ow3X!p_wsG6k##yu)ELQ78{3%yQ*Obu(+gFQ~}DGN`SdpNZBoBpU}%b`0- z_FU;S_rNRghdfO8COZfD+53ER()c!&C8#`i9qTqB1#@X9%qP1EPW61rlhm|FnkS|S zaRCh{Up}tqlz4&Nn@ zq#FbvFpWr1xFM}(AN+u#vn+>Gg7*Mope!S3Bh!U`mW#^RLD5jNOTu20uo5mj}UJfey5NTNDOxMr)CM>=sW^e|>{m2dszoq2WRx$Cd&T_*S6^&tb?P_EvhN{5qD z_5P?^KP5M(@DndZG=`?hM!)(~o?=qEh_j&%OA!iDq)@s+^&J`?*P;2PTu;tdZM|)a zqF5|uc>&<$G}?$pKFBensL?>8X0+u{;?MASKt5frID;I*zuO&9j1lQG)ICFbj)=otHlI(qumM0o;mWkIB3M?r>uR zpnrR{>|Q!_yR(`zE25@lSU3n45jG;+Ku(?fI{l~74KiIg=;jG3T*QG=?aQ6t7VNl`?`8+P(sx0sp{`(9QsY63mu{5Pg{9R6kV&v_Yu>(_{`dzW)moJ( zpSxPF&vMUeUTlFmXt#5aj}j)NQxrd<+W`*KDUng|7p|FT3LKaNDne84oDEilWMKU% zdl>w1poll?3WDd9p*3a&J2!R8`$ehthRg3Q{ZZ5;Px}A1&80K zDa`~QGTN<@@?<9$`~bzwl*voUq!<{W5Dn)8izT_<+j)O3A8@-qJzG9~*dL#sKYsYZ z?YHjTefLlay=;Yz86cOEgAgrC>*TgW4{{Eor#MKifgMsb9Rqg*LY@n*I`3$Gr4X~y zR80emaru|O{rSK3x6)z(e1wbR{yNrw|Ht3Cd-r|s>VvvZ4IqdsX*6BX;tblBMCULA z)&Z`8j*iJU;bsH)^Ns{X#SKT8I@omC#;k8M-CuhCnQ#Bcf9r+c`kl!uU(q*T%x*k0 zxwIEE{YY*5Jc99ODpD{XMaNK9QmwR!0{oxIU$Ta&N>;fji>$m3Bqh@MFm!#Nl#hU- zOtbUz+`z3*vcPn(0sw(FGo}0&V9anAJ_QRRi`o+JM7>i!nS-M8vt{bmWhF(UKu`=OV%q2Rv7 zj4M@A8i>%trc?N6lKlYG;6d?=s-STSAO;|i1mU5eTg7+C*{44E-sAx&rSFHfD?sFx z5_zTjVY8+M_CSBPg&FIxi|3 zX96B^gHPwm0EN&P5-bkRVdxtgu*9KI8H$Caz5kpPdGNAtMYrL7!@D;6kzz2OH8pgU zO?Rpppq-A?2tXj8jDnE!L?ex`jFJQ;wom)hN{hRON^r_u+cOICc0$%W^L{Ze-urP| zWmjJPrC+M1@(=z$f6#Y5ZkURsu#GUdF3Z)8XP>$G+)ZeV^&V}n2z%19<(Tw9Yp>jM zQ}_ISTNYc?U#6TW(gj`^;lucfPy{`X2N}XKriXeJ-=b?j`C|N!cl0s+!C(4}3LtoR zfk+~55a1*ZG(`glLL)LTDvs;f-TUhJ9Mv9j3hRYpTL__`7LY|YfA!0+UBC7`UQ^j) z#RvyMjm85n=&BdreR}+5KYk_%!iE4O4gKrE$doLzY*v=tX8ZWzeF$7Rq)h1J+}0&u z6q%|!bG&I>f0z|;Ay1UoL#W?>FrQWBjhE}iT*5!ZWPK~&_&EOQ>o6L8vI9%y+(vfG z9Z$Q@o=zuyB?B;lFpUqbj?*G5YTD5yOibB!sx;u*;I|Yu5n?V4%A|eSLeS&NLf{}s zI>qg^RD%66Nzx-v|1KQB4nTy zcd%G^2s3=Lm1Gbw`A|xs!F_2oM1t38PW!LD({2CD`|p0|-be4e`Q`^ddgI}Tx8HmB zom)?D_1*GH(&br~_s~OW1sfFaWU7O0`!0Bz)rW3^Zpgtw%jptCObw?Y7jInR870*; ztBqOgUizKiI{1xW@0HE~KZazSP5tK2{_wxI#}6mASu6)Y5HO}(YH;fysqbVarvOQ` zJP*G~HUJI`@HQjQZ z8o1y1q3&d4g~_WThqoL0fJWjX=WJ^VX~QPZCxT5A-=!a^>(;8--4Sm=l1Z$R!lTDCPxTcJzxRKLJ;Cw9rSWq5zud z@Bo}Hs%c(AFjq%M4akTMMcZ$8clXYY>h1ajIPJzW`$eft7T{>T6}hgYq^PnGfJ->p z6cj%mqhm}`l^)~fR!Rz9#(;d9dQ}pYysdxVJ()8jAw@iRdXH>Tf%%qdRWM3U5KefimE zPw(A_?K!iZfUB8Jn_=6*w^e3$8LLgd&I9GwEM?5a;lt+Xd$;(dgTqEo6FBZ+!WTUe3m3{VZB`d z0RQw!L_t)@b#~t9<+@L;mh&Omfzgh9G8*Nj@w7Er1~7p8r%k0e9PgGBk=u!?vo%bV zFhwZL8@l^mSl@nhYHux<_qHG0|M;Wh+iiQkr}L@fyPceF2_1E4O|)d>1CK+g1uSGc z6sRvHO7N6so?>a4cMjG-MiDi$%JH++WX-O8=}Y2wIT;6FBX$oU9Xp? z=g(ZZ{)ON8jhDXmD{@MP)kY9Xcmd?gwPR|Z3^oCXk3nPHk1 zXXpgjmiM?V&Nl39KDa$50Y>iGb=~%=Pq=nfT<&ALT|JpQcG;JC9r8ZtE=I2_bZv5r zOl3ae+Ouo|YM+;7A)|6FcbyGT$mU}<5V`{d5y`Rl%3H|NLO6pYe5_|?#z z4R*+i1=mxarTIZ~Fx&4tapz9jt`}uB(Zwpd^KR{JyK`gT%w`?BjW!>^okd?KZsC(0 zQ`XK(#j{|Oud;;+GnS?vjl%}=J3-l=Hrl;V zlc&Bq%qUh#E$XIybo}w<8;93!PBZNi;I=g}SafZk?`E1}P|;^@Uh+dMTz zo@)W>u?1vRY?pJte`Ry$1J-Q10cIvI40JDslgFoh+x*hEzgCuWp)}Zs3w>_TBreN# zjM&}uw_H3z;eh&NvE;x?H~W;wy{2ne_uM5CVZ613ctg zPm8W6g>PQDR3A>4OyHil0T+XzB_B^?6u=F52J|3&1lvs`cLXv}SpXEg!AFszSjMr5 z(U#*GC*ligs0)08|5V^OVnjcxg~SaOeb^>tmDIFFG$nOi+`ir4xmyo0<`WHzNy+R5 z1f*t3z3|)@UwH0wMKPsfX>Vr=^r2VdK^GaH|J@g#9)F3CpKT)MFEA_)8a0K`j>o~3 zs~_C@*mpLg9FsP$N(zkfd_OVK^clc2*dgRt11aQw+vWFbRTlYYu2F8AfBgpgqaVn# zGZ-AHK!B51usS58P$3<~u49w7e`-?n?D`h?gWuhQg2ZRnvR$7GcvAqOtb}<0VOC>c zdq(R^7~lwqhmj(uoEl)zfh#}k8ovwX&K4^>*@RA~lU=^jS=D;eg*F$>O!YdszRQl= zZt#iHqK*R{;7+-L3kM~U9#y5mX;NN%1xEv)z*7+;!G^&>2m9Rxf97g-v42R}l1fk(lu*Mft z=b)!bEf06@?@#ZCemGgR-WnIf)2EMazx(D#KTg)|)a<#(p>RxU)0O&MvsD;681T*} zp`#u*DjgeHaoUs<78z|sp?5GHKA?XJ+`VRB|=WjNHHX?gu~q zHzyCC>_%CwJG1SD8x$?(8DJy}8WIW#-&3_MX+}!LO-Lq(bL-wq(8r`e~X=1KXW167bfO zWwEl=HXoKzK90NZvFaVEJ}lYW#=Nfi+j;)M)Vw$4@6E(V6Y;*0A8~Ulm+Kv|)S>O` z;iySVIJ%rsX1KGJYb+#jx}VWjzdg`m8bN6tXfLy5i>WT=j7;47~h$ztB)UAb8urJ0&MyFZytgiXDd@Ul#@0Ya@9<))>j_Y~1W z^D&teSxegzF|Vd(rjv}+v$P}NrQPSY=W2ao+GV#p7u?mNEB*4?{l_2Od@kR=+~*nV z`qSyWPqK!6$TJPM2igHJ4!I`BDdFy=Ds({qN@g;eUI7xpx9A1QcGuhP5E4_TGiGv{e;!vhNkAIf(*@@MH;_f7A;59zFJ+ly zG!_Ca8I_j&x8(xjWVwFKVjBm*5nIfQZ8QDJTbn=o^EWn|N14nhREUs+8g~SA&)&TB z(#tQFRoPiuZ3`NdD2gbdTo>^yck6v~16;JRc#2sY3GI0VE2 z7;<62saj-U@g?dxSfP)55C>~@ya0-4ve^Kao4ghF@jtb*~aGFA;IW(WbL zv>ZZ%=gID#;Ogw*6TjJ#<0Q|VN!s9)P4kK`*Rdb=vJxhBsr|Hf<^7d|&HD1Q*+lU_ z`(gX$o4S%Lc*=YOA0QdbDtAc_q4IH$hJ)Er0l}9$gK7%BEQFy9pIK`AsTbuC!8s^{ zK}?i1j7C_a6A2JRS`V}#C`Bp=Pi$2y$2AJFwPG_AgAJMRReB=TWMf^3>p~LIEVG15 z))6)dei=7JGt4lQl$R$em`fih9TAM$IO>`Wa9Ob}Sk(vII_>I>Rxw2}-_I`}%4ZG^ zXNzh+&31QY^Tj?ZW?MLb9(14=i3TQ6l@zcc-clNcajKgZ{J}uO z;lXagVA{+)F#O-FPyXngpS<(E?|=BlTR(pDjUWH;d+*(Od)cjT^y*5Z7Ec>xw9j;F zq}2kJs~y}HWr8=+SS`#yu^u8#oaU+W3{Dug8<>I<5_?^k=xpaR&wl0~{2tpmq@DGN zK?OAAPk#8Pci#PBT($c_=bJ7ygQjpu$i<*&lQ4=~q!maZ<-nD+Lk|_+4DEeOE2zz^K1Fly&pfh(`p7>gUZt= zGMHy(0x?XQcSCEVBTyhnDKR?9bDV9kY3xHrd69RYx%J5 zd~~`UCQOv%gJ>$>CKq5Kol}ZN=BddE4x?2-b3vc^t|})g0|Hptws#gDLDPhyZg}9E zVX;j+vP9$Rtz87ubM0y;8zEMlpQ&=0muDG&;@!E^jY(@ZoOEv0#^u(Y0d@4*$I6_w zygRG=<1+^+Fi~<69c!6;y0kJBmxL(7rVr$m3ag7D4>s0a15BDrP7Z+v>=TEOXXEk@ znMs|?TmL zO}0`w@Ql6%)<8?qI%$dqA+-gLlmtg83kj}DnP+iNAy`OWk>}Id&bDbbja;q(L=QBO zGlZ-Uw{E@n{Eg?XT)J9LtKezQ1?oq1o&%O$;i=oUw?kNKisXXW0LeqSG`ba!F@+GY zBqg+owrsYx-a4pymeD{AVNA$H=4LzjWUliPV3uOnA$78J{th zQIzWF?>WSV4-9<>NXH+c*=P|R>s#-B_`}T~{j0}szWG3+^$6PG~oi2 zc=37kL)!zsXxt3V(t>75J|tYgUzwi2aOn(;$vfJPBIu0_CG0YpWqP160vC7?X&Glh z@EJ5{gdkKoLL>xDM%Y0R1s5Une(@nG)W1E4&wuFhO^MA-p$by4Rbm04If^0eOL20p+Adyr*;h4cEnW8Un2Y)5Xfr+9~vx+O+L@^~G;}?brX_-=Dnj zImRZ7>E-g^vRmxlm+SA`ekbH&wSmVUN|ZZsS?!W4UJ^SNu9ahxeEP3rTItBstt z5Wmd%RM)m$_UY95$F@HTekId-hi{6oGJb7huPB>?v(Y*gb`NHHQl+!a@c0bSA?1-x zTcsw&c71AHTNUzPTGA>Y3OWJ+64o+EJ&-uh072k;0hE2RjViTMu}$!X9&H7`XcXkf z?(TYMa=lEC?{@-CQzVf$DwzBC&*7Y|-^?yu%Ig&*a8D*3%$6Al3j7@)KV%!NO#-P> zEKOEI>ENurCnTk5XfT`DY%;*SJbfINXYhimEI35#=;_0!$4_4R%=0&H-f+%>vBUbn z4!BgqLFNFZNo>3Kyg$$64nPp0VyGjG4V?)EgJUEo3kiinKz5}zS)qyvJ*ugh?eN|G z>3oNVQ$gkxG-14D#dGrAlReN zYqQqy9vBVQi9@+OHQ^YB0(GS8!{yV$EOPwx4NL)y$M}Z61@gdyS^mM9F1~24r;g;00I2hi6$I5@qg$p%Yf6&v{;&NqTU^y%i81bFyIp_p$=h$g^Hu@=_~cZcHT$9{As`Mt zn*gUWn!^I>p@!1JYzj5tz zU%dLYFXuO|o2&aLp*pUSF2?^oYp}^ zadU6JfLH|8(GCHf9ei&AkUieXJkjEsjH1qURVJkXY=AOLMd7`a`bMg%v_;k?s~_BA zakwJj?9BjYM9~#>0^+;=%pBV3+HDTK-l6?+$+JRULXwfdLGVxNdSHIw-V@9qD;|55wS+XE2M z{vJ?}fy|Q-Q4-X6_4?)KUwCFdFFnn_NMH<5E9kvafM>99vt4s~bJ6d@Zl)&kbEt6S zS5&eiDi*6{U6FJL|PEXDs9&s0yR;^|hL})h8LGoS52gjC6SHi?c zS(SWAOJ=g*r!?bhVgUf)Xl;uSG|f(qQOG1J|J~B3$&0qcB{$2UiFEKqcp3@o$6(!oRA6!{EuLqAdD~fVv%4`TlGxTcMo0T)qUV8OQfAjzRf4cgczk2z# zZ%tqOrM=(y<-@Ok;Vh3ExE{p>yx@8$2C(-G;y2E`6S)WLcGIN96FlaJH_D*=9RG?Ml?PcjQL58=#;4sDU|{GBY&+W*L*~3EEOVC4hCx zNS0SX$Xb-Ni=7{M+(I2{(08Y%!|qg;-QZ5!kg>h1VQ05@xohj*!L{i&)0;e7=lMDl zPq{vphi9%hP5hyc_xgC(+mHI@t)cnJu(|h`e|*kw5AK2Pwi-yGm2EBi!ZNRBt6otK z6(x3!FmPag7?ztfjJvgxV;)5GrQm?|vV??k8Z}g+C}gp-)9Q(OKU1&E1E$^CEloD__mbg#0DhCn)(&bbv11yG zy}Erj%d}DDNaLZXz?kr<=xV?VT5sZ9=UoR0&azMxDa*ad@S2bK!wcHgfTG}_qBML$ z^GCFX2z4J}$AqPMVik-4MTc-$E7V}_`7i$k+;&{-&vzEy z_VC<6X$s}B-aY@q%@<#KHY;=(N9CNO88*m@)*5itx~_PG zd!_?M88?L|LJVlO5loEuUO)hj* zh)lr@nDv%*y@%C=y^W00H{*#S6KFCg!s9VoG7nD(?yoiQ1=<8|*fN<+aD~-JGk!A7 z%1%~IYGfL6xVd~#D9MVg1}cR8+l9`&j+{2f zq&YBa6blX&CiFpx6+9q_1b1bWOm?)?pv$n}0BtP{#2x^1Vmg`3nc>fm9S3Bp~_GGfnU&S*j!5)&j}^sx$}%LICA7Q~K? zm6FSDHMI3i7GL@+zxwKb_Iq8n$ntrU7v7Y<%HMtX@n+c4>fvo8*M80mka6P3u-Oni z#ema5MS(NfBv&!2!J?z!3#WMrJks{{W7{oQvCs3OG@S&htao&tO=cGOQg~_DW-$%K0?(%_{Y)Da^LcTd%flD19MR>_d#U5Frv&#OhZ*k@G+ zn3KAb)Rtji=M`kWZJTY~6)K;mR6%&oBGCxkL(S|m##LhHA|9pgsjD9k{*1+COf`>9 zvJK=$bFXFc(<-Z`ldLF?PtTU;Hrcsm+pLP)rdywI*9K|iCzIWIZ-Oi%Ww6#&xxyGQE{-cO-q+USQ5p8(_R?q2%L zi=Wfd0NZ(*pfHZ&+?mM_;0Am9fXQ=1z>>qvK*?Z?NNRz|X+e!2H~FK?D4ODFlBPv? zcxFa3B`MaGMnNER5D7)ozN4eoG=Ra;AydZD_JAO$>^KDj6f*An!x+E;o|n*YAeZA) z@dy9a>U)0<%v*P*K+W#okMF*}ZHEb}5@HLprD4ncW_RbxU-|a0RmB`C zk4C;Ido1bSUggu{7w!0&AP8i6gs~(>I7qa|1CmG!5>o8{+~0r#i|uDZCYgv;c#_hmiMPGg{9;KMLFmiFcZRM$hA4XHq3TI304&Jkma zff+tbq|cy;PH=gt&sa2P6AIhoJqyL+cJMf?R31HUg{p2#**`+DJo;t8^3imycm*F|9xnFg z&z04om}G1x6PbQ~cDUOmd9*3EcE{+Jby{;kkmy6qwH{px$R1c_q*!4}V2^r|p{DIW zk{jBxRBh~l-m1y8uJ)JL_usSi`efZ~S7%|_wnz0l@7;O-UB0bl)6fuCpdC*e5!ccy z>u5l391_AEj1OQl-UqiJOs38!lsJCY!q3UDpu2u}eEjUSo3H)W-`IKWn}HkAaW`h# z49@=K$3JYg=LQhubmPxz6UZ$ACqug7sDMc`N?;$gASAu#L>5x5yex{te1co*lW%MU zc%y7=0GGUe_JwP|{@cIx!Z*KBeDN!@S6(h(d{#YwX)_UR3J@xYB~YmkO-P+$v52Cg zz#r$*`Fi4_un^-Sh`E|cUe-X6Jhtt5EmlsXY1$2q9m2_E%Cl&$4j~)#RDgU7KzWt1 zjQdid9z_6W=aH$XGgRIy;7`G?rKxYT0XUfJ1K=P=TQ0ZK^nR*^Q=*5)oNsI)ssli! zrq}Hb?@X*kw-I(D?YZb5rR}{?y;sINia#{nt)ag)_(!RIVEf06Jr(h|>z;I`p3UMe zTe|L1S2R;wt?PcZGd~3Ce{}bFsouJGa`dg`aClZFqKiesZ+@>X%>J-Pr}cmI`EG4KsoE zfmG+|KnORm9|7AyZouH77DVi!XIv^+9nf@;3X-5P@|rf{5eA*gJWvQtz5tq#VxsIc zhUUUZf$-oJpwkFJ*pw0))6@*U!ZVGvj^LxmYl=V%8R*fYhwS(Ni~jw0r@AciY0qPy zYjmRap#>tFFLplv`B!E$uqV;h046yg4p~^h8fb1{6VY6spIq97;W!hVcGXg>0AgjK zzhH->i6(PR5nibDIM_j8VnhM>fAJc}Pd}s|T)e{ni%;{SG1~IW{AXL?XCddF9 z8GLd3e)!;nZR9h2Ykfl*pTP%G`|S14y!z_blq^APz(dfgpInQ|{q*<+J^uZ~f?OP* zydMP$stairQ7A1Y`@2qrrw{H$m@}DN=B1JAtURC3ENq5%!nzLbf;Otsrz~#3?wjsF z$lg>spRjC7+URM36AV2KLy{CdP*^?hX>H|M#?~|%0Z-&;J!!56s96$VufPuHVc@Vc z_yMd~279bvj4291$|y7Zq3x4oETqWcdEr7bQ;Hh8Gr@JZ+7!GkDM&)w{>*@27KNu| z*frQZC_9r`?*RR2`GhQBw-j?zkqqoNO|77MEO&`!hlID%J8na=vsz@GPs+558BVR% zt+M@g!ir)-&KkGaSvRMnu4Ie3v6P~cSRalqaKPSN^Bcr02%Do`)Sn#uZX zH)vL5^{fg(hRy{+V-Bp;MLzM3v#WX#j_2TmXfjIo2sEZ*0v1pg-3YEfW|u5uj)r80 zmMH+{G)%UcnCi5D{l%Tj2h(RSUA}t#%HfqOS1-+`d07FQZ2{(@9THq8#gQ0VZNtX> z!e};4(X+9NE_=UpIW_L%yedp}-kM4Z@#=AdxeCO`ncRzmo z@kbADzwOV@Z}4n!ye(ICq#Rvco>j`pO>|rD`#?)4l-B43Tn%Pb^v)TTOfh8!FxQVO zw)bQPzvZ4Dz5J`+IQZMYRor+%Ip8{$rP?*C`t0cA@BTnOI-5Gtu9x=obl=CJD4e8p zmo!>K(KnhP8(>f8fk&8uuz@$D1;NVGb;o?jo-Q9;Dg32`p0mI6*Z$_O{oe1Xzx^B6 zzWlAd&%Sv1YhN%gU0+YL6WhT$d+%%Bp;)2JMus?1^SlZJAeBDcbZEwyK}}`O+7UGTy}0@i3_1CxAJ9 z=byxh4Z6(Ytg?Q_HklcsD3jaSx+8c^cw_jpENFYS(p@{RW|vj5S~sB={7g;UUfNdj zaoBql!_$7Ua^{}QpBDb8>2JmS?&acr(J!Bvx43w3;_vC=BX{{u%4&7S8n1SI*7V_Q zPcPCofAI8pv0q);nN7~SrR26@VU<#$@PE6Vk_euG~hFWcyEL1UX z(}^#R_in1a!&gqu#q9?Vi+oYAd=aKi-+y#|TQU3j8!t}}_noa3M1vK9MpDt_`&q7= zcsFw^nLI8$DM|31C1NjAZFNpVjU%*G&b<63J1|oZBV*LUTtA4NI_k%vIL|)2lcLv#Ph3*aI?jYjh}gw84jG__yfl&9JRk%NBG$%T`LZTJ=C7 zLtisrRwk)fu?oM$M(-g{(vE?MdP$v*57kOdAEORUroBm+s z6>38snmgJeN5lK>N;V3OcQz*QoP)+X98KL_n`0)U2FDFc%gXpd4| zCi+akdC%6v)NxM39k554Rz?T7YDZJTLO?Hrrf^is13=Y<{{<0lFO}s)e zKd@Hu%_JMj42Bat9!3O~OK3fS*$oZr+R}y@`jeLQ!uebmQBk!Q$=B-^`dSjF2Ds2Za7bVn}ZF}&^f#* zniz6`G9eZ*1+N$d~)>8?Vr5<){o!*$#Qvo zu(z0kmmZzVWlI64c_wDlL5iUtV93w}G+F`iBe^6C2slEHfO5e21kOB;MWc%kQkLcB znb*F0@XOy6`-d&~sj`CznI9hAyLEp0knv&j;DNpKcsFLidmO~vd!1+yg|-Up2Z^_^ z$|?sJ1?u9k!jYIS8Y-tQQbAhnZPvKS{^2+N=HI&V>eoUw=h;qN%;dqG@05*>YvEWX zw?k)^txAkClyTT{Re0w5-o;3p(g?T(L+PIL+MVni%?QFo8;-kn@M zeChdDs_CrhS_qt{;Q_c?Elj3lf2vkiJE;eiDVnh5AukN!zS>aE8BqvMAe;h3Xh1OY zMnG<1(13O`jS|3vfJ>o!6p)Uy(7+}Y9F~bgJ|TrYEt8>GkT6ciz-ly%_tBAcSuN9_ z{fYc%|7`7&nk`HLYboL6X_#;H&FO^~Z$9(vbtp>T^^i5l2o2MCZ($o_C>%eSEDxrS zrozQwoPyCXDoj*Jj`t{l*2_`05<-*=3;>3ROf)@_`NlN}QxFQF=TDCD!gwO^0G>c$ zzeLu9KB3RX6VP&Wpam-?0I~)(7kEtf!f_yimYRLWV`A0FKN+-JXf zczAem!LbCY)c9w7_v!HqdHh@;2t*l1U&7na_AFK@Ih{@NB0nGM<0nrdY!f(kqA1dQ zQLO+Bmd!GNBj|za5CqKcS=&A7S{K}jcgM~@weH;cZH%y7YYW{2jLD*cEyxOPc06U) zI-l{HvJQISew&kb$E$497t5}ReV1u)ai~(m!%DlvV`0Oh1=OIC1X_ba**1e1JZ!z| zTpU;0L8;+cg_K2Q)BLzAnhsa7wDCTilaMY5m=&}P1d6p4YU*lY|e+4X&V&K(r(^P0Jy;1Lpg%#p=A70rf?W zp4h-@!l>XJJP3k;%yWvm4K$HK%mzH2_9|s)k1V>Z?RQSvvxz*Lf;s{srkHE+ZO}Dl zG%6C$S4G#Wlz`R5e43f8v=oX@vI0y)Q7sg~n*zKzg$u*m1se1j0Pv*BV4sWm<>BR< z`tvUy?Cf3Qlbg@Hm@Q`2{%j88+}L!oE`~TM3Z7+yNXu@E`Z6vlV?Mk@j1+T19#)E+ z;)I+B>H_ov1c7J-7k$2Td|KJ-2b+VPM{R4Zb-r_1;LZA@ci-sS^E7PI!{f=*da9~( zfJ_;Cj}qdT6ejrqnF+X&Tu;zq03V>`6v!A@#^gk0Q$I{6hS#mEhfB}D{7ZlT@0BmT z!hn{&Oj>urogO`TeDwHqyBs$4=E2kA9L+_E-V9e2mpQGtp$+IXJUt`t2b?H^(>zv! z%@~^q)r8^PH8PWj(`w%Bi*s=S=~S5(~~z zGCF;#%q*W)rgRO^rZc*Qq*|a&rl%=f5zT5cLxJ581|XMm3iz1@_+@!xzH_Nql(oyy zd;K=^zNElSs9CBDdzP=llnoA7h(ocBiy(Pk=mG`zl!|mHvc#*z%5bz^oq_(!NnS(a z)oETFpVyN{Ueh5z4HL@x!otReWg5=7eU$i{oABl`{iJ5^`t(i+ZwK~4%xXCEsCw4=(^XB=3MffPhCT5g5gyZaA;OAh@jWKP>*>zjCkt*qTDmcTgY7BuZOa zQ?w@Zg@5kzpWQ#$g+=WL%R))S0RqlwgIXAx9o{@MKVMWwK*~O5Uf?@Ly&6G#Xwk2d zG>!C$o2NL`zkm`y4eX%T^y$bNaX;f{~W2oW)0AM?qByZ4&)wk#$AW-SFhq20 zZ#n<25bqiDu99!2^j7firu2aj?>c`g#18~}UB}nm@Il+%3*j8_K3AHSmnv(SVRD{9 zL)b~|o^~~@5F`q~8(hVEZUGLU%OVsM$^bS4L!X?Zlwdq6kQ3kxW_#N>*85!ef?FA% zssy_RM#J(fWU^&L6T7Wzlq2pzNy$L;DN-E{9Sp}7fi|N7jY3N(!D-cKl)|Tz2`^eZ zS=+KDs@u=1ZIy4}F}Gk2y2m?_ZrPc<;KSbKb$iad5y3U?WrpSc6Z1duRx1{O@UIL;^vfX=u_6G!2b|u0ij~ z!j{F4{pR-{y#GJG{`%wB-@E&Rw|@MCAAIoOGd6ax#$6|^jpN#imlSa~=T%Ii%(z}8|090VE~8I)Uf%{=OI*@*2X3xnx< z+xH>Us(@F~fIFs;1Him?Az!OWR?>>7WDP(c4GrZkl>?szwPNdaA-h6}wgc$l(w{dV z&ms(`H}&pLlr75Ny12HR6$;B@D9eqR9!d37+Vjkv3UfCU@3p&+_RR;ZxK-)*3;#x~ z-(BzC$)0(7h_ar#CNMEkC8$VHeslMc9ERQN&ph+&v$T0OMO~u}m3PpgMK1S!*!JwS zQ!MS|zG_3+#WF%Md=YK#V-bKQRFN_>#v{vK3qX8FyTecl7?k3GK&9&mmIxiW32cYO zLyCfyXx@(S2V|8-Qaoo{#?C1!g-?gDdjFlp@BhEzqo*G2RaJRT8KDJmog;DM^ZE3Z z&wZBW-@GM4(IlcEBrQMrujFgw0pE-SNDka-Xjnj-{2fG9eGTQuQJk~G?6{Pbe@ zVLU!D(W9BhJ0eba{cjH%1;H_{XU2hV=?}$x<9UQ4&?SnlHIzkxx4g7NU*7##zx7U^ zWJZ&}%t;A#!MWx$pZUV)KJ!(=E?{4vA#_3V5>)1=$1m{l?;#fC|Mvjxq``JbZK6f< z5VVw{2B#~F+?dsRy=v-kk=L?!h0d*%=RO|S-T9`bX!H?Ix53F6T#-DLZT+)<2`gr1!eAjpXtUJ23S^C?j-My3B5AJ{e?k!m9 z=gX;l|DJg8wC_7c62&_}G;|I{6_PooO#CPgrCUeIYKc7(O&n_xoeu!Dr5F8q%`P82 z^P7Kl{>!h0JahQC8fU$veemFe_1TlGAJ*@DoF1N)0F-4x^J~_^3#eS9uTOJ*u zOhw2EzJ-S7q@HOtjgm&+L@aHR>;Bq{FMa*5|IW47ev3_ahD+Dt^_$|_v*!Bsww#nN zJU8ELw)aom*%r-@qD-RMxFG?NvW(Gi8bxXYJX6y_Z?o$I-x_gOx>MKZJ{<5=C{LT% zTR-#a>SPD#Ttbv$qKz4a89K{WdC}-17@bO5GZK7dcXXu5faC<=U*-%R#%Ed3x-yQt z4Ubl43ASQbXI%DdXVtE*vc--!ay^twCsvfMb}Fl$K|=vwB<1%lbo%VpNg0gavV5E3C zvARBf{P^|9;XyB!UFf83r+kz7R)tPbn!+&?k2b>O3ci&x=bAW}K){Lno;iqzl(}R& zH315q#LUZGIBc>9yr)$*WDXs{k+cT>NR%gSdbV!9|J}tO{C?f^zM6{MfTwf1|4+DCx0&R%EgHU9Z({ghW5djQ*4di@RFaO zP2YQ~y#1j4i>!eF>YztyGCBC{E1!S%`e)D%xHm#Dgm-Yjuw7i@)8iNP__;t38k8HQ z9FF+n#W)s1$$R$q_Iu~5w4_}jC(^l*k>QW%mvdK?WZN%WH+`2o++wn2D`BB>rH*0 z+!kL6btc3;*a|1k7+*Sm1^~p;krBtGS9mhfY+02{IA-YQ19 zQ_#ddS`~*}!7++~nI4u%_NDGC%B&>^)WEmk)Va))nr~dbwm!Hm2ol^WDoDe@D8$PU z4VSRwWWE!vJw$~|!X>oivaRGgG%WCDXpcqRPPLDw6nV2eJHstZs)Z?aYsI$ZsE>@j zWI4<`K`>kdVn&nlwA2Phf4EphL7|5#oXJ2rs(b>H6lu^!XckRFh%?n8T_{ zOEm}1`tY7S-IQgPPs?VzN}fi_jLu=1S%B;1In29FlxhYSM&IMsA(?j; z-s#)7)2cBA<;elq10LqIRa?-3mQqq|0d7G;pakx(0IVv21gg%X&V!M0s?-c*xV$f)giL5Jornh@; zu?R{yb;8Zl*c%b9=DVgXTL6O%-;32vvAfu+sxvb_Ekm}qwc6T3i33wCXmzpEnaCGK zbZ~Xdb!0ka_w zKq&z0sNqn3xH|raZ^=J6s{W1BZ%>DxRQ5v|KhW%+Ne_j8;QdkHOCi^)=;x`gf(5rI zm793ncP4$0*8I@ zfF|fpiaaGokm0hhqx8*q;LT4DdQaE_I`J2uUf7X~SEERi@fzoA=$wmh$G>=i|B2xi zW-R64VKVO{EAQT!z4JCd+jig(Kps#^;8E9wo6mmkGq1e7yK@zi4*4DPs*M#Gv;5%` zy5^_HFXZuafgl&K10L}LabLWk&*7t$DT-?7yVLVyC`MKk&0u>SqtQK!tD#*pyAp04 z2P-MX`oJiR5G7LBB5`yGZs>yRDSIM3F->)Xk=4vE?J!1|sSE}&lkl}|-xwu#raL*; z8|I(b?Xm0Ej5jJ+QW^sEZ2L)}rtjf`v(jj%Tafs6KUrYlp68@tm_&jFzB%qA}Ve@+7MyswfJ|xugo6 zPr+fJzM8d$Rs{>|y`hCPtk98&3M2Q%SyxH47lqQd>i`BEQ%M1>@OZ(GGcO?ML~6Cd zSwvyM!j#N}LgfHB29R~j%$72Y^o1HG;PHuD7k%n7-Qm;}C(Tgxq33muvN!{VqqC{| zk_TqWC?Yi%vLs8QX10T{*r1dhq7>aMNV9k&H4 z2a5wUhQEXrNGfQTPq26?;bVmh!djXs%XOF0KvUOP=G>IBZOnW*bMTmyloPzpFlzsy zqbzO%fMTu;?M0Ikcp`urZ~&z#LtO#%1{#zmLkDY2Gv)9EL@=`sMxM*v#p1=AS3dWd z^6LKKi!WTddGpeAZ?Q8i@+`KET(_pNxzU~?g(-xEY2nF~CmPuDNjMuMjZ9pab(9QC zPol3V5iB#H?^(mxpW3s3^wy95?9X5S(RW|}_$MFS``%kmKDq^`Q~?)#{J4JemTr6S zYgfn?@Jui#coUuEA{%iPZQn!Ch5}uIKJY_Yl-m!JfZH~Pv7&J{iC6yK-@No|uf_SS zcD+$q@Du<|OPxW7H}%o?-dMkXr*eQ=Igo4SY2JWw1+fHGrT_&(X*4a5yQ8h_Vqfrl zCzNW4);30loycaulsoyCfA?>E!(ET5-*>;YKv90~>8;RRU{P>-NkcgRf1r3LUs z(?Pw^QS-75ZhdlkcD8--GdB*eUXr4KPBGeFg%BT0g&gMo2j}K{$HfP=K9Ti(^oYf zz<^U28qJ>ao{47MroR*PzzO>8x57XDC-$B9`=a9eyAx;*#d#5TBL}{}zyIQkFXnj( z?Ez@?Gz*#n+omu95R0+{_u>e|;3q_&Q$Rb=6`switdi-1<2oAUek}uG$aYO_MbP8?& zXks><=9x*!-FtX%HT3z;Obo;J{5&7m-=CbH4t+n#a0a*}ZIc2_A7Ev{M7hj>GAK|> zfEMQgo-1{*%Af@BjZyYm_Auh4ra^hHX&*5GT`x^}s{NDHEStI;LMM%fCGJx%MD62A zOh-l^RpoJ3o~mN0^0Q`mm)Q>tyHlFCGxleqdxH%Rz28bPHRVDT5}sjjxtF3U>v_2w zvu(3oZQpse{ z6i1p;zFLaD1kZK8RLI^~%G%8GMa8LoowXfTn1xnkL8NXAlrkc$rCaTNXWHKvRMWaCT zE|>@BzU_d6vO)oGHp%xqfYcZ8)&R!N0TRSf&LQZKc^~{IAjG<@^fNS1VBgE^A1$Ar zpVsG(mbX59^z`l9Pww8=hZA&K^UlZ3M|YV>xt6}vJ%KR=lvDRTq@@bV`2cE3Gv`cz zX#)B{*ax5#T}=UqfZ_z-2`bGdpZf=YxBSW%CCdw-TiVTyTrq$?Wai|ZTaSPAgZ|co z5=f&Y1wzGg+U7u4UQxn0z!1tk41kH20{R(pbY_ryQ5WO~`^vBd7vKt$-TANlC;ywn zuYF5Q_w{5F<`cg+H_u$3zWB}A7Y-*kFT=t2=UcntQtyPRoASI5Zh+Jq6J*i$LITE! z9U+%{Ltc5_$n8?ut=CW!wTN?1gA3kn^l~YDAMwp*Y5lftVi&D<9cx>vQI&yXCoyz|P#eOv?R~GnIW1+Ri}Iyqw@nb^pO*rutVt_t~ArRT4-X@aydE z#`XDpzo`A>@uoa=m8h&^S6sf=s@-k2f1d9hO?DqmckWJSA5YYKL;ils-gecSefFa! z{HST)>iYNGwmfSV+3LWw88i_(wb6+eYL|zSw%HV2q(D?WV3Ry$IpX}g-|PPAKkc6$ zvH6akl;~k_EObYL0fCNOzI6Gy2>Q5XYNOQj?DX*MckJzlXIYsW7&t=cGB><$!)veo`psvrbCzHD1?Mbm{Y7;y zuJ-Bi3w!*$AjririYxE{kO!^C>}cCI1Awr%w-4&IIo)*UYu>xQq0KbBkAt! zmQGE1!6PLj!QIY#O#yP`xoF*9=NznX$n~Z~X|#-pc9DaV%X1iK>xRj3qdLcCnF&n7 zBAZNY2T`aBG_C7}9irqLBWk$t;C2E41n-3C3!O_oZF;@6&J=EU@4WDN&_x4uAls?5 z71P1ytA5ea(p(ey4u#%OBt>PTq{Pi>#^HKsc&r0cE)<}|Y)CVvxA~CxFkkn&cdHU6 zw=&5%<7;7>Ntpq@6qGe{`k-!OJ5!mUEKT?a*vSAyU}aILaiZ7UDH;KxU>Qk)6lH<{ z!6)WitBK|FA@zIZc_qs_WI}c>(Ej@e`;dyX+OF)nA;6fbXhDZVvC%MOq38km$c>`s-%*hSZ0kr z%qExN2bn`J$^bwg<}W?-ng8{FTu_1#aQ!ct1_1RGXgOn$2n)D4jfvf#cZMS^5(y7mi^3wUXYtN@&eD3BKU%By_ zm$T=t$o;vze(9hBb6GqsG{ESzPO|OOLRaXSzGK|d7?Jgp09+O!4=mFqQvmnH5Y{Su zoV!+v%U!YKaAWo3M^Ex%_R32ymsw6(0rA^<6WeAud#u{Cuz6Z`$~vhU5Dsl>U7iGed;7#x+2SC(n(1P#-BvV^#awAAAaWW7L1s>q z{}A9mSv28l?eu^B-%S45Kj~y*)2X5{Dn6J144d5GX4CoMono)4NPGz@q59}3wQMSU;}>teo!$CKHFcaF4hkySU;UKoVUDhMmU5$3anoVl*Z8>G2DC{JbE@DAFX{B=Q%tFd%L4_rqXF z{?a7Rs=Qd9ogF`U+V^c!*L~MTPxA}(OGr3)_ef&LfkJo?f)ii{2H*nxo{at&fk~tt z>Ol}E;Ro<*;7=58#%M+zw$H;WgG3u)G^hsvPm4$BExcBdC5khnId(HL(9EYiq#XwS z=c}0Tpr!qI(441Ou|d%;4`fV24l^Jr;UU0*rU?sY?fH7W?FOezFV)KWn#IRF-s1Kh z=HKV;{ovn8!%uklNzUGs{uYmSdAcvyy~OWZ|FE_XY~RAgO?FCCK>wlNphP+YI|T!@ z1DYtfmPgPiSo9*RC>kTeuF>2BtQ?n=Qmhzfg$a&HN@xJ04q&D2FyA)yr1Yigra62+ zY8$|mC^}Q+>$dAV-rGE}%H*(cpqDw&9TSw_CDGi17DdkFgv)}9Ieko-VJR4NaDaUs z@FgW>s{kBpE?U$)m({eYTrx|b%9e~b*d6Kud&szEuujCrG~5{IEP9U8W0OmSWuyEh z=+?;K!+;3EYa1;a_|thVQ&tQN2!@v5puDzA-L^>%bQ669)4FBDAOdW0>EX*M{ujaq zM~I8Ud*gGMd)j*s;)wDsgvvKscz7e70V;#6%1H?@;r%d#KCRYl04P9HKujoP0yhr9 z9CMt2a-&e1KDrQi{2whigGV1y*!Hc+v-!>Bfr(i^Chcmu@`&?ELCMHqCk6 z@W-dR84R!v&dWbp68AzE2a0fJU*S}f7WjP z*`3?(-MaPo?#K5(eE;FC+sgAxR}O_6KK@t#di~Z1aAL)*phYi%7EIMB8Fwq81EiUs zgw8;ZfHG4wxEAeI4|tV)3HaeyYp3&_-EV*W#lP{_r}N9KMN3$r*&wn3G6t>f>fz~Q z|M>CLM&9<&W#`kRsAvf``5E*t1d%4-D6y|29iojHv}#pq677ID6=q@6KJAQ?f9ZFB z=i7h(@9cc@tLY0b;-cl(zn*>m75~{6hZk<}y@NP-f4ZD>UKg}CE+riTie;>YdNYSXIu>O$Ea=?}q)smE1d- zItY@4c2azJ0&ay#SV?Xm)m-^ox7&aIPuLqj3S};*Q?0TR$}A$}jS%f(v2*SEwX4^! zke&1Rn8N@jG2mN4i+*`2S95bZQMF{Wk-`PUAY&N`DL@%$ISd(7^7ZJ_{|WB+pC04S zAZm2_C}Q|GP6^{P(o;M`cIfjlAo~KNP_Ahds;21C;^~v(-JhgKk5NONPo#6eg%BuO zvUcOfbD#g*tCMO**#YUGl?rrCI!L6)$EU|H=<)L%1-UpbAPAl*77!2}>^uaW7jrPD z$Ugk=!@GCxo}Zp~O-B=*z}sOIUD!2JCGw{5SD=Hm?>6P;(gg)6(5N8@1`$TG%@l_S zf29}{gOX%ePx(1il3@1Tn8+OT8)xI2u4`Oyv|$XK7D0XBd^mBbVbo0frl11yojgnZ!V6z)pMhS4%5;7iC1 zcqi=zvl&_u>V4yPX9X|wRTS1Mlc!15fQ@g~gX?3pHz?rs3#66|2U(BU(RDr(GDVTN)W^*HkOfPLeAjRhcLf(21l5fT zzze}9l(v(WWNd7|b={n+XRFCUO!dP@>+{na*RNc;c{4|Cn^k_+mG_R>NB5hD_lJ4| z2o9{Kb*2K>oEZT*@&IfAtCSQ>_`o6fH1QUpC9rA~t|RhC9EjY2&FodcU%2hT_ib#9 z>d6ezCf|b)XnuS{2==?*Z~o~&=J)Po2m4uB0eYhGq)fFV9GEU$KDc)M^3Lu~Ke#Xm zKL82v+QUmJ1#}Xq64O(aGpdUo*J8>d|LZOWDapxjpbtX4 zc;E!|=EVbMjc_!*!GDy5??|#KTk=>6{TQMM^%zSOX~xusXM=NlAHJ8r^KLp{c?Ali zNy%{a5CAsCH^2ES&p-EBP3zHVFloF5l|LRASN`<)#XWxR5QMDH2ti2f;MRdA@b*H= zp-J<}AN|Q6zxTlhb=O+Jf<)^a`vK(CQ>q1cL7XT8SxfvHhlgXP2t)8zoEXymCX9n9rt`hQY1QdSe7b69W_Z zPA6BIZkB`9t7d@tjz!+=PL*F~t06XRGP0y0X>Z33`~WKxKqUM*+|v+PZ-HYNm@#Z2 z44s4@RuszGbZxXlk*vu@G4+mj(HW*fUUWOUa!%E)wII3{ZfwllL|C_ztcn~+3Tzwb zgw{WxNk_NfSZGZG{w>Mx+G&?EnXl*Q0uv|sx$Q+4Xj`0FQK)>V`?RfrWoTf^k%!KV z(L&q4hXE#g3RD2`B)d<*i!3|j3IG*MH8^>)<)@v~xxF-N3TbUWY&LARmuvZ^?(Lv zx#tGbtEVOJn)<wl1nxGA=SxCBJZYMC@`5rYJE<+~OfF%c zNT_H>TG|p=SOXlC4pUX?*-T9#oL!&SURd6{Bmi!mNYEtItc__ypgUCm;t$;){UJYJ zPA*;InL-CZXoTWT+eh5;wd+?eUpZ99bUmd#BUOa-fqF>VX*lDN!FlWV)%3 z2@9u^7t0`qqtn@se2K9&k=$U^cW9_8mJse@hHpSb^!a3L%74H@BiEX?!SL>{M0APp^b+PzIT*_hh|m? zRzMXX&`>_ov=BhfEDgP8ifai&=K|aqtw4kI1k#8ADnutKjRnpA(>KNj*!f|#S#O)# z!>3aahU*4POATlogt#C*<3e!CJW0YKu6c!t?)d1$gS+S4Z8v=A?CA=Qq92rT^D4o%wW;XgA#|E#@bu-f={BhNkb{kb^S5Em zyKQuE|1cO8htH<%P|$~~%uJ-#N^Pfxb2FH&XwB}>hAQi|P@ zAcA8lM z0Fn1FXmXfkMJDpW4TEK!tzrT|Vq+)5LyEqq!6EV!QV9(>Lel6!znL{OQ3Wg6DIh60 z6>*d?SC#$Yq-h52;qG9-h1i=y!px=%ZKqmW((;BeBmhXk)8;LZau{bCFG>vl1@bzI ztYE|7Aaeq6&ZzpJJefw(In_8yr%{$^Rzfj`w(nNw_<2UM%N$J#(hLup3#H>y zKqj=H2jGSj2@);mgD99VAqnts#x_zEU;NyqufDo}aBXjIZ~yX@8`rPz9W0n|=IqSB z@nPAxq(u*)j9*g<5Y(H`MNWtS|A0T>pedAqc)FDURuWX37shLDSlXe~B-zWk0Nyus6_?(SW6bewNDVznB&)}bB95=2y#7Se+TF+v?NDM%9ZV4S^zaf8_y zpta2RYWH%yel_f0_0n$ClkM(CWUOdK&s$1=!cvC26`fDZn8J2h{-fXTzx&-}eZIeo z62ZU##UTWpb!j%8KKK01!%K$%dHvu)5YTza1;EN64GTrZo1N^*T(5E(nFMSACSXJr z=&tb>SOFh9`i3M2Qi*0HVWp?h^^+|ghe7Z;y{F%eOJZ;WJ<(TWw}EIV|JWE|a)BOb za2jA6kHn{_9sB53`J*4%WzEe*Oc#3S+&FX%?G2O3&R_ZVuV-dPB1TsErGc2Bi4s)({{lB5vNdGs&f=V zc!5KFh;Z$&21KTWuzsL~3L z56?2d{6W{DwrXTea9DUrUL+Z4BFipDjKKydu>=J!fW+xMDAXSIfa6+i$6OyZ=M}7{ zp$R71CxrY2lyn$|rUnN>Q50?BB`m0Sk}@#J(j2QIa}(u5o{~@lBE-to+$Y=H&1hYq~)35r(B!` zejM53$nJ7}OR~FSc(83xoNH!PHlH1eVj4JY9&gg5$cr*x+5WWYwzTUd?R0-Ghb3AM zHYTxB8K5FsIT5H&;J*P>z=aCW7Xgk6HSYJf#<;Yj%ftD?XtiqUHBeevl!i9twIOWR zD^Htrz^HR@f3GwJ|G1!NOLm|hO8G?t#X18rgqa4!v^>K3q!7)f2Of)y*|0yM1raW~ zfuWwhl#@xtS}TrM=oDS5NL#sC)zVBHoG$7NKnZh7oA-DxLh35n77#M=K&hl0@36nJw|3Q}x;0fEjj_&CIvkWk*>q4W z?c+iY53f-^T!1CX3IN~ZzzFoF+S!{;rsn$PYCbRLJJ)B2SE_l?a1o(CK8t4?;EVx4 zG1IgwY#?-(!FAyeG!#k_L3`m-@QEB~ctS)p5AGD8+}hIdfvG2o{b7IdS z_fE@AUmVV2Db+yxA#^NcURDNDCfYEdfo7(fiL4B~vF=cax#l#YC`g1hj~-nsio->r zwoN=b3J)Hr(^J*7w4hDNLi!}FGD#994C4;EPzAi`XeBCCb(}Et=q?8ZP{Wl~eCDQ_ zyrh<8w60wY{h~?vCi;v6UjU~v+Odg=O-TCo``Lf~59^O^r!3ER=N{mmx`lH50hIW| zgM;U8zOb{{9UyD8zX8k!&_krOytEZ(n#%P;9Zgh24FgO-9Z6&WAO_?M{f>`8anP$H z2!~Ok(GYxy(`d{XtxwMvk8yqluSSYUumq2bSEP;jiuRh}ggGuowNM~gcTqy{*@MUF zCvWk4k91OHIft3FZQYNvFsN*Pt@^aJd58H^_A2WHw2f}kXB?isCrcJ_fT7?{4r1aZ(n~k}@Bj6Y+ ztwlbYIF>ejf6{DM!ETLoS!M}Q0qM}nJta)e&CIbXP|_ywMyqtIb!${_@^zK1Y*=}K zAu-8|ovegOS^L(4q5%XQ?9_lA?QlBubzS#`>I7d0v2lPn>_mnm79Pj&7-p>(%Mi{J ztE2XV9vtnZLmkSbYr?v@1ZR1Q*}1#SGjXl{3l!8{yX!DHKMo20(aVeSzNMKnyfN6p2Si6wWB52Q(i7K2Dtg z9@187mJeL_JM;eK8{u$wR?I6=wB2xYc7EDzrqk*sIQeGXKRr?&t~=On0G?nJKMqB< z2`Gdm2l$7}(O3dJ5WFoPNM*T60*@FxaBuFV+gVKi+OKsly#Vy0t?&C~Z&x+?!IZQ# zgY=E|eu`S?g9Y!~=Fv(2^hA~rXbrVb5jyGMiYJWHB;y{@_~<=K_m|>jQHX9sOWBQ_ z3G1%)>S<9U6`{~+FYdK8OjNmP_kV+<#_kBP4?!OHG&3`wnwtNNz zmqS){l(dRp0y)Zf^~&|@*KZWX6zCM~h`yneJvf2nTW5Tjij$c*%S9)kd^9Wpdx+)@ zlsgYf1t0?b!dn`k?Y)G2h6q={q(@fD#23O=HJ^$4k= zISr`?ehCaKEr->~s;9@{o%hlQAE?gnWmO4dXMGE>X-wAl!*sIq>X*Oq+|3tp+YqM+ zgGw-m%7Zt+3p|aE;nU+6_xQO$5J=bs{=o55{DBW)>A*cmxM_i;JU=`8hyVHia~Ot8 z2ZvCC&3aw0YuF|H5-tQ-!GhjluV?-P*k8`Ss6>1In=Fgn{~Yz9BM%Z6}laJpOhL@^01r~MFt(tEYz4t zKE4J+*OY7;-~)FFw;Bw`OQU6~6__$}GPdABl7^1p|7z=MV3M9^LPr`n zqR<)C28>KmBSbmYA2h^jcn~lbSpdH&SmrTbWk||-c;+EXTj_Q?7Q3OH8UQZXmZ9t2 z(RmNjEQ>zsO_Gn2zvVaY+3iQc-c9LG*zny@|0vnFB>O&(-%H&Gsei=WdE0!HhYv*e z*!Cz*UOUK5sgGJGih5=Woy{8`>P=`mgSMTNJ-`b@B8(6eHqc1)w4wDNwBl1q88X;M zIYB?jtmf#Ow%-f^(9@{xqHMC#v@z~va&YsqRKeQwGXPsY47hhQD=F&*>@N8STE*=s z&o-Y(y=ddqDnKQaUgx6DXe^|q6c~00al1DiXW=MGn(SRNl2>wys%{6L@`h6l`VT@P(BPc-x_3QA-bq7Qv$dVl&TacHwOv@3>UdrVfF_Y~YiS4~3d^sm|+gwxWhe0%GqaTXG9U#1&{}XPFcRZ9qTxo_5qxN`py2 zjbQ_T;~DvDf%+GbGL{cC7o#d}01=3&E50y`lcM++{pz3JzJ2@cyUUO6{P^|nJ~@4` zyK`fI=MZe(TShtX;EF{A*xtK-5RcC4+jslzvg3p09;&K2U}e<31x^D;0dS8Ns^kl$ zVyRfc8LhUJyIkuA_|v2FHr6gkMy)nvp=r7iBVjMN{h28~jHAb{FrLt!FmBRJSN;ByjmC>Y5&3@T~TSOG71 zI}E31r<-jJEdXR1|fFP44?~+x=M@zj22MDLdifa zg<%xi&{KFNkDDzJ)Vki*P2GUwz*XQUFlDHG0_eeQE8>=LwUjgimRKk#J{$_={rS-%1e2JQ&#$>)hp*Vy6A7{9z#zc0g zK`4U?Wo01t44^V(89%d=*C7KhWeIWe)$(u!ML zX`AgV^Zloyc&zoQ$d7dSP-S-oyPNz&79Z&Bj;ZbkeX7cj&bD{Z1m)z);q@v4e}y{q znU7^|!cMv5;k2zcuurh9DeDsDY3ibHDdf~;@LDD#n238yavD@QR*w>?<(V?se&G4C z*3+_BOyN+%(Ch?WMs*H?cx3^EJ8b*5?ufb4-O{X{pk>+)t(mcay9d)&a7t;2(mCpC zvD=F2AXmx@&(+iI1dM-gB6dpV$n6x3_mxRiA&bH-YX+>qlVSd_GL%9c{2g9*iMY%ULvE6R7zKLo` z6IlfE95h5nvJAnJZMV156!39<-sGuwJ)m3aJfBUw zonqbF#qD)<)SS&lo3q(KrBaA8Pe5t3;l0$1_7sNRNgA2sz`K+wK6CI_5$$j7c0y^= z)b_<^rnB8Eda`$E|6pf#S>{T_!MaOrs+RS}u3Q+ji#^19=zASDkRnJWpqvNRM}GvL z1Q~-w?j4W;xD5y#HUTwREvo;qIr_854<5XK@80Y0yz$QKZ{2-&wccEt&x_ft$cs+0 zR)-Pv)dx4`SrUyg;{WBpxcklragxVbC5oK% zm&PCfqGXtrdoOrfxXBE8bg3h(wT@AZ>IdL(rYcdaZG_$tN=`q>Jv#D zJv$nif$xn#gZ|?tAapd&OCxF*AO6MjXgC340AI%8k#Rs$q#z?mLg0KM7^Q)8-fLJR zXjEED)x3M})wka3?mbc4zGA8@r&G!Q)Z^z1LH=illwb=m(R7@hoqhMa-~IUGkMZHfNJ*aO@ElD; zE_@vPq-0Per_d94Y&t-rfXrzy1PX-{@RHs_V-&60Ae1v6<5m6wa?=>UqLB&j0BP#F z4iUvNU?4w^SbQ?YPN$NIrvVFGfplclOngi_GBN`iiNOI=NwtRixj3^MdSW!HskzFrW$@|XEpQ18d*2T+ zg`u|~G-MZPfCxpQRZy{UPGBr>)NRsrJX5)_Rp9h+J&uk*phx97;1tL;O>kp~Xksg0crb8Hi@CfCmWmP-Wv{;&w`4uV}p<5-?Vf6up%9RxDTCbw(NV zBN0WMjaDD0AxTj2j`|wCgn#64fGlCf3oddf0a{6k8qRlr9*Z0(Hn+@pQETQikpZRv zf_FWIh)Cr~?MP(M0y1&*4aIMdcR{0kln*`TIEB``0Nqj~2Xw|I754VIsRltwc&otX zS(S!1h-3z5ddp~$j*n0Y+d-1>F9K%+8iP5LbbFFV3cQ72LxMQqICaAKXd}0?Nq^(2 zzjQdQc0epVw|%>f9c^ZL^VKf_geFJLk#Q9?@4484)i8X0ezv*$sGxvH<*hGx&cm3} zjkYz$UD99@TB{gy`2jva7d7o`%_#*A-5{WT%)IyKTWzC6^`MMsUBL$+^F(5TdP2g` z9Z+Pb?`R8XT?n2jAT@F|pR+4hVNT_nX6 z7(KEiNDL|j(ZhSP0`zzMg8or$N2@@8Mw3PgNgv=n+8^&na|OvGqd{l{A42Lu2Pm5k zgnKQ-GA1kK-uda|Pu^fpj=|gJNls|E&%hMGKy4vNC=-z6*&8o>{_|f}a?H4c%R*AA z^~P$A*QJj>dHw0}3wr!qAjpM?k@34IXxF~zfI#4)KJi}wArdIWL|Q^DQwApsVLd~_B$_bWW!yHFzMq!mUURM)~=iLTlMxvowozpzvw1|sJgW2Z6?{_G`Vr8 z5tHfTj(B4lDNP%8UV<}#X@*e-_b`i_mSwL}^jUhf3Y(oRie4T>*`OH@PY2rJmgv{)=kJh(K{gsWSD71BWs+ArRZw=L*Nz5%^zB>qq2^w%CvOtp62T)b=Hk_>S1&zqIZl$Q!26(=aiq1c z=`^A~!I^o-J^v{2XQAE_fZk&aN;B!lICMvC&PI;YS^6m=u1V6vGRj?D5E4`0$g5?9 z@kd&>ZPCK|&J`;T#2%JjdEE;SE3Y@1KlF`n_+R_s$+FC{;eHVJDjYApe6XmBX%xgo z-t3>d{KVs*zzabEqjKd^%LS36<5*Mms1S?YhrhJ&aqWW0`rZ@K_;x@E1|tSGfQn$};J@gsq|tAZM30&x!W`RPwLy~N zWE6fko6-n<3Jzr5VMg1c@E{%aB<7|IS^Vk#1FKCWt6Ev~!x~MJ(56b%1)iomZ!Rd^?J6B+<<{y5og+{oqCz zz7zRBjOVYn)y=MXf4O+SSl*6WZ*S8d4kABBSN!#$?*PFMgE(%wS=dbn!7%P;RlTh9s3@8w zTyFOJVV}iq-Uf>-O8aTVP%Mjdy7W(GU5bU%FhH{MVfCRK`pCHnxbYDti?N4O7YxI= z#~7^JJZXcvf!8*S%6``NGq}Tq=27fz^um4|FY@GYR?yA9ZT>mKgF}zkt4bJ4xN2=U zO5?JL>2Kr~`*q~wY4z|-ydarX5f0@zTWsocG|95==6R6>vm~gZu3zJ(RO*Sv%-3g( z8m1GjtM2$zo-g?`!ZjYXmw-iOVCey8H)5GVmF_I28yg!}FK=AF5S`oFy0H7`g)95J z=Qc;r1^^fS=XX`O=+}N_3Dc3X8fqiQ0wUnxcWBJ2*`ImA+}6AFta> zx^F?p4@UmpZhLVQcye20)nT!10=n^*7cM80ptwC=`u%XP?M)Zq>v!6>-Z)v_&icJb zZ$x1t1#~yk?|OsYgI6Ei+1u3~%(C)Y*o8a2s+iHB7y0_ro_COVM@gvj&^iL`N3i4c z6U~v%ktT4n-#iaegg^?~L3%*?N?Jx|MwIDrrOHq>As!5aKnG$vR(`b~#Ca8Yc*=JJ z|D+4z!`ZoSzr68JfAj9C@AWr!vO&LW%g)bZhM&G%Rrb>nTI#V!pZer8pV`>lg%y6R z8L0{eRw`7w1Rn0YAb;86W4sZ=KwHHem{oMcUV9wZ&I=> z!h*LdXgFy+Xi%U0a-Mmy>7mCOQ(Uw1Pz3a$1AC^KuKJLw8u_V-8Q$4xKU(;D) z6$T)K1u=r|zrfW*r7epz+#q5)&8j=5C>K}2ky;kTWICNprh0bS-HX9(5_vt&BTFS2 zP#N^me&SZ18Geja!fe-0Dyl`qy#znO533S;vCz&(qIYF!6;@O_+tPIU;ObJ}8}{@7 zjqbLfi&lpty9h<6T>#d~IxDaH`(a%ri&^HQFPmOsoO{c>Xgq(MrM+Q4$7fPoL%hMk zc(dsI_a`UEi)C4`#7x5=tNd``2YH;f{oZWQoAt9Y%zQ7c{N$vc+#V&jlD2GvAQ{|j z%G*IR$*Z6W&TpN|l1R6#=*DFgM@ctI+g@_x_MMaC(>YEjDm02_U2{^F$5nGs*Vlsj zTHD-;{J9sFO>i3Njg`Toi`zJCqfrxItOw_cbivZ|%Kp5cz;j%7LDg1iRAhRVwaxSS z(L~QmF*;Zx>iN>PK%XOH4Xec0hZuF(6c1$C4`+I7uQ%|LW)PjmMRe;VotMG(X1K92 z$-)F9j~l1+)qb=&!1gz{5ByFq{h;Tx|BuC!yQ_YMkQ@u=^q|%C$$oNlilaX2dzFX0 zy7p*+*!}&TML*4bFROy2s&xdom$LR>&gaY7q$?{NNBoXh-<_cnZ2>YJsIdy#r0VqP zzaY$`pkz+fUdmdZaj+=c*%F_l8~6L;QP`u`JjRFKw2ME`U~bD|I%lx@Wt~)dBG=Pv z02v{=qZGS4K8>%vM>$pa{o3EB@tRut^q_4}G)&I2X}lO$7>}jtSow6_p}Pyi(xexscqbkrZfi|7d7B7D6IaJZxZ2vT zcenkGEWq`sYE65;YW!tbl>R|8I-dANe!3Z+4EmG9_~q|TzW@E{jUPAFB1^O~f`Yw%Y`eEhsxkO^p7X0B-cdxWaspSs|S8I=ywL>#m!+#Sy~B`Y<-*wSO-|>}e)2QVJ@;81ym9`At6sG@UE~-P zi}ziSzwGd_A4gq}Ho)yt$fdY`{rWe*`OWv=e;|+z4CE8-3O^8r!l4ns!(KH~CbN)vK5EX_b#T(6Lth8(a`qT)A2j5f8#t zZxhED=n+9jin;3GtOZP6$eN?0x1i}1o!;xf48{%NM=Q*~aa$mIRY~O@3#J(;E^24O zQLk8)e}J`86;1`HDmenWA%YT<^>O}J@D`$FQ?@u#df31}F7i1m_0a1L2Wgf@XvbXl)_c8y z7suC^r_&SXG*w_};Cyz24Ptx8)1n{D*D+T35g6 zHE(#$n_c;CQ@@?(FSpA#tKxmHyVJBs^YV@PK+;{6@yt6#@nx4Fc#iYGZB+hh=?{o0F5Jhez4u5bNu85U^ham4C8J)RBcO}{rNH;1!f zG{E1(&0OX!R%U0j4!iR7IGoOP%2oX*8?9kdYuk>|lEtYWA@bT3{{!(i`f5t2a&bKb-587TcrwD5?fgk8YWjgu&KmvE6TqJUl!u7Sqgq8Yy*0CA^STxO`F*M_aU^zLpc593BmJ zx5Dv&84@!FnN}!+is>JC=XdqSoeyrj_s*NWs_SnJ7{2*pu9uRhc&&xV`eG+{0rK}hd#F(SD zogtbUH+oFhIVDb=p=(elQbGJX16C$fq*<)UN+F3Bt!XO1S}v+7?I^uRfAHqczx<== z@4xt7H%veE=|{(-A>KHnZ-6J&;<8C`q3?V@`t+wh|ImYvOJlg5k4~>n)dEkd$~a?v zbQZf0e`(?4azQkN&%nl+rmXWnh=1!_-+JMN7fw&{oiQ9b3&PMe2L&sR|Dg?ukR^m( zP*yjnKDiy(bu2Lo1f@j!gVzG3$exw1l z(SX&**WpV3jkDq`Dl`pk=B}nI43Lg`qE_d1;C9FXQY~Q!Wr{&c+aIV8IUJpNA@D@5 zO+L+jajhRw<6JSl=E~(TgLTV^WQj$qB;Ay0%d%cB7rI?i>b0WfGRJ+8|72$n91-~i zPJ7T;$GPIrfxK>==*0{qh<&Lj3i^TGMynUfx1}~(W(UW|cMcD6cl2U5Ifpa`H7{4M zlkw0?Frba&qZg#GCJduSFFuUDtY3w39mI%4Qjrqu3RcDKqVd~}!6@qjPcBHyQkk_a zEu`v2wJiMxV^v@#SV`lBv=zp?S9Gzg3yteA0R2i|5cay)9bFWQz+XfG z&KC9(dmI%V29U++!mE~n9-GixCcNla4~{mO?gj*D6(q}M&a!zUX_HiMjcALMkrgG= zF}UsU?xZdC+?M)^w$X>O?%1SOPqFIZ8!WmuS~No#hdqqDzQu_1N1*^YS4}<4n%#j8 z+m=m|Q$af2&H91Ac{(c>r~O)oSYvl55Kq6B@Wk6N(Lou83>KI<5$ij;DQUIet2g5? zD7#|OPN*O}zA&B+^#JwGoL=`PJ-^N5l?RJ5m@K2ksZL~T+YOJ2O4`ux7~*t@Efbh= zI>SZdSa(-V(CM4EY2@|tI?26uJZjEucS+W3V#ZSudDF=$7C-7|qomg)I#$Z;U?ejs zaS@}<%xjC|>(}Drsb*4#Gtla!sZ2PNO{Xm)ZDQ!vs4OLznI4WwVW2jxda^>R1i@L{(uMacs z1$1)W0=&&S?dHAuIBHHpuhdcSAZBtf+oS_Q*Auz)BrSITt!TjKvPoIC}^3zZ% z7DXB+xRNLd98{+3d^x{-`GM!3`|R${`3CPv`WV9KLmi28`Wfj_xip<)M)CXbmlHn5 zU69qtcH_)|xbuSjuYK)nFTM0qQ50BZyFY@V!^1$K;CyHcp>5BfKaUk$E|>TrATel zaY0lZJWU(Oif6Uq44S6aF+NsNETg2oJ-j5e8jOLjaA=oyOUZTXGV~bu zP9#VGeM1vemBfTLVo9nE3pA8aan{J9EGm`tInGkf(s;2rnaz(*PUPvdQm=Je){VZ+ zrUhhIvmR{Py!D&XYnEMGqCtbG4KcD9sbSIJ#-(*$MpeT)Zk(pga(UBR6w7>XV^ezx zI^Yl-PEM-8+x607F`rVWZuvk--@nzH=8Afw@;7QMZ&dZ8Dhu34{Bd%+N!HzIW@)75 zd!FD-9*qKB$W)1Y@>>^Cdj5~ za@f;7ATLM{dkHvrFUN!an@M{ddCR)K@!osq)4^bK+u!Of!zRj$VH3nr><)dMk9IJw zQh6gXSplXcPW5;W9tkORyx5|$rC%<)lVTAjcdwkAk9$$lJAbO9Ri|SllMTBdKAm|- zGwq!9a^4&E z(_9nn*wa$`_|5@?_u}~rRiYEMv=v{r(OcB~c%0&hMz@aIx2_fWjK#qK@5S?%Mag*S z(e>q$)+M<29^S8fEX*yQ_%iV3UOVyXWfDv)of`6sN^jKFNfl-XJ`PThmvW_>Fij{| z3M{Dy9AHQV7x$~(aZ-o5KRperv`rJ7r3K#aJeb#0za1P`{nOyR+skiM{=0*5wAmYE zWnb?ws&(Qb^xUg(yg?rqfgWZt#0wyZz?1Tbn!WXFh*^d+=mFuUggyy&*m(S~Sc0)VnNZpLqJ&C!hS} zpf{#sw`<%uCt5d)rAVZC1deC@b>V&Z%LpIiaa0ZQdmOQke(6UiTq#{K>PvXjXap3y9LDplK+C8~khD1Qs<4|nEu zq5SovDBOu}mRZbx6oHm9q)?*{z)5i+M3%UzK3k>l-Aw1pLS*%pwQ8Xo0$5lw_1rQ| z5Nk-pSuaOipWm_9u<7h5DJUIzDpaZs4%8f8z+|@Mhx4QpC1}5VQRaHILyIlSAY@Qk z&vuEVO^;yvw90RywoYKXS|)lKeW~}k1wk9oaQwA?GAqM^HC3CA2FZBH0$i_AIlMb9 z7uxm+qXywrZLE)yY8RJE>PR1(t%AyL@`$B>*OYny=8))^LQoFfYry^VyUZr7^anZX}ARhF&#ns;#<7wBD=-I80HWzD$a4 zW9j$0I7+j0ym{^P6cOwWH@A8ldEKxwW{pUv3`ZkBOMiTL@YeBh?k9E7TeQh>m)!QE z_u}TIpnEAv-%Q4Dd4t!2?A5?~z3$%6+iOwwjvpT8!L$zV`rV=^!;|G^)ZdHy;c##x zEDyb6REJqKo<9EAj}K3dkLKHRZ=>@M7RSf9U0YjakWO>I=V#kpG-y2Bp^(+L*QI%J zoVIaO#EEy3luZ)!5!-Y*j*@nFm~0N`MRPIO_VVD`_F#HxznFxhL%Ez@J{xCYmf|`y zW*F(ovYxjQP8_a>AGT#!=}ixjb|0rn-rRWE3};1|&x@UYx{)mqsNZF6;<1kC z4|=1)o%!MB@e$r_h?AuEr4~L;j2DzaSYamJHV6}#DXmQfT%fv6i}WsRj5f3#)|CG7 zk=~*D*!E62@?YIVH~nn|qBQucj+ z)Ox+n$LnPV1jw1u83s6OF@}1sH-|J=E=HFwB=NAS%cSd#^DJ5vUYCcAxM>+Irs;AT z)N{|PK9TJ#`}JXRde=X^T-NSR8}qZ@cySPCD4PrC_pe^L9Atf|LbOkVgEVUWk?$cF zZ_u75)y=fMnZjwKQ^%E`Ec`HLA%L#)BKpPC$HJuqS!&4mm77El{v*M zwdQ{J;V&w8ONO?xj0mLwqe(!VEQ&yosm+6}qW%PbrZj;wWiW zITRh@GXw)GWu$C7N4eT+?%X>eJa-A8|rePp3oO-6JEHTA<^aql#Tb zTi1wC8Crx^kU}7V7xa2rk|xLlAC0=GNFTe2qGeg0&gXfJ4fYmoJ>wS#2Z49DpWNN( z-5y4_d%>O5yBRg_2i1E?hlBFISH0WjZ+H3Y-Qq{pIG!FYW~alt9tF{|Dk`}jagi_aAaSf^u@D!Yp5B;; zk!kb9&*R8Td%hp}`fx1XT0kw{#&&Nw4toPV$%=eqhD08BO_*2Fq==6fSlD)$>BJIa zs@50&^f0pr5k^diZEE!jRzK4dvdk#WVfs6nH^sc_(xf@J6J{fwh1Qo9nr0^3%QQ-R zeLbx%*Ir$V;~utcFUdA{dT+n-%6L}xx^9-W-5|jM>fF)P${AdZ0|u=h)b8Cd3k-9G zXNgY|MV%Mpm39qY-O$s^-BXqss)9c6&@zn9T0W}>re-W2-|l9xy(RzN4IAH$FpuF- zMW4PvEB}X#2CS(>XbMxwHwR2sp57$b>GM~Lv_zepL&rm z(sq&WXZWyn>*0F%CBup}MOqdtaOO=I`SGQ;d*Ifct#7~h-Z#Jf`kjL#yua}{I={dD z=pzqTUF2S1t!EV>OwS+yh$cz)`OklGZ+9QXi!LcO%1H*)09C65 zvdDzcvd%&;j^JM|5e~<6IypVT138fcGRFlepbRr2=RyGbj+**{f+DUf-4!z8t}Udy zvy)MXmtaSLlQbO;24L!)F9m(7(ZVHJtD9D?Fv?vUK@`?eK&m5Md`e=DI2BVRLUEbh zY&KmMc`r@J8)I^*4uPp3NB!aUcHT4}92^`Yu`rki-Vzz6*}V0a^jg+ylZ@^sK8LF) zo+R-kijSkJ&RWEMWxj!6kZ*Fge{iJAvLZ`4Nmwj@%cKXs|wvs)5Zwk(?oPEpz+#t8RCM~jWQT(jVV~&G zx~m~t5ea;~vxAAyHsL7k;-I%^ssq~Eb^Dv))|NLKR7DvzahH3|vaT14;l{>bIKabY zaD{q2*F7uS>v@;A>Z)G8@WO8h9%E4NphFX(N*EhDOT~cc_x=6dU~3acfx)Fmq!?yR?c?$m zc{`go^I2C-qouYf-|K?kuBYD(nktI6n`n{Z^ia1xGvu}P*7nAQ%a?ce_o7H|)nf?Y zSIg~|?<~quyXeYezdqJ2Pz_TYxm2y`N|pg`roa;!c-Y#VK`csi6Hz0XfQq!!Dg{ar z7Jza*SX`(*p*OADs$Z7=oP|NyHPQZ^lM8RWGkWp6Cog>K?Q7Q$*C zeRR3>a6urMBoVV15>63$=g(jM%%?v$9&Ng5<*Mh8G`42heYg+z!pG}^+zYZHzK>!1 z)nEP9YuB!sd$IN&qz+t!sb%)qJO&VOGAO7i=YT|10P29DPbn;rt?8{Sz+X)St&q)c zP+6DmzB}p;kaCHOpnD>&F0#x%866hY5GI$96j!sTfoTYeoXsXhU6wV0sYt|{W+ogf z3r6g|HY2+)1U zO)><6MSyru$9-fnowQf>K(s%qpRPjtGC+boxuNb(ET_L-U++AesIuBZujEjwyfsmvhxlzf4p#MRtRu%cFT3(CS{%;fF*Qck5p2&rARAaddhb<%J&RcF(^sgb2Gphb86z z=`|aAyG0W=C9Z+gu9FV`#Q-49dOHT%T-7q9A2yFh4m>hy83c2(uKMAJlRS zyg13*`Y?<3E}uVs_npb>Z;YE}Bg@?DcA|#a$!OIc3lm#6P}NEu!qg#^xYMpeKk$2= zH}JZ?Pu%N=kv=2ESkdkyE{MLc$hf2d8ilpr4F}=*J%3{;_k&T(z{GpR9+!oeFPrJS zT`YoP8W!ND-*3C$F6XazUYex4UObH$L4Fd1tab2a_V>?SymEQCF=8+v7Fp%76GfzMLOqyoQHJiCG;pUmmwfk@%K7@Z8E{Gd{8hn_v zqobo=`ITQm$?ojzkO&ZGg3BJbEd)Xokh62rPlTjs8ad~KEW)zTTdw&hqvxGL^c0Qg4Sc8N%*I)^F6hx=l?ED*;FahwQSbj~&vp zIxC8NI2defjHwQ%XG+gj70zlH$J51P!jczGl4MScF&I#xy0(e&iS!;)n$zl=M;aky zf};0zW?npCHF-3z7e%k%?{AL%IK(E<;6+s>TcdDeFkKeMcaInIx{Bgu6dzRHanl|6 z!L2a7)_L#L&D%};R@1!ZN3X}>TW$AlUBB8DKWOLg*7=S3{N;T5b~!(dyqznTBaBv| zhlfv!YCFq%{obr8ZXF-aXG?trCGd;LpXBwTMwA%XAoZhO5XocG%N@ElOq*7BXu7a1 z1HC*`Z}kfNyjgU^q~7c!{UF!p0mFVj*y!bq%Gqgr^LR8_l2fP7{^7>>HG`U=fkTl6 zUeDK-gE}saH{;=O*;HMd_kwg|ROMxHXHo=JyFV%iLn;?riC^W#X{}p4z45RYr`j52 z9tGjNDf{7|8>G>8-@koOe*2ZZ{;#XWn51H$-%pNbafJ1b!?2nK%8 z$Nva|Uf^ZE-wXAWi+iG9Ly*y?J0FaRC~EX2P2bxb`R8|o45yP}+4!tv^iGh{D@t#< z^k&m;u}rGDhr{9b{;;k7sLpS--geyE2*O!VL^z~ysV38i%9r&iUHOYD3l) zv^olPgrq9+`DC$d!?_pa;YJldaI$>pjrRtB{GHoh|IUw=i#+QkJb^Qjs0cZ&BChEJ3+A% zQu|2Q*JHza(^pn`{W2KWQPPE7S>afhK@$$LY&49*pegDc=dz#mH#VXmnjX(ijwg${ zEyAD;vL=YzBx{ni4AUY^$|S3@UKb6^tXJx?e-H+@!)}(Qvn2X)xxAU@C)35|cqdB- zdV@KZWLXT0+Uq6Z&S+836vo_O5mDuUCtgbRR7`7bQ5Q3=BPu+aZ)T?WLEmT;9KMp7odZO_7eO zjie{^7;vM{*yg8gIq}-LwmlfYJ}m15HyjCB{)#3(J_dk%8O(0gp}}nP6pmXj((6rX z`k<2sT^4!O6u6UBd>7|!bU7S9_THVrzxtzVU-^R{y?Om+7uB1ixHn)Xvr?F3z223p zk6ya`cvInp=eT3?Ox?N*g^CL@8gBgjU;l;ic!LQg*2MrIt;Lja@%wNeK7@aJyC4QE zN#Ap zk{p9U7v{@yHqp0{p^O!g4^fo(aXproh(t##7)5013F<^oWrta$mzm1og$WBtx&aGR zrcsn7jn~Xd+$ClN_LF5kV@1}5HYL7JcuuCvXZx4Xr=)04xhy35iy_xyR=O}o0+ulBaP zosA$4meWahItxerWNU-Ta6FkEoF3&>juTKYXzONmlTWuT8k{uUh^f0KPMTR2H$k0* zb9{rUiNnMTqp`b{6OOl|v=`{Hn-cS1&{!7Yc{R*>>9EH%W^6@R^m!FzVH-y2_C^}` zAH4c%n3q8sy92Ru)bWtq-VJdbkk!pGGyu+!kEq)O|3k0C_oAl7J@WNkf>u7hZp3tY zs4T&kK@s^u(u>aRdOJEH6yVQw^r3qveO`8X-c9HJe6APOdu1MFFIVk9EhpFUZK7;1 zif}?ToLe`5eQ$ej@5%#Lch7Az;E;)ip|bSVV(Ax8-^=qB$8|mT+8N_jK8NQHpo19T zOYv9p0$jIBF&)$RB&xW4c^xKkPYzc4=z+E^eF6&lk%-Mf7G;k~^}Zrs((9|XhnjpJmw&}$JMdHC_a z^2NXERvoTRt=T?QJDSM%;Xd30AD0Wl3^MbujvMs*eb&}*zWL_K$;s~SZmmaTW%w=E z3^`MWA{HTB+i4I8QTKs6`NiOtd2qV|&bDbCYz6NHQe@rlxh+C%mcpf}K`ycAa6*j$ znu$dOT-Yl>2(g-Q2O~yOwqA`hp5;X_PMfU2O=h(nnymdHPH~9CGYNIASF&PvVG*6ABk=Bt5(uK82q_B@ipYq&bjU-^ ziCHz0Xv8V8W*+~EL^=yVL5n@NWg$Vh|7Vm%Lf(dq~l{*;%25W3bL;=bYbVn|1{l;~Kqc5vrRS4)rcyrre>S7#R1X8fTbB{X_ z*O3C}-#`>hB9tYLX(wIHciZdkb&%xi2D_XH4Xe1;v41bk@Rgg%1nV3O2K}li^F=YA z%?|G#OeYhlL1#XnH?*Rk;E6yXlkLz;RAu3k6ibl=toFNQTNg>ROvB@#J@V@&38GA< zZMm4`MIMLoFzMk&guMibEayvHp(IKdi{-(|$pSI;+Xmt3)l{8cyRIV|45=#92h+-^ z={9sx3|Jc}1<>rgM-su2?Tg``N(jW$}2F z=T&cW+->&p_v(4k-`uEs>Gt7qeRNU`N9p!nf2%*~idor?2IHt~i-Qw<{PEsSlJxYf zc3J!Vw94x=Na`%eE^l=2ykGqIy+xaECMhF;!Nd%~1&Knvs7xt39P2zrrgqmRxXefw zwj3I|071Laj#GlP0xtzo&PJGK;kg}uqfeiPIS!G&=A!qZRkgQRcJqbLPYS1;gvm=q z_3Kq}N>3-fozSbYD()C>%pGm~?O(ib<;vyltqlg7++Su0-oECHd*xn>Bb&E+)!Ve~ z=DHCh%g#u|OV!l%Iz6?cnJ8CXo++ao|Blh^Cb}N~1rgSo)`wWfJfr1t7WPJdwv+pN zvufjwH}fC7a{B$358wabG_Pm9L7DYyMsNsr&@R;c6@0qr)liwow&OX_u-@PG46se1OeFx2c!@(A}?ONcyMrV z>(;I5bc#n}n1m>C^!>^(xJv`eH4lU0=z=(wWr7-sI3E}%&@cel4*SW(IRi^N_~aNJ zB95}yaiRW`4uA%zVu238!Iy;)bNh`{m0;J<8GfkOSCHYz%2!MC@aQBqVXoe_{aKP!Fwf1odVlvOX#e;fR07Vwy)d{GVX*E7%V|}nJ?!U7~eZOIXXB#I6gg|EoO^+Q8g9nU2lv) zl=K31?k(oX?j9&VwF~!bA4y{fKot9pe|FUdrmnN!>N2UwY8hH*iV}DSS<5lcFsq zvk9~3{Kfq|Xu~AI<0;Fg*B^&zf12mhS#fYQKaJ|8=a)g0`*9gyDtl!#EW+L*$d1G4 zc9t9k$;|6b;>{1D{_9=~%kubO zHeEJHNp#o+(|ggP^|DbPzl<=!RZgmI;ty{D@EJnal_Im4-zkk&$Z#R^X}<)j>8|kf8#4J9=-O? zwS&W3X)xOvM1xRgsN*JOoa!0ux-2U1nNNQ5!G|7Xk8pCZl7!Dy>MnqM*B7}wmvLyn<&+rwoL?Qr~gcv?@ zfpsY&fYqZ!l@q9-PLbL*1YujQj8NPP05DSc0ss*VA;n}ub=$zT6YZxHX{((cM`{JG za#>bbGWx~}q%ep0a9Ng($74jwiXU4G1yWd`W4S2~C!ooGI;xZ<6gO&!h>K5mN8A$i z--*ph0QIAf_d%g?H)M=6GKkE+s~Ie0*|pa*7KDVQQc%=bX7M3Aa}cy0~Gf z-F5Im3-M!Pj2NQ`S4oai5bK13p09zfiG}WlkKtf|JA#y9|MYZ9Jko}o*58Z8Oboc` z!unQ~!I68o6#m2_*F^P@gI2+MeQOYAIKna&x|@`w(Qq_cN-EH(!zAtx2EDYmST0x_ zELc5Lfkdg(6WS4S<2lLGw2pdp+;8Ghn+?0H*I?w+sGqQ)Pr4vqlQ*tktA@i_6fKhIplNPamKA1scq zFDEz4$*ppByPY4j%L6YjCe1R8^}4=AJ?WaGt*p5)P6lZ;Z`%T%qN;5UXVYvr+}YT{ z1p95_C5gWCRC`Gj47WyEUY)#qx4V8l>!pl1ZL2Z}Vn1(6o#_nQIM9v+O9btLw0_d) zY)VfbnRhpa>H4DV=8JYV!~f88F^r5b zdAAL|Qs>{*P0aCjGKfQckR@sLRlGV3dgH-E4?eKHy@?}%3!(vA>y57b@Fub(@akn# zoK~}&ezyqx!qbz=oqNa*vCy1>?}c)?YWkcmr;FvwMuFa4>~(tJx~@t&vbt>*Qw9E(p_u(1zgIKop?U z(0SO){r!E?UwY}K+qZ9%g8s#Pve+|&LAbUV_kuL8?V0PS;7VUZRyx<+J^+K_;7}1@ zl^Qc^pk8B%B4`XK80MO1(bU>q+T1WLT`77=kdSq#(1EgOmg7PZfp8qvm7hc&bz#WU zvnNf^?9_%q#dL~*3@Aldp}F#Bl-Gb_^H})0NI5dNx{bmW{~gcJ(0;Z2COoHB8#YCSHE|n1p|9H;T?1u21wzWB zdnpWQqpCU_xX8*hTDpPa?nDcbT<>Jmh7drDu;d6aO7y6SHYa4x>34TC%n1uBj-LKN zO5B@FT;+1BT$9k9ATgW($PyQE_obo8xmS*i_Gxf;bq}2du;_`Zo+yxIr(3NSei{{Y zt2{;>QuZ0N^SQnupmFKkXy-|2XGRVh?Q_N88~!mXl!^7shZfxOP#Qc0y?+D2(TNn$ z#!?tE0hkgH$QUqfyO_@p4|T5x%jAxmXpWFhjc^M`t}gX*qsM z484Rb@)~=nwU_ilefW?OUc1@vI+}hme4f+8VSGyfyTc9lPtz{_O5Y8juV^%rHx2{sErr1%_rf}l+GVV5I>sbjDTh_BKK1L(ak#e^54Qru zUTN<^w}DvyZKt!KSOgUwMNtOhZ@2Alm5aBU4xtRAM34O=z$Vgrh?8h%fA_(M zu5NA&TfeJX`H0Yr!-ScJs!4G(mPgCkK{3D1=m_;G-%>szQm^!coel))zSg{Ja^EL+ zftqo%w$Pbbebz~j0LA^S-uRLJ#?z(uiG%5dSKkT$zR)ry8(az2r-2;iEWYL}8Ra1iOTZb-ReHfvV^y5|Jk|rR#}1`C|&e zN8oOM2t%zW3|lNWtrUYWESo4tLmi;42KrT!7swS-z5Tv6+Z|!&!N^sFb9sT#fRIW# z4-8|CE=8nbRz0qhsL)o&=!6ZyN~*Bu4&h{p`*=!S)%g;Sp;n2eV^}f{TS+v4by#d_ z*0EZU<0AMT3uSepb0eWno5U`L2ePs5`?x-kKgSY!fs7CFJ`N5}^fK8gUI^}pJaHZ1 zRrAdgf-kjBqr{z&2Gm$}y~#UEGM&1RlSP^j1)P12<}~f6y`El#)y!u)yIZz3L*?%A zDN?HR_>dDC5)bsf6fdmWsA)0R?%)BIPh0ysznL)Fpv=;q9%Gg=spB}^7;g;2I4#=% zkG1s@R>#9JllYAfu1&FFzTbrLyz^#(HwnX86wHEb=>;=Cm=Sg!Sqslw;y+c%ouZj` z;Yrorm@jWkW?d0n9q)I$J>*s9B{GfEY%+!F^1}XJ5ce1pG%ATAyyiUcve9;byj$IV z=R5DeUq;S%DuZTL$LY9T)V(SGNG05bR;F4Kcnt zHWK>1ez>viX9K)NJamM?s)CmK`P`dL{Q1n&hk`5mV$qKNpsRnkn4NasUe=F;xWuao z+q8_AT^$b63s)~*dEg43Qq}7Fllb8JDlUD+NP^d>n;hLbKD^o0lb*Ieadq@vC@+e% z%$)VTS0lK20M}OfUbB$PL>(YzDgbp4daJR|~HT0kuX-{D6cfdd zO2Cy>1UC2~NyQ{q`*fCConmd>T_h-rxO0W*2RaD)wsse$N(n@9Mbn8u_k-0CfQTh3 zuD-*^(EblCTsjw%CPb`JvD~E&fzlkE{gLZHV^u%|S50uCD*n*_uq^7P2v*u^f>qeY zWm3cJ*bw7Kp8!P9B0v~ctL46`_!)6kCZETgM%Ocv1}p&xyWh)@FrM*Zu|O2cb|OM2 zGejYPxgex2$~ysS=t?foOfYs4j)VNxjv=c325MwbJIC737m%Iff}EV3%;!WG)9EZ< z=8QHRHh4iAhzf>jnYRAgHr3%oy+K@#3=N?5j%UOHVXA;z7uCyn5D7I8k`x2nmd#`~ z(VOn{oJhEkL)a{IfOoamsM~&F*m#NOCxkvfKh@j3{Iv1oK#Ok~W!)AEx;$S_XLu1^ zGROuxGL4(p7EKu>0W+P|`e89WoSjY%_Y+)NlT@*IhJ|eN62x!?_Jp2{v(*Yho)RVA?t%?0I^lGh4 zv|kl=QJVSmwjLpdt*m7%v~8?c+O}O$2FpdToCouHn=hHTNbXJ<{ccx&qh7$vE(@?O zsM|72a2UcW^pfqtl}E4apWjL1u&8k(^q{aF7)DKKH5H@n-h21$>+ik4m@o14aCeIW zc?PvdkLVM}c{MNFu14Zs(zIz&$E`OA!_8UUTP$}b)19M}(X~6?8`qYvzB_yUz3H{v zZ(O^1e0ZEQjG{Qm^xm5+sIt19G9*xJObLb!GsF!dFKCOf>z~`X`uNjNj5gCUDwcS_ zVH&hcO%e}%-jzl3z|}{deB$Zz=P$bXN5 zH@@0YTa;5-&qkeSA?WkXb8js!;yYo*ej0I$^E=uEsfS|QI`on=MBAzM5B@ytA4y7<>x>ceXP67R} ztJ34~Iy||rA#}WuD;Rx5sQldNCp|K*4HVER7YWYD@ z7c1e54I%(IbX=Nc-Dk@ zU>@N(V#MpA&#u;^wxBTp0-8)iioBT37v3OF`@P;q-;4ZNu~>qZCVoFH;^xle=+4RU zqOO883i@dStuPoji)mHJk2^U!KkW#Seb)&D*zr)Ru1!(?2YZ zzUk+0HRTWM{6|Ipda-=FEUq=p&9eERYN{fc6~VF!7hN{@;yg^EH0|~KUXpfYQ_L4A z0}uP1^%)0LR+V*76v1NV&F9`?+UA7@Q565EtbV5{U-g=e#NSRM_Yg@CrEQn{O)uEE zu=T*>S2s3?3^Y0y`>)5vBy;?O*bAehlgTSTcBuHcpJT<*{tiWWw|+<52uU4^}FQGFdhB8ph^3-}%l9FTAk1xrrV{ z13C??l_)Be2;myvA_n(T13&{vXWDRS#nGNdjX3FMCk)>xkZ!paSp$q&NVjRnEpEVIlw#T)joU zB(ZkqNbpFc_C*E*FN+LGm;%{#9F6t$ge#)+11;i}rCQVyfgLx2J-NEz%ysK!N))oE z^VzL~JGXA%J~=u*x^oD}I3o0flfS^mZP=AwfK$@?UK4nYc+q!RsyH1&5EkwBker+( zf#=y|#*i6pZVraMpy`TbG0hiquN#iWRo%`P`5Y^bKN}~Qa*bcT)e9Nws3uEqKWw^~ zF6`nqX{xXa5`VbWCH<=IB0p~R4)kS~rQ`7cX6mwVyPnx(kq2cF4SW4TKSW|h$<$eCx-K5N@^L4p~sx)MK)K}oGaoMNlHyunKgW>fF5qG%iHOgAz_v_p$# z4T2&s8H79Mw=X|@De6TzJ}|?Nd8D&eu!+1;MCng`?u(B-_Bb=*Y*^X^|8Sb$hx_oS z;o~}vDy6p?f@>vc7DYRg@4ox)*T4Stx88bdV`GCMi$_8hU}dcos@yKuU^oDAsDWVV zL<||qC`y1_E~PYePP1pZB)aJ#)eo$R8$nA1h*OXd1PZS0E|)qCQR?FzC~Z0~CZJ;I;!Orv&i$V_aE# z&E>MPlp@`kZy{?1?+9|C(%Tb)r=!;Ot%2#*IU{!8jUAfD!?er`Tm^f$h^wi^LLqZ;p zij(N{;hBIO7=04X(!f;N+C5RM7t#W*qp{Mld+G-SiDIQODJ5UQ)x-c(E`lTj#(I5x z8eOvL1r0BU;?zoV*Xg(<<-#J-_mbMR{^~+7xv!=><61EtXd{k0Ijv z58o3v2hv_1RsBqUO0VwP$t10d&5i7EcI)(Lmi3e2fFSDORyH1$R;{1kxiO8Z!Pdqo z?$h;6=oeiT=XHH&+UvsUox`IWw`WIFT((}?OTr}1+hHB|nlxzjG;ZbhORvB1vPF_D zy7(vv-%b5jg5sTaG4t>d{3n)SllWfjca=6tqAm*3q{`x;Y@)jIrjz>U$XhIF1)|IA z=6AgL*Nb)*#+&`9hhZ=KxK&-K18m7gZ|8w?mmj*w7}6VM$~ul>Mkqz=rev_toI3}T zciy_W%E}w>#!gRCcNE zWHC{qut{SL9p5X_D?wKy@F>juAYn+cd}FXNRsjt~xw(|mBgVMsmmj!r_0g+QmMwFg zm5$v*>!_v*&$ID++2D&`_$&MS=bg6Epmh^Le_ePV?!%uAAJx5XwXx=d!`j zq@Wcyf~0_pa@XcQSy(e|;-YbMq!ChOp_iA(`gTn!i`%kb*R3CZ>*;I^Tg1Rc#R4IU z!>k7FfoGU@Il6nI+8v*uIbOsmjPjRDu|zqw1>uV-nBXhRy@&-~V=a~BH1Hz}5)z8? zR`iJiWD&xlYqO;ZKp=s1C=&-9KN=O}QY{usjOktm{((Sidp*L6u8hT*k(Ps?XA{7o zc@zgz6z=hIT0OW#Iu+_eEsk=->K`A+)u~sW==6g`!wAu)Go(8Yr^l`JaSnM7S(h<&x-;k@y}=p-9ckvIf5$is0W_s&B(#G`(gBg`frt`bU)5$S1Wz6Y~_lt$s=&UP(4jHKY zC`^|VXgI{Nj-Et57M0Pb&3_s8uIe_Ejp_VwaWV<(aC>8aFxu4KPtZnjcR1_vX&!do zXmgnKA`C6lbv~PZaB}D7;jM$o@dt;u@17hLdh<<6i=xIoc%>0QFKg!|4!uODbm}l{ zV!d9!x6C%~Wa(V5l=TKpbh*ebbjds`CehM6I_l#+;{?^dcRH_TC+*^>>*h^SB=Pp2 zgxx=Hy6<}RM%(Sdv)A;yWvCt1cIHRp-Qm?o_pV&sLz1<;J`FMYkp9BOWSrxJ<9%&! zZ9o1b{~o@0`TWCAJ$mt>%a<;l-`m?dx3`tVVKN%^2YtM${xA!ZATJknSNHot9iMnX zB`2$C`3>R#uPO9=T*$c7!`A9UjX;Jm@|9Qb6bbW%mUOHEG|u6w84NeVN1wiU{^EAq zCal8TEl#Fzkmq`{3<~wim8;J^_uP2AsR@g~L`t-12s%I`L_fQ{5BK3i_;_!`FbV-P z833b`(aos+gFpC#H{X2I649qwmO9^{vY(8DKE0@?G~Iw+Sr?-TaCvWvT@oQh*2e8& zSXtueS3+uWSRGCevm6D0uICao!04>w5V1H2mTsXn1V%wH_l0z*0c5R#M8L`#7^yWi z=M@O-5>fy}(CzD$G`ZlDNSx^mrlqX$sYqFlE5H)DbeM7%EDjK{EE2$U2m;Fjj2pQh z0-?#=tBCM*El|~VNfw+?#8Oo8J@hTnU9K3ocNfIc0aB0y1zj6gEMaT2UTW5zTz8vA zk0yXjHD}V0-vbJH{D|x1;GYEu37XI$PIpt>*k(wOLL7cP*;ctYAiyRUq@#3&u<}1d z%80nJno$ZIF4v8*OXz42yKNilqOH2ovbu+b!{H8mxSbX4a0Bk-$4W+S)5riUh`3=U z$C^sP;?jUDm2qr~o@*wYIFZ0FBGEG}{B;UnxO59K98=2K}vDCr@)Mo>A zBG@X|eLZV6ED;hnX05RXY765>U7<`Waz{{v2K~_}W3o>tQ>f8e=pG*(-M)SM#?2cD zIMK1NE???BZ!FqrLM=+pSV2fW9BGJ}cFFCKe?Y5U8}YL`y=|pgOqVb^9_YREaS~Te zO&gl3y>s{0VlnOY)7_m-9LwqP;e0;5efRFQ>mR)H&f9km4wj3Yg1BOKJ{XdYWu(FI zb}nS#$9j9dW=Dj_7Ne<` zeY==_Ew8Wp?Kq0ZS+DiV9ztzHEs~OC|LWe=M=y-GhRl6EK#S_aHz12as27a{Nz&il zIsec@k3as{(+@uUz||{P9)0xDOP4M^_W0vZJo)6q4?Xno!w>JC+kfh*r#|tCr!QT) zsLy|P-tqAq?_U(|$dF|2&uH#G?LZ|(; z7h;$gb#h4|mkij*KKiew^QO+wG_*eQFL-}G*?-GA(QCXk*P)w zXfgDru60O)f*qzpdmavqf>mlMis)UmAF{g60+%>Iq6yhTBMwkI)~+f`FvtjWLxX=@ zLBXB;6-5aI>49vgK&-5|buN)H<2cs=5x1pKI3c)~i>$1;8iLP39H0V(vsK1CXD(TUqjfguy7# z-5DJl5;B!77I*`Ck-AKC+u?}hxn6l^ZJvn_q+M=H@f!N_ja=WFvOv$GQ9{s%00b;B#s|kI$NT5bJ^uLP`xnk%x_tT5 zpZVMqPdxF-PkiF3r=NW6k;f?b_FHcumPngR5pry*T7B%^dcz>Zbwl8CNbPqIFdeC# z5GgQ77}bml$~^e!rH3E8%7~xOao?Gzj6V>9x?)LLMPd4jzxcP$?d?;DvEiiZ+VUX~ zr}B?hb|3D;$LfOE5M)53tt>(c;cKtG_N{My>-zQUxF8I1Qi@^;Zj$IJgT-P#ola2W zuAEdqGm4l2aeyL#(X_}Kr~+F~h$R5u%?A;g&*zx);c$rR;}RScJ!l|M3QQ|Y2z?R( zfc8Jszh||JXChXq0~t$fDnH%eh6?siRcT*Dd-E#; zC4yGPIu4ODxr%c_q-S0oJg*0U9zF!sxnd%Z($*_IjEqbI$Z$n_duOlGH_F6~VNxs? z&bef;xkTMrhZ`9w_cyYKM3IR&QezFE20ln)#=Tq)-bg``mIV%M4+aAeB=EY@XX#`F zAWVNITFCVmf*GWv2H_of{T2T>dmKRun~MR}}Os@!es`uyJh#&|qE zo!+<&+`4h&gFAN*CzEMYV{4gEiE|980(nvaE!R&Q5;!}$8Q1wujgN-gr5k%`+P`#u zYi}t=2)XE$wxcxB*ORZk|G_t3_~YOIgFkrj#TVax z`)y|J#Y-2{L`SU`^Tlkct)|gvynk*Fk>9*|^V;1lt)lHT=4XW?753=lWC z%>{9y79e5j1&1!N`NyD|&GX^r=&{GIUbwQ4=&QO-;tV~6FXiJ%Yo_MF zIdH&?VnAc<(76B?7CJz`OZ8dEj~d*iwl{3(o31qam;?a&xF9e2CV1iWorCV0C?#VrYZ_lmQ~B6+}=sHOn~dj=EbU zghtsyD^5hZfay>KD&-ImrnQd}Tp}0DE45P)WHKm7#EM%S zq%|D?R!lCW^4D+-xI}IgTywI{pdu)VY!qY9Rk6#Y8$hLq$xu#;)#XZALG9DHFAq>0 zwsIX?E~~Nvmx5GdCr%7lO42})c8-8pb>l&eaWXIMK#8P5@~UZM(T~I(!s`7oP?PCm zK42|%IJyU7Bj<88o+Uar5;RG0 zy@`#%i3xKfQ{o~L__~=PSlcpnfU8+MC9c)#N>b>LJTGRmDM-jiTP^yc2}^W&v6x2i zR2njJJzW2}3&|X&-N#YHmD;4633~H~2AjSjpBFi0o3_ap#jV?S@pg`mPx57X_wFGx zbno1SIEvqX@0}YrZe07|gX81Vd|5EMW#_}VF7*{R`MK64e)zU}F*|=?2xm|pPhHhX z7jDJl&C3`1`#ZC?@J}Y22a9phF1zw1s{KVfn&+XMx56vy#2fyoX#bfvd*4s`Ni<01 zF1fumJt#{1jvDlbPdxGD=Ef#PP?37_-1RtfeKZ=v!K<&nx|}aj8(EqlIt2OQgmPmJZ1V-!ie|Tqii!}@Vq^|U(Z0WK2te}4%f9&aJpM5Tl^qL&XYEU_V z!hN_8e=&S4E{F}md*f?BUH3hp)8ciQZ-JOlR^`WCP1P^z#(xR zt}Kp>6l5ug(T()bT^Qlj@gvK;H&Sr?SZc8rqz1|YRu`dFq`Fnnhunf}{RI(lp+H4$ zxvYMqDO_5vV~5KR{X&2U1gU~J;aX_ac80G*FrZ+g;1UihXmgRC?bDX~mIT}Jp z+;WNA_;eOut>{EZR+MEaDUL^xCwpBAQ4pt~8_9AL8OzkTJ`17_bIu(6IKjwaf=bh2 zLFHcH?}+HxaCKByqmfIbVwE`)D=E6&3hl=uR4O9VFpJ#2F$BGcQdA8ZqzuQnIb+cG5=Ck=^Hu>Pjt;uAHlL6%$H*OuDoDK#fuukWv@4ol` zd+%LCx8U~BMM#03ZEA5yduWr0DJBtBaTB>Wp)`qCGWqHzYod*0v~%HHu+f`!RXfjz z^Exf-Cg}3m_a?JQFD`Flc}l_3&;Ddl{EMVG@}sRVNE1d_7xS-+aO=u`_`oBV&R^N< zZzK#uT0x)F8=+q7>}GoHg+Z_18x6A2@$tzIe(=%@FZ>CDAvepiE0-_-)KC4?&dv_* z2rQC<5CBG9uh-w&+GdQr`Nms_m*K{AL8+{IO~cGhKr0{-OUQt0zJ{@+>gJb<2f^hB zENazx4!Nvry=IhLrU$@q#|ATnpaG8R<-MFbQgB*}6i1t{HZDp-6SaddYWS~_C z=FmAf+U`O`fFWB!sv-RF($Tlt36&&r`r|lJ%)oNRfujbN#Yv=VtapSH=q#$aAc&3- z2ACaS>hPj_Y}Qra$m^jhtwCL5Rij$rB<8^J<9K#airGCJsu64Q707{^FwkuXd60T` z3`+$k;K2aI85pDyheIQ1Y(te4$2HVdjx>6k-s7LE!3BZO*kbzIJk@xhkaj@86mxRb zKs@V83W)=Rqz1X0BQzOT3bYodUmH|Z1x;!$$^wfxoy|_BljUN;B%aM?r<0TUe10;S z%$74SuV24$^X5%`Sx|4R7eiErg_g^pDl`UY3LcQ;8P-uvT2M;}O;|SlbdX`*_cn3r z+d#J>^w{unnRr2pc)GF52#2ee}|~ zi(6?wZ1Hm4q0UYNGpTF53gnOt1{<5BozZA~?b`c4_~G}iUAvyTyGFY^JI_D={BzGe z7x}?_HtP?2>OePr&}_Jxqv816x&3Q5ZXBN+A_`YXeTWQW9h}k|YeNlUHR@#~hDiuDBM3+>Iv2$0 zM!}kYV;dZ18is)gM3}MULIi-mSt%lfRuItCbW@u6nvTWq1=0c2@-PoUh=68yk)TW# zDF6sY5LidnKrSKaU|KFA6yTW@s-UruC51Qwf$ZA0QI<;ZK#0&66f}TeM_a_tEX{{N zK`2;Ud9Kq9h)0nOEx;uRPyo23Hgr7#28VQ8MG-f)0nn^*oor6f)Ow77OE@=72y&UY z7s*?effc86NYOg$BU()sag#6zTw0UqWqQ+@pH*qfg+YYDqf+X&2ATk^A|fCXQDYo6 z*Icy)YL@7zt$-{`T-R%CfbXgkfMes(MjZk$YNP;^vbMkpm-EGvL62-`0b$$JWu;Tn zFln_|X!MO|fy@klNP`Wkpm9ni5&V^KSjcN0=^VEc4?Ql25)PS1gf@PRipdsGTwz@Wc6s${`t+x5W<+7-EcXu9t?BR=-E;3b@d4a5u8{@)j z+NutUyt;7V;!l0Ov?f9U zQHw6*I`CIE0F8#0Av7MctdHx0yK-`JinspABaim`gUMuie0(yS&2d7|f$Mi*yDb(p zq+AnIjsOuZslv$8DA*>`)uww8#6dT`hLS~Z5_i1mM{__kWQ+gA&$5sfQj!GEtgJCW zA|bv4UV>R5u!+ErAp^2t&Rp0f5ol9+)N_?4k77|fTcls<))BCxTa6Ns!?W4MG&$C zr8t8}H}V+;6b9K5Q8Paz>YhMx6)6`c3GWq}!MZMN5HvLYprH24Lc6cUYRJJh6s!nf zb&+CZErpQkNOz-gb-cq8jVnR}lbgjsHaeiuDU39gm9Hb-jG&{mDvqxKW!9k#Obh|( zR9@Az3q&>FSki?nNbAM1gHB_NdO=vZeFu`F8pN%C3ztfY+d_Gw$B;KVy-iw<^D_lQ2o#TF*n^Xv! z{NNZysVLN&_p-|Ol3{Xje|H!}RkZzxne(DoYryp%3yTN3`18IIZPVU2f_|xz)?t(C^4Tv)$ zfj3_N@xS;N|AG`IKO>XDTI9Mj0Y3}n}X60VIZS zxTFkqamnNdh@b+8;9+dT3gHzB_Oy&TQdx2a+5X&+E zpG#}3!(FjN#BvEKMW+Cib-lb|&oHg5DsYGX>=Jgsp}l|`ODj$cKp-TIEXtAVEP^pC zQij8&D=uFFvXOJ$xMXz>OKUoANDBv1*s!sB&uS4>5{*6t$l?#VfFZkFx?Yyg3CTHX z4oETniQ6C-jg@4K;9BzXRvjtp+?6~X7$A|{_~&u)TihL1jr>JvNbVUE5v*le(ewc=+)PL zIGs!e{fORHiyM=ei126Sa@Z_DYC7o)0lXRYR9RO{phq5i_{!Cb_%^os(i6;HfDg%H zpeU;I=g)uQ=}%mJ-~mz8K`YZgaxq;Bu#Vh^`|xML$K`@Bf(?kfK`(gwt+#&bw|9t#r3v8kC+>Q_LkSZp+G(S=;ONC@z)ktiDrdP}VGU+KLHcYRi<7W}h(5 z)IAZV1oLw~pKWh%{guD+#m|5Kr=EZQxvN*NpyIyutru`XnC?bl?I;j24F#aW42%aH z5;yViLvTmryMXNU@~XYmWyn^1?YI~bgEd(q-~%ve00m2jc~r2Q%u?K@Ysi8ci6|Fm zpCk^6)qxeaTp~^k9{~~p&_Fg{!5FaO!~qi5hW1|ij=(Aoj$N*6v2=hez&NKk3=>K( zx|a=5sl8VNOmOf&j14F_oRtd#rct|>G5`j>W?qX`O$g6aL7!2UbP^5768}!auF5+g z9k7U{P!Qk}ObAh}i+9)}($^?33^*K(C{npZ;zU%R1BWciG@Q`USq()(*s~C@6o)Rb zvfx`U1LPu{d-*5DiV(s9-Gn5;p){oche;s*4H*ER6smQ}0xW|0SDH}E=lVu44EukQcH1+uSOu?P&Dcwj(9-;NT-}t zA-axpqYu7IR9OSqC&Yzvy(D2WLO=l(3p&@AX2AvrJ`GcDGaf3aL{4u%)TTjxd_O&CuComAbKgiYz+PTC`{SmfoPD0_Z5^x{Pjy&uJIqw$u- ztn)|7Ack;L(X65>8qXhZ?>zkYV|!OOqu47O_YFQTY3m@@LHmj+$VeXzw|95;lce{( z@4fW(uYdjc_=KK8GFw|)zwisc@Y&CP7R6${0NW-pYcFb(4kGv0e*K@n{q~!IU#B`g zE}79Trja{?CBWgJxCv8o@O0NqD-g9Z^mGQ97C+=ssqKKA3N76+Io`7(d)wb$Ny>ut?^z2#==%yFq_ z5p+%tbe3I}j%GPXv~t$F+hxb|GSuEPhO>41hfEezd><+lOsX64=rT+N`b_mZtrR@} z{HOl@-~aa?d+hP8t!*xkj*ee^@jE9cr%t=AC^#a_$rb;`yp*EpGl3{_d8i=7YusFzIQWl*>3I$PBMAW#mwG_IH6wnAQvW^2r4X|_~ z>qPUApbQbC3<8%ljmtH0W1G;Jp&)TH9)BK?O~GET&v>x@;^)MJPE53c?o1t;7a(Gn zQM@{r1CT;R>*_?*kp)P!w$roZn*w#(7?8UIfM#TkXDi4hm@4M%x6ude65tvfLpCrX z>-d@_5{YQgxHq>Nn*0R^j@XB!Sfhe~V2Lx>jU_|m|GhO@oPb6V2V8HN;SupwqN~E< z0PQi8W&>Y@9RidH0WR0{fpxtuA|J=tfiXic%ylU{8$^VVfkBfElYTV%_ZD&0ty*L$ zT)ITS>RqwnKym)l`AM9@KT`%295x!%=~bq8CaeYC&rw_Z`T70M&*OyqhMF(~L%9hd$~V)?!AegB)^{F9=R)3LCm(fh$fG#MPPA4ke%AJolj?G^q@RVzy?Tv zttoKHJjOlY=T;^x$aGl5et1-bcG`rHA1VB7>lh$n+b3X9mQ4geDwXfoDotQVMUa+PTp%f9Lyuv;cAV5vV7>SlboRE&DMaBmacOT}@ z0I~_Giz1LD4nC!rG!`KQNLN$USi5qZkh?k>vcfTNIVvccYYroci`;wbA|l@O<}?AA zW^$mh4k2cwT&WdtfCymtltrY_v0+a-9YshH8<5tIT%MIyE(INf0-~glOCn%#{NztT9`rLERKl0GyEX{Og z_^cz&`b8kZ_u)SL`S7uy1zBAvX=>`ldZev`}@NfyJ5R0QwQYnwt3`f?5H%B%P2rq%!wv zS6k><5dg9%Ab>aoDGU7RiY(&d`u+|aIfoCWueLx0A4%AOaN zp1y{N*^ipiZz^#XL|n$NzWVxWufB8Vj$V(%tb|ki52S=*V72n*TW@^_-{kw>f9=OV ze$~Bf`g`B|-s`WwPK&m-w(Rrccr7o#{KMI7%8ZXAm0by0tu|RnSk`b|!U`hwHM!{Q zJa59pf8xm}uRd^vGAxJ!+@mDb+sSGMs@7LmuRQq7C!RZZ?mPv_gb4LYa8AOac{bSY z!+rSk;N#r|F<>AXltr0l+2-cvbar|=Ii4?0(hOy%d!N_^={*(^A*-vvJ)ViSX3ny( zYqDP4>n93(@p#m!oHwNSJXk&A=@c9E}Lef!l7#Jch*A$jyyC$`cSfT;N2`NPu=~O|4c3})e#Q`ZA zOs;D8jD(N@B5SY|z~W#+3YGxpli`lU{KJINQiQW!-5D~qI3daDab#ABe;TZaq3O~g zb7`EDLgsq;Wl!|1(bnSS(!dF1C2B5VmIye2^^v8!p(th?5Bzoi8S!Uw zbC&`l0QiKidE7*B67$QIAE7X0fy!7IW%LQQbwPS zFbWD4Sq&8vKhZO?fYk^=(&Qx3r+7SPvPD*qqlg*~We@=R6VVv~g0&aIrC1SLbv78B zJAZyO+VE?sCBO0-KUf4+QRek@kxv)Xc`=zy?{vjM?A>XaWf<2{ka~WvY-+Ej!-F^~ zYq=Ra7xo^0;_BA9fqNr->)|7`L0xo>KL6%-ew#0<7r*`e8#nI4BbvbVa?>AVNu0XX zN_lc}dU$wzczERAH-F>$_3Q6CVESLYcyVuU59V2xE#}4X$??(MlQdyQAU8Q}5{OSow>l@CDathK z^p?ObidlYPKiW9)lazt)wO!e?g}$Qh*M!U&^k)=f$#hRQ&0^-~VA$g~-Wc*5>C>6+ zwLUwWdwbi&A%1Xh`}zm(z5Cuvl#d^~Lt^=iTL2O3^7i8^)+#A8Su}ko&VvPwK=9Ewu z^{yQhgkU@nC&du#(imFX>m8|Btydij4@Y*-X657S8RwkE}dCb zl4ZHdRhJ_|q9g-xI*sA4yt9ou>Ln!0ra8<~gnZ&g8G0gyw7s_U+RAGOn;UyOd*j|P zDDX(|L&(xM=XBF_zL-oFr}Jg*)hB*cK(h7+VNZ{)LZU3FM8i9bin@)`^vXjQA9(yi zZ>*<<(G&XqZ{s(WHeAAlLfxHP$KU(jOQ$Eg{Ypc`V}$=*H#&a7#AM_rX^IE0h8IOe zw=+l#+*iKffPE{@uH`Ke%y?@f$^Ho-atrdaOHf!5efVT7tptY`jzl zA#u`0tV53wL8)o^Qa9LC9kGDEI~TtWsm2+bcN8&ID)3#TdL+#{IKlycs^YSwZ<3PLryZUvm5 zfhN%t{w71qLI^fojRDdDm?Z@Y7+i>f*OXNpM0-2uc6WD?XX8Gb!*H(2$jf|D%xBB# zY+5jjs4&Wsb+ zO%<1gB7?!e_rmFPLNlRA50*ufxcv;bM$me|1{tBM>bx&};q$=u&JGQr)%*L~=+c|o zDY@AN%#Nh>Ds)f3->XZO8XaRL@#2d0n=D$_tSz_vw|6$Twl{WmHg|Tn z_Rejc+uzyW-@R}VPX*6qo0Pr1@otaZ*4T73z&-|t(Zt5m%JSd-Un2P_w`4zhH@^(D?F)C?2KR81G#GpnRn z)u0h4qHey24nVqVyTC3j0$5oHQiO=5TXAK76xkw>B6pp5FOX;jRks7^LmcTD{{TE^ z?r~*u4Idz#`1%s$dwE#LL2#i3Mo^{rgS5c0xH~y0A`U^YCPf5l3F@!N9llCw z#LA7A*kCa`*dN{gK`XTe{`Rh5K25_X*DaMZ>SfU{S_r}Q*oRM9J zj_OJ{L{K!U{-ca>Y0_SUAyBF1!UhQE_RrhvmFY4kgq4fWV4hB=v)PP+jZCOa?;gXC z6gSL%60r1egMkm2>YKY8S01`}?$R#4B9qDK0I~z@b>PQ(i@P6Qx^(5)XPV);habA~z!h3sReB{F z0zo)U%_@Sf_b*kz~wr;5BK3OfREh;VO-h(Wt0Bjn0@L0DmZz=CDn@rhVb`K(3JRB0CX`dNRF>ekO7 zac52X`xiF%_Ha;k_V)Pg?(E2L&^;b>-@#X&Z3MFf!IlB(8Z?QY9ov>dXl3ovKzoU2uu5@YWf7oFkTqFC zSC8(N(Mr&x%7nd$wCgjpuM6Vez3(VdVXOhu$_cFo;|3!Y2V_z=?3F4X= z>UEbMyma-EOIy1`9rGw_EIKX-5<)N{+-jAzvwiN#C!gNh+Is)}>)-wEcbP}jo20=* z4?X-3{=q-^(wDx3pYhmZkA3o!pCt11(@&!lo`3#%ypw01dB)}xwc-**VX(J%jsbk@ z=8bFD-d`@5abB9lWufo$F@CfqyM9_5@vG@N{!%yH{>A;Lo_-1?R_V2kIYR>7i&W4G zy7d#LpZUyZAA9r@3{=V>5ZX$(BIRHmxexc@FMyBT1+j>!O9RtLIQvZ3XP$ZP*3G*I z2M6!Je@#aL!zeG7{AG5=afB^n(T;_d6A;^-Ri-J{QpS?v+JaRr{G>ZTb`h7Rd!F{z zfz_AvQ8cRFDL62=RAC2B)krY`%q6#B+oB+tt7XX))LmHSo|}Z))^N&7Tf|9{_Imv| z!Z7H0iY!f?gVO8wb;M*e?vLG(6jmzuBKRdbGrPUbr8~E-2YKX|477JLpj2**K* z%-YYEfA(k()PLq@{@UY@KQS5&XS3-$@4WrHzxyxWeDe(!WBq>5sa9zdnn3$#qc!th zh$DS0Hwv{cjr&1Euo<*V`!sHiN@=tvHBv7>r03L&7QSd$R2x-rO*)r^Ye3(bw}HCE z1-Tc@5dpz4O@qS>q$~xn;zkn$B5V3wT9GwSkQCztIy4!z>v~O9kV081fhLh#O^)|8&_^>`%c@pcza~gpxpvZ(c)0|uQyA64yN6pV=?Ic2 z<7yMl6*Ai+P8|M690dpxfhDVpPL%GqN zEHBb4i(pEd8(dekJq{my{K1P?_IjhJZu6=_II(WN)V}WHmUyC3FYBM*zc?I@-h1!; zZ++{t3OFZh?w;dYC)3!}y(6Z0Cq2Ohlo#FJ0NY0T7>N2N2EtxcbZh~yfO=h1bbx?}#VtZBS0Ztj_S0Uygog%M;YbSZUW_(o z^u9=ZAo-3iUEqYb5|_m-7rB{sMuq@!WDZyaWlbUx3^^%A(=LT{b}AMyC&t2c#B@C& zK=CzDoq_Q~6@;)vDb}VGBu+0Q9LuFr0Q@zkg$87Cc`txTBHRM&8rKm3KL9jvC~idn z($@q527txap`i)GfhEF{6*Os3%KQ%^hF~L>IAsYf9e_9UQ9#xVT7f=RM>>D`kqdnQ zd`M9d#X+E~r5GI&A@0ytw;QZ35Ddo!`WrZppGJU!3)^qGq49QBM4Vei)<73u zF%O9Jhca1-#nLS_9)NqvuHzpCq49@YfQX~%QXNDY(iCn00PcfHL_t(qLaba6LfU8u zgjNJFR;^NS0Hle%-`Uk;CX7I`03!4hBMp;3olc2}P7vD10+EQG>eCz8H1W`3$h7sk z-gx-XV-M_{-w0CXs$PH|28r(_aD>Bv$osv~?(Y8i^OxZ3hd=z`_rCkR8#iv!kFc@7 zfBvU_>T}OL^9*DA^z?K#o54Rrkr1}66|i*s_U*&NLlXD*_qim3zjEQig_Gl>J9qD# zo=o5pWr8LJ=y2F`-Ap{z%{BL;BgW2y4?pLJl0J1oK@R5(U~Bn^Y|3RlX#G3Q&r2^^UJ1j#DO+DNkk^ zwU}x)wPGw8P&*43shl$~1Pk?DD))6QrW`Z~iDQqn1tQfH2~TT+fHeV_ZHxB+d<(s8uc$+Jh!)p zKQfxnXLs-3diR}oUVZgPFTe7GrY$x%#(R4^dSEXJdwo{QX}_P*T&OuW0!iSs(Oeyo zYjt4u!(Z3cFu)Jr4kdOb1}$;5Msf%GOfV)J*ATTtjlTyZ37-DcOQb;@%CLtVxFnZK z4b6%Gq=R70SeDgJcyHYH=NJvWUY{TJ(E0qx2Mr={ZW}GmUs(ZUowNXLv=~5;dR?3~1ujbfGC-EQTJZ_cWUGY`cgEsI#3B%}_)ow(%RniPEb%o# z3)fYU2@h6^h%xUEL*k4pLdr4>=q5%Z{>SPrjOLOyGisd&@9_TO zFn03x^~^8g3jFhz&p+_U<*mJ8;}z}!IJ}e;?V;5RC~Ytp4A1Rd*xK5G_zzxs`TO7h z{>jOyjkkv$dgNz+_Gd3%yo9d94{$A3{2|I!82D!F9QA{eB~ z<+2Qe_~C~ieeStW$GTB2X&8q@V93UUn*C8R-iQ0}XTqPMF8^l)h%+vUFdPA#@+67S z<7h|b49h$lvW9tde1H-}11y(w=Eh_)VWu;;nMD8*COlJ%&l~4GIR7vP6JOD`K!tG|F~q z_=d3V1yW#x6hjtW2gJ!W1S>_NMF1l7mvx-WS2`gy8C1m0N1+IDLXUSd#*X+od7E17HmVm>o7p=zXdJfu4oz=H@17AgpUQKsH97 zEJ7PRF5Nr{9bqI9R*?yzAFQknVD%EAh!H2WOX}v*rDy;EV6Jlo?tK+hVB-_8iBAq_ z2-(0DRVlIJ${N}3o_jz>nTUk|$br8)!vSSDXVyU9h})hJz(h0gLPtg1%f23e{P8%+ zAVSxW4h0G#QpUrdl@1X}Dxpe93ty{PLKmYWf|MqYH_UY*q$}FzF{N*qIhyUS! zu(!8oyji=9XZnG}?d@&)^dJ4BfAl-Q^E($WUi{Dh^Z)$n)vGoadTvMUH-G&%{^>vc zr?0;H?J)}=)v41FjK`AeiKn0X%;!FR`GG6b`2<}Oxf^HhP--}t%yxJ7 z|LT{1?h9Y|D`~t*Sw;dpPzw=6M<{Wh4R1&OKHP^t7k<)&{Lcc=w82Nj=re*{4k-#; zuEskNhA;Ux+sPxM>EIAhwyuaPb7qWzWqyMCn9X$y7G2<$!PeT`r==TR!5oL`-Ln8_oXv)qzv(?V|06;Tv+^!}bjo?y5 zbT3#m426b}>o8X#pd3ex6qo^<1TKlAAK_|pIwcEb1m|I>y;&3sSwt`d(xE|277_He z5izhhVUf$0P`hbi3(4~QRu9_gSv#B+P>dzYpgC6~1T2$3At~baj6FiTB;7Sr&9G9I zjsOjfEYhJs3Odo!xip#}Se!(oLs=5Jv|Izr0*G5WaY~{7h`=Es#L2QAq!#Q70#q5- z^`sMmPe>J(4p`hOB@3WxkkRZULdpgbL&(MzBW*YwZftBo-E8Ex1R2{>w#BYMoxZg|S(63v$ zAiB>|XT#pl{M=uCS z{*%A+@BLjoA)1L08A$WV9GbuU|N4K=mj`L455m}*BZ|!bVA6SvGTimgeeQFg`polN zyW7X7N9KYc6BI3@;N)cT*rQMWt-tw84?g&C6pT!^a83vqSH`4uiiP*#KKyy0`M-+( zFAA_>K%7x)U|IhrpgXdx(9jV~ys3LwjyTH{F3}Wr4;3q7zKf|6<}e|^F_g`tLcbHSE3ws)A+3UZVPt>v5t=EaREwIjh+Q!{o(~^4(%cUE$H^;aTK*5 zwE9HG$~YOUE<%jQ!7*wS zN479vHKujc`So}+{l)*y&tJH_6(mhj&YQMO!rjHZ(%mONK0ZC!+1Y#ak*Ch@U#6CC ze)F5Z{L8=m?z`_oin<cel|NdA0 zI{6GK6Z~W$O?QW0JR49-z zsM^{~q}`6L4=o-iQ0}7sLNrTo3?Gj2WkDR_gEH2-;4niinO+LC}%Zfj2CEyWropwv)*P7!DcC6*jey>UXi$ek@lgO7efg3vB&{G(M&w59X# z5cGHuBv%#!F#^O%Ap)*tk>C<3=S87h1ZpJ&fsiWT5c}b{5}3_6aPDbo?j0 zDB@HHdlmt#2oXX{w}w-eI3fIyix7xF({dpTdjJt@6p^)`LBTak0Ew1G3b_;q-{_EN z6y!2Er-9IjlZDJF=-8|;Uc89^K`ZbxNTe*x&@ZTk$z*cmz?w`gq@zZ_p|cRFB|@-X zlvx%%^zh}M{p(-Y+V0n0Q8x=jTNi!WMK_-{FT4@Qx84*5DOJ^L3+J3PJ-F|#J!v;{;ALX)qnRF|Bi;Vr}_J*0ZFc6_u)SL z55dQK9QEG_7`SU#CH)(MY%~U6&&|sEI^*wtE^+mfSz)=8q)BhkAN8`q*47TchaO_3 z@fbgB&+q)p-~8eie)^aG_TTv%KmWJ>#^3mb=b!(~rHfa}qCPmda_ow{>X;BUy#LzBWXqGUlu8VF_GxhvJC1b465$E`uzQ3V9G zd4Ss@HCeUPAa40lGv%;lLFgl+C=L_70zc8SJnjYd1Ae2P9yZ<>Zf%eG?d)#uo!j0& zzkB}tJ}WJIKZ>68+1=gS+vYbM_T5X{bj&vEY0Fu^1S3?-r}8l#at`#C+Xj13+3Rlk zHIf^)$hK|VL&f%zI=NOlPN&ehRW@b_&AQknYT89nte}xVyBGi~<1N{*0A+3t6M+EB zSBU{?uj-0ac~=-13>D!TST=)faVrG^MhNXs5l0zI&_WCPR--eu#OYA|j1kI`N(_Lv zH5frc4cRlhE26Z2n0_FHdpNw3fetea961AbKK8^Ye>Pd)bNBagt3c3jE| zVMmdkOl+ExnYgjB{n(>VK6v#}ot|||tUnD9xexc@eX8|{)f zI-H0!kkd6N2qrm`mgx;Fm&L2EzV^p|{ICDLzx(fh@e5zNbm@T$=dWD7`Vj8K+i$;r z?b^+3IM&o_nw>%P%wrcHdwB2S`QgP&8xLOIyLfKAw>dbsJvxU~-WZGr*?1Ta(lAZD zH1v|7i^47pnkew}5-?A%aE2YMK--}`+p;cn22@<>kpmPa%B=N5_ugi789oJAvRonmoj)n^^Ony4?Nv$$G^~FoL1-b^$;FDklrZoC=+68`8j*) z-gYXtNdAGNCZ74}JLhpoh=XErd=#BmkvWOeG(pW_HAdsXcw@M^IojW68Nb1LcxRUd z{l?bz$bMXsxV1GJZwyA`Y&gP4NpMr5xJ@%(x2t88R(lC}4q{BVgB0q{ko%o!e%WRx zjFr{2h$y(-b+V9<^FJ^-5h%{wKs&;%G0z4`kSpmsK_WTlu3>mOASy1^#j1;B0r_$OEnOSuJz1AJqQvW|V-W?BPlqS0vZ z{>rcXw_pGI*RNl{L2HlXmjt#o^C>;qm=*{dqoH=nO}|(mh|GPMEe4Y6V*} zUzr>opJ0KXYelR3G)1G;v&_Fty_R1jgQ@qCxN~7xG3`QxEHbcy9*&ArpwfL@pbl0q zS#n+H9=j3HHj;wQ3lnK)fEGDLD!q&~ZTP1qIWx05tD(XakvRU8eCk@~{O!_i+7MS6 z2PQNF!?{<>uLTZZqhV%^rUsr}THJ2!m>D3aX-hmJ)}?iY+kqPGB)3M2{vNb@0FUk- zSl3I(t=FSqkxr$=Nf*;Fpzo-NXTt}G8=Tz$52&;$P!|YNyG&q z9jl221vrV#e|y3xXsHjpr@nY>2csd{R3%~FS|Ji@`pFQ-@LzBq~ zZUkk^a{0%9{LO##fBnZlc|BHa}peb_(e>&xV9ITX!6<-6Bb`^7A zItXynbaigd>iX4R{ndZ`kN@%Gk3I8W{1^Yl`SZKXeY6(ozxHdt_S?Vx+t;suu(N-0 zIz8P;%g;PE`Wrv}#CX(AXGaBV=s=s5UW@9FL*1lGvjQDp7Z?u6UX-j?vXCUNB25_8i&Otq@YuMDL0qVnx6-1Y9UfH{sKK!?8qw z2*{QQP~zT1PF{qWcnm6l5hd%~ zxpNmUUWC5bcMV*F5g|1803!u}39Rb^fx587Q}?zED@6(+rj#n^adPi%`@M9Gf|UY@ z*d=IIgyNt<9NUkP>BCI0 znJ=3(8Q^w&@1^g5?Q37Z@xgKIUdn>=0pM`h_77bTS2PpXgcL$9UwP$~uYUEb`b3nT z^y$)6@1tXu!#r$*Je@3;`SO9Q5B%M~`*;7-|MWj)FvB@n8yh2f`2Y5g{_p?oul(|@ z8@G0Lbj)b6$it|6#8kh<@!?#i#8|sy zp2i`fGfxEy#D#rE#}WbjIzp(Smz@V9ABB`6Uu~H#CDIfr0wO?y1W16Gfj7^?ozIlx$^Lyi&bmuZer^Ct{0U+mwa0{od`w+8>+{Mg`PK@{vEqr2) zu#V2A%1pLeSlQXx*;=heT7+~QZjg&-BXx*d7a9DzQ;0T6u+qP}A zDFTx^SHin^T+H~mbRm2;Jl$0#v|bsA7TfO@iSr7NXuJRghtGJC@LXN?-Mh}mU6sIF zh`_FT@Cv5a$z(%fICk&e4T|D*9sz(z-N7K<;$32xac=& zlm7Jdj#>+%`Tg}Dx2P}Ilhzu5?F-?25& zUf2@G``gbx^OdiBDNcrSb0|N5te6^+wkb17Z2hj z*4MD4dAn=7 zREvRlc2qYCg&Kl3qYwUZl&?jRb{U(gyi`s zbCfeOl!~^2Tza-tLQI%Cg*suDeB+BL#ZBpug8tjONgac0*%9HeJnL3DuoGs((62XY z%~oTg)26F8M}f)FnVFrQoz(#wQ&W@E(^Io^ow>PbJg256fRz)SiH_E+OjN7(`M>}} zhfRWY_$M!zRaCib*~X8=Ng0;1EH=~0EhvFLw5G|hF1&>Vly${0wt^-T5e|3je4ICK z3DiPb7DZ$bANSPxaEn!wIE-)*#@*t-L0Cj+d}BC+TY@=H7nmz)Z6rs`q(W>EvW1*K z0r2PQc-tUu9l2aMPwX)!kX!so&RvZKt(kCG!DYvV-+0&gxLe3X_XgY{T5fp?;ikc2 ziQ$keI8Rc+9|YjSTij#7@n#O4!;uTgTjbGc0IpbcVs`R`TgN|cEHNPoPYeUwMu#nT z0^}{OxC!idg9wQyk|gqN+olg3+&??pNz#F>;*@HD5d>4OHEXrT;^Oi%&wT6Rh0DN< zQsL*L6drhy3~uo062gZ#Ng4)lz#;zdr13TEpY3_vFeXajSUVQIC$vLp;A%q z_Ew9Lw`I#VVmo{G%=LxqIx4#>Y zv|(KI`$@mYOL>%x(yWvKZ?aMvr^8;{>!-pe!x$BjWu@UDS?dnEtNs33Z#anigGfWh zy1@=*1exUD$o0id`B%1co9vXXuAPL5g zS0zVVg`)K&<53XhUq7Dmiryk~$U*`qkQEAL1fapV>aCWVIb85Q9Z)UbLJ2z$D6EuV}88(_hy%Dr0YK>+XR>6^#dP7}ga1Ys$ z5DjXm%q3Y(4w?1gKL#Fd;k=S-)3^r0c!Ao8ZCJlzV7OxJsS7q0~xb;yUgQqrei@)T*I? zj>RCtL0}wQ;gGBIAw2oS$I(WFzh1E%M?d;E1H1m31#dZ+?o~ zRVl6naDlnyie;5hYz+#G@d)$-;jOg&k2e2!n~TA}oOr z9{=Mfy1m#c?x+@2`9rfIpOtdpSA6wl$U>;mM;tEKkdp%q3n^MnAo84tAZeK4C0-^B z<-c%kVcU-FhYuZXwp(i}DOqZ_o1M-S`1ZNyUeL!u!_to3I}RT^NYj9yK`#%3mU2^$ z>>R|bQm)*3>um=Q94dQZr5vj2Nz9wHNk0(1Gk3&nkkdGh-t4BWa&>Bp_RN(=_L84nvpfSigh`BkhuHa5+RnC`x2ILb*h8YC%DV;E%v{qp`W z9So8z4~7vYBm>7(zy_W_%Dgnm;uHmno<+-4fG}~AqvvDni0nnu1B$G!(&It@moQG) zq-X%Tk$D-)8qp1ohV*vmQ4JEz4H_7TM2y-h1CzO#JTt7)aHxKA;*&9_AN2zzU=sK% zRj8o+e=BK}!U7o_B#giZrhy(Com+Worw$H+n7OTREi`CSQFxhbU`mD3(7|G5|9gLE ze+m@B;Rwk?h5$q+_BVJ7L#3;YJXOC|tJc={8+Rs~6CG_fo}6k=P3t3qQ`5pIlbyNg zsaf}%nw;x&rYAeoQ&o{%^!l`!=rk=v7Rqd zwpL+0;PqzO@WFvl6x1Bf^g18MGj0-vH+;aC-~b$?NVI0DMa1LYf;QaFK@5u8h+6`4 zMJ*W58ruL;5QhA6#h+}ht*wz9kGSP6g24c8O5eQ>ku$R2YPI+8pWm@_YqjdO{*oz@ zkQ;PTDf@`~@|7zuzVLD!*_L=KbONoHB+y(91ZGLjF$UqVkj68j*8X-qB3Z63zkZ-i zUSudhRdxHc?rmGQA3A)PMh0WNtuJ?XI*W@7=P#T_J?z=L>%hSSv@dqXh zaHE0Qz`jRT3xhh^uW;YYqqi+&qBSm<4onJ=p-NCtP!^9eI>kwfy+EP%2bh|85Ouq& z(XfvyR6iM*5)H5_0GG@`6f-%zME71XqwzIEqe&VKx^d>@bs#a*O4A??`gqP*kjFHSa$c48?g+@xyj7V<$tA#bt z%=i4PBdSqx{V{?qh~fsGrCDrervdNi%Ey!xMj3#Kt;Bd~%tjwK&FNs0Zll#`wraK* zw2DJ8Wl|f7=eBg_=BDff6diwJpF5u0vSk*ZjgKMoo9Hxbzj4)lY~NVYs76`yH3A>p zT4kgf3Ni49D`o(0$5zNyt98K|dJtCR>K?gY5QOBI0EBct#L3V1#7};4*o;RBtZa|JEVr&z57I7$7_e=5Pj4AsKhz@&*scge&g4eb5Ku5iudWZQJG#9o{*&WeP4pfHric zLL}d`$}k9e{o$#TXD*( zbhBbOZ8xXyd+#HST8Gw)e2}QsrA^wTABf(85QL`lJ&r$-Xr)f);zo0wI(6y`U--iG z^z@^TKDu@Lc5EVc0j2ibcb@y>uYMIBPJ2%Cx}PV9_m7V3nQR1MVoJ4)P0^eM3Jz76 zqg`mOBU@!+4OPm*RP7tO-bP=?9Z+W#aH7SMywC@L<7}9wyL2E5?| zgLG6@ihjVJx0fqQ}RRbY1HzXnJEu*c3v!H?ks6Yy9Yp<}u*-0m09N$DV#74UD8+DM)KFPi zN3tt^G-IOCTp7=xtV7|n9@m}ZFdC)kd;~&o&GP znVgxKt~bJ#7E@{@rrxLtQc5Tl0ZB8iR35Gn6%~SKmE5{bg-!9V*|D*YBg=&(Z`f4j z4!;VnwYT~y+v{M3@)1m3hc8^6gJ7y7_LGE--i%HhQF|dA7-k>{SKtWE11Ar8*P>FA z$lpO4yXrsj5Fxp9QQ>x}Kh+D3R37rVJd8XY*WZ~uYqtyWEzU1&yd zy<{uJbRtaDJ4afJMV zzqEuLUZ~-5+6(>0?p+6u-*`u*T+_-eZSOBEBb&5IKM=i>M?qXW{Ld5mh1QO0_~IA8 z_~MH%9y@mI10VQ6rBOx4116RhuKw{?A3t&W1YLok>ZfU~Hj3VJV`Il$!}sc?vNwo} zdabJVi1xQ$snd4SeMQMl#9BIN0;v@AhhGUQW%N3sGc9D0<`|)b<0y%ecn}RD^j4bC zH(KfTQRG_5kvGg zd6vMYnIJ-GAqf0wCPZ<745V`Ual1Re_+1L&}8GsEvRMKi-y3MUW5~q1foh3>=4Y89qCeFn;ASbnrtB{gG@kCa7O@ssCqM^ z{7lilan(u>$YIU25~BaO(Gs)ZnZqeuB4nG z7hcQ^HJV+MSkTTYR0tkr$klm;KvWo9JPn;-C&nfu2+I^=vsr7mo9%XeqSKn_G^eH} zre}3%+w9z=ezViylIa;u0L{z*Ql_S+I{Z2vP5AI@HUX0rvpp&}GZij_fZBB^rga`< zMlg^}s#dWztBQG;+6y1341{AKchBN0dL+ zgHkYN9O4&_0lM(xDe!jvBfk3MMp;ygjJV}$pu|-(5n@-N8gWbh@xejTI9zyG0t!Gl z@Ry7Xf55|=Nf}rt*yifO<96X`4qQoy)Cup>f-7-jK7_=_WuI5bpaE;uX^G30IvqIx zLP5R0dc%$#Ge8IUCGv_ERwy3Q*LUo^^7U&Aue@>s&JjE*B5E?J*9%mTdK%zSt3u^^ z=90KgrJ(BFbn~&v&I}?XJ7_$8j=~$E59nUhYVAAkxPSY$y`U^XA&q#_ z&(d_vCT-FWLhnonf;xc4H{YKKgD#-0qPBkJSAK<_&3oVb-h1!8x1c?b)T_97?);Y@ z|MJqxQkJLcg%su4W^mWdlT(cved$r9NaKvIeV(NxMr=+cW!NqoJCz!dMvyu)cB~_) ziHMZQ%RcwgcNh*-D_T0vq?>K&=&09^R@Zv{0bMTXS^{F3c}vSOLu|H}=}2|2;u{$8 zv_zDslw4U8I%uLSjq?#YsN6R#)pX=&nIr_O^;+(eIz17HQUI_UEQv}oA3Hy}sLE4}6AwUw3L z>Izn;zp~O_TjNpG>khkJI?xy%kd@A=&o!vzG`Wl{;7P+flAh$IQySF<3l8Dz+`4Uh$eP$8} zlUkcHIn|n)Zrg2hVnS!m>hM`YwjD0f;rG1WXx6G#KTxF*mUAM(gyC>*ekv{dQA)0G zAw63sUgPR~xH`fUjva0IKyP;Q$X)T_UE+5BE;910)C+8zct|tgESOfH!LGs&71aV-p&1z$=|rb~^yuL&TV|YYAgW5)2OshhLaI0G zQJkGWck#7XPiEtFU1A_jw98zLz2b#|Pjlz0RjERag0lb%dOlVDXt>NZ+cFTB+9mng z;2G%&t!RXGJZY;X=%dp7*7-*t{ZOmbY&4qndSh{M>34qTw_bYr+grCyA3uJ~_p4;i z+Fq&-NJ)I6ou($|9=QJljrxQg%C1I2_He`SCT-FWLStR?ZX zw(2vJ&6;1qsk{h)FoA7_1qmvkLRgalTPKC}M%rXS zJY-6@8az^dD^;CaYC!W1e;mW1I^xdFi=3 z&dm6c^K`G^aMjYe6_E*wgv$1{VRy?F835WW6@_$h6HIdmA{lSUu>mF@9hE2ISvf-<~n%xHg&tqCQk8e*Y#z#F%Y2m`??6(-iQvoigPet+2Q57ea@ zl^V?kRYAOIB4$LGiHV61fAk~&=)e6Zj$v4M;rW;T-rxV*3rpwjy62X=@46?6OVN<# z2}~R|+rB$%l~#W6z_Gvd<3C*~1H@fr9)TbOU!UUJq)qxk=pDWs^*>LvUYay&<>i-O z{_WrX?fdS#@1chtLXTkAeGJL!;2Tdp{nS(6s5a=Eb}+=%pnqido_*V^zE=#>QIhv2 znyqr0p&p101uq4mt@+Z(Qiam3{CJ3R!3XuGM4bg7w5A=@L-lo(Di(UEQ3GvI>8C5J z{qEXOO9_LjUn%RWwWb)cG2jA}6*d|pi2mm~D(G5icthy`5HQ%%?Fl-z(FmK38WtfM z4h#>t?jQlAxS=4ZYBHHu@zYfr9J@dm44FnZ1Z?ycEL$$fm2ef@;E4yyQTh?`P@o7v zKPg5V2+(|ntt}<2qQgeYaFR$lPb;YG7*G-=15~GGYP3k8T%^OHmNX{uFpe~HW6NSS zNkyj^r&i6<`(5ANqfgtJS#^98wIefuKqWYXJ^hfT99n=f9zD^d4gc(ilw3B+Be|2f z4PND7NiFozPeoXwEO3w*`Li62Q`UU1X5A#T>`QX?CFK}fx_t>QKXBR5wq4ie|~;Alr@mu$<0KEOr%BRMq;Qet-}Rs07TR=5D}p}K3`w_ z7P8p8clSp=`qBIDeZbH#)jv3K^0i<4_rEgHX&k@l(EQe|{a#FaVP~7m7mauB2C+UF>IerwhHADgvRR7yOY32E za;jYoe0_pNXCwqg2^Fs+#*yhpsY#mFBPW$aOM2x2dyZTwaFwM85(VSq$$i-Xb)5<0 z`rdLF;Sc+cZL;S3+JT*>IwDh9&>@)W{~;@MG?t7Wc3DGUu%vW}!BqglC|*G@jS`U- zuefN-m9a?OEe_X{9_2QjufuiiT{q!`8BqSl71cTP&~lAgvY&j+lO!r7Z7&k!gC*Va zqK(iL)_b;iEc7@bZ8}xrcBHr15XKTwAm*<%5H9a7Bsheink!t#Tx7uY*`e$M|#|sY-ytwIoLP~`q4Vh`BMosXpRjakIQl&>;@w8>YFN6pEflI2?ym6}Uj?wNLEL;P2kYsZBw20M6=bZ*BjasWUE_z zuGn-}Qc73M;U;P7_PDJ0<(j)N{G#C{xs?gyS#3t5QCT?Vl_%NhagN}h*1F-zt*|34 z)1+ySXdRLZ4u_pAX{FB37RIKL8%?tv#e?RSKw>2nv(Uj&0Gnxu z7On=W3^r+#eh_+BLlBxeE$Z9f{`TiT|M}y`k3aO#Lo+iov|hUOX*BrS*PeL#*>9s3 zTFrJej9Rtof!&Q8_HC~R`dls69O>yeO7&ONnL`s1p^MXWsJg$V93iO(6bsgkkY>2m zehHTA3%YbQwT6|RWE{oaev}ZcjxG04BSfmR#iW6;7BVWl7=(3<6?!#EzzSG#tiD+n zOBoA^K}8oe>S3#13w)1cQ2jsjhcbGA3Uqox%o8;H!BY9dc5Y zdetO~gp5A|FQk3T72`p2gG;-mus23X*6BC(-sD z%#9{~FgjS8E=DJbw0Jg+-Cmx)?Ze3FQ}zZ}AeA%7=m=UtM!6*$D_y}9QX%fKX*a=2w)Q#|SmXcLK~408 zG=zGiRp+Xeu$|WAgigVq1ba-jbduY2#}2&5vxQ@3W^zKict9mp_jAXh0Cxa4*lX?b zFca$XV)an96aiZ0gC*b#JYi4`q!^hb#-gAmud~f-nj>>;+mcC*SG^g65Rc5Ypg*s= zn2Ar1sN@iZ>#mMe_C#tvsz}xl98n>y9AQB0Qkcq>ALx)8WL_zyNz|y8ckSMG^w{CB z>T8I?IM*;wd1N>v;CJon(yOnYymaX*HJ8?6!mxp&QVH?Ysyg5fT;qq@@=f;xhF$TY zIfPS1~j~%}I__164N@&6y(F!dspshgICT-FWLhtrb zkmcp&Z+`Qe&p!L?M?UhABS(&)G0{(`wF~D@Kk?)fr%s=3PfTM?qCszRqH%OzZRfTb zeU>thu!({oHUvWZN5e_6neNApgMRb6vXlNZQuh==rpw(^>(vbDFc}_ zZET|;I#*1bm|e1^2*j;z8t6N%y0_tFBb1tkD9~mG8x*&EHMD~Sh!B3Xi$wlBDOdD? zi;|~R1DFj%7G_I5vO^R}n%mcF$h3?e`LToP$*F9je6&Qv3oCv#kRd^v+KLu~OL{7^ z;Yj^@?u}px=whZvnh|p>(=O&U-@qMgAQ~M~4-?{y7$tfv3rG#=+UA`B$U{J+w?xCa+LI5RPRlYLGTJ}+B0!P?Vh|c|V zt7$MBIuf}qsf55qR#hUG6x3ICux7jh6oDy}h3AGaO4I=qf>|vc0}Y&VA6i7 zqlG2~c*_{pkONt6G$bW1t+Vs1DF2{oMa=dYi9{p9ju4}6y9s95z}8~q(Wa97S#&6mMB9St>buMCJfeB|&W?|=XC z<2NNq3eVkc@5v{>`kBxCulo<|yz$0E;KC^GTQ8tWoFy;S8F=Y{GCh3o?tOc2C<^6K zQq|OziUu$&0d3MI{Q&f?h9D@ElP6C;@x&9?u3h`or#`iJ?_R?VD2U=)Pe1+C(@!rh zb!*KD4ML=Y`I+{O2OHB<4KIr`OpDn&^buWMYmHI_5UUZ zVg)at)@4}IY@{Wb+Tt>bv@a%2@JaH)Afd-j$no~OQUQ1MdZpQFhP4K7>075U9W|+7 zR3mzlcr8}VBUA&wt!Wt4#3%!(2u5g427p0oN}xf54e&|a8$DfvAo?tf6ea}dksUXc ztQi*q;3+gf*6aw8GP$>$$=G9~oPl?C47URx@Rb53G-1ROV&Fwj=RjiccvY!sK}je} zjYGCj>JF_sB6hPS*v;QvNk9%=DGDc3-N*3|JV*7*vY2Y9ny52plPr(0xW12( z_GDA5544-6%kB=Dotm0#fTUZX zl_m~r3bsnqK!9bMT2JK?npeUJ_)lX|s&4kPEbHeydBZX?_Qb6UZEe9aN@bIL@FZp@ z2Le%px#BjTu}sK3Y&d>+T8x6SAEe$WN{5q^6Gsl;ux=g!O8m*hd(qVzrSJiVHeo!aGKF1hTYE{1m456;7LI{m1 zUq}J$>3OkMdFuclw-!XeX;eJ)(1Q;>^bl2XFz6%Yix)0`@ejZ7)Hl9y=Uq4N+O>`3 zhEd-ufuX@dwDh!8jsacUx9_@P|E=>|c4V0_y@cQ(hy=9>K{n|JrFS(1L2*3(_~VZ~ z_SoFq++X+$e_?WR(kUGb-yePDD=)wDTAX0@o5TL=wEEH8mS`cX2BlR;$XqH4e( z=N7#uOQ?f4{Xn}3O4{MlZj~#ccJQvo=mmfUDaynb&PJE=EDkH>MlEbqwWW2W9h!mx zaW>L9qTV(MLle2fl~0qhA+PH9&%)mac|)%{KeU!MR~f0yC(R!ZJzFa7mG9?g0&|jy4Qvnus)X4jS+4IVFX0 zpg=2rQS$r4bhR6mFi(Dn%u(gLcI~xLO*-$VhC4m!6q>505sXS|Y|6tWMp|+>BMl-M*9Al2#DqTq z#y9{em$cKz7yQ-tdaBi0y&g83wN|?^(b4g;?t4A@(6M2ZnHf8`Z5lWSeCbS2gJX13 zey3w!Jl2>>z22z#foG_I>aEHG5(eszRQEMK=zc(T;dNzE7TRT&tMNImq7swkM*@?C zt+r^Ul>n-T&WB<#d5nTe6G%OXhxAQ$?bvqo=%LPJI~oj1BehW2(0b%jZWy=P?+;#j z{>0_W*Cvug2Koei)M{FdP3zNirK&52-_`kC;F&N;tg7=u#EqL`Q!z=P#6||9 zIEm0HnR+i#q?P5g@sEG}<9FO~2STRO?%c8CrI%j)?C<^V`3tA-yZ`p-8B`x?A}yC| zloEBn5+(r6QSKc*{GNjcZft{|DJxC>Qi#gFNx;>mP1>YCJ-w?T2pZ(GpZ)9$FT8N? zz4t!+@WZrblroBbW%c?We(6i+&R;EgbyQkBT-(wqA2~R?Z%4C~r&$`KYIAI`1^_Z? zRNLT6Y#aKEtC8_p=#LXUoAwMNgTw6u)%LhoP$h_hr%7d7}HC7MLFTCJr6$-olCk4e#%nkX&M zM)0WKGr2D`!lAhj`)r$fm!Wn5qy7we1Wh8K|Ej5I&D=}vC?i}#E;cJ|1pXjXf>~0^ zcyJ3B((cZZ6(9?=zE-3tdC7yIn0_9jU~R%+l#)WNRsqtHWeH8GX}({kt?Xkr^nFe( z2QiI|Y^4xMniNg6*ani-i(-I;wB*pHv9K{1Tc^*(5V2U#()i|H@5$U?U=X5NCc3lv z$Xo5B$}>9F%9zbR-FV}Tciwp?m=);*3@%>0^xSjbdH(sAun#JQY-Gp0`CQ5Np56N% zxc}jO`wjr}nvDta_sws7>!p`oxqf{K{Lx*D78iPJE79`xm6fHnwUvHvZP@P(yQ_U} zmzP$%-AL!Q_2Yrg!O!&39*vd(CzDhegHULaPYob%_OxAHs&rH~uioVFh zb=}?8T#t@!tLyOlX0=wW*+C&%Iclg*kV>;%$^{t{Fmh6J^%o9RgRKseHe1xFf9q9pK@d^8B;02F?3AX};t7Io<1BTaR78VWax^R>RFx&$<3t}#g2 z?YG}{*Ilx5zrYo-sS;p6g>ORg9Qf5EM{d0HuDcrbcDFk~v==X* z{^}E7xp3jU@mWqN^g%oziGDKZ%E7O@)?Hp)y?$-!+LhI7*B2KSmKGM4mzGvnme*ES zd)+mCvBx%S=tIXgd6%Ui678I|^W@2>pq?rj*i-n6?5ad0Kb5}C-Po<9G_IIdNVws@ zqVXVnC3SoxU0$-lDq_k`Y2cJwo2yNvdQ6MW zX1_eaPfkos073BVcDqkK^;LSSnE7_2St&3S*AE?-*>_;;bgQB`AHug-xqhEb+ZWJIGl!n>5jX@4;A z{R&+-ugGd;)D9{@eIWXG-=$R?p*l72*sU|6D`(5I92pC#uA`}tv6MUIUn~pQL_M|B26aS>ar>w zBGJr?&I2LlGUb9%wW86 z-+J=NC#?smc+6ZWM@brO+cy86_uO*defKUeFV*Wc!kj#L`U_w9BE?L#!K6@2s$pH0 z+Z%;pS({k{nQb7chBv%&nt-3M4Ozb*uj!~d>Smw+t1I2L)is@L-&>0WNqSMYH|+Lw zVoY}sb%#+eih8k@*y_|>FONp)kUCQ2Q8CilE2^NXp`!q6O6KfW!W}1hoTO9Rjj(we{J-1~_D^a%U>^6L+v=6z{Y}VZ| z`R*fv)ta`b_<a zK5ZSAin0&#sDxES*zFJKpU{HTQYpluLK=@g`oRYue5l!IMZuZ?#kW$#S^M*q=9G~oL0Yt7>1_!>R(#)|*oAd+GyP^&` z1c0_sJ2xO=-X$Q&a5&tzZy$Q6W`{Qu2D@_M{3XBvMxWN0#)DR~HaXR5H#Iw8kQOi^^its5L@>NCF?r!5b3TNY@emJQYB( z7prJ^4Uwbdwa>@}c473c9d!UXe~4^C+zJzpvpVtT#7`@BY1PE@7%eQs=`z71VUI_Tf2Jo>gwt$3=^S+9~UBFwrtt5 zYu7F^NDKt#m5UcIQr{H05y5zg9|_9xzDcSGkGHG}kr6!b(UrHzit3m44cKF5{j~zdLwSFSXh)tQ+Y7mU&-auOm=IMGyHQJ$aQ)^2qyaS`R?_}QdQ z`m>^U3k0Esk8ezmb495=_uO+hjvYJJYPFm{O%ZK=`t(^$Nxjyh%|*lRWT!ek*{p^h z>e9VSZ2ZM-s$+~uHV7Z715Gw-ScUNJm5oQ-a+NwMds(3kBgBl>&^gg`yVIP;?}!*s z95Tx`X^oz()@$@vG_(=R+7Z==xD}(_!qI3{3(F1Li;EUECeeE8Pvf>*tsN+%V}tN|k zX@{KrA(wHdUh$;2jIG5#i=ze!HS79VxgBO@Gb3h}wYXHHz6ejBJ(1wG-xN`TQ{0be zjU2oaVFGPaj1rKTm8yFJ4>ALKWUGO5w>yddg^vBuHYGaFB`={vZHH083=H!MaU48& z5D0<;(}*Y59teVp#|K80iV;tVpO8QnUZ*BdZr~M6zI&0tE<(s0@*x-nV!Sy|2@3h( zR8B;Qky@uk0SYj_svctBwC71;*P%6Dk$RZeQC!LgrK}eZdV|4Aw|8xI?aK1<EE`O<~Ur%s+bdEzWT9B0p5JP%5_aP`XN z1x*YsEw8Sut*v$k{b6ihYa=;B1VNRGQ4Im9ji#2A)?3w98&F%*Vvbr+4ahR4F^=Ma z6^kP)Bs;WM1%U0OjP;{QWZb&7#MYERV?n9#N4eJ704n5)gzUrrarI$M$-Ok4b_VHyNRM3#q{-Acrs?JtWPSQCG%#fG`m8P$(pU z4{itS=I7^+A3xq~Ht_*97NzX@7oJ;KygD;z@>o<0{Ri*ANN2q&y2+KHy+P2aoG;fKFHZ zdaS7msZ?}UP(}R$Y6NR|+8-o?0a`}p%9(!`8xC|Xx}1J#v!Ruw^yT3}!LUjrO@C-| zXgxd_h2ATsGYI`!NPcazpC8yl5O4-cZ^Vx@t6@bxRbTjnh&3#V@aMi79yPL#_)(EkLmaRVDvfPhcZWg4FbYz#A;V4D zq(4&{>$`V6(Hgm0tCpKq`r?Z(cDvmjJ9g~dyVo^N{OPK`^2#gAORLuWJvtQinzwCB zr=v9)I>Z#!py<}gDGu7F^CupsaPdKzZG_>v!GI%a4%2-!ZxoI@(E}TU+tj7t3%5z^ z6bk(knNl!9G>li(2gPh_;?~8CDYsbB(4~r3(1#xdd`5z!B^<5QbZipJwBAT!CjH_-S(t9WZPs@jyg~(scQi0W{6%#NtwMJ_O^| z1%RAeVTw_!QJ$TdoStk_vO=gyx!fBDk2rNz}W&T7@x+|>Ns^xSl3x?S&7RmZUA z;N5yXZ0J;t@sCPlC7F}ek*|%YNI)ZZ`hl(ah7`B0U8E{K@qrwa8Lv!=1SA5fz@!3 zgmn_cTG^wh=v`1|v{E$=fieZNit03mKBor?(YtCLI_0Rb+?%vXKM1Y2ws!~7kemZm z`}EUK)1$rNh8r*~G$;3HX=#b>U}0(+i$H&IX0kaq-3UVrM6%Hhb&(EpkCpDr(+vqyM^(g^GcsH8m4psUF3G$ zSCMI60v#tk1zA$2#R^+R23H#HHdUpSq?mv5=!Nu^w9!WAYAAkmy-l#&bguQjcLz=EcTN3yip9=)O)F1jN&7r*giq;tK-M2^NAFtICQv!s3`cuPw@MZ^Ya zdoouQtPM&Po{fUYbdRutI(u7dfQWFpDN~sb9gxE}yl#qMTeXvbG^2n7(SRk`d<0=Ya%{1L&!$-F9 z#nMHth*#tCWh`=mG4_I@ROKfCE4N>a0*xOige)_BQW<2Ttu(1J)BwzzD=e3su_?lB z7TWf(z*kWUyi!Pgs}#e*YJY8Ib$MxdVP)~^^0iBg7tUWlcjoG;lNVop@zjgYpLqGD z6ED8-+6&LWe&PJpI2uJ!+V4jzD_vmC^=r%Sh!lOJ)e^O8;|fp^$t^db7y(RHwM9Gw z44cel6v>f3tQe=Xi$OomQt(qjLRywuuKATZSNoizvTuVZ)Ge`ZIS6bvZY*19oMD?Z zv8p6eih+>51IMJBWl^a}1(ayhDd1%7Y;q+TW)sz2Qy@`0F{2Rfr%PcWF4UVVyw-{%}z~Ewd*x{u2~pp)h+zUj2bhVq_&N-WQaf5UCrEpPgD+qL9Se2o)jrfvs+bt zJKbn(u*jfnnsy-5(Y1Lb>zTr^K|zzX6gPj;TnDHiQNp;~p|6h|IWjXdLppFncsi2T zu3aNvM61-TVkpv*zI3{8-@d7-DMG>`G`PZI%_NC{ZeewD4y!_IOuf6i}>#x6tAkUsT zbNXzcQD`ix1+q1~E9BSZ|gi5g9 zdaQtS)r}!S{nfF4AYH_RsLEln6lBAYS{jskm1u3a&|NqeBul=g=`>ph0YS(J-3&yF zoOuAL60WxnHDr^&Bl;IgR6m0TNfJkq4y&!RUH*IvrlYpTH!#UOzRS*KW7>?K>bw-UNnR$W7X$KSO#qLJ-VGx7)pR z>5>kCo|#cQx5i0J2Aa@62o&0I|V|V{$muia*>iD5I-R(#Sm3hbDd=IodFyypFDc#Eq?5 zwCAQoO=HUcO^mr^6S8?B_8TE+tD$}}NMxcYDIX50h-8qaKRAq|SiE5k^ixUUYJIJK7H04PtSl@n;2@-nkVtT7pbemBMZk{;_#p(#j>eoId#V>5xnf6b z{A58DgqP(heQENs0Ec?FTxg7B+cttZw%1{ot8U7*$zYQ<=?5ii z9Pc=y?LpEQMwoc)4K0}#$Wv6ni!Z*6S^?&7-@X%ddeb8zpC53Ra7f0#np0q zI5S!A_zkZ=Dh;Cn+JWZh>nNdEM?z`X-1pSKp;@{Xjw&z%=cBhBfRIVVs>|MJ2vuL8 zQ?JGr_9xh!fR1H6N`~1WDn)*)+MJxoM&9-7-PKjhV09P=t4TlhDyyk~ak+G5xw0CS zvT{;w#iL?~HY$(8u++$tA|6JS@~G2lPPEXe5e)dm9bkiOO)GY}LWdPI4BE))<9V7B z(1%>92C%iE5A7prvUzl?yi$f8PT(&_J7b@vdJHcO%O!mYFDM5^DacEe9KaC-bnE<3 zBjhCvpjU2$wJb`y(P(X$g!P(+d*TRSP$XWhJdxNwz?mt3=hkMel7}d|Qe~Ltm7-n? zChB1mP*h5bdO56B!V-og8kJIyfc~gjCRCzX6P+4SDb=)k#79F{kbmISDx=WL!g3LK zqq<)-!%EH9Obf}8|3Cl@`!S$aCwg_@X+8M%D@W}KgcV7u8{!0fn9ymIlimoB~X!ui)`YIzCoAP3j#3Tm**+%Zg_z=aST2vEsF&qYlG5mT}JqSE#KQLQ>r`1Q4T_4?YW%PUv23KFZAipteX zi@l{mDJdh8TG*+04NQDk_GzYhlqG{vDe<2wm6B1h+#ALP6&*>3z(iP{pPvJQY?<3i6Ry|WT+g1l^uh}-%*;;B z&(DIKlDMdb4X>P)%4;QmMJEguG@!YuiG7{cR{%sl~-bLgF*ZQ_SG>M621XOGR66v(Q5E z@9KX;v~$7(I$RGM1A`~QFvBjS3m_G?(QUG&kHkSRj8+tD@!=2$qs;(1JWY5D(j1WiFWA#ei`I%LcIzVPMfiaP%vW5C+DQD+otdZKs51h1?J$rN9*;Ze2AIG0p-3h*sRMues$#C+NxFr~`xWGh39oV{c>*VAl zf$>CK7cN}5cI_IdWg|iyE(ub04B)41>bN#H1*6R&-`x#96F0nDC=I0$rAZop#W_yJs-%U)sXje! zB?Q;{42sPsSwBH+U`COiMFPQ~CFMwNJoO6v=>T&rGPPhzcXhS9yxgTMu3n`$uAV)6 z;l&qT{o0e?eBt?*PMeXvp*H(Mit}b-fhH;dGil(OKu-04yzdp*#c!Ib?5QMhJ2ebt>4I`Ru zzc=jnc`;R1V?XMT;z2P=!Q-u}-!8IX>H1*JrjJk_$xs`S2E(4tT&n^=?GSXE0a`CZ zZd5mr2{k9t>9=<9t+jVNA=1T%o`d6pDuY|hBq^E$hbtXI@(O79(4j+N6<9N%rVR#z zmtTGvHA4M_sH=FokXr9*q9!DrV_2n)*Tu7KOp`I$O_*%gWZSNZlWlv#$<~C)O}0%%Ol-^3ldpnD1r!jXn3B>6uoGqxzCVG>3sc`ye0y zyM%C1GNLkf7PH_t)OGq54KdK3LmtM^c>|Mqgu&>k2PDb7+aQ6(sNU z7u(+U!3Hgxi%<%+F*#sKRs2xv`hHQO76nx(mi( z-6uw0{|vE{*)mO(zs5Yy*RGwMQV6`24D#Sz3nyRU(1<&N9A&=w{HNa-A?B3;P4+4c zNpqPC+f#jz)9rBK2EiY@eKgt$avIi3yfzuFn@OF#wIaK$#YF^9gV7XgkS!}S6T~2s zu4BE7GzTC$p|x__XdwcxIlqITyMWx}KGZG32Z!b4SF7kLzF1UNJLP4&auz~WDj4J+ zP$kul2ya5IA9lS=Q_yn)gDu88ci=$FF*|iYk0oVryir%nujx zBd9k>!c{zSpQ+&Nn%IiYJXexx3e*y7@R3@$*UGR|u6MUnkLOqzs{n!U)c;N@Ug+(v zg*f)1554=Nko4_oqZ2+TpPP&8r7K*>b8Nzck-19n{@$|dU+iJmTQxqZ|JiB0@4oHk z`vP(?#h=66m-ktvS1{>&f9XZX?uO5WAH)yK$qR^{zudG00JI^l))L0(Q#MXQTp70xz&s`@6IU*%h z%8ELNBCZ9QGifaPZ6R-et_KV69Io9aV*HTabh79w@>Z#cnk!SQ=c*&Qb5iFuj7~nm z-FxXbmQbE6u8Txa{lY5|Nyb=7q>1eo;9&gC_mwJ?Euk}>!&h!~@(<_g5M^W7B%K(K zuK!qg@jf{99YZL1x?Sbbxz;{LEoS`=Y}^q(2GFhV4|DEpRr z>NHjvML6rxsZ5(1Et#TWU4n0&xy3mazGG{QgSgZPXLU+TnpL(Lfth+9c?rz?%o4-v zvT5#GAlrKb=vQqO0z zva?sa{e{R?PCb(_D=-#@J0%Ff@X!=%iV6zn8=b4L2Y5!ONjdu6HEtJ@Vj{0=?<0@LlK-@nE8Is7iShw)Iq_^{lW?-mxnV!&#Ru9$Bo-9_>GT5Qz^%52H-N7=lihA((%+=S=;ftGJ_}IN22L|``_1|r&VvZFjJ&B*OJzi zI+?T6{5&!>yzX4eu+1ci7fkr2_kCvLWCC6!y?>d|=4f=x6s5IKRAI&9{32CR_iSv# z=jjes=k$Cao(QJ8@8EQrE&S&Ugox0v$V4TBo(*s+G-McL>_l@x?Eu&zo`~iXmn6}% z9*W+2Se4FTFdBmUK;&6-DOR$Yi+nq7$tI6#VLyn#pRI)<7(Nt zl=aqn{YIaPcg3UlctXg2TXN8!{Ankh!N#3Av1yjp5|=*)Y4amZfE@`1w6$9hmlrSe z2D$_Xd$aXq!YUa=Hhwr{kV^qa8R67uSAK7QbMw%ZoedXF)Xt3k68{dzO~G)@Pd)+Y zP|)_y{7O5GQoTV96L8S=P&=b#2H-{M3P_1^%H54;j_al2_#XV3hzL@O1CBK;(bWCG(X#FipN}K9VbxeRMHXrJTz-O;?z z>1KVMs;St0a}x<9j0`(Gz0A#-6mMC{Is{o##hqJx?2Wfyn<@{}(wOgFqE#AkhAORB z6yQfj@Au^nS#pGY{OrwRpCeQ3+1z9{J=y9k3M+Prie1>HEj3x>hQ#$dxGLY(D9<=wO*qGoJdLKt+}LKWGqrgzW7B$S{yP3yG)?$2@R!nRog5B9 z*i>nVVU_&3yu^&-F_v!v(zHcmLBqIe-2vNR%P0f2P=51mHcplVH|jwo+@x>>A4lV- zJsL{gxlZNvdPqU<_u!f(CJxuho_1b@dm2cwPLU4o2>8Atp1rK3UxT7yG9CoC2&6oW zDDg*bsA~?J-JT@Zb>(ewy1=tA` zh6^9x{rv^Pidviq`nG6A=uCobJ@$)Z3EAFll>04^5Q?s0Weh4!P>Gjyao-|BtmqU= z@5uG=Kpk|l9;Z>BHa1A=g22(4bqNCJKM&D-`FDX(nMb@mdWfjc2o1h3?pRx2jMox~ zGbv(ZgJM=qh@g;TS4IgClE)c<&Mu#dSNg>u*=LpUS8j*C9@Oo!A%(_XSG?aRNq85- z0f=};1%tszRF>SE)OIq^<`D7l0&T8Yu#Qt*&cNPY|Lp86Lv05j>DAdj#(8&I zu(zn_i~Qum!h$NBn3$Lv9}fe;1@nAeD^l>zJ|aOD*;w;*YS+yl1h|26lpV(<#4UEq zqLro21)0a&dAzPsw$*qibyWo!R$P{)I@l8!2qpoL)e-L8)vYx!Br;$kUY>GkP}Ql4 z0Vro~Wv1v(wC-+Ua%gPX?T<)fmkO&wSf3SZ#B|4zHN`d)$KW%ad>USst>pemvZ3k_ zGoZbBe;9zwQPq7LvvX0GgAm!rmC~e=S*}=CQ9Pu3_dp%e>7ZjbWsen7@y-jUCjKIR z@cA|I9lT5}>8h1H=cj(mC(0Q_YU0*DazWVWGfP`WR%6eCal}u3Zsm-whABs&q>gi5 zLYCYND>b&jy^31u7AvFI?eYSBvArHV6|4+2&eq_FUq|PbJwtAEi}`2c*^mqIdtB0pvWFfQ+;qG@p91>m zei{to$SJE5n4(UXD@aH%g~W4zZzQ=He{kV10cP&7xxbyfyhck(U%aH%Cuyx43@j7BZOmQ5DM*T!8-ck#f#)G@A-gWp1fpZSvR&@Q-z!<;=zrgJ$}4zz70zW2ECju|GpDGI5_a`+^Bt9seRjg zANY6*H+*f-{Tqx(iyN|N)!3V#)lW&Un*_lOFvwO;rvzTkYXQ2+rr*Iac5Nr$+2aUD z4y3O*Yt%i7p^kTwc;AN8w4t`vQO!|wm@sLS#oAAbuHPvyZ{odb^@o5FX=3X+~;Jw zflBS*EUV)}Yt<9DF9^p~>5%C>M(}$D?B{F?@d>V{OuAy>x)}W${`u)g3s>9@^69b6 z{deH$RT!~-5Oyn+oZEB)p6b&HO<~p#YMnQ?c176%nx`gu|F6m?r5bA%ca(g{7nQzN6?~LDcEj4Ni464qvE2*Hv#a=vXmOezjhP$GC|6vxWhpo4%cll*4H8X9a)ENFG)5DA zvaN5Oltdm?sZ*k8p6+!J{>3(jC12t9$S8LzG^u%dF|an6ZiE8$oP{S*Gofbah`M8u z5Z6MmDT>hI>)~VqgoxbrswXH^#09p~h$;4%lHiJw+UU@k5yi+gGKbJ8!_~-!5F4ac zFyaBh)1m!Mqodq$wRr-%s_Xrp_G7>M6~Fsmc6Z_-JtkIh133>L`F|#MAa65+2qBCA zk=}JTVE79B0QF(^%5t@v&|H|^mFR$GTJg-v@zgV~#)g3jg9rBJ*eQE@v-`*Ft>woHZw?d}}3Bo%;?rZBy z*fnbVSX}adMA5{#czIhbFPXnm!R^VjUJW(bF0NoJcpE|pyz28(Fw@Eu-n_p4ToqIZ zf6ZC^-#kyubx9(jswTPnl9a``QoC%Yq%W8SKXU>Pbmg8|@R$tCZTE$=h70v*OA)G>@9Gn1QFMxT?j)Ugw@D|helY{d_CgrS*9K$3D0>=hY;4@xfC-!YE;MNgF(@nX zDLF1{m6*{iEu|>81hjU*S}=bJB^U-+`;Ysf7b%$36kcZPYAC&erU62km17vG@W=Iz1P3d3RT7F3Hcf;AS2dP$e@eTBww(wBo6(e- zS)pn~D7H7#%YIPaWHHnJd_jJ}TXF#QQW_#Bb{x1==g${WR3C_6_HGh$%G5%02n5Go zxKW)c!Eib`kv7$!;{l4|tBOEDRq3>Hg@-`QhQb^rEn&X~@#eK39VtsJud*`4WiBG9 zNc1d!o=+~ejW0AVb|N2abdM5DgyaN?t zjqeoy){vgIkb)XEK?9=~I&eEaz<8k6IosmCuB4-0LbMZU8FTF7c&8`CqkZmm3pPrW-wvItX+!Jeg-2HG(NCbb}xCO_8t-Z_(o z5LeBrR<(NG`cj%@)T*Wx^;PC#UI*1G(OnQKN{a0sQpU?V#X6r-Bv=h1Pna2(E7lgr z3|L9jnWk#z;ri4_yK8uwFXlxP+}jo460h%17l9_X`i_Qay9FBBRW)vb@`B+dbeP{| zP{VkEp9GwS@undZ=FNWf0L-2Zn*Tp45HjhT!vP%UzkN~%K)BVopp5F!m z_~GIER!f=&b6gZiQ!z?a?Pk|uzVpu?Pd|{4Gne7f%UJNr4QmIxH2!WudZf@Wnkw=iS*jkx(>1d@nlguJK*BB+gbxP%nF-}qkK~GG%ZTXLK{nLM~*IM#iZ7{Y{ zeVW~$__eP54319k2%wKW2o2+dW? zNM$IU-zdoO(K9ja(8U*U#x;B;x(_6$lg`0Wm&NurTGDxH#ukiW&3cg16fh1~JK8Of z8_4+0{M23?x{w2#jjNNKP}pDDgg0!)D(_Y!62;3tFV1R@O=s4`84yh67LYLw*ZYIk z`V0Oj=5^t>k@PVl&Dnl<*z?yw5eL&k)pQGdgh1b?#J#!#SU7|45@b}+SXrzT*v!2^ z7s0H#xJk!ks!OZOK9asnt_w1>_>SmKZcffRa5^uY6Co1DAo%07-TUwM5HYxHAi&x+ zwH(t?gr5I2Yy}}Ub$!XTgTS1!4x8O!)}`F_M+k9phYAu#xtIwHz5$GT5`+17LZ(~F zqGp!wYJ(ZkymQQjY^JAX?h#n?oS8IuGND^0GNwU9Jw4|X&es?{&IRbC&~jXTT+IDF zi(XAzGy>%zMjV=<5s)ru`0=;Sids;1w0u>Ak|TB`4C5gnA-0)<=NXuY7(U>${&}+} z!!G#kTW52#Bo~Cu&ofif>|ejs6j6{xQ;r|bSDiDwCbwby4E+A>Tju%V6^SN^66fNh ziu@+JaDt2wo*3me!IT_`Xhg-uL_GLa`Hd)^*-D5#HOu{XS0u`{&31Z@D6$oIkraQ) z-cSs=K$B-IEoQqzE7JF%VF>E1XnL5*7&l}NYR8EZ1&)^sk{kJO=;`+vF`l!PR`_O2 zC~YnMbHJVghxT~BI)v*|oeIGkMk&K?bUuE^cuuGYa4A*H>k5{Doj|wj=2qzA*7T4+ z!iqc2N`Gy3!%C%uR5Bc$^eXr)(^1Ip{`uIiyQRa$-uZZRcD89`gl2svNvg#ZHGevO zfmy%(`MDLjHmB?6`QQHU^o2?N69XNcwzf4x9XXA~f+mBu1ts|4pRD6^Kc&+pg2|~- zoN(!|ZjetS6T&Pmi*Jt2XFbBnYv+kAoRiQBQkdl&F&@2VY5s0SibC*whC zg_uQQQ4H2I5WMt8kYNmkMe8Wdj;o?d?8P3X6QQ9NbyAem5hPHeSnd01x*IPWkCPJ;I6x37T-hu&Fy9#@ZqUZW}^ZKANVNz0A4*n zWLMB^0NXGzG6E9-Hozz2@!FH@9SBMde*1#bMozkw!oAamTf$ATYh4@1rc{7rM+0dK z(i3^6d?`ZY))sG2pcrkWF`yG8%O@1(87RbB%%r2hN}Rt73#;e6mpIJ_2Ee|rrw`A; z#w8#IXX#gZc+pWjZ6a`mVWnz&2j+nqgU#r0LNA9#pn1cBC^U{z>!$@#0Z3Brg_8SU zJw`i?F$rF{^~qsTI?1xVDdM4eOuM61KiNevz|0EQ81*ibVm)e21|(>OsZGpZKli{& z?wx1Hk(RoxVSO5P0L)>)050hJ%t;qWMaL+6*b@kyg5NT)lVru6T_k7x!~TQ59{Z0D zI7^{l0YbCCNbcfQn7>Cx^ra9Q)t}Q1$~=CnXt{$; z`f-%wu~D7G@=|@!FUQjT1W0H)-J6|{8;^=^IzeL18*ooi(7e;PpvOl44-k+!wp-vg zJt~(R*!)j{ir&b?*z-Y{NGr+5;4`q%%o#aYOFOpA^`gHDmMk1}<|9JI&7^Xk zK$r5ePT1?DGbD~n(@3_B4z65WR5bkKwmm!hPYy8SF#l?GIv@X6Njs&_=X^0*e5yI6 zZ_wf7b-dHGZ;QNci`+S;hu>ZqZ1w|4PaczffjhR!h$(1HF)KD!?e9tZN-8enpWyx? zqg3i|6hZ0Ma{TEm^}FQkVyf~GYJR1;i0kWdyv<*M=a_dv$!3FlT9klkAt>1lZ55^H z%1^2;?48C-taD+xoDhMt17CF^a^smg-9CG33PCvqdy882i#b_hPLDR@C|>r#`+IVT zg<`F_8<^aiqRyZG#8D&Ylr`YImoZD7rDIA@DpxdhDNra$qM|^X=g*wAKoe)d9ghw| zl9hUrfRLou8zVd7wlNHIYZ!|SQ?KjaqwWK4Q%q$$UO|LmMXUxPB3RNJX=Dt7u>wZA zksvw<`Cz&^#;$^-k@Ce;bfH&(ClDEl7$PHjM@j1c>de#9%MhY+LL-e(=W>|i(Y$Kk z$a|Ul)p@7V@a?44^$;USUG#}-OeP3HbA*EB{0NaN>Oj-pm^$>R_e(Zb(0H|cEasH+ zm^Zm1ZkSCJE@~!F!=8^w&L|_Ugo(P%7Ekp#$U(sb2D^W{)YKjne2ywo)%n+{T1b9Y z0D&4$PD9_HU0MeNuMUL%`hpM+j0G_L;EhgpUm<^O!b}-X7l3@!KW}rq@ z4I~D$Wz^+WgwewnAq?dq<7t2X8!b-7V~l}j0L3xO3{&^H+D)jVBlPDT_K(=4isw2r6`p=U;X{U@_Izu;;>89}53(A2Xh+_}N@5V=EKXwM>)(S_h9L1gk_+WY$2rQl()w4htZz^A= zfBx}ihxM-IL{eT+QN2t0`GbJvzA*H{352h&8(YhW#%yqDU~rVz-R$x(3nYoh@M~%e z{IiRoHNhQxsbEcgEn5a4C@j zsJ0|7@wr2_!o}3G@ns5YvGur2zbgKIkk|L44IhQ|j1S@4nE&Pj&T-JV%fHNC4 zV*<};vMg`je`yQd{!g^^stf{q`I^$9cf}O<;U9GRnO{YR(Q5=&O`#`yDq0hR1Mo*U zTGL!;pnEYKdZgK|3<=0dM^>ce#tfbi6yZ`{k)=TWD*G~3sK_@A9Zb3hf_ETvfK)OS zi42$P`>^czbC;Na6(h`~fl^+T{|=TE%5)F{Y0bs=`MC7sDgMLL-X8S@f2ckXqS``| z!YzsGyxAe-hb&C_Xk!wK7}<%iEkvXM5<39~RZMQ`SnFBP!FGx{1AH*a4K9_+106-b z#3vK|#FuB;I@K-9dW=5=)Ci%p0?=MnRrfDq_6IOzWk?8c7~^sMGh13BTva^6vV6=E zebUXJR1xFkG=@eK)52WUR_W$kPf-(>goTB z#lSPK7J&>Vlb&tvohRm6p&9nY7^uMCAEjgP?lkbQzXy&0uCA^Ku?zFZZfm(GKouw8 z)C{<#YpC(vJRDA>tk#HT-HX72NnFZ`{JxfyNIp9~9Ig_1b}FDz%|LJKoJLkXoxD;N zdrZbd0*#<;o(Pl5VGNhrh?jaICzwKTKj)H;$e(OJP?WXBu8(j-iDCoU+5$-xtan5a z%PabTQ>9N{;fDkLsgR1MF^ZC@s?h?=+fDa3uM_Zky9dzF zE+jkYWFYAeNuHn`h0NAW!~t}ObO9KQUU!WCL{nS9-FTkw0ShBSY4mHpl&v^C$BwJ? zpydoE2ne-!Sv&t|;E0y(do9Z1C&S6_Pj+cRLu!ulvuPr-QX%yw1@^zyLlIx^zlAQ; zBSCgJD7#qQetLId11n^g5)v)xRd=_k25pUa`i7sG86WV|;N-^oz)csUS;`R$UP&-f z$kYn)%vGGa=M{0iC@Qsg(F|_#C*TH>FOsBk&sr4^{H zi^~}0)XZRzXuX=NtmN2ioD(xRC(!HrKfUSX*#`<9J4NY~gfK~`_Pl%0{*`QVfmn%> zkUU1YjVIxnaWZ>`E9z`Q0LMm%T3FvUz_KLmyqlHNV&th8T?im+Zf*p6 zzAxbguL6O17ughWrlNh?JvIE`d(OG|dW=CZhUO6X9Vkt$LJ&O&PozO!A`mVx4zBky zV4(pUcQ#yV_Dk{Erkbesz9)u;8>41*8N1?0f z|LiM8!Ye7ysg>#f-8=K1-SEFw zW@#iI>%gwVf0TnLqIVj;po>|(k{&q^xhl9)u}PYrYqfqjW!UDqjWp2?7JbPu5MD2! zqW=u!!>vk@+b~~>Cu?Gg+UldQ_o=GM?Uk9q^N-M9Jj=qe6fjN&qUwO^_BVQ|8`x@=2|H<@-y+V$MQ)REmyVZ#Oi#rYqpty`yA*;gi;Hm z&L>$+b{Aw*uEPXM;^eDAbXAJ6A%zShkpq##c>jCKCs*mm=tzcTue_qTYv%u~z(W8# zmiOZv$=VpizW8MjO4^dInyN2uee3+|ViGccyYp)`VE|De4DKkD&E1ok%a2*}Flq;$ zN{;VGu3w3YWkQ$-J$V6Ib%8}clZXeVRe}c3-##?ap;v^Ut7&$MRa=SD=el^L{^~*i`zJUhwjG>pHziP15^KmDZx%jF;=UM@@l`-*AXNCG+HpK)v#@kflJLeKS;@b*pnSHOgh>#7*lpD%f@KC zng*xC`t*>b;igg9#0R@^il(X2o|1D3)LJ#z9iX#O(D{C9(NlgzIacl25{V?Sh+&YG zShZJMTM~%UL$oPIsK*e_7ps!%$ofvzZKeZ8rcqmW+vY_iPUN6y$ttgqDOVW|fK*?L z;*TWF|GY<8yBH5Artl0|+*?=j6ih}GB=^jD1w0{kgR?E?=H^n4!Ihd*zj%Xb*`T?U z5&k>e5 zmE$$*1)3=*c5#e=$W*)gC2-gga(^w!hMbuHw()$xllOdY_;Gh9e+ZN-j87_*TEoB> z5ooB#mVdEM;vqiw^@(3|d&L9iB^puN-K5x+l>lv`o!{=zNMW7N;eBl01}Pwz%8o7X zb)d=Wd>%Kb6l)FJ{QxHyBfv59E>wvw0BtrZgy7p0T zK`0MbfIjROt5k=%#w*J8zDrw}Dr+nZ3>+L~pM{n-Sv(sjbEzp$QtmGRg# zwN0v&@dT3H<2e;+56n2++BWOlAD2f?s{LNCX`&@M*U-<=ha_rDN4pixGsXykDx#m^ zvN&ahH~-Uo9Xs<>S17(aO_}4JW%UT6g^<*e50}JWYqv5+MF#QmoaL2Dkh8P@IfL;` zp@_7~mChG=)*@uFonxfQdo5hKVGJ&x6nAZ#LxavuaA17de{q1Lp1{^sw0({j5+$&b zQBCa*w8U!eMsNycO}?##5!@8i**)aT$TobuHe`uF2ZJir&4DYW_-L%0a+ zhzBFId3riJNpJce78x-4epSsLv!S8BHYmTWk3*gtCwo=b=ZVwqsuwzOgOsJyJP6Uv zSF5tv5p9PtGidup%aY6O-UO(GL-K- z)c2$t^dN%zoMPM%jS6v={C*S~&sy}C1*~`%>Sc>)gzhGuHDS$L1+bUPmq&ex!Tp8H zjbCq%0TT`pA%d|@l0^=MIXDFO;+~*0eJb(xw{A0j2L}36k~47bVD|>nZzxyeC31UjL>6iSI8p&}0A|iXj+9VUU@XMFC8OcDQ=MuGLWGZZs>L zjTI&1YLZYY5TvmNiKOPs8u|=Ed%}cR{i<^%NpevF`T4`2wArgzUO|EgAH}2rgyNxh zFd}yB$i}e7ts2FHl|5dD$>mwV$9s-GVmN1#_Fg?neFeebWsan2fXJmA2Z(Vo#JXFZ0t6>^zW!5DD zTpHk(4!lbM#cbhnQ9aO`c4_-M1*X|^DDK=1&hY1TsEGgc>7#YLh%#w${c(f}-{?+^ zMa`uKR*V7Cr75jgEy9=tm}QZ(OW&b@;)v3wf&iS7F5qjzMEmp0bu{OdB|$G4}dJ=-fFYybQ?+3}m)GX7E;dpg$KQ@b{yHh6RxUCNlLdXYgmS*Pg& zt8sLV^bMEH(m8tfqRh-?DXD01wti zSJJh5A{2fU0hcI1!)__6=BILu@^p}am8(mvQ#~0sZ?byDJNR_0PClI|qP*!#vB^i5 zFR<57pPk`RNQLyj0nM%5SG~wuUm!xxItN8DLIoe8DPCtt->7~dc2G14-uQi>3n~?# z+H2DGbO1NsosKk(9)e%~zfQS*1JR}NLzKg6RG7k1~9E$PpI2G^}%Hmb2 zpTr~98i{|ommU1crQK$0QW$F2fp*Ro%iEEF!09%GHt_*xZQAf0^-0Nex38R{&AAk- zsIKB%f#8%Ws62p^6Ot{EgaWqa{;FPHC;+bmCk~~&u&@w7L*@SOX8-tjxi384sP{KY zkycjrDpY@~_dYN$9Tw2_MFrc=;8shT7iin6`pU5pinAkNi>Q{UQGrlwg|^U&Xs^mj zD#xiZ7kc9xJh8Yo`}aF}6UBZNIa=L_YFV_}LSNaF$VuuqSNB zEDC1S19zEbN#H#a4cuye-e4T&#xOjOmA!sVVOjlhff<6<-*HMhraI+A*}AZwAyo9) zyKQlI9b?s!sC#OYZaO$sMnBA%q^@9G5d!gXgKJh;s~S0x$kv(Z0U=sCwkJz5ghP=o z5yviE?S9$sR2s?d+K@HwtIGQlywcGKWBYtP-|fcE&I)Uo?Y%AA)r7|Bg06!vFoI=G zz_kWG+5%pPe|yQaioeKEd&|(u@r=WM91MZP!U2Xe`n=7LD9q>|=g(jkziXkK255T5 zxeON@$OG9N?HJNXF?1?Bw zZbBGb9gN9!p=6@mHwhvvLd=ydq$jlWKVLAE2`KDq7fEZ};ZyPkzi{4BJ0t(2lSzf- zty#3K=AIVW%HkXO{^ao>1CDLO(upnfv;HHxW_#PXqr5GKRHzM~8v}dvgtMURMW_CI z*JM>EBzLD)*3o+Ybp8-YMj7DtcJpY>$+Q{qzo;cjTZK_TxC#qn)D4q(tj*YQW8%lJ zo^x|Q0OlM53pQ4wKxr$h@85GwhvLX-qGH_mlar|)S59m1+Mo@@p<*RjIl$IjM2*T( zIRXioo~jP>oNnRKUzu23G9twLYjy0j`_k#7>B_i?t{}dsaS0Y=Z9=>zuEN$v@mDpEH?mlw|`8lmKGMJB?o*t) zmy|N~ox#QeK&u@rYgz5Lg7)YrC6062#8Ebhpq)gbhqv+P<%P!Ltn>K0W|XKi=JU;O zv&YdrFy#_o%sY#$(I(vT!=8+9=?hUhzfdZ8EX8nZ4Z?N6O2LS)#p|}!(s3A*HGZW> zosf#hDuX;LGd9Tr!*zC8G#Q{jA;!%I*{q}6K4(ccmF&~PRZaggpmuv(6Yb=)$1Qr) zytd7t43=^_RBODkB{dmp*sb;rpmNwmD%XgT_69$OqS=A0V08;3A&5&7cxUC)mc{nN zk07wW7V*zSNe2uSs+Qc>$$oDr46%cNw71VY$`_y_=%o}ehKS`HhCVVKY){%RF5Y+e z6zhrI+IMnxH@;rLzn%4oY+TdO_a6P@3LT*9o*+rmh(aRhtfVy(W^k8tVe0$PcQm4Ly~l^}+>;;wJO0ZCMT%w=nMJ7JV42%L(V9iLv^0^zj8&>4X ztDZN$)hf$hm1N1N36pp_C~;<2xAmJ-vh+@yjKDa|=0}w`f=R6fl2+&V^@>81}TBKNv)gGW^C4!O& z*pm*>^{T6?7+F{@fv+aeNYVcrIA>M^Bai3x0KQV5paOPDt}>IR=3;@B=hM}8Ypb@v zu_uOwpWkUyrDm;OYg^k&an_W)f?cKv?);YkRl@l)J`LOy&A4H-k5p)o^pHSN%$3x+ zO7*~c9Kv|}19hP=@>Dew0UYQCp=7%jYz8yi8B!_5CuSG&+E~S~sA}#lzlDB>K`k$n zh|zT2yz20>G$iN%Kjl$cQUaj`l(wf%{e19fcF5s(d+HG{jeMXW`%_w_ZRkeU7TUoX zN78w`6C?%-uizX>PnMjdY^TPg4 zXA@Oj9)-}*#~a#^Qb(xCuqfSixQs=N27n&s2~g`_iDPF1VmNgJyfhkS%QL7Z4wq_6 zYQ6H2$la*+1plc(Cq4;UiC0?n)oE06>D*gX&YV1nRO?j28>1SAe3xiF>CrmYDCfk0 zK!o1!l@0#W)EjrvMMKOPmPnh0Fv}CbRc=}uQ|bT9);R_v9Z6m_;XVm?s)@QMh}RT{ zz(AF?;*YzL(^T8b1coLx$7Wt75u(V4wmmV6vM4q*fkl#(Ge8EU`vlcK7pCU zP9VzER+7nrr=e4Nx>ysJsd|ztipN`DkP{$jdi0msYrG52v`Wh4GW?BITy-s|@j1Gv zf^?g7`$*LUU}wGY8>;B3hCyz7lwXt)>l`7ue;PY`dHpEc#u93L!aAW>s`t$@rZXp- z)sQoMp#4TJWAhUcndUvU=*o?J5AIkh9?yvQ5SXEhPa}7JCdAkFO1kB za5mm= zRw`qU*Vjse*EB?!TQv=n3{!?uCnNBxN#jILt`p6MYIv14cNOr~p;J3!G~bMph4@!h zUesPOsqs^4UP;S|E}gSFaA4OMsC;_ zl9h3mdsz#9@hKNo6MFlshQ}8_Xn+dr`pGrt^Lux%Y4*U}xzTdD1rn2rCuu(pd?9T; zyzl}3g|@>t9|Ir#w}OFj{pjsc$PJKA+uxdfHg9v=fxo=p3Zz_ZInT`6Sg}zA+n#gI z8vOk_>(Lkv?Q2%tvT$1MzFQ| zZXeXLs@5}-BjOS@j;km=KEcRKP}FN$r~!X?br(7!GK3v=`>$5b~>|x-%ccLuFnPU=S0)aV{6|FX-3?3cYFW4;LFWs``mu| zu9k*|yCMJAexUanLXIk$NgWg?X#~p$z%M`8;gD5>A3l-mYY@~TuPAYr z7NyrwhGt~NAsa8{tJFF3$*+lrmURr-f z`=3Z^nKfJ5i%NCL)EJ^GagLDx=TEIb9UV~06U5r}Z^F^@zzgqByJ%+gCdu(M^$Maw>X$iZX zryjz9AIvVrTWNiuO_Lggvdu)=!-P9cU7hRgEsz4LuQ0x^*u4$%L8W;a!IDUWtJKz)cF}(}i}UVxb1#C}l{CY_ zuWZtP&TaAs(b*KPw(@Jmq9ne&t7@=wG-iYe#Jf*Md8Mib8JevYzt1(CmkJvD?wy z_tQ?nF`v*9(%A}#D&?24JLou9^Y^ddKV;S?4$3;p4|_=;@+c^B$f_V$HQIwy!Jn-N zqh-}g1+Bg%dxk0Pj0gAFwm@dF%86q6JI*FW9eP_T2U@t=Uo8ayT6? zna+K+r&#mn`BTriV1M_IQ;me7%lC^*zn9g`i+gXFA9(4E%D?gO(|0*H0Aaez_vP@Q zCT7v`i!Ro!HB2v&88cFJ>&OdGEWU(jB#1XmuE$i&e z{pb(Q={g&R+D5{Ww4@B>VK%!ZTxs>P(N*sT<$g^`UzUJHY@5KgW!3O?2mgKRHV?V)rt@)K-w}q${uA|8$@ldl8BVvQONqyg zm+8OI;gAA@!A?j;4IHXi|Cs{NJCPTIr1^)bmZ!LQBMu^Zlb~Lh=i?VJT8%Og-bcBb z5hyt@XWgvUEq=?y``g&qxVz(-x7Z%mtouAb%Ri8Q_1p>*(?dHGs&l-2hlY26DF4Lk z@)|}Q_leK#?h0hO#&_1>zi9w3LQ z2=9LX75=>l98`n716S0b;wJ-+59b+$>}t-$1BfK-k=3Vt3-D>dB_8wCT)2~l0WmMZ;7NhIzp8ChDi6Q^Vd<3;w67wTg)V) zVThXY3E`@H9G^jgqI%WMm9g&C8|4ctV4Fe>N2oXDbqIWgzsP2-$NsVyyLb?sA=yP& zY~s5N%gu>Uc5aDs?B-)cjHZ>LshoScv3U54Cg&m3Q25II7y9j&-5)@Geq6u-D@Wh< z*0G~a`1#68)|dbkWKe$L9A{qMru(KZI)GhzXl`a<5=NlCTZ3}#YlStu{>@=vqOV&AS5JJ$v z(D>Y-E!I^i_<0-M`LhD-GGP+}6}wir2j7M@(*CV@@P=}ZbtTQH;TJA}y;aEHS)q_Y zFiXB9jgI{Bb^(DQPnC_x*>b&-NH$Bau}*Y9GdtDr&RJT-<6!N%O zGX+))aIN1DXXlx36n<@ZjTXu%2rkCg-lcQPU9RZs&_<(eD? zueqPKz3Vru`83;nyUsbUgF7N*v?X6uvZJIF)aib(FMUZbia^)q9J4#KM;L{E+l5E? zz7_<8`WmcUvsg>Vm5)oQWmRU(0AJFyO+=+I<&gYKrG$8F9mdaZ537LJ>)I4s$_zi{ z5WG>F6@G4|1!GEm_iswLjYDJ5+kmUska`KlrJLEsIW6vIs18aoh<|q>#wsuWTi@i} zv4jD)r54Cq6a?1BKx!~2u=KFqL|BP)G=$K)S8n`)6%lsT>SSMVy=?tR^JfYB{CaHMMKYE^+IOGv2h{go-+kEyc3t20Jtpzo3V6+H-}pxw zFqXLOH-r-DakbU$aGVboqbUTIS6Fiu%zw|dRpBI>@qu1s(?B7zVjUKgTa9n|vWKu<5= zi7wC*>n)g15%C+_kLPe@<@w$W-l<4C?z?ZI0;j1U9R~bxnx$Mc$VQyXSvRe1;`&Sl zFk=C2lGy~YYZv~W&5?rNWbwtF-r^;mAHA4#<@9%th6GHVPst%xV}0}HH?YJ$QQ5Di zye(jCkrXQ-QjpbImU?}u6I~38S*|70)Vm=!XH-+%9MAT*TQFEtc!y$xA`CoE3p`Bh z{Wr}q3&cfCVdM&agd~v7hwA$LfCqy*+D5|5Ji0lECBbqG&51%E_|Z2K#mn~iV+gI# z(9zWM`b(k@>b47cDinVt|7n*DlV01wm}A(^??9EZlYRdZfGF0p2I?B1=do_L47LJ< z^E(C%D^iHW2raX7FtDZB( z;k1H{sjJ(pKxM8fDaH7K5&{Ufor%YPWYh|=gHa;3_Zt;Mmym@*BtjpSrDTcG&P~PJ zJmpJNAk?1Mrx4>ucVL$LH$v@X9-?B;EHV+z6apzPRWc8gj3t*{PS}$+jd(rwpH9hX zO+$TsJ?4)bD00>?j0|*d@G9ufMKC^Czw#eh;IU`#&3%K%YS)Z3?>guk|GmDJ1(Ic) zzO8~$7}7X*GLmIdTYm#D&otzR25RlDo-ikMMafFdvZze$N)05F!2=aF(KshT#yB!m zsOds4W9=0OI;9+C8x&wqOMCT2VXDTpc0$;m4*?_J=k=r{5xi(l8T06V-;16793Xoe zsA=f+yJhCN{L^PZi-hmS70p)(8M$@2`3e&BI9obs8J&pJJVu8y~eWhmglZgHgL#1M+W()$$d*@ECM&O(2EB=CKbDi=z|pV9Sen|&R&)e-HdJF zQ}MMq#I_ROF#%=5^EQ$&%Q z=*0J7mA7HAVd~0?kA?;ZIPF)Ne0Y97fLje0ddwiYWTL;)YA?}=fqP>C=VRa(Iv(P$ zhsfvK?SGuAXWzb0zK;7T$RkNdZ2G_-DKkE6OCRteaukTkq=JWq$()M88M6$m!^rmY zyn!PPufJE!2(%Xf)1_)GP?O>gj;)*$>#S1`HzJ9UT6XG57NR(-oUOC}5JC=&3oqvQ z;pz;bI$Cq;=pM&Qq`~`z6NE|>O3UI{sJ?vabl&(Od0~<5?7XVT;LOLVXdZb@gj*)K zv(w>NYy*b{I4kr@!k1PyTL{v#`@vOjJwis+XgO?bDuTGyZ@QM4s@`hdY4v=LV<_wN zwBEu?crQQdrF6N2!|s(U_I1E`rq-!dya<2H_S1@G>;uth4ZOkZjF}K|pbpE^qOmMS z;O;tqlFrx+M$mBB^Yqr3nm&VXbF+b$&)`pI8%=G zQcGPE5D!RY`0ypxL?$$bQ;yV9q+U!pzc0;UP|G?vaNA#4TR^30!Y`+DW%A1ZY?7ui z+#Qrtf=8XV!+7aW6{JA-kIM$6eoF#o>@BS;WHvCtnsG$i8ByC~kM9?JEC#+zs03gh zRT+V2zAuTNHzFT{tZ%7|IhoJhGg| z2Ay<5%w7jvQU$WKAc%b+kN?edcWcv@)bKpezkkHKe{Au_J7 zi%hVzU)1G1z;%lKCH2#7`|7cKlLY`<_wC}PY}ci~&cNYI+{>4+@+clJiRSG2RONP7 zH$6{elYJSFK?p>9)IsL2mg}_0sHA*@W8uS)5PFZquV1+W|IjyH4ry87;B%1Uq)@PX zPG6gDF|j(J zO_9vywHGD({xq)OxCaNK_p$8{lfOb1#VL|P)`fXf19x}lCLdFQ&tQ<<()4tkl%e0p zZNcY%T)-)vdO1gKOw;vor>n$mkY+X4ZVG1toIWgAp&!>_{Y$*tcs3?-V+ia51q6vs zSsfO|{Vmd7n6$CE_eA(ARag@cnd0k^iCnTd5=TJ(iUblch^ZN~kmK%Kl&4w{ntr@> zN~X@r37hA>CT+6m;SaIleViXxJTi8C@)0xH?G}F|E3o>l*a3U$86n@$A)h2nbYZ3; zwK&)?h=0>ykgzMW_8He{Rkr~qQ~~ZX99Ti&h@x6J6THng=#he)tCnRT4toHV90$Bu zQ%XXH7-_ty%@t07cikToUE>AY+{vPYbxzm_Ego*;gHwok3Klka(ByBN$ibY@3br8) z5)4O^*bxzB_uguzZ`cSKS}{%r{Gv%7HTvM?2qI3>!<>5WFl$=DQIAyektK#T2Y66$ zH7>u+o+9lZwC;=ZWY*NXN#BCi6On` zBB?`7Nww)WtqD+t$3}s7fccN}5U`6EunVp!C`=AKJv<(c13!)f4|M`M=aD~nL>?xj z7s-%yh*uf1aAWMECjJjn6DM{_-7$mWz{i_Hh0$SX=(~PW{kqA@91% z*d;=TIsD?`&(nDwXs+>@zvor+nX~^5HxT;74~>sH_6RnrP(_Vjjk8|}|DnUpL0F>x z=SNKclnXB^8~&Y-5yi#fNXbXtdi=}0aTBz>v$ep$cEL5L@JY}IFEtO46l80zT_V4X-?5>bGSTHklc zK6WEXeE{9ET~D7|SMOV&Zz7+psL4Lo7}1f8x{$6jiorCRh5&=jE2s~~7vjiBQ!Ao8 z*$M16;;&i^Zq0JpdV5?-)=`aj*;I>&a74W12z7`AW|#w*x|b*bbyHXkh!E}$+f$UZ zLM(>KG9TT#)f`dQMmuLV7;gwHbT$f1Ooj#d&U!4~TT6S2wI6jTUX#tdWZF&Y7#JqX z6(VI%drJzY#4v*f;zUi;E)^rA`t2pC?F~aFTv6dnREV-;7avKNUMSYgSV5 zSWrV$MId#fe$sr`gnmu9u_yE6rF+%VdBZ&5hbi(8f=-M1Q|=HJ8fE4@G`4^tI)K%} zLmbrg)~HR*H;EA#ZHB#E^U+qv;p_2h*`Zgpc2wbxy;8JBlvA(@F2wG#m!ok@}btol|Ht& zuKIIKi-Ub#EpRY;`UDx1W?YVUtGHFc1#btmU}oc6(#)gbenVb&0uOe45v`iDw_N$41YHP@&N4kgSa?j^kT_d?9}$>rxV#p4N_MS}>+D zV!ZJG`Wi(jSnB!yY&|@*`u6s3lA;}m8EFb6hWW~k9~bfwP5>YqXZ(BM7G-O;cGoe! zNWtq@x}&;DBq~{MjZEled5Xq04Vw!jRFK0Rts|NL*)@ZRkfobA_HaL*;zV^(Z%rTt zMQSb~A@C5Qicn4vN))l?>Yo)MV^$_cIssUx5_e3=AwlztKd>NWTl3oU7`W#1x(3P@ z(A~%o&Vnli4Hcn7xUJSNqTyD{{f&c5lJSbBDtl3@uwv5TD>vq6K^~SEl#HtBiH*Yd zKFdmGNr>&e+L3DzICgw;*w1h<V#5Mp;C(fcv&K^c@rc6dyqRZHe*5Vpzg_qeDw?%@I$LL8_)-Ov*}UK^*r+1v9K7 z!q<2K6d}<53zSz-XWqdTLpdiJysN6PaGeg3cGUNU`N4$}cT!Ay_&a1P70KNI8q`fx zS5av z+*9kD-{Mw;I{~iL=5&cOY}4K4 z0PJuHk(Qp0b6+&`qp>kaAjTI?YUytqplq)bC6vY|8*tM9eyo@r;C9<5a-f?egq=3B_4=FP6R@D5Z5$v{$@ZMVFrH5fqPf$HQEB?(7V=XH2ZL`$w!C996vy8A6P}w-i4HGg!mhL#gO#GLT#;)YjDbK+%$07W1 z!DWsJrDut8Pn=f47C=QX@;wtu41&Kb1al#u46Er^Y01=;##|W?BEhx{79VEMZlsX> zlMBl#oc4%|r3^E<*0CJfKVtVYd&TfFXRp8ou@qyrOMrS&}{q{=>+3yMk& zpVImZk&WI`JUxTywn76~$!XU|TeF2!MY7@dQnuU2;uI&T0LIlQ_$NdkXJ0dwJY!3RgGx>x(*P zcx%7DmRFA6IQLLHWS`|6DL;$D?8Jy@W+7ZYzUqPis$l5tJ4x2<_hxk?FqNQGM>SjX9t4#xDJQ zsFEjMl}-DPp_NqoX}BW=e8GJC0dc)E^%-G=b98JPhgSPsun3&@(L*lxi zV0;;OX7^z_KI^nFY05^mU`OnE8Yqu`RHByI{Q$HRQ`w0)CBZOerUzT>PD#e!(^c%O zHUbVs83yLiH|@DlzrT&fu2AYG5>utvvf6&{Q4b=Jg;a1>SK}m1L0>wP(dP>*F~k5a z79)iMx5mdTDaxvp8=Vv!x-^(WK@n;g@CeB`9vzaov{i8W3(38b5Vt|-GdK7{cURPr zq9HK8OYXl|t|d31Fm@CNYBTJ@$FpEQAP{6nrKKRaDXFH6a*2R+E!EHuJA6&MB(aK` zO(eF%Wwx;?WT$KHNQL@lVv;e#Ah~IV1_n4`?sXmz=wE9HQcXbqgH5@BK>MsGO=U8b zRMD$t3sYPX263!JE95RCw00B-dl(3ilJka=W()xm+R|4SZQCyyFkc)&c?UgK2iu@y zO`HM0{3vy$G~JTzOcT^|7fR;$`FV)<(f$64 zraq08w=y``8u&5$`ONy+9rzWz`wToNA*)@P+`Rl!R(~>;yFm;8E3z{ghc=97(ZC-pIQfBWhZXYneUS+L;5B(Vaz4=Yb}Q?es821o=E<%GpW8-CkAOAuBc@gM@Q9`Ho_|ZI#r#5!fO7KFKwCmttpv# zkBwa7A=|jTT`4Z6-+Z6h1(y!^V`My=dcH9j4o#HXXEs8&1p+!rbw0wXA2}H%Wv%pw znvm&elO7^nRiXOy3|IS1dp4JI7;`*_NP|6vv=iLs;f+z{W;M@Br#-$S4^ydF0Alp*|a-H)iMnw@_-J*%`zZ;KMF z`4$5~haMIew;zTlKODZ=z}1W^rhu zkq#G@t~B63{`D}2F*b$<)fm52UlC4{CC59aIj1#do%MYshzn!oj4KGED@W&M7jnSG zl+kN`ktwo;`+yi`$F7{zEkW;_IIf2EK?@)RRbYTKh*Hf3jn@?mYu^mgJE0}5Fs*{W z$LePv$P^ZS6%iMmBND|!fv%-F6&Ytd;<1H-Yem`860vv>Wmus_R_2eyPfQ~x98Y5? z6*}>KG-%&3ADZdV5D?nQ)+5lQbg?9D@@izr-FR+s&bLylh;Bg zgi~Y6FZcHAQ`2Y=2K+sF#WAT71^U)+cK#yvu`Fs#d`*(6gPErjFP~-hR?|k-aMGSo z_zgh88ISusb3;E;O_N<^$ijg&?i_$^Qe>;oVEs9$QE!Q^l4&Am0H_Qb7z@TKr}AdB z>X)%8W?!~@PB%|0%knUd-eW8S4Ue?8a<0~MPHsF(0HX{N5D8!)Lm|in{kt(kd`aBY zSKKz)Y};CQO7x-Ev7^Qx#%+toA|xsmswwsir}5IRDmA0`_U=>hei?OatyVb_HbI3D zce;M6yf2x&3Wz*DYU{kXj5C6pkg>os=XXclMB#tQXcyakkCV%>;=wNv4bpl$F1(7} z4)Z^+{7=RL&nrxG%c1v@T~-a~Bn6#&|3`(g#R_p;D8O=BYH2^^A{8V0_(i^0DCSz1 z3Y%|=1CB@z;$ugih4sIhRxk5G&Nx!Y6Y>NTR8ujweo$EyhYf(SJVBcRd5>Z`e-Xu) z+N^j#SvdtI1BmD7Zx6ruo0fjYOI>^N&P56BTFH+Io?*0?W?5WsFLk&G1Of!2Z+4^v zJHwqU`jsw4bp`d5wg$)MrK!5g^;<)SMk1c~Cn;UvKXwS3h#h<@t;m3wNMt*s@~QOk z?4^V>17G*u=Rz$a9N4SlV>*mk+kUkkS<_SpP^+}yi^0!P7?{ai@Q$?EZxzvv#6Z;V z$oPevxAcl_`nY$uZY^YnwPFpe>O_dr!JWG3B{-6zv7gYa_GJB99+#o2#Ke*QCkG&# zdBl$tXV%286LAkAoC++-+LA{ULB0J6LkkFouri@-1SrQL_8I1XuWkP`quq@v8Kfmr zxzw+rjhli$J|z#FXf1_b*SyPvFOo5z6O}E$nxl9i7bOg;e1SkRKGDhMw_|l&@-9Kf zbu9s+hJf)MthHfF43@<)YAld+k*>y?44cMo|L&F*GVxk62pV%JSgtkB?I*psTm$jIPmWfv#p(3|jY2eOmh0Ir4V+|vr`H(Q*T zHRit%6iH#Y)JdEx%SWBSj=_(Kf2Pht{+%WIeSFLwZTHC?6`+1Ti_1aF7O|xb}Fz}Ug zl=JirACw&W%!q(j$XRXk%m(;Z6>Z;5;8UiCS*DkprtT6%BZe6bkRZJm7)XwBMu)K>fT17;L=W^mf0gUzE4j{JJ3?Ty z>E`jw>7=4{Lqiae<#8WLsTnH|fB^Ra<|Q^>z&IwTSrTUcbh%I;g%Bn1z0reBhCp=> z2v~y#6dT$OXdnGmm`dklMQL_)=L)zVes);ZaSBfp!Ium+`K;>uhb8jp8St?7qhw0K zK_k_mAn@ba>%H;K~A>bU#bJORHWJcPdt{aiF4zld6iCpIM_wq2%;!@~OBWlCWF+4XAa{CMb}5cbEpBlIUc81!3}x|J`i!0o*SDoh zyAs^691JGmZFpfuQ$D8I8p--$Pw}tN|9!1>M*r!#)d<{=TT1}(9gxNsi&0NeHl#&} zfxe>4$%~L;A;PE?kp8g8h|LoN%YxZ--|)L4B314nhuBj7=$$-rc$7I=wS*jjfPmR* zS(G6OxKSx)*i!r6RD9C(Eo{9l9Qg9@$0$ht(6C07E3BjllM=b-k9fF&_*_R2MADG4 z^HbpCeO;Icl`CW(a){{`BpjB~b{?qs_B>R5nGLXu0FSCgYBsY=b8)*+k)jy)A|Ha# zWU0!kBu$Ng_D4lpwo-FV=aK>C!dDH`EGX?81w($4Q__vUQcg%8XH(e~SB3*)=*i1+ zE1n78=EaCuUCcGa@~uJJ`+MNEXW&u8rzQH6XuGukX)G8$A@cnExsSvu^vLs3L$=xK zfCkaBdKIypveI_am@AkNlYV$vLiV)wO7?s$=}V~M)vEvIPyYKqfjP+>bj#E&4>$Me z?=Ujk`}?Oro#RAi7vU4>$1z2uJ0lV(>`1)GF+Ft1e4(4;S=3B47_y&W z32EikOXHcqDyRWG>}Ki@M-~bH-1Ms#W_;QnqCqw5 z)(%N5f^gx$5=b;FsFhuAcH-Li{?0sog@+O7ESg65s%3p$_&pdaU^WOmfUFET;3NV7 z7ibIQU!uOEbFRXzKi}$@1l%hc|EqD&%a`%*d98o^xca=@eoiKPUb_!xOwIc)So8K8 z_<8ktGy6$KQ*kPClPa&soa{AM3d7neFtSwm5@CTCkox|z;mvc|NFuHr5^gf zoerq(2dUHQ@-PN{e&Em_K<`4reB zR_9R)@uluI$K=Mp1dMXc&ihdT7xru8^_T?|yR~9{x*3H+iUHKRR%!~RN%Wj6SZ{Jw z3)(#VP#TtXrSJBc0*5M{ZFS9vEiC9lgbJf>kGOkPS-W=Y&0_HztU5u!`$h=dFfH1@ z6id-%A>`m(473EoQ`@R^9OX}X)GBZ3!vd$C~%2+4uANV&=zk-;2)YV&5~__T%^_nvh$KN!7g%w7D(ku3^=f+SXaQXe!v^ zL<5ZLYmX552C6$~Ll6VcOA5gA5}KbEckie8+A=N*@8vFWX8POjn$YUk_(=GF_T8eC` z)GFh=&@lPkSE!V{xWv7d|NU#yClh6o$jTAdn938Gjgn`MnhCatd z%U8~TuC>^`(?UMq%MCC0M-m&0n2@bGzOUb>b(~;xMEG?i{TStMWvT&;R$I5Q&@L6` z!2rv)L1sLD(P}ATf1PB^Ab5$GjshcHfmd{ns-diaxp z=mbeXE>?`_otqe@>OFCzahMGGZLOu~On7nV$*A=1mK%OVD1!z>{JKEc(>TUf5pxE!9a}7KxOy~E$ z0Xtxic_bB~=R=9r3nTqrm+SsrvdbQ@IqK5*XQ3nk@Hrlj^iBKe2YGbGY%&% ztIyJz zv}iK~45!d^q_q9C^jy69aOANo?V=lkebCKr1A9klyjFK@Inu-w*Y%*KOIf26olH$X z7mTT)Rk2O2!4G%-+)IqBR8-4JOx@nKvm3p!#ub2QNxyj!{%?)??p=I{81W(7{JYL7 zULza1Lr_O4Ee1i^#RRj^tCAo--I5n{4=pL?>>-r0+(a0FE}G+jzOSj9e;SC;aR6)f zVu4vMDaDiu&6xU8p=Aw0Z{G^nr+@r&xaZ54p}%Z2N%5jIr&Oy3yg@v{AsXD>t@uQ zF^MmUGk9#_B$EMi`0)w%z9tE1h_SEPDNo@4@E{Pn=$tpP5u{9u%5UX$G8dd_{89oh z@(jS1#zynJ`u+NHCIU9xy<%l9@O}9{J3CV{I%$hvGEHbntxr$^eTj4;^m1~H8}K)w z?pEL_0Hci3`MbL_(@@9sbs!BI;pidERm0MFfxlVh!f+7_mEE$UyE?*gu z-oT%Diki_aLjkvR@Tw~=PHd6_ZWN|Z-$E^fc&f1y;aMxKBwS(Uw=$_0%3mwlAaZ_0 zmuQ#-HdJ0H{2te}#HVo_^l);Uz?b(++c1&3fWC&QME62i(c!Sr-jyh*R?7{j)4J6T zy0jSR^5j2)Z22ZDw}D?6yhy$!JulI9=f9oYP z_XU09yScOLXQz#TFt7AcC2T58$s!p%MVRpz6~oG>C}VO`{!WG?i`jy*yklk75#!UT z4M!tX?II1mi95k^TPcJqqHCW*Hvp-#ZhBW0#KJHrsy{q=*FpNz;et_{;j$7^GiYj4 zvq})kqskVw{(CW_a;x}XbeMCmgnxzcxwYarUQRcdix!zm=63#(4y8lvze8S+SDffF zeAl}ZRP>rD#8iQkXnvKIgj4`YiRH3PIedYAwKox)KcDZ-UjzI>#Iy-xV?0^7q|TBZf11zOZrb zxv_57-`6Cf2Jj?~8QDeRk1nwxm>b@tZ4WgXd!PJkp8xy>ZwEcCN#*+;ICsHJ&PI${ zBnTG@3B^|5@tdsWFgmz|?cfcS2Xywxw;LMEE@L=o8+DSEpVH#nXr@Z@6zp2TYPB5P zIf!SMrS@AKGPro%HUusv+57&p(x*dR$(&UITFVZnKBElN9N*;XuaJ0jP=c6`yd6jaCcVNeRwP4a>JdtaPx@kJHut&m1FT%^TGFo1sO9)mbp?^nx5KZhL zU)SI~6ewddyk3)bjzyKv9M$ZV)*!rE4#e5n1bsc#8;9Ac^$W60&(PHmfVZZcOt?2H z_MTh=b_VieQC(a*N~G) z6i@Tn%bzrug|e7*?}^|y4a)d3T36;ichzE<^h8c@gdFacGy2ke!0aI$1Eh^9gI|d2 zPh)q!YV0S_k*I=L$TW4d=dR!JMmVT}h<}-o(>UwS<6`Rp>~$~vu~tR$=Rv{~j_YxT z=kr13aQb3woX$K$r!T?D8-ktawV-A*jx5rN-kckL#UEWq;5%7txC?_~r#qhbiY zj^K!|?)hSRWZP#-{8;+^Jll6RV)Lx~(dC$(N)Sd=7>VN8ZW1Mh89;-RIL=CD-J`pC z1H|gtHKoedgftrn{l^ zv=7QE+(h{V(DFji4yo0mg~%TaZgg%{g$h}D5yQQ>1&-PpY{MD-Q4!!uSg3X8`O_%( zY2T{4xzcDRLovfd45`w@LSzLG0Sg=@5bTlM-FvYyc#EFT#Jz-o4iMi?XeqrIVZ72l zoA2?)LSTL`07nPuNP4%wYM5u+ZOEa)|FvFagCt=+YbNLT<9u1iIB;Je=Qwms7_Ek(bBM28n|6TjO*lC|UMnV}udy8A_(L zqmFSyQLR*!br5zn__p>6*Q0fTm@o9eG8_AS>ACV@vYeV;i*ppDP9{etiq!n@9A=Of8@ zxFu=gaJ_bptb*;2>Ba3Hk8Q{{f!&0DTZBPgdvFNnWJfT^*THWjd853==Ib0|G2)5& zJQ*zRUr! zGC8-3_Zg~c>LL-S_dbnP`53qgtXVzNG!g-1JHM~~t>}9TZ=dbEkM2$o%L5aQWypUT z&il4zCmuce&by$Ktp#rC^!@W|W{<>gK@6V~g1W2rC^S<{)cP!rFjFLZCkta=T*T~@ zFC;OrqD)Tlty20@xjxz+NT`6%sT9hT{UeIWJgGNoevv|YC~63;9*-UBi%iKpgt(<3 z=|trOgm~$)zBV&pk2nZ$r|gT7Z^6W;r^!qtb<0Br5RyOKWN%jbqmk&gRR zvF-v=&WQAU{21k<&z8@?D=$!qO$g~n=6gNtw-u^7TGZvE! zFeq5I_43SO^oMMZNa5+>M&WdST~|}NKg8>IUVXZoEjgeEt#oke5>W20aN8 z?9~4S$@Jilib0y)?tpLsJKIumtSoB_LJd5V6z_Owf@$c*@7B+O{LD^P|KfbJ$Hnem-1%zFgY`+@I9R%&Beu(v?oB zP68(R2XBWd^7%|%B)+dy83{a!KNgPNMXdjd&PXpYQ$$MzM%-Xnm3%7wAjsVDe`k$- zp7)OQv~V}-j9!R|*|(SIgJL1~?SvVwl~duFK`1)kf^~-~sR7144K#+ARHiDkH-%6t z!$ZGJKfoIi$nV-B>bxzyHQS%Ue2C@sEc!HJk;9ng;DoIMX~SZQJ9a3;>CIav>IG5R z9)oc>e_pxfuxdiK$_NE_C&{4bbZp|!m9m`@4@05DFrmr@R(?RsR%NQnN9CX44S=_wY0E$fK_>Ceq|&sv+2rX{8m}UP>I3 z)F;%sl9IUCH-s!DH{XXQFrwn-hZ%7pA^0fv={DAkwSl2;6Qi=B_(AwLxrdA1Dc`~< zF?XY&)bg@DKu}XMSibp0CzkO`(?zIGLFG%sJ(IBrfgRkD?l%)i*{S$a9T@vd&&-V=;vQqCi zG&}hsCpN8CCR)P0?TC_;eUf474_|Myrc=ontM5KB5RwrgmQiB*Fbnt$GD2!@f!H{) z?4Ar$yoZ!LsNchVRJ|%z-D?Im%IlI;T)%8Im34Y<=UX?gSMo%bD5oS4#Va`%7zw*Q zS<5C_v~Oih^dzp>;y3^Il=wAt!dSwE>Ee863c6T&A8+fG{8aOdQlfHJ$WZKHO>V-{ zVHLa4NNtgr&I0&2{o^|P(uVczN)Z{%WB_vF#F~xk!yN-`TJCe6b4XWytS8xuqo< z@REQWp2NROJ*-t49vS+TWzgbEC)NIQbw2Iu@sd+U0(~fCK>$+;eKOfW356|wTCglu z+ZdzJ_fB4@E*vCVaw82|QA&2}6y$>#Np1|+>gUL|i23vCeQn~)wvaSCLh8R>w@1(5 zz~Q*f4knU;T^{V1(L^3kuspZCRd!b0nURxHzH0kSu$4#2p%1Z@PiD{NrW_iu4_(2M zaEU(1AxJ&Amr(F20*6qLZKZ=ao{@-ps?A)*ZFCbt$B#%h_QF*D6fH7R!D~h_;H-H? zlqARHx%f$02X@V|04T*O9z9ZO1@qyoPQy?O#E~sWQ0`)`zBa<#DX>Jvexf@^-XuUAw}+Z_!=zfGy~9yDru)#zV|o zTvmkt`VC{74P_Dj@3^T)WafOZDl-v%>0SBUy0pInsprysn2wb=SXQKh*qcD!;=MTx zj{Hz5(iO5X|8$c6so9pZRK~e>SP57{VvpJ*3?36vmJ9HPDxCU2`HME_5%7xP-vBh$ zho9|%Y5SJ>FC|e>H^cPl0pe#TfT^>sF6EE_$uUemQ}K zE4GOYJx|J20#8>_Nd)5#vKeRT!m$r+*VxJ<{yXL^o-+}iNjSv@<+0MbDhEo97|p{q zw_7eG8^jLgh# zA>k+)tyqns!eD8HXBP`gx4oz{tCYBWIy%A^Xsy!RkSeeIOf60^^*U{PcR&d?!3~E< zpZDj7zkugO)ZpDic=u)JE11N(N`Xhjyu|#^n49H7+~Bw!H9usZfp2Bm$GAW+mv)}XfE4&s55VDxb4zfh)w@ieSq>YDyG2xB-Y zLDVQb6=t}Rh9x_#U&SsbU6IPw={2pLYvoO&6YGYq!H_Q+4$MT%juwc;Bv+uDviXJx z2cCKwkpRr3s8v6*@rSaY{=4QKF?7N=A1blk^EUgV1b@@IMl%%18Bp={(xQVNyzNOwpK5~3j8IU)iAA_7W>l$3yUGb++0AfPB94N}t0DBT@OcgN5* z@m-#Cp199*p7*@Z*YEe;<8SM==i0Ml?Y-Cfum4(Neqt5?3N>X_WdI8c3wQ?p0Wgac zc2!B8Q`T0`&5Ec{`krot{7L;HU5|S1XmKGBR{;ThPa~9XW z*t)yFlok+ha^p9*a<;JMw{&(C@HT%bAjB^y0LVhUUz%GwSi7@XSlie+$#L&Dz`5D% ztmL@$#54poUMgDK+CA`fwbt={^u*HF!BWbK8!AsqBd$`N7dwAGcNk2D#E@ok6CB|oA zE@H(eBxGgIXKp1T#AhWUVkIFaBq{t{$b$VZ6Lfs}*Wv$5QGnxtOOjS}wKjLRz7H1p z-y-D`6y+0?c=8u9^9u=y%L@FbcCrG$C-!#}mH+o|z_o)o)Hl-s@}vA_6?Z z+&sKIzdOMqAS5KZMnpqQOvA&>z|8Y6e=y$xNb^x0a3x^U5(*{7m=oTIr z1N$8Y`;QM6HV!TxJ^|r1B4V&X6$OBeg@c2Qi-U)U3kJim0>JkGE+rn-4Iu@5YAtgD zb{87q*Krwy9QVq8&}t7OI7KX6-&`Z2qi0~e&UKUf)@>e9F>wh=DQU&~O3Eq^RMm8z zJk{0HH!!rcvVLx3YiIA~?&0a>?c*EtHaH|SEIcAU;eBFK@`sNpnOWI6xq0~oU&|{h ztEy{i>*`xt+uA!iySjTuM#sh{CV&2#T3lLQSzTM-*xWieJUTu(Jv+a+{JkzL0O#MA z_1BgCr*%<+>%zvx#la=`y)Gq`_k(R=~v!<G(w2QnmV(GeL1c%Sc9ZXkmznZlkEzjB=B{-f=F&0Y*}tq{(jlFmE+H z>uLdY`_i;2XIn#f)2nQzl9)-Y;PV%cnU4hHk8E-7MHGk^SUP?++#H?hNKUrj#pOhf z;4)gse=Kwdw3Kictd756N34E1|G2RIapcy?)nhBiuo0*GmK!Xu%qD8mpO(cw4SndB z-@bDoI;@cXargmVXbtj2Pouf#ZFRP$xMsutQ#$jeI`Z(bWt>A!O~80vXlvVyp4OzXjf#a^eK59*>t*IC5*K_2 zOos>uZgdb9jV|!rIcGlC8*IF~me6-3QTi!eqJO&v;un(&m6k5uF1;YmNk7Sm5NK3f zGO=va*{ol-6R&6aQB_kNGbcgamCu->{XI3i8qjWZ`#iD#T1>s)d2u44z~0U0%uDx; zs?`*|8}liEWn2?^Jgx7st8u(5(hhTI4!%FU=}t zD9%$Q)xkDSy>bP=lMPa=QHtLrk8+YY5J=y&Ogs0mv4$ZuA61RB#~4ZRSySKnLd)B9 z^m&53b=MOGT_mq;sBizYQ4`;w7FnC^hQ&nB!S$e0LfQTJz_a>^MI_*EnDTC z=vkU*^!v|=me+YH2Q|j)+!jfBwx3irTDcn;U2{LKjtY+KPGDr{@V$kD`&8ygN?=>% z^4rJ+y2dP{)vj3xUUT3X^K4u!+UUW!?1@k5jztLlZAK4UqOaBR+ETa_ZYjk+CFga` zjIqqEOCq?*4`Wh%r`m>Ese34Hae2`L>zr|87WKOli%n_iKG}o(6@{kJG;!vnZE-u{ zL^MC|eVGyTP4i}6mRb^n5#{C(d;7IcIY$&P#$V_g&5;XeR%+d{iPJnF!KqTDOc;7x zqkcJmc}zWp0VZ{dA~1mQm^`_0#VPV7NLcgI2qXudxcdhE zn!X%G4v3pkc(=>adn{ER5c1i4Rkcszvx6kwF|#{tcE#VFiBVv_wWnHAqf|d}oE}#E z#eS+UrKxHn#W^e9mLobN&Wf-{9P2Rk`zu#v>G4wpUD6y?E#e?;eXgm_nn z&Qv^*qcv1z*Xl z+wE~6jy3Vh>C>K$-sGiPNbU1_MuP1cKOIZb!FLZHWP$KrEJ=kSSqHVe;(+av0(uC^Vr>3T9_;O)u}^H<}0bvztn91)}r3< z7ETI!>Ok$#vWCs0?|G%H+!CLP)`V60n0ZauotsKR*ut&^t^peMlUzcFXs(S&NKdis z_t!H%RFHMemok^PGT-6RXx;sn3T09bId_02!!Fam9BRKonSLq~4?7BRIJlj;k%#_BMEpmp-V3=O7ohbTl4HABUp0|@+rj3-XkU4z@JUAlyirO^_e@hQ z^BV?Oycr_LPyFl4yX@=&%6FdMcHAPo55zJ?H4fW_qOA{qy_CR-S}#@GSdVohQ}qqa4jbkiKxQ>&3Z^XzXx8Bige4&%(}&88SIyAb=;_N3~;>+ zw&bTFe^8to@jUJ>-#2W0WtWNc%2*daDNk|xRCKXTZi!Pa(a$c0UPw#X37o3ehFNQ> zjmp51iVFFjAdj`GQ$sYFTC_q&rmRFNY>oi#hVR1V`1UUKVqiL|sAA?}ZpX=sU$JTac{erR zFZlnWtl@}}Yj>3#j-35;^u+eaj0^*G4d;Nya|L?IP+H^=>$r*@tkeH>_FlN1CQ4*JS?sto2);r$Z?k|f0T`j5qV?FoPF}NN7vL<0PJZUiQd=^QqmU+s)z`sEMIbqj8``qRDq{cnT zXu@dPJ@j^hvs1Yh_mG#<0?Bdltd90|lSbEoG^3;>>tK$se2f0keF~^y0eP53{2`Mn zA9qciPn!VAwAW2b8`4BhihGnl&` z02{MYuHmoZ;`XYJoZNv+U8lf)=TqJH(|aDbKYZtM%_!^aA(I^7tw{3zLi9Y5W5%=O z6o-50@kmD$?aEWm1#Fju&3hxQLP!p$iDp*)sVQ}Z)9_z65?^-Z+VBV+v*(tD+&{Qk z$lI|bMMWC(Wbqr5q}+j?vw(T|>p8v0KNu5<0W%yGUg5<6NW9R?!R^lUOX zXI?~`F>M$+y@ut?*&gr})reeB{eTd&TPAhBaJh)cd#XKPAb_`)<>vx(Ev({9J^JR0 zHC3$h`F-k820iU_hwonJ%9}=+#)Sf995njKIr?!NcfIiB?FO1;o1H*NO{J{5%*CF} z>nJ_|^{FK~?fRa}>#f51qp#bC+iTf7O?q8#Ysc zsl3t>LTcp#PoJqQ8V25YEasU8J@Fze&$x^|_-b}dV2Qdd%BYQAY9r_FDU;GO`-*PI z9AkCz`6ml8b0y2s_=DEneO7n(_V2Z!d!E z%TsIR?w+0&zEohTyhg%9OYsa#PpU)JfRa$M#w`b76;jnrt`KKnG; z(aK`w!wCnO3*GPSr@dhr_`DwPu!}lha=Hy*aS%kg={fsrI_GUCO*yWnj;VXGg%Foh z_xKR)5ueqZc6ct!KCc!M&o5!RcQ6eh)2}*d+AGX&YM7bfdw=Vp%QZ&DZ#}V#-*Gq> z7Opq>9gsh$u8CipAf8p8Aim#NTU!w(tUz6|%9ljINwR=_cV$7lo+Wk1!(9(ru zIQOdSiCuj{Q)5H&ngOFko7?nW`SMuAnizz_J03m8~wexs^VI;^_#bCj(d$~(`neLZpit(Z|*i7sC7>WF$ZrJxE&j2+1-5QhPXu5{&>l}#NwOF!u4JZ+)j z;;b)$zb-PTEBUo)hKRFGKV|@7#`kOx2S69uhoKun<{03$Dq3u zKBtglO%G=zHTU@hWa>ldC4TbBA*3Sqh&2(!7M@qktDh6m!zq}y$-JeYE zIo;GzYjSUGAgCTy61jgi*|uGKQuDt z%x!uu-*^ib$OUycoDmfn7x_-brwzk%7v~Og3sO@1yrr;@@3eA31C| z6TrIon&D%U1A&ZX4HZN4yGa!aaI;bIi?YPo*DjxJw#}5iWzY(aC+OUo(t6?7!&*wT z1GcVn0_Q$tnb9ny8AYlt;mDGQ4|+wVA$Y(wwj)L+YSCe&@x*5J!G}4wnA0hD^c->yY1GO-uTeEoQLLwKc{GV@p5?q(ekxXKYL}-#7I~#$ z`fHPiqh_o!&clbqpQi_cRrV7+oEZ?q<9a{v?3J|bOraZsT_vE0I+X&K`x5AcUK5W$ zR5h?Rz>CB7pAF1^R~KqjcaU2xe(%{Y`a&Snl9Puq3;0~a7Taf0*qg_XOPp>sxX}PjV$i<{C}Sc6!;|iM$i* zw9R~9k*Cm^1D8sfkh}P1I?HF@ypYVGhba?VbndlY)wXEo8;8UcxNoZ;DahBYr_DsY zAy+i0_NC29?9pU0elT31fB&fQ4V!N;iTCA6C(A9x=gJO8&$yx z2TnHgPiJMTF5A-_5m@8Q-=tpt_6I*;m8}dwd%Mq#*I8d(i|J%uz{^a$|=Z z_5Ks5%0_J6r@Ep3kuQk_?_n(pC3S+S9cdFr{Z8cK?eU8FwQ0AG*MR$qC8wVe)9<4e zmOooY>}{5Ff1=KKZqlQ?D#@|ocO6>ViwvskJGbZkxc}2M1p0I11-mB(NQ!=^j=sf? zR43ZvX^M`L4#XBZDMR<%!c~>KfO9b!OOd6Hp~9>x#UyME20Km z!Ko#O86oB(wi9{uxW0zSOU80PqHpfeiaY(T6Y*hVRuv@7zRSg2*40^F+Zm>7Yw8Ul zDV9l=7k*FApT}yAE|-4@TMLy}JbeLb$fA0lCq*Z>I~7Jaly0cf6yE-U|4EnC<>f2Q z)a~ytr8wrYrs;jiQAbaEe;Utrzt|=1jo)2u`P>)^D$45#+D%4v91rwf2;S`av87Uw zD|(eNMNg3nJVY(|rFV@{wFfI^0NX zWay(-E{~TARhB=UrQCk>I$GSs;JB*(%06kPh7|vZb?(!O-b9aarZ7v zozNT$@30Y?fv76llEbwv>(S(lHUn=W44@n$u%qEB$u0hTU`e&8vEBWMWjs+ax~SQb zOqF2do4?|sUo^Ew^RVol%OIHTX4#Z1$0NIV-6ukYJ{Q+0J0zS2Sp*%%ZF8K`Cr=8D z2hKpqK*9%WjV|$iY^Un^VvpiJ!i2|Ju$vK2pCsx~+NMeTtmWN|xAbJ|X$2~c$+_Zf z!t*_Lcc+gmo|aPkDf5}>M#wI;ZvIZWQg7w?wv^D1g^#Q&)b&D`9)CDo2_%`W=*4=~ zNaD6_cxm0#pPTIH409LYXOH4c#+FO7!(pmkSx7H7%#04L{TsodJV}v7>yxF+qVSCH z3z^%JKtwJ=^OcwYh2gY{2VZ((H6z2<>I*F?j!{n-5dysHw#Co4O-E0pj)|FnX7`lk zv_{W8d+ho^PJDu{bXk+?Jg@a|vwlC!$?3&j^+$7Fs-UV?vhXyb*q%DG9VUT`t50aO zz_}hryMhcvQ!~V6^i9fY#iZMK`stTR;=t`zU*FO!V<~8t4s00k0JftWF2!n2zjKcPj?_sT) z=RxS;SqU@-=r+|u1zBSNs2gm)9YjyiZ!h5Md(Kzq@I{r0FOaQfnJc)@o;>qG@nmcu ztH0)iK=F;r`y!PTEWrxzQY!#q4Z4(@&$q$&+l+la?Y)EZN~+CZCqR55Mz z)e}NAPsnJ#g;Hk)|C+oKR!m|`KR-<#sgDJIZs|g4gub3zjJEb&a)wCmT0W&Fm%dXr z&3h<$ylujxrd2QR*>uf(TkZW>WZAYy%W<_X=b(1BX!fRx>0;m6 zox!@cHZCVg@lKE%b-cH;;R5=)zbqoA%DlLwIIG>o&8BeB3FpB=Cj*E5g5X&}^hBE3 zR~}tokihvk=dF2fNOTvbJGLVhJYFTI)ED1##>?Bu>a7qHAqh$J7+;mA9}-O`M|zLl z@t3nrni#hIY8}n+P0tQ%CEkaFc57UHQ5Rjbqkf(W66pN2T{Ga`KN^B>H_l&b@_CH^ zu`Y_gA5&WL!e8$Cl(Ae!LsLy<{3_XX-1xgi-%lka3Cg5OpzX`*h|}aEJ44TpUyV$9 zpO+VpnlRF>(%A+*`>5{J`#Om@&8OYh`Xss}&r&QY1J{dg^tLK{oNEy;sVv^&3Dq^e zy%L=E6%3HQMNj=gqi0&rFEz`xV3~zSd-8G@4g0W<@*lAFmnojLOZmDfUgH~>e&=+= zXwxe>$JF}X!`>!?D79rA#vNBctjwllY7?Cj5Ch(_0g;=k*S6@BU~tGVaDHU?H@61~V)s2&pU#z+P60`T2<{(IfS`-t%PG z{GF9O&h-MREF&3G!>#ojeoOmw1}qO$@nbq#H8h@nD@P8q{Cev@@3-Qdo~M~qH0M44 zgs#4%%+lEgm5}`~PLt$E1fJ4SlUgo|vpgHKjJsY;4MLU@`wY&n zoLXLbU+s3Sr&Z~~@HX`5TegfO?mT>P5E+iE{Q*IlCOB;zMM8&*ki(OQPr^W#{Nz_) zjTEV$;doWAx?iP{WaS5>lCy2xyE&i3y{GC)19JwNy)}7KyGAe1I}X)l7#~vL*G=Y( zGLRfxmyKX>JNp(ionWZr&2cwf+hNm@Q@E;Sc86X&tZ|hsT=v_vgcZqWtFtXTl{b}? zg&4ptAYQYQIKApCD%Xtf=01C8!!yg7*Mq)V!<-fTm38Cd*-2X%i&6Tk%nU&4Mwq55BA7!{7mE+Wlg*n;Xks+uYW4; z{Nf9|%27qlB*Uk+n#EE+3zdF!+)t6oRTA3~vrEZF2@oVWo6%#!CnxZHA<5yii=!TE0P1ic@N#v^l?p zN0{W+mufN|AA$kS(e^LjC#oN@qB^*1%`R-vJs2SNf~NSSNo^AKbmqgcTWw&KVyPjI zar(XYdOBukDxKyS00WqL!)$xe{vd+@(Fphm^7-!LaD=b`nmx7xiXuy?LE|fd zL+kay|NghtjY44P4MBqe4n$#vKVvV+(ai|-a5C~7WH#heu0$}v&?d-GSeYS}r0%T6 zwRA4Cn0z=U_M+s*0L-NyFu>pSAl9%DpmM+dJormzZqYqhHO}FW%4G+e&wAp#oNYrH z(uFL6Pi7mY*X-1pw=@)n?NOSUvNB$7x#xRE#325 z8i=lPfwQ=B-gRgcrJ_WXXnTri0t%~(>cxG*;E z@3O=-T=_};L5U&vd$Ime9&?wp`&R4eYAuo^^+tN&UI`b!U*0g98jY{7KTDeJZXRBY zy~Hg=6QzR?FKd^T0Rwzd!vG5)XgrVD=xiONW$^{$7l+5`mHOG5yaCl3*$=K6LwKPr zZtb9oq4S2Djxm=@%!p7!mVzXl z3fE~Y32cZ9_Ft_@&j*B%dL0iX8M6L@D7SR8r1?)o?)z0V9Uts4D0Sv(K^)j?YfYGkrdi;1<$+p3gXa1|UXrr;3xaLw52maPj#A`vnm1c%0wD5wWnA-cM-C z*ZFVJ9WdyX;*MX%x=J+MW_NO5*ZFl7Zq>Qb0jXGM&FG%9yJ!5|HGX>cuM>yCY|PZ@ zIbO|VV~q++0`xZGp?K_)wZj#W7L zR)^8gW3~2!!2R?4rKgr&NkVBKXLz5?d?&aZ1EZC}uJX4g$+8w3dYMc_9t+PXcZGH@ zP{uS)c-pA0Qp4;qfcZ2Aa6rYP6)$1QrzYrxbs0GML{r|6`9oso(i5?x!O-IXO|_w) zTPYs1$sbEMKgkc{sKBw8C1>z`V+Wc;5MIbP)7vNwkEh1f%0gbhV_ju;R`-xzd9BNS zFybjA6Eiaj(9<8@Q&-{$y0JTbR03HtP0Tvi({l{$ZNHuz>OuN=H)&ooa^T7U(q7@Z za5VPW>M{k6m_oNcI)Fwyp7?!mtkNCNjzgXi4w8fTB`e_~LX)_gAVywrYmPJ4vEx%_ zOSL%FiSE0@J$R}7+b22wy_>M)lMLtCwJUh(;7}Ff)wzW_%e?^N#|>j*23Dl`{rM%+ zZ+tpbBu$&HT~21}eb}s_ONrej^^t$u%_)AVl9;bfe#?6P@Qn)ItIib_`{S*KIZz9m zgxQZcT<-lhFqe@0Zf3;oe~5_x&58WSX!*bJ4r}H3Ntsc%1dm|TuNa`9xz`E4?Mwr? zuRUMv)5EvrE89(bs}N>W>0IYCc%>D0?dk+S4r1y^cqo2L<@!TASH3n!r$*4?x$2r}=Ra2WX_ZT6= zYf}R|C=PeODAgU96Iua`uyuk>W)@r$y5vNr(`s9?M7bRq!~(RMQ|?#Ca^<(Q{DTQ3!M9~Pp0w6}5=@;M;34 z0xwq3PwJS)$v?j6sp4yvMHqO!y4E2wm3w#xzK&R*>=E7AwWKOkddUT>6HPNA`iaOE zR*EdW)9sBq*S!O`^;w_w=VVV(LX|I$oT6sjIT%ig$f>5q&UU`?eW`Z1`APSq?wpOQ z`9Ow1SNnHYm3#X5%W)~keA1+9j%H4wZVuKj^B-MJtE8%(G3h>$T5)S&9q*aZ$lEr> z3;J<(S!t>FsqHAI#W1%U--A)VKFeuJ&BD&wTTNnBAv|!LtV8eeF1tp@^%EaVKD*Yg`vgt zU6-!1W=`wq4>b`OKx8%c{O*b7#l9T|2ml*Xt037xzx}KdR1V6tluN*npK;^`_c`q2Vdo!zoQ0;4(?R=9!R8%7%QFco z97Kj_`XxhEde1xth}HtNHnl2DXt_7xt`;3QUxu}Z#2lX_!LE9kKp zDF1rT^qbPbo>%L!hU@Jr)H~dL<3$*NLpo8|3qQZbe^$W3Y+ouiGW}3`6Lv}tE>M|I zae+KSubFH_pt9Eyn^b}HsCQj8pW%@jTgNc9uSdVefg4)IL;(Hc5Vp}?N;M&dQhzv6 zvQS=oxGe0{(Js5-8*9JY8<2O32eE0IUmN_~BFodCd!Sl-cszFrdAOO*BCzk#B;5fc znr>y;-J#2UGH%cpXch6P`UAd8gJf5!MQI$8mv^w}+|b~WsfOmG=aL<&Y3vT$5&DJ+ z1^DYtgI>}?KeJ;eGQttP0m`+o z4h1^zDGwPF1ThtSfhZFBV1Akp62Pt+rxzvJ6G{nm%W;^G(lpAwYsrv&mX? zUQH=7QGf zCZ7+`i|ZD!-TAJIZWtLisQdJqEoc*#;1|?lrB?)lU`%VOs*t-Kc6igl?35h*jZ&3Z zErjnJ)=^*8p3|HrilW+Fc=DPXK2=(i8KY0v`K|xiR7t^7z`fJuD<#WX&c3a_Wlv2` zJZ%8?>^si1sJGomjs_03(8n{hDxZge;%+Rj0=V zPo%-IA7p=k=+}dZWiI_TL0YHS0tTQkZwzWVh}JZY)&IE9@k_YnUE$d;bn#R=w6}JGv2wWeda<)xF0tF*~nC+JMME@+-Tz&FcXea)u%`~(ZNJCth4 z-`5pW$H|*}p?k#cK~58N{{C3(OF1cbD?-zzzkO}hr=bJuDr*#ZrL8sj*mYFFDvg}H z^VCm^wjJ~eOhousV^JW2g`#Xj!%KrmiW|rlTBM2sn{4w2E{Wqj#P=MZHB|?ws6XU~ zjyS65qdIF~M;)RuEFr_eIDn0qSmMqEy}De5qsNwv;IaI;mr2bVsp9n-Gv3|D;f9bs z>djrnabvoej;D5p8(v<5;VXx`U*x!I9bb)2xl`za*VW!knXA{a`t7kNi~beSU=zG< z?56On+JGNf?+$^zuByFE^)U#Vtu|X%9qn1>hJ_%h!j9ORH$)6&^~%VKoulHJ@|gk`psOu~t&Spzd0eAgPGE)Mx-0cDSsd?~WKvalZ> zH3pg$yI1{EUzFVP2NQ60bIt#fg=?JL201?&0@afcIr`1X#3a`N0b0%-dPSlLIwno7 z%h1`cuwb;3;*v_NzcHwZM!}TPZ~p0*LJr?$K|-5@cJiwALJyAor|)#@G?8KXm+=12 z-oI8UFex#vSN8sYlN<|1j$vxCWHC#ZX z1Qy%2Ze>QC_1*i&EWoGZcS7>A=JYFG&_9;tDobs6ABC=*SnzjSq@Bgva0oX)B5`S> zQ@+Lt7kX-K%#3&-^Pa>l<$J~Gz8GVaE?tFjmlQ7*9mmXajw9^(^ttmB_y|((*|v`} z8xy11mjTaRkL|=8G0MCW561W^w?pIieh9pOMaxnhEJfhy@)@00#|+UcwBc6Vh?e+H zFJVeNdXTTd>~-CklF757k%`lr);BWxlj7%H%4G<@%w)KC>32O->av)n^~Y6p^K4O_ zgaN(p+NkU9{+OCQYWGtPI*4qkPNN@vv0wFIc-PS}aojvL`%YZOGnhNQOppL+OsMRF z_gRD(ga|@b9QrmZgxc(Um3T5&r4$DE=Xr$O-dhKvn$qApulZ#o4SO-Cxz_$~~*(3%qj6GN1kyAl| zn>taVsPiQgRJecpCJRkW!^i&MARtDP0}ZA( zZa-yV$Zc4TG^+9^ri~9w_fHf8k2Jdt;&*OhVZoMeiu@-zbdK~72kiZL!XUfQ;P&R3A8N)jA!7B+}%ya1iks5de-8XWiR7IcE+mjZ&D5LoRX7zv4K z1W&Ik1W5!EQr>xtOkrASs=E)`gkLN(4(vP|5}DRJjjbb*9VBg2K=1y7T=5xHp|Y0j z^i91z#$6IAjaSn9mAu(SuHBOwd>LS`ErPm5dCY*y7NwO;R~iHHa`|I0PWuQP=pAAn zh3%o)14Z*RyCvN=dA)G8_GtxP1q85wF|Zqp@JrmS^!G62Q*NYaEOvvhfNERvI`UBI^R_^ZI zwb{kkmE2_X^?S~jbQ~bN0`7FjcI$VdMiQ)_+TTc7$8S^&tS*aU?evlv-yzY=+v249ruIEtXwt#!(xWty{+3H^`SE&{QCV~P!!f@7V&?3L z!=kcpl0S6f?n0ckw2ai(rxf{x*4V4%vqT@`R{k}S>%V8$edO-S&%(Z{p@hIISooW3k_4UeR9@^}e zl7L$$caw0c60LyyV^;?qLzOGN;AOtvsfUjtr}{P*qZTlURtZW8 ziZtu@&jRp-8O80AZ-d?(qsofg)5#T0&5zm#6iH$^X*8FC)Hsaq)6%J!hGvp!(iIo2=ccX#L<%ZO6OzIB+* z_Dp;S0VP^LZm@GK8k~9{qPBbI!v@3WrIO4y>hB|*G#XOPK&UA>f6@;BP_kAF$NS!2 zpb15E(v6;QV}K%u%902uRp;``sg-8Xa&?x3 zf@U`ic1&MlY;#qmiGX+I`#(6?|Lwuq{l$axCJ2YGSk!|VCorBf&|dztcaxy><7gpz z7ZtBTC#eUvXqK^M`VV&eg1QBANQFp7y>*{QL1+WKjDHHeF)g~{XGhBkAXJWQ!jUl0 z_D_N;b36D99qepsxj1-^9EWY!!#1i)ADv?W3~-~A7<7(^_fbT1jh(IO2Nz$#syhZ4 zb}%iGK`W^vRn~mc4{SEzqAoR%!`n4iS)j94vVQ6Xn&>)ul=mR0wI)ejK*jJ0Ru4Vq z*@M}@E_mZ$lTjGpiqGeRW6oA!MjPaa9CX%}FVp7Whff+oO=Wrty(CGjL(HS^Gm)Qx z=3;nX-vNy2tG7c=_ANn#)NPbb3OacT-!MQR48?k~_6)4qg=2sk7{@vnQZiMEM$7af z4D`jYl8d|@?jHb}yG=I-ka;t9i@LnW+;IkGh$18{IN6R*U>A5EqB?61&v`kLK=0gU zq4bhYbp8qf!ic|BcndPqMH_H?_{o%>*B11_jUKOt@ZSamRs z;Q#(V(}b0F7^~}B?7?%8@qjz${W5%DIx#@V9G#OD{v>Ym9Zx&WE8bR^?S4Z>0NCW0 z!%X4d)ogKEtV}laB)hh?!cU{ivv|psx}XoAj9I*5kM--a@|Y3|CMccA>1W9Bm6-TL z8aL73rFG+Ubr$PIC=!KP>$ODj=67)*3TYnW+CPl`?5MRpmko7C-P%^T%GMZOPp`F1x){W9O8mt7T$+ zm&4fJDHCpy`ZhhS8@*G?W@(fH4apmG;p^DoyP}e} zxg_5AmAO#M2AXKt`OY6v(6f;y1sMUufO|h1oFBnST zbC8}U5Dom3S5-Z*6(yB%^os@9p>X=S-iB}TTj&bcqQDj5Cj3&K=W?(4{y(}Y;=~Kd zh4Q^&@K|*uCG!6mcU1US?kMg5rQFef7pkXSf>ydy1;i@W;+#2f#wDb^eWh|JwmZI* zUI}X2@aLhM>#D!67JyLueVGUpPcmN*p=^Q7h+F@(d_j#KX9k^Vj=Yke{lksa%7bWNwR6vE{2jyI=u?)U5a!)bBc=-NS(3a$+sRuZaKs^Z0V< z)JKBh!U}5_+)is#J{N(;1jc(EA~99YEpTdCGgyh?^tNx1sLpM365EWjaDx6$=3L*& zPwM#&HNju5sGYngpZ_#+x9$2Wel(m&pO7#w=a7N8lROEdv`Em6&Z>>;c#=COTOjmW zhc6;#-LD8~4gH0F6zsr0pZ(fk?>!Bhm4xD?WT7-c$E`i8fkEB!xYE22_Xo+aN&ABr zj)tNpiMd1DQi6Zzen0xKa10eH?shj~Q8XOg6Yb}hli3-)6U$6C@VpgU{$RV^Iw$(Y zp5I`I$IY?h0#1*qp;=9=^^$Hz1!SgisjoZs{S-WUWGlP282+0v^9&9$(j@EelY1dSY zIi*a@ovQNnhyd$cy4nj6K6vOz{T6~x7i~oTYx{>@ipf}#Q}TwzM<$Y2*{A_OJzg*k zc0L^RQJlu0`-iY#xAC@n36-%%c<+~l#%9$t3}oyF3pPrVpo=mGP!#D@C_TyRva$|HPST4hlo!Z29tnVS-0UP4Gy0f|?7KfCNqX+x<3>%9XH( zoLxX$VoOGj$p638-f|ga!-ImBnHB=}sFA#St#cv=_tWkSWhJ+zyhRw>>mH~w$K+Tk zzr!YHArxJX%Da7QyCBgN(ms;M6WuYa=NZtfGLqQsuKoj*gNWixmLinsgxK~4gaQi}4@MA21k&V%~ppT-r&J7HY~urTDH2>K3+el13P8LcFa z0o-95PiN2rV841`Zb>O41~@fbEP<}*IG?GYgG~l^_CfIJDsXv_jsdJoMMx`~G{+=^ z(B>d?o`LC1PomY5BcR)JogjpXuaRd0QF)L#8i@fe<+e#-D+S(J=%yXmF(a?rA{-ee z4%r_Bmp0ef2SG*)K~MKr{8!+i)cL=e4_1?zpWej!b>C|J96s!R=oIyy2_3U(auczu zn9jFD8Wi8pUZ8Khdkv}EP*xYsOdU}O^Q(!Y%v~?r7}HDcdKO;YyIib9CK57c0rCqX z10c-GIQQe;0cQgr@va)1*R1Dn+ zfMb9k@6CSa^ZYbhO`c)>e|(;%jt7JHE63znH4BUhu9QFbAZTBZG<^LWgS=k&zp?k8 zVNo^Px+n+=h=2%4rcqFkEExn^K(a(7NNSM`0wOuKh=61f0Y#uCXIgTmm7H^soO8|% zH0>$BwfEUe*ZTIp=REhv{c(RmH&o4bL1zmSR@2pSm=N@5@s?Xh0Nd z&6^qpI}XJ#o6RF<^|iXc4%x^jJT90l+amq&zH;_JQ_joc#{CuF5{+82e@4{>q2KDR zgWam5>8sV|OFOLxmew-%%+Z^&gJxe>${({zQ8Y;uAo;2YOXJ&6jvLX+?Ycecgu z7kr`%!@42x1&1NoyK+`ICT1~4Cb7MSq|t0XIm-bf=4NSk^f8IP`e}05S1DKj9+s>E#B6$E z*jQlBu}&F<628sTxW~Z@Aruv1MabE<8Epj3x^S;gK}RDUcc|@41MK|cexAEmvL;Ac zrL=Hp4req7E}CNtwz0K6*f*t4%7Yu5`2l6A_WSkaoG&iS1TsHO#rqL)Ub~haTt7LF z9PNf~rxyexB_!`XkBYiJd$F-1`~z2K$44~n580-4ReY0l zgh%{mVVH(BA6tXjp$Ru8fdSKU9liXZ*nn29X|6n_7B#)yvEl-Q27$L@v(cV!Q{NfH z;Zokb@CfRac+#!@&~rGm;jozLUf~&0Wajn*xsXfa!h8mZ>hj&}*v_o2P<|U~7A=J7 zJcX2Goy~A$(^%s1TfuEU{YI$)x@S{3{uf&eU9#ev`%3S$J%@-z!j5uNqAsQ9j;ecE zUX!dzo{yNqC3?5O;EKOHF?_o#DRieAD-ASI=Rw<`GKJxBWPytpJY-nm{vbCO59wR1 z>EwjmwIYvszgh^J6!6Vsbw0}sFTSVtLm1VVQhuBWdNDH-6$LUT5LD>{rsz)@KsPux zX;kkVG)k3U-}t>|cAw#pX0GZAsb#Z{n||Cz!z`z*fd{X>d0iy=wyRT$8K?SXA;``X%`6#`d+I9q=_zd_bF;O2WHzoO^}y*q~oAS#YF)JL5Y zyTZ`?aIAo#=vxb|xHCp3_v0%4^Mx9@%lg`hpXR`}_FJEV@OrX2hf^vcIEK3ISFpbX zUOxv`>WV=T*ny&f35$o$Is!e>0rx0;2K)!Q%jrzw4C|+h#Yc4_kbrJjp8bELSEe2* z0M)fYawYFR+5g||e>(}}bB6O+^1qfvKUfx z#*{VRD2?5l*|{qIt&_6(i_}y-A^8a=cf^NwR^{xsP@TiEEF?OH?-ED%7KXL-RUI8X ztd8~@7me?v{#fxLln6N_!~aWv06F}L1Nf%o^p^a zhHDMoFd=d1$j*J}Tu+~`)x7=RfTsewzeimAeB&yE=dy31OAu^r%b{fL-$JLa{~hA$ z{0<)70B{fNu?pQPXh+6fdaP16042tmCn39tF^TzaW7Z7hSyv!u7KavV=)t9Q5Tj^qAO@CBdH~Jpy`O0{R#v*i$f;gkw^z7CbJJSbQnXv# zl3*`)dMCg=7aOn%o&_!h!`Y9r+^(J@%ST~{kOqAl5>MvnX?YJmlhEiBXK&7nh=*mf zcxaV8h|#0D@_~(3(sr6(N*@?}&L-FauMGlC2!dk@m>b3%VA**+1|bXu;NYANV98;O z@SeyZ)Q&9_L@_l1nTU))Ew?mGqlFOQ*=G?WZh^;7HHSQ*|i!-11@6-fo}t<8bY zumC30$NFEIfUD}Z!1m{7w=r}8lC}8*Zw{vaXA|fw)$RxejrIaK6})A8 zLby%~D6~usSY9$m**|e!MPe!8|9or6{C{Zz*$F|fW4*m40i1mTBGPoPD)(T2P9yZ6 z?@f0Y@n@Szw4ApKAo8S`fE56y1rvVX@PzmGd4&9SbDZny|I$VQbF)qyY!eVN_{=aI zEB}SZ8?b}F&10UPyRFdx@B3w~e%}128nQ})S3>yt#8`&wz*T>r;Gtz0wP2!`YT-Zx z>QdrW4}$|Km?C9qxD z_N0RBR+J`8U3E5*qG6iSTg)ZxM}z6D4P9&Am>As~lztJP77o5#VfPhPP7+1Pp!(i5 zmTy`_H{6|odVIZ>=5!J=iU+Mmo9?t}*1x##gb`Dlw(MqxK9X0<l!2}6gk$%ww5u*B|a3fUD4!w%Oue_ePIadnzP-XebKt}m)uWEC< zqqY|r_rI&yaVGe`@^Td-2?{lzgIZgbu4g_l?i9vG;w zFYc#|Te7~`FnigRm|XYbk*k{5TxhK?42dCWFT&O-q#D_JYRAlt8Lzpz9&=R>)7n!p zAhWcbB0cj9Y}Zq3^GmKr!=|T-xl7Y-N&BR7HGO=QbBSL)YfaUo{Ov(U7ery0i}!iT zpgF3p*y@l%!po0I3!g*n{9E=I4hu;_gl+XMRYWS;TjzYZQn9%IlNObrEK^zhYWY$kx;gC7F&9k_F`g6-tFKlKPstKe5g9nR;9Q~ z#kN+tn`q%_Hf3>6F-0$qnv!I0*zPm;=tfsx)q>!xvC)Yq6EeL--1r%fUL~3Ee0w18 zRI=5&T&h*OW1Q)gx}Gcb@%`kam8)yn;uL?g)lhkXQ!@=x0`JGJiUI6&9SeK=1a`Uy zgh<~GRJfH}9)(Y<)|OW*PNbGx%k$H7dF227C|9V*s){S#Ayg>zL#c|_z0U>@-nNun za=v!yMB(8De^yUVUD<~U4ZoDrQ7B!&6O5t`gmb0nhD-;{Zd>u*lEIV~Be%ZOu-UR) z@DX=DT*?KGzx+82ivmHHzHkHM%TUYWnkq7vrC{%=0(hy=5=)s$H9 zPv=UxMw*#!4S{Mi?uU%>{rA#1rRrNl80;5F6Cmwhr{}3d&C2y|$2aSZ&^+Pl3xeo- z!)P%kSDuMl7KIbYsXV~(y^tC!x6d+xp|YI|RWULtL2LwbTMqLq!b(b#o6WuxSh18o zsp!M_N|?o;=lRk{1^5+NrBx(elK6I3boKOE;tou!VhGD13-{E{tf;PdFO&O9>0NZo zywRbRg}bxxm~OByJ({;ZPJF1!I8md;kuki{j>}wY-j&MlTkBRS04SFUs!zqnR zPxmxPBpJ!o)IN;=iPMcevOKhbwAL+nsAJd}>9K)~PW#}3^S}@C>qD)Wj6m-J=gBx< z4)O$v+1@t!|I|NwAMUcuCdR!MyvL}ZK6J>L8Gm9obq~p!{fNGNr#Vwhb1EAHuul|t zyRqN>ffjn?3&tCK=2QVRVh#M1Lw|q!4Qfvc_>({Q;45PdqS;~#+7pw9uy`@+fj0s) z?3`9dCrL)T5UjGoTh#h4>VVux_ca`_h>+8tIEBD`_E*B*0$`#g0Vpq6_^;r~S`9#$ zH;@3WjevBMz?k_4w4fC1z0~p@>?KYN*`ZWLfyx{i#&ZRJL=yxsr02TrAJTy8Ld4b( zv>t%DrQ}_fmO37I>uNd}qLlhMP3a8NZEy!6>*uqW+-dCJ{>d;C`{1z;Y^j?7bOZLK z0N1&?&w~A{+p}!YtFPW6ZWuFFJg?B>Fy&~7VJpUWPwaMQLwMRaI z=O2~9hMmMjCdBQ`-J27^L?=36Yt{Fu<{>3Pn737K=WhtGuZA`NU;h6H`M-n~A5ZQQ z41@Q{W~35re>$&%X31Z>&hOzS9G<66yh&0zJU9DcX2%21-N9=S#|{w4`Ci5V z_1!+7gPktt17_hYK$mVi09nSuS}oZ0E22?e}pB^g02`>0DS9=06gnX zxHJIShb>s*G(f`ILi1HlXot>&)UmHkjz7V7dSMi(6=1#Eh#jyZKpsZjxP3~C+LIXv z`4GdI7#0oSUpW56dA$k+d6%6|FXD}!lxXA!`?LPV}!G0e_ zADGaKyZ5kx4w!eq63x2+f8n>rX!$Q-Zau*Yz6e+YK_44fYr`2S;vBzWn;$qkzl|gE z_sPpw|D!RyUWnkFcm#sxiT*`zuWMoDAwQhK!@Ujh01x}OfjGnec&s*mwEp8s=*R8x zVH+~RR>61HiTZsY8S1+fO;Te1mLa9;<=nacgl7_(n_Q&6b72RJwy@tjlJiJaurv{j zTBW}Jj1N*sc59r$Y+Y7FjE4W1c5bX1Cjt6PSC!be@6wP(QqPG{hnKl)RHr z{l6qkzZhQ)*LOZ*$h@&>d34OIE%CZnHhHRf5^<=taEBc`!#Ux?RojKCE#GTnhHJi} zq3ZtHbpx?_X0BdJWrZC4{G`$tE4)cmQH@tR``IOwNuGS>+e3QToz{bC$bQpHEIYd3 z^nnN#vTGc4EAimSK5Mv~n4fX&zQiW8MOEYm0%HB?jNt8aA@`QaNX?SHgfoZ8lPF`V zUC;T)mAkDzFPrH(3$5u&UUV%bGtBt=ooEmcAEv~<|1WI{*(6k%{g>nfZ*vmV!*WF& zHbD=_<>)|i-zIcD1io@J1gH3)xpDCOMNUb2m4O0_ih+aidry|dV)d9GTSKRq&9FkQ zA?z2Tt;P)2LbIhlTa2vn@q}GA$IF~gNUXILscmkr{U36zx{j})v0zkV`RZKt`7yAa)rJDo3U;K|w9 zH{O(~#)1+l^k9g9uvm-DH> z5HOB5cG#iDDhb8?RbW(BX!UQi4RIGi7!bOk+z%);UI;cMw&rY>7ZVBI%cCohQ{k%d zGj&o`MYv|uM^hz_Uy%tW??@+gl94yhJApSH-21hS1!FP zo@0t;TvH)H50kum`!U6UkZ99kSX~B*)#At&Fu94EaQ$$vm6*t@=t$sgvoyjE(bK1d z1-aj$AVe8?4hN8U#oB1%2zrSZ$sD`fKzH8Mo#s}*cl%3^Q*>B1Z`^X&zK-)c^v!_c zX1cp=WA~}kB`5o;VByZRnFMINwCn+g59fPPi)1wsv>lr1hz!CYDc$MUTAJ;guqXO7ChpMjjl!cq{Pk8b?&06w&1LxQsVTfvTGqUDpK~htXwu9dmQ~y>B^U z_^yvub^RlU_D#ht%Q2!AYHYPVEsHf$EX%2Wx&dHY!v_=&? zrHklz_DYfdg*Q)MY4Nzf5wJom4x6?1282Sb&e_~{s$YjPD&CcR`rLVES>P(4X*Zv^ z&f`1cn%1?GJx&5G3iMhOA>~|JXGp9i_5T2Wc&1f%(ubpy4cw=tcf+x@M>yR@9a)`C z_04SN7i4gzbVa`{`sAcp?|AZ-m57rCQ*88eOvZ@6-Akwpm&NYCesVeNSnHmy#ZBLF zf&YdM z32`+~nkf*GskGyuM3%EE&ii(wCS%WdZ}gDx=sN8WBQu)T&G?0M)q&bGguy4%`S2sd z!g8+1zVo0Q#oy*f6kMX84l1V`eD^&A-LI-67F%;WD)bgSfEcMrqwjmD3Z3BnY^S7 zip58u{uYW&x+gnVlunZ?&D%mL)HB*7h@L;+;=NcHo*e8N5OTkgKbEFhNhmnCVW&Z( zro3Nh6R&AR_uAE+CsV>18!aU5sY*SUCn9B4sQhERRXN(m-~Yt9_r~0+bYh=(^lS_5 zzwYo8r_^@r0Cgg=4K~9ON$^==Libi?`S*N|?zwH{J_$Kw0 ziM~mdX8f}0Lom5WwcU3HZY{K{aeXcuBUybR~qcrQk)BSe!J!KLSe$goDUiV zsn#%t8q>@e>PO>i?3eC35)$ki>Wa<7sg>qoS9x+JbH>^hSXJqyW|WtsPDaH35X3{O zd_Vl6|1=23tNzI}3vQoW9D|Qg{))0t;#&M?q3OT*N%q!T6YRvUNZ^?j!&fYl2M!Zu zRl@u07wTDWL{KRa;G13JCnaJqWuD8}RltM;^Xv<7XL5YU7lO%&9uMbZYAwO{D6W=O zzXKYYrn{CgPpx$1$?tYBOHj!1g=t*SKGW7IG`aoI_$klTSB)?D1SXavNHp?Qc^|8a zZ0x=5ERuF(0P3cg*Y6yYMw{93oOE`&KbxkUBR5X-)4Fh7&K?&Qr6pPPQQ*7^BI*{*`Qxd+7EJcEUOgJDhSj zzXFo_KVvQexU6daj}({QF3&$^^FO3{RG;Qlg6$-@a|{i{BCPUnIXe#N-C!P0G;=Qp zrOhp|H2}`{lHhm*y#Wc62uiCd$gZjT+#)Z_HC0MoVI>KxC;9@-iyP`fp7XOzA`$FGoYRA*QOk90k4fohPCPs$zb z2c%%?_2Z1x>H{^Va2Mil&$RF6JrfG!cts%b6dUscZCY=9XDIJLor*2Og4)6Che|bm zqNX{a9@!_al>JS^YzcWj&-^LC>3U@v9CEkyHY<2b?}dGXvt|| z3m0HQx-l;Ppwqh28ci!dfby$2SPqFFpB1jO&a)Oz@D)%mUA?NcW7nr7l3b81GQ8>ZS?PVk8fKN|-xX`LTzq3_KJ4>6PO`_mSgM?h>6cvsI;l2q72xKwv}W zWV^Isuj$^e6t6;eJ{1;MCfeVIZ8T2wb8HgaLo*Gnr^H5Buyk?x(z-{g?=p|rVeC;3 z*KamBSrh8E(-YE6kFblKf>J?0amd^ev&Vj0r7G$S#+~cV{epMLSv6zhpLO4FYvEDj z99!?kiUB9`4iIb=fX!~@yQaKL_M{93AuZBwn& zllj<;t&p@Gv`X*%w#QyaWb?w>Roq)j(8SKfH$LpLbIC0WxywZNPG}f8Z5)E?*s4Y> zhPEWU92q-f`^G6OGg+Ba1itokI(3Gx8V4!*uBLwSYrrrMm2#VY-|xyZZu63GD{8zI zN6S&sqP)%7Ed|J!7_c@?0AKSFsgVER-|2m+=HMl67=KXpc9R$Tnsc195!7BB-8D%u z*nq`9VV$0MiW@m{@P+K+FH!FoXQ=)i%4Oic>Hl}?`TrZQ2=@;!iQvQfG>(L1zO9>n zhz<3y#gZ&%6H|Y3a9gvy=dk1XXF=XmQXA-TJ3PQkk`i|wveV^BeNG@mb~X#GkH*p> zWq}jFlnRcaU_C0J^(#$fu4K^{_4c0j||gN3QkBt z%o-2K;h4D_H0Vf??`)QZr*HE~M_0+ly0Wn%8bKDuKc6agjo?vaJ`Uw0??&t?)|vLI ziwkB2ckmH@Vfkc~dS3v~0d^1TjI-9d`?Sa3CF&=RngD#|QtA4yl6mwC@5*_aW27vS6fFM;X9N+;ILvLUQ(5T{?$4|^bHO=IZ+zPpuKzt zV(k+7DD#q23$zWo(iHkj$b4=t;s2H(yqnqTQ;N0&_Ru{0_QPy_2Va(uT+;a zZa58u9PpxHQjpPSn$Z&PljC)Ixpx)k%ac8VFAJGI8^db>#lJi@2r3pFd! zENl`?CH-y}dcK9L*>S2Gk=kn1pKhrHB$}P2wm%9pJx2`J7S%cLxV`0)5XrF~*`IFW zy4vV=Kbl$0YIowWVC{ImCuqZNE=h%WIpPVEkkt|2E#c*apExD#@7?eQt&l=cdO^*6 zLu>dbAP23=6{66FCRZ!BS2(_)&t~V-OVIr^viV@W`4culZPXJX8g7?oH|xmh0M%XWuR_BRq=`*GjlOX-rj`3a_*; zCatkDdqO^kc;^wrE(?a%5;u$mBC_zQ$!+-K$jfF#E}Hc8hHT{~?Icc?9>jNbg*Uog zl{^{cQlm9Ewi3NrMK=i2=KuNq{KxOc^k)h_lf>&Hpo+)hKYh5*L@kH^ir<}5eEDVW z)8!z%Qw?011E_w4h+PwFvjVf<;A8)Pr0M;sYW(YSs_44Xaq4WPL?G;;2442B?J`^? znV79B>CNSLAV1;@S-JB+LsRSD@|Z4k0qo5%9pMe?x8cbKJsy5ql|)of>FV z=kGdGX=JDSzvfBtuZXykPfxC%#>Sblcj}5qMqO@~)O=W-;FTqaqDd)>t3S2rvEbc8 zmEOEA{QgRd(Dw*An810!#e|46KKI)>?y%VnqC2QT!okufeD*?|r4zt5xZuuGI$yr) z7t)+=EdO5jc~_l0 zC4v1W?mT4xlx~6;A4+G(t{~N-cS_d5hnAs9;(la<*iwyUvoV35Z%=ZuV64dVXZ^Q6 zg-Rh@!t(3p+d>{v;hYbDKkRHSURsPVrjLkwxQ?1l$1sAt-$^Gd25k5(R$x<)+i^R` zbLlzTB?A#YWZdWzn%viUnfTj;xuZEGMYj&2AKVUUBKd@d3Dl zgm-59^wK)wcn*TS2S{v`KWc@(06zT|j^6a1tD_q+G#50I4$3NZI_F3niWvgw-Q(8z z31I>8{BI%+>2OYMv2?KS(+4CY(CtPj#uX$!|30>pqG{P7B+Cb`G*_j+ z6O{UJ&#DKCGa+ZkedOn+en>Xz-8m9%HN3_zy54kqgMZ|I8qc7VBuIdlwfkV{_`8Y3WGP zlxrw>#kJ;PUcr|b<}=;m5wSUXJsuZD2{cRGb2j>3VJVY!CBMC)$QJz9TQk!uZpUSh zh=NAxVHNlB+A49G%{JAer?ZzTd9Ps}47qH-edJ!&^+=`Koc!B6%p4{8iPy^pM4XuD zcCYRa=xD5IdLrul6jYbSc9$@6GlMlKlljrIk=k=B-6x|ZbJB3TB;pbO1MLwWAhF2%AZG-vJc{I6m{O zj9unEPC^5mhKl|Cukr4-EyPM3FGQmUE^ruXY4u*pFNqItj2+oE^4)8(kzdZc{HiD^ zQB-ujKTX_cLSypen z$(pLTlCQqAFVmbmyajA=93ioM6ul-11a3WG~}MNREcdW1-4 zC(+(~2;bd=D>$jWq>|Y<3OUnqSq3nL7acA(S7q7p*sq#69^h!pwy_=x6=2DC8FaAT z@uX>A=kIl;&Y$Q=YvpPC;e%s>?)V*yd?P!#y$P6>_wXCW$;Pl9JgibRd}IO9s+*-n z16YfHDHEt0jO{BcDnq19=0smpVSTRf>^{p0-BEk{E?dxZ??+!Iti@BJ@#nXBr{oy| znPz$kn%?uEKPlixa0pdMHzbCM=Q@TQ*1~28g7fWRXScmnRs{C0M|XI8`M0b;LG7eU zynrvZkARY!?_Wub5_teChC^d`d?+Nqr_I%Z<07=O>rJ>@62AZ4{CeLz;}xe9JT-^W z@n(^NY{{ihcI0ah@)msQt?=5G1_5F8xwcFCypRpE2kWlQfR4K9aRz%UJcCY_JDpp@ zXJbowPiga^J5(ri&Lwx`Q6p-<3oZ^VV+Ez`R8B@p$wn<7ZO?hBV=g*iIU>>K`6}2z z+kbolF3Q<6*vS$q5i$;T%^o4l`q=LsLVxQXXV)aR9ljWkb%xu5;HkvOJ`#x01N8?% zG!{rOzv+NrZ5H^#U=X-U|Md-C6TEa0jK=n)?;OdC*$20gi=}mV^o#BS;Zs~7R|8cz z{`lex85MRo8tcKfWYbj(>QqDBKPzM*P5!0#?6$MJ>sQ0T$&9e`6+_FzFA5)Am>ONO zZoE^ViGan#MR<*X*lU9nx_L6BN$N8{-uL}cb*#Svh8;=^nH_-t%BSBI#9f>%Zx=rA z8$3lQC()Qyeq#0`ZsWw4V|)_)4R05z1i`7XOt4gi9PPOSfPwN8c`FEb7(8tDa`j^+Ji+K`YI*k9|w(zMbdHII)L1x4@`UL zfju70#D2=JWoI9_F}mV(*!2=5IF+0wsz?{AvbLRP+xf-`n?EihB8LRu?W1+O?RjB6 ziDSwSo^=~R85gT+v&U}DZ5E~1JlVY13SCZjQr^u=@5`m*HZ{#ga-!=lpj|iff$5&L z-_)OG^qv;G8|hm*30p^*6~)fMIHuS~xLJ{}{0F0(+=Ieu950T`=4ErItq#yW5A!E@ zRLgKf!{e^J+LHa7SNB4+B~O|;Q!5lERf}6|tiB>6T@FiI-U;1{ViLF8H-MzuVEBN( zp$)!1`4cDoCBNccd%tqiWZSQEPb5{{5SKRKB@*r?D^l$nT`MBMx6a)yNEMhGhN9mu zkJWh%!xxGaz{`6CiZ9&q(RN51Z?P{dx=?YJiCESi|31a^etT2PYMA>4jYxuBDsNQp zR`bidPtG3PW7rC1S|=hab$4jK5lOBOAHf4FithBiUU&@4q( zRR8lWBY8Yk`-uCeQ3@r}rX5(?f^CvjQ*7dJj`uU8x@$F%O)!kq>$S1t4P!gZs4SBH|VP+lSg2?=|7I=sM1wH{U}d*^-iK^wng+2=Y?1Y^G5CJC}kc-8bNIWq3%j&E|l@fyXrk^@c1p5iBS3xXG7lDLP+ zY>A5i8>=C(>+lu%1V2V9N=*&T1=N-K5xK}9Z$|gA<-n-{wYsW=yt`~k(>7rl!!F*h ziV}9jZq^cfuVX2Tt}mM&r<{1e+PxQQn&z_5_+C`$D3ox zUNf?B!>9Tjl?pf%{T8qfKEhaGr~AORz-N#|XHc^n5FVIzU?z!rib0>^Nj!NJq{QW}ZH&qR-W2lXP35eK9|F@lnh z+&JqwB`}0frz#ZXVvt*8)+#4)Q$Dl*$CvNh$oYxGdFDT+g*87$xWgS*K&s94La?&| z6HW&$KY*VS>w$bjWq7zZmW7##u94rgjd?x89q|GN7_ z*YZ3YS%qB~h@q)u5jrPIo0gZAT$SLaQ6w@px45l= zxof0GIr(*63!DO?9`>OHsY_45-^>wI7cSO>`rMY7{&1s_0U>SF<9EnttF@a{fMp&! zFw$}v*pyL9H6%)v+h?1N7;3PT@O)MrGaT0UWG!O8J+(c%P@a=d!eL%Lz!`FNZH#Z1 zEac11PRN}H7FPZzl`NtsK@Z8g>&yo8XN!mIH}iRPwg@fV=PES)I0BhPnPx0^k(pQ# z>nWnTAwd{g?J#unu8x?uzcsDTJZCkO#recXe56x6!PU`b#Budy&G4Oj`6WeH1e$3! zp8@qb!IxZvD~Bk5U+N%b^m;~$tt)l71?!7mMOwB=a+7ZPPR?6A{|d3mbj+JIm8We?(MC1+8w}<$a5kX`?CZ|I*Ti zUnsbTJMK!Wt^T!JQdK`lJw#HbdrXknF4KTFnug($*nRj#E$EDP?)?Z`&4KRZ%(}#R zVq#U9dQE=`cA4ZuGuD{R{R?o?(tTavEC=nm6E|{FUfEkMe_ESY@N&Xu!NC#HNDebB z3e?KuC;U!O>*3JC&CiJl;FU;qj`!&oYwh%agrsH@w$x$VzSnb=!2N##U7oCvh z8jTjMzwuIZJ0Rm`fR}x=$t)xFEIhDOQnx;8?RYG&`G=iPUiXv2_iFcWjX8Qd7&JRr z)e74ZBiiqKyL{g^u0|?@4H?gyK*E+q!ZYGfukM7ovVOM@uOKwjP>oT8&t^GlvP7yp>>L$1ALa;~1c2rAKb=aMz^jR|@am zH@pxIWR;#~TCLtBS7N;|6zLs|L!COa`CG>y_8H&ZrC~5<@TKau>8n9q^kr%x;$*RT zm?OKv{0RmTaX{K28sp-wqJtV-siP(?e%5?#MWdFaiQDWeeHk*}Bl+XF3&+_rjp@Pw z#t|B5x?>+dqM1YKk-7IKJx}K@C!X5cac=oEMyLj`Mmk;k|--H71$B4Wy*#wc> zczVVnmHnH(Vm7=vCmdL#it<>PgvWD@D@(Vvq%tA{sS&ojnZW~X5jU(;l&n(3Xb0bp zYFyQe4kOdYnW^Ebk@c&jg~)5k1lyYn5xy=-F}BEV`zC(lUF$vwK`XI(j|@$&al6;S2*8uJ+=kvYcjmQQAa$ZO-bWf{D&pPouNi_RP}O>*|HMI_sk zG^NjZ7fZ9NHdKjSZuhBzWKrUN_a-Wf@A#&ByNq;J zmZZ$VH6rtjAUm8NevK%fF*HGS0&T5l}*dEQqYNuwa zb%%G(sLsih3IjOBS|LVgKtfh9movX!XkYNDy?;0R0`4n9EmHVsZk&E>an4%Rf~Qn6 zV|d1g!e&Fi5S`0F3lRlMOJaCs^`k24fQF5?$}qw#p>Jcvzpk9+lyC|HmGT((uVZA3K|d8 zQHSTA@q>RJyO`@%`H`LVirIXveijdT+ZBJQlnetB%DSFSh0*gI`FF`D-(gv4`?+^x zx>6=+S)!<-lXYk>eYzcLEr2JK$A6WNSe}$1U3*w4*N#}NdT@JTFW+vUGio=1EYoui zKI`qyi-m6i?+ZlslCxpbiQ5>KBgp4?RIfGWBZGg^x6_e9V}Q`3*wg_rj5=U} z@qjtI1xMQGCk`c)tpxjUnJIUYO7}eVv0dZ60HTp5e?i+auM5A*DSxqy!f^YDVQ-Ho zipZe);d2TuOY|Mt8T)V_+wi)lG%b>n3Z)+DhY`6vh1rrNt`;nC$C5SyPI!Uumm64@ z4J=tNMj_Q(sXsEf6tyWW736W`SQ!};Y$xJ^SD?Fxq#3-vf9CLLuk_x>M`tq2k9{O|_0YZ&BP$AUCRKfoS0YMy@v{#Fk+ z6rf!QIL;$&91g&1XwMnocSYoZH2L(3F?{+LYh2ZE=0p#2eyD-FgaaM)o-UC(;ytnl zu@4F0MPmrz*qf0XlMYx9YmjgO8ersZ|JGc18ldWD``BNkYIxsyW%y4VMCcYsNQA6O zIgCNPsLwnjqtyBgS`u^02V?aRLhl3k9paDp@?iXe347WFhFVCH!W(ZCr zKOY56HT~bu7qt8?YJb;fdI#@Zq3cX`+tMo~?JKq`iO--!Ywr9wP3;AI@C7OEIjCgf z{{t0zn4Gan9sdw+QaVYp*jX$9;dl5*i^J^9lt9Ecbe-~9czt+%8W|IMYKl-*<$;t$q^8T>;u-XZ;%dxf5`3~{9>!;5(YkgVqHZ-j1!oO<#F&Smjeeyji6K_laQ^ zUh)hDOcR}?6IAb6lHH(S$$96PP}ReszGL(H_ID=yex!r(i2m2E&g<&5I-m3u@m}&h zPQ8xLG_7fjn41Rm;Ss01pMh^9^dM|!sSxDS89@z7%&m~zA1bs+o7bdI8SBe(7kUCw zlt>980ewRm2WO9Q=dzQA8xq%L;F`T>x;56*)EF|KONS%FgHZ^M#miKfmP0|@NdY@8 zbqD3$?J7)b2x-pMmVI zv50eG)qw&RLY}Sbi(8vbHJ8}?`}I=qUWCmuF!8H13>ValOI<>f_%{c*Fa*B4mfNv+ ze;J}YSI0sd8Ir0SLbKW5j$gcI&d+J^hRML5`I_STJE@p4_rT2qut!K;tO?ehn%3CY zHZ;4I-c43c`KmNeAww?9-Bs}*vS@O`X86@Z=TF=!RPVO!HWWFg?+_2V<@ibt+m*n> zl330j9$&X}a-h_l(r;!`B>mCGd`IZZEYODZ!ng!-MNbBg7t; zRp?+`>F+wPJiOYv*>1{~u9{n-w4*+|K2Z@tHTbc0gP+Q~rHv(Nh_uozvtw?XMBaD6 zFcfr)sn;(H$aH@!i5Xdx=)1UC!mk#3)<&=` z!g6s==qY8`dooR9?=$b_(c_n{%l)-v->2w`P&<-`3s~>;bP`r-eqt4!JBgV+9OIFl zzJ^HS8r{V5Dba7sgzg%c>np{fccDku>dFlPg%D#7G*|-wH=W^Gsc2M23TVO!QH$>IwNw{!gU#C7ArjfK)55Kzh zb&4k;ZESpOjD|(`$D>ZW?!}LHL>F+Qn_lW810B2t(#k$1Pr@dQjI4=F_=1$JwPwDU z%dnD^T|aqys|{#c9;XEJ*nu=TSeD%0hNHubSjK>*_TY8;?EHfR8I!3(C7UKcDBlE4 zf@uVSemE9l*fS?MWbeYM;0UMMhyH+iKcT$yR?+O9>CC%|c}aEOxe&PR=Oy0ajy*o- zZDLu=ndsT-?79JBX;!k^UDf`vJ+z`{Qzh3h7U}>)!Z$hfQqyyzj`LtO(0ce%-Hw& ze!qMIPk2`izsP9$?JJrTF<}XbYDLJR*6GmJ>qxHuj;~6!xP{k|t)O=NCuC=hZkP_v zn#W!%Q0eHVRk^$RT21mk5&}T6_PoO>bpd=k?N<~*6|b^&Bo%WRXiH-ehpW5?c@Ai8 zV_`t>dM;y6)v+Aa@Ha_>yO1Dn55}d^bX9BnUL~5SQAMs7_h-)N=ymXY2uVcg!suQI zwLW1MYIRRhRhw^ow>qY}SY_B@U3IlTMd`WQYzA&rIR?c;fGSYXCwYMtvZBzDvWUAi zG#LAqYe6SQMVVFfvHReMr!Mq?QO2$xtApuzYhQ6!U`APL9q=9>v%aH? z0NH-YZ3mfnnv;+NC8-a+5Ylz{9%K-@zNUUoI5INz3oUaroCBEI8}987&}A!J10;B7 zLl0Ptktvv$s+?*ntbvO+g74Dkk#{S#wQ-3ql|NJH6V#0y^X)UHGf-^Wj40Um+b@#7 z-tU9*01=l4IkXDaZ*1fo4fJafgQGFd0<%2+*#>A>gA_;a^QWk)_wCr>TLd3liB0sbyc5@k`yuw^ z4tUSpL9P2>&R$L#Qd=w)>NR{tvk$rhqyFn)Bu+R!xSiA#_)HzB+E%5{&N$iyuP@(G zKff%_h9w5F&0i-m1vtzgPAQ$$G1N`J>L97e;kr7(cJeV4AT2N=7$jAoL2WqbtO1%0 z8^8#@ytoTW@AUWGH%b`6{C7)tGPL0(ynXNqD9%C_MYFESRCGJNv3=tSkZz@CUaqnFNt6jh)1 z|Dx_K!`gbkZP8FDlww7STai+{xO=hU?xaPE26qdE0>!OBOOX~WMN-_|io0uYCqV-Q z{&)TMIp;om@3YT+?!MpdC&Egy*2Cgm^PO|dF~{I7<;vv#R-bZ$ZSt)sMIKJ&6W2_O z(b^O+XKl%SC-1ieMwsW&WpvwOuHY4Zk(9Q>9AMs`o(#m;r?;ht1Qh}*K0_N~dsb*J z9F#6Yd^<_jGb*u*seY9HJYnutZklZ~Vz$q)%lty@l+KUa6;<4uc^YF=C;cL0*y&vt z?{b;nsK7Y>#q*CE_*c0f#SLMl?e9q>I^0o%R$+fVS`F&L*UaWiD3h3*3E>8op@0dn@Tl4^ zFyF{453gdQJRLTI32JE$7k*;vQL`|5Q4X-owlyNc`uY``n=7YX@Mn>NKR@8r{^3`~ zj2S{fH;%!o6D(DK5chqhPv4rWf?Si5_zB5o`=f*WD~90B^DhCmRh(y!RbX^CM7A62 ze&W#5Yn6G){-Qm(#Xwp^2PjOsNY4ECAs!13tTx?;3a-#IEolF6m^9-G%OgZ9T+;gLYHY3wn(6C9rB1e?zCM|Qg8GL+^ zF`iI6e>fbC5a@sistP*&3PUzOHlhj&(*iN*so;9ioQ98VNC|nZ@S3P~`#!6;^Q=*A zfw1lFXBoElsI^BR{SIy<^@+y}shxNXI0aT1~u5{$6T6w4=xltl9v_uU^H1jIt-vz0YMJwJ%_?{&diPG z$>aN6aY1R9AXJxt9d9<=)ztTBx6S=8;~d+1?iwmkC4u27*n*D;D?{TQ%-PzG>vZRt zzoLXu0}9)KQo;9?A`O z|E~83k?q{bE}G{a!gXBnQmL-~+>++kkF&ncQ5#*{J~wP4>^~vIJZsdb0biB*sS~Ar z&z1*-$HK03t=7h9dx^aar4V~f=|{X8ZPF$oHE%=G|BB)L-#zx+bX(-Fz`Q|bjD6f! z4mU-1$He+^;m?%T5x5S^q-!yAA$WCQwzK5RTA}9 zkj016Qn?aKv+qkX%zs}KC>#|s_$c5vmD-RHiLF};&0?CLH0H02RrHoDIm}Z3E^iD! znyYd?OE@}JsEm?&(y=FYtl<)#FBru6Uidp4^{$b5*e=B)Oz%~kMEVojvn4r9>6t15 zYd>Z~3*OXaimv5aSST*Lxs4niEvkKj2ilQ&?USL762*AV z3sQbXp{Q5@=t+9`3FNuDKo|JeoV=h|Env0k=w_-$>x0x1oLU+7>Bo{AwXxp+yY8V1 zvPrg#g11K{ub37rDn+|;;bT~+f%(b5LIWi1|2{3QJL`#A)r)(+HK5v>NR!vPriXIy zzVhMU3n2Uz>QSf08qx7Dkb5{8+x@oCb{h-g_kNP_&q7tnSv=lkL0`V3hN_Gd=5N6r zqVK!kT`-3J)O{{ZE<#=}orR(T79v<4a6(ADf0feu2tbL}?a;}=cn_;G7kO_lo{lH| zuTtUP|16{PS944k1;8wzqo*@_X?-x%Y)}o1YmfrJ0-NXe?M%sPqo7LVbWXlpk&wx& z0atJMtgOeOXHM`Y(6U7|-4<_#WUMb8mg7B;2D==-H6ZoJUL+4*|9ZXqWWIlBf40qP zW}`CPv?W%#A@Dm^_Uxhq1p&*u>@p>6T*@Pk*=~u%Q0SR?i^RVP=W4MAC;kV78&2q78)R_EB zJa!bvm>J(??zfouLR{DHbxv#*6&w%vm03zaL_r%ZV;u}cHSNTH!L@XnX7R_IOkA2| zuPCp?%FCf}&1eVs-BKz0$!5+fd763xo#sRqaiSyAQ7NN-)*_HD+4Cxpwxx}CDo25N z1w6QvwxdT+vK4avO26@GyXYvt`1;chBzbA^0nGU}xGcR0>ovrOph>7d-2=2sg|jCn zBy}ALIl{hf%~7%FlH)Qw=+Zm)>_$jiqJamvvX(~c=wA0=xb56kptqfJrS|iv%+sp` zrdC%!5xttp7B$+%*cP8j1)=5vYFG9hrN1<;LFD_!LbGV8If$T!L;PqoPoZG`HK`fH z+G5@8<4ro;ZabU??8r$YD{i!A*r1exn($o8fM9@k3lY|ABHrUS9nkO9KF_BQ5el9N z-VQel)$LB6pH<3#Y4kI&wk|eW?)t=?uS^Fr)rOAcIU@)&e8(kq`A*7c8cxF$176m# zx`s)E$oFYevQ@BDLpFtXJ6xSF3knJbi`4G?g zBE&XM0HYy!08=P`W4@=o2D_+QC~q+>>iFeW_XEtz&h`7*$-R5#IFe?iyL3;5xPtps zsMNtWT|-H=CCVh`i%NlkjYVfDGh?V&!EEv->Ux87&zS(7?jtw(yn$GNJeqX-?~BBd zsk4FgKY}gTR6$ys;EcD%?bSvD)N1UX*v1l+q2}keMwsgcQ-Cl8L&LP`nyJ$WkBpG+ z=!KQ8YNxTfjWa`!hx`7BuMB}zgV`ymxrM`39k+L$vUuU|G(&rJECHq}&YfuBHXQWlHPj<6>0#II&`?|~0afv5Jlu2WubhW4)JP!=V zxVp$9uD%4Hd4#-QtoGt14r0sb5%&s!M(}Pl1^$|)qSloc1C)tYeMEm-vJkFepr5{Q zOK>fiKb_FLd97hOz3KzS?emtv&E$T&cC6h?d~PYfN#g&Vf^)Bd^7>Gg&NWUeOo-^S zQ5`ib;-pr}^p$mrL&~<5ZnF|!lOpY-$1m?QV zyq()U=Xazt@d)zN!0B6Y%p%RJ?cBdr6kLCa`CscF{|gkzFk0qEe#LqE*^)hFW&KqX zSM+x02goN;H{s`!DH5r(p`t`j91NRwGShiCS`{>tmiyYR6Xsjww%k5<+=S;SX^K|x zygA#p8TF~8x~!;|LrUisE;^9I$iN@Yvkrb;sd8#YG<4_qgTG+JJ<|%<>Y}O;HtQR< z`12WCbznU((~3$hOh1d35cdLRfe`74S2i|=p>>ao7E&lpKi=)*v|r2U9dWL3p&8(Z z1b{~dglXJZ6a#J_j?1@FJ$;wsfPwUWei9;zdNgR;j?iz;IHeQ+u=@boyTrb-W13WCE2<#9GPx1=|-5MZ>zBBN`7o`FW0McrT)hcRJ=GroN6$>ATA zucg`H*Mf8z?xZrmF<`LlwuxJ3PJ@E*=T|~m(GfR_TpEqsxD2_6uC=BO(I8;Hdh_&n z*JX66)d?%eWg;Rf`TjdJ%e%`Os3Ku}?MN(<5OE9d7fJHY$XE?tn#DH(1pmO#Rz z+q!X4-rSF z?vVmSMwkS0E{40s;CHvT1J<7c_b*K5Hd(us`6*IiN4Lt|^rBGW{n>h`^_|EfGg1A> zTD??t&4)Z>Mh}%FbHPa96+`WfqSBbi2agW##bBrY7FMK|I^rSK&dJl-mwBm=I4;o5 z{Za@gq3xx^D#wIfRdsb!^frfrT0JH{kyY@kt;BcDQX-veR4hoFITb-@RdBAIi~~`# z4|JY#-{M2&=k5>KH#FYH68Pzu&vp8_I@>}bCoP0+`fl!r1sXC@!PUcA z3=YHQmxm(tU-dp-zzG+mbmch`yh#!?jp!XM4#!#uh?t?CzV^-3kE?{|H<>If( zQ%s%-Ch+r1?;Xe7oWie~aa+c{DPAzSd*=_T{tKjk%GVerbL#3%f8exN&U4JeH6cfD z_$| zizjPo%lpz#lqP~`C#;hoUQTK6_Y{X~*Nh$`G(R+;Wb!p$il|)k%wLM|XG%ghVvp%g z2xC3H*rv)2Pc~RpB;(_@h+emk`a<44^1L+y>vDTG8!2-Ur^RHKhi5S;Xu?EOjb}8_ zb(tDH)Pbvh-^x~PYUP94t8j6d83eY1H*>`X?O}YgXgwIp=dz4ckGiqBzCMl3_`Oms zzh-5Y$1nXzR^Ocb6h$?6m|xSR6F0{JfxJj-bK1KG2CF;0o=VQgeWxtK8*2vO<{XEM zhD6o<+5Gy(u(K5&?w1LEHZ&Hk9JeV5%ZJV$hkS%M z`vS`UMC7O_lk8(O&uzqz>3qMW?M97Kj_yer8==wDrx0mv+O6FmrKYgYl8TS}+M)D$ zf0p*H>nh6=7bemblbLwRP-DofXUb9@qD8en5A}cO6BYeuVH@SH-PhE+SDz;FBBFPu z^6fXBz>F%<0OxSWMPt3GvcLE_dF=+nGkaf(MccYRnV(AO;wCILTT=%>6Z$-!MR5)`1t+p000Zn zQiiFU9gfQ_g=4CUa_l^vtAmmBA=;~`-e5W8lmQ|k!~F*XmA$~>(+6l0)7Sp(Q0uj< z*P|ZoX+iB}TGpQBmKp_SLWOau0%je@4LzUGzcn@8qz-1grJ~lMF(j@Geqf~phl0f_ zPTYLV_r!mfv`e;?&2v1ooQz*8TWWJvVk_RnVXLzQh zYZkgR$iAM1*>BnUd#)?qS~I+h8{!^_C7|rKonrDRi}u~Q1w~Bl{R>IvlBj9!+~K+u zp*P>u1o)Fcn1_~9s=Tf)nr(JAMkf!x^W4?B$>I|0g^>XF&|gC_ks~mN z(C*ZZ;U=*?+okMWH9%L$vaEj?MAX;NPTw?8w$QY~y;=K-^@J?UMiSk> zMp?1h!&QP{>xgGLb`IAbQV-{*971<5dzZOsYj^iD{caxldbThA4Ot&0gjaXoTRRh9 zzLYJ;V<{FMssK9DCm|FkB=BluuCAL75%-InJ+@6YT_iu78(r*tqps#JTMr_UaKRMJ zti8&0|FswG^t+og+hsbh(;ur388miT^?6gbO!Thje$(($zbSQd>~n8kS?=DS^uz&w z%G?zQBQtwf9c9)gXp8ztfD0{Q8w~C9U}-A*e$gX3Q@smY>tH!kdM&qE?iqqLoqpFX zY}jpFuPV4vsqExlO!Y>0fcZ%5|Ww15_)4$xv85Qvn-JYD?lcunC7z{gJod&kYeJlipM$It$jh(1w1W!M3o zkLg{Onx2&g5g6`@Ui&tcA_DEAS*3>N7I{p4kZ@;OMzidaT zLoGol{Co}lCQuuDH^$po5SAEFy|QLz(#`!vC1eUGlT|_|3_t0&DuaImyeX*oK=dNN-(6^~KVE56j9X#Zw6BzI81HF?}3cJ?pc2ycnGrrHFW zH0q#cM%m(^z0JrEH!4!4yzA)+O|YIjkz`+GYnl~?UvQ`)Lz-6zVbxqsJHh8AgDD=v z9Z|cQ`o`vLzAVH?m_F;DB+PDkV}py%#1tc2+ex86Ds5%iZDQ8 z7Ij!#raZaKpBeeOd9F!41_l04$ZO#r$ZLypniH5(u>)kcUyl5*;UL+r|7y1H|HCmN z&ikK&@oJ_hsI_ap!?o$B!{5rxicXksJKyNW_q<}GVzgTZ1T_$$sQ!ltDNmq9Q4O>x zt_jF65Z7o%X+EGOp=A!VB%A?QisAp)pK|nb>dIl8Xi>BM+$Eb%Z^o#jqlMlT&EX0nP)I^W51>|iBfKn?$sA4z%G;p{p6nwFHwKbXUnE-5sz9R93h(@?MaL~q(AA!p{NqNA$5gU=&5#>zUvmv^%7 zpKhtuyP!8uA)8X}y*3A{_>bW|-`EnNHhZ-qlNYjiY>3eaPX{L_&wOJw*AJc$(j{gtnUk>B?GYN%v4zX~)*1~{uGiIKDd*J98so#CVPnUj~@K_=spb{Z4Y8APX{j(zr=B zbti|~JjP!3^XO2gaF0EjI>DTyIgg3OpS~}l@$>`l`vQssPP+#ebgsSiP-1TaK1thp zwdx2q;q%4C!3U?L*FQ)WhL{q>?J{?Sf?xIxY1IUZome8bQzX7SlrKnTLDsueo6Ng{TVz3I{>#s9KKmp?j@R@gSH4mgo=T9#A}bT4$c%}Il+mDDz~ z)~8DhseWzRANsQuo8rd^9eTOkUpHY%jEL%{7S2cN$<@}jHa8`iw#*@a4`6&m*Ar2_ z!{}ha4<9`;nz4LQRXf#!@q5wOtQX??{L^5v{6_<&?(wHq^EbQj-H(Eh!0z&2jwM`^ zg2OSTFSLJHPnARbV&REVy0F!>lnV_7WKk&6+;`(>*OykYgOxG9NB-zoF8aW>@mbBzTm@O4X=bL>C6XP0W5w%jnWnOmIl`i?E1`0Df%=qLLUu2aZ=QS!$8_YQ&He#XN zeN{IrBCxPp+rNNVLjPe-Q!l4n^qdQIU$)B;17mSJvVWSvFd(C0*T za$-}Pu&5Soxyq#OF8C?Wt^!AHdRjJlDkdiB>dQ9XNg1(^L$*v}{@G=-{F$;~m9hNU z$TQH}Wi&b<&d6?~5er;>9aiwF3ajPAt4)sib5ZG;t+YdWAY!Nb0&)StGG{4i93i8b z5vT75&V`5RD0=(#<^(l(=qTP!twXF9J)AeZA)Oru!-3R$Xoupq{5yF|WwJWQ14Q!k z zAE9okaeoN+_DtMMU#0hTq6pcz^CT56Wx7|CE6%^sqzDX$;ip1uFW=Ad?Z}Lvyh~h% zPsNGWg<(_A~Pc7 z0-P!6zrkyOhS~ps*ZvnjN(A6Xp(6q!F#mC~6@9|%;_|@aI6JlC)W>P|mjtWYe2M9+ zwH1r#CQFL{p8dnpbUR#m#c}5hTwhpl!h^GhB>_@yc+`Xe{}2m|`4^@)mzV}u*<^0a zvew%daKwDQ*{}osj)O2wn=W{k^8QyKwRJbghH~+XbPT4QcOyEgROz~G_O+(+&Mjg-*N$u<-z|);( zYiVjGe>HbQK|Wb0f{pd)DbMciR0(ByX*&VSV*Kb&+Y-zDIp1fBm;=t%l1jsaZhIZM zU&C|wwD&`Z>ZgP#Pff3O&fHn5hgkboCWjA7cIbX!e6sif0%1*ALgy|~q*J%Y4U#|ZxvU= zDza~K47<-f+!nR~X*Hu=1YON7SCh$%(Bt~%6jk1_lW#B+WJ4ogc5x{7NCTaOl^T#A znmJ}tO}t=c2o!chJDR!?n~1;f zo4n>w?;b!1v%#t?$}GQP zEHTn2O6%z4a!^3}LfyUgmvNY)wt3QnFDwQ30yh};0eGyGY? zx+<cTm3wTdTyR;&6R?(R@HR%8KuA|aQ%vCb^8l9;$p z={1$M0IhpE+xbpB0LR}uQ=3px7x$P!q_4~jA{Vq47iV!#c@JpA%u70SJN>Xy zFG{?ibZxCA4zo=zUo2e8HKwO%(w3fL%yyA=?~F)uTpJl)d%~dwffd`@c2(J$?P^tR@P+zguk{I(eZ_upsq^Z!vQX zc=l{A9-0AmPw9UH@&C`-YyYo)H(q5zv}Q#ANRU{l_`$cum7eOa6{eru;2EalAu&5b z=8S{AhJzLyU+b}*t~(&T&vWDXJ9HDK{xObs7-RFf2ScPO3q|A(`{m;=WgKS5Y%Ge+ z@7SoAcf@cQky-0T@692(Xcp5QSOpFASu9N;x9no~Q{z6A4jCk6WI)VQSq(pO4lWXP zbX>L`wyAe^^tI;2$st4#{$uZpRlyLNwS zEO`&Hu3v{)*X7V78B*x@D!?V+j!gV_uM_H@9aD7C(;|Wv)64B3&s#@UKeV-HKiFZW z4EIOSjlP!1EH3k_?ru7bsBMN2fhR9HKTQ=U=T)~P*csr3^|1e2v1sTUFPKZbgu(-7 zf}aac^cR^ozwtt4_!0AQCjT8%p8-ENaiUId{Auh5J>ry_i*ki0!_*>-7mhla?b&=( zt`3#Dml5T>aJIP1c%CJlsf(KQ*&RL>O_zL&!2nwFzok$_K}#S&>j&6*2p--Cj<%1e zcWjC9(eF+H%;!g@foyyv263d4W|988AE4BS9AaOM5n4}!u)>0wR3)8+cCtfQC9LW) zh4tvM3Eh@=rS6RQkaqCdv~|&o;z^#96UEbS?Z=Nbg^&AQ<6M{SUnPi$c^Mx6g<;}6DDWdVnF?-N`)jM&sBvZ!V)EP9v^`2Fm&6Zp@qIvJrtT;8=g7>u zi7LTC%Cz{`65g;T^{}+4r`Dura#v`W(JYnzbNTl z0ddG?LL4QRj&5%Sz4f;;fD(#Z{X(TljwJ?6a<@#WJ2RiXm1FrE|M|u%E|N1Y(MnMn z@vwR_w!s?*Z;d1;97x2n8;6sN_OD>#BsymFm{ydRIUak$PVU}me-dQk2ki-m zO4&CzFep5X{nOz5{?N|yAm1wA(*AF)Rp)fCjt>1?uwTF=b#2~uqGGLAk6?BUn&Alz4lNW#H@&6eX@o!mmz}gIZw5p!U2#J z@DUA?0=`kL349|8%?amtg~#9n?b`as?oQ!D?!Q36xqw$61zY#nEsY@1+y%Ht5kYMK zoT(jU-cBU5=M2n2wSE6b)iPoPasCk5Of=Ho)kc;VT6t}R=7B~*FNEeFAP;1@h$d+| z;4hs6x~_@Ph#>BN&XJ3>feiu+K{5@ zsgrRY7m~1$2f2;8zJe5wC;Ygho`gk(JVB-0b+?my8C0izqK+RlS?+GeV^Z+}7NP=C zVQ{ay9I&O~WIT-DM(kuGLar>N51dR)cgT40zCa3ZsA#V$raCDEEYZ@4NY z@LQEO#vu6<#}md2#;YF$2men(r~hByD=c*q_ldB*8nL>fkqACy_$~mUNtC-3;`!;9 z>GRz)kfT}|f;TwWs-mrmxfZh_WC6BBJ}yf1v|b-kSAM=l(U@{F?jnoZaer;82>NhH z&xH8UxH;rm;`D6jJ$dFjq$x#^{8~90HJY5S={({6p4kiUt>fyPs7GJgva?&U~KBXq!t}S9HYZ zvJcJXumm3|wN$08$38<1vDiGfyR%tf48@=tea&Z)W_3+zG%Q1P>;*+>*80!sHi)P1 zRXbd1tt2Kxw~J0SLr!ahrN9C~b}gS#V}^CW4GmebS)o9yw+FVMe?wcVmkRZLNd+Xu zO7L8tE)~>?_!8qjdCW8zb)FU;X6B+KQQ`S9i9r7L$kgI&>41NYCf1t9yd^p4dQgOc zN7gK&8)MY(crtICw`1~1@Gx7-#j24ccwfFWPld%9j_0izdcJSc1n65%sCknruyCjk z<6;LF4pLZGs#>ha`D}hPebNa0i>%B|-)8t4#r2Jf%DQH$ywQw{;_gcKb_Pf#Q=+gp z)isFz*fv6xui`Y?$f-cf=9se-bez@Di4_-oG#543X66UeMnF4daLw)O(tRmJs%sl5 z*pocW6Fm6-(x%GBWi!L)!fMJL`?VQ}owtQEh)19GHv?A`(y!VzA2$-kjS->1)(o|5Z~_X47ueMQk8v^Iz^&m9EA|N*#R*L^@ft)-kmk zW1pqjD^VXyP|$91%?ux|d=qjp>-)nJMeC0ZF3eImqCc#I@bdixI{6L;bHu7z9wzJ0 z2o3ax4#!r-4$VKKjMf2irO?Z%2Q)9>cWbfM-Og}m$qEUP3Vd5#^Ig5>JVmI^e#v*F z8(Vs2cpj~Zd?+j`yex|NDb*Zi5X+Pr9)9)><9J_|I-ug?daD-vAs!xuT*-1O{CkEM z`dj^bEG=ZEfA#X%IKZfT4Rb%BH~SW?Sevvsnu_)M*GlcjK40Wy6CHRXq|z4A3}D!G zQ#IG^Gd!%3D#KW?!C~xiLeH~=OC_1ltD?2j&ZH(2US@%Tu?^*G@0F5$Uo&{As7M7Q zyn5tHvDZd|RE~DNw10T9G>?Z$q52Vz8ELQ-stI3_`_&?04F^9lKQv820X%`m_NsJp z!k@SwcEy%GJY-BKk#-4}$1?qkk+B6!d*k!-9jQa!L2=})FFcIH$A&vV*#5t27|5N( zM}L;?XD(Blbv5a&EG-+eb8_ThKGM?E!g}=N2T|_v@oq~?eNFY}5qD1x1+w>HCm%#H z***?bv@OA5iDeZjff{sqX<{ZMSI?9mWQ;8VHcj%HEMS(F-Tn~w{1{9UWDE0i(wpQ$ zi#;xz1hWheNpinneQHf<`+$TIz3#Ir*?1q-U9g-Qa1%7*(8a@}D>-F=@<%e5Hks6N z^N!id#*Fxa7zvk!48Oy{i7vE~w{po{zayRIRl7n#clV)~i1Jpgjk!dC780&kHCeur zBpz88loW{MHiX8v@kQ4SVW&rd;ALBYct68sb|-d~-e`alL*h-^9gLsT6(dNcc9udv zR>QTf)a88f4BL5=YP)fxU!v8f1(-zWSBv zU7L_Om*Df+bW+iIQwl$vRzDNgE5l%)(KlvTIR)W)6nVB)okU9?b?^Gt{HFJTGDK#F zyl}@Ckg2W!Mp>{>>iYpv5iYx5M$b+nPu5%rrEKWa=7EU`*Aigo%`Jhh8^HbrqODMd zU-riadBgKd>8#&Y_KZ+`5iDWZPw?DL1iw9i!pV@}d;D9Y2V5{f9&>Cwhiyk~K3LWA z@`F(tmom4cm%Qkw0KIrKEqoKOk4K7ptc@ob>++q@3U);FomnhFbd~j@#SO>MOgWrD zZjlSf0CWN`&NQr1O=G<|6o`@!!+lvae=h){E{1XDusyPzZ-Hc+mtlfVXVci4LH1j-cb>FtX-#8~2=&Wz9i4ZKX;Y=Hq@&ZB$k?jb4qkR-m;b2u4?+5VYudf)M9?jL&XFBr@T=h2^MmkW- z=DncrkmE2;{F<9|wLgwB>NK@1h11~OE#VfZMK#~qqJ7^JWVv%BZSWI56eNe|I_~fU znezm(Lw>YH6mc1L-1rjLcKtQKObgAh7TZrLP5|{P7x{H-PiCl?`IRqteJe_5Jm?=j zmya^qO?%<~F`+1`nc@vZCeq6m0YW;KcYe&jdr~*Bao2p(f7_ZXEz{yNM`S_jH>d3+ zTzMz;^m*IXSGFMMI!C%K1+ z>Vp`YO-1egw9SCtHiEco*eqrH%RM(Z%cR&0Rco4E z^sR@FJRi7Fu#LKz+Iy16lO%%@v9Zs29XM70kbL9b`Ir?L@?2?ZlPI36>|O1rJzK_j zYu#Cr6!|#(2S8=K#&+U?OiQwQWP^sC_1kcY$||$RXwOzk(5mVsP(i#yvjBq@mw?x` z)<4RJPu$7P^S=DKq`3eH0q$eC@g6Qhx|X?!r|pQQ7SF>U0BYI>evnZ{^T23t_heAK zKsuN>13O~)lzTy62}Go5Ai+Oon3uto*^>e)f(RhWBNt(piCn-{9CPP}6H5T%{_eqD z#?5mm+}m$=PVS$%y>@g+BFe&2>~b860P_NV8l~X>bPAb2Atcc803ZW>$_9j}8fcln z-94uML)-gHNhtar>;bs3Q1mcR1lg7Vn@DA|IPbzqIcp@Cr_TUV_KB91543*S32^$5 zCN*g@l8oMmG($_!qoLNyg+b!(liE&}t3D{7dH?4cFfdmIHb~W&E!%2Q6U$touynvv zd3KBuG}WBt9-evhz+|zyaM(tYs)1yUieeSl*!bRj_iJ6*Vm6o2P8ll;GtTa*|3-ab zV)tf-&{K~vFz^@hPh>Kc}_G6$|BKcRW1Mt)1W(R?4{W_dSUde!KLOQ*?MU%?CK zN>N2Dj_fuioEbK^@_OP$seV89w4DhBg-<`ju}oVSzZM~Hb3%>Y_M=$?s_JT~rhFA+ ziRw$} z{Dp+b=fwe!$`KZJL3J75X6tZ9H*60r#$YE2gK1uf`mOo+qWr*D8z;|}FRS1W$NlmB z(rvXrArP)ryf*?Cy_f|Fli&DUKB<6|XaEfYm^rPH0KdOy(@iW7(VD!9Yf$ERiuh&w zbEY8#W+&eOV>C4~Tt)5$&Z$_(Zp_)+%QccgMikMygL;)ba~t=L68}KhE+c(`-lLh3 znkGobCx{g<)X`f)$U<8_sSMD~`>A)=x74tn6(YnNy%jmO362q>+KS|@TzEOM1w2l_qkj2gA7EO{Ko0#aQR-$)vb>HymZTlb1kn3iScoA0@+r>eSc zJ(p)$Y_kl}#*y1|ibHHF^L+f-vPf4pwPdDorRel)BL|V5>NekTlf1r}M8n~edDup` zA_pz=tJkjoRuH&C&KW&XEa0!p-=^okwV7DtzSv^A)MFZ7?J%jx5_mD~Rr?`YRkkNr z)6FwFHRx!5E1Z1E!mXU{CdlD`IcG( zwf&Y=FPL6GK}l?@LRQj7r%Zsilju|XCG!gUIivn6gnlwZy}jX&|LG&ix^0E$ZQ-Nwap}hy{#LPtIPkEd8M?TL&~2+?=XVv1NXx-I;yyws}C&0i-_VfOi+i-s`AmlT{e5PO ze8^RM5kr}WkwAst`38NsUy_Aior78*3pTbgrSx6E3{@Mu-|b4*$cEE+uR$obKsQKP zZcj0Qy|@y`lj3N9=0MHd^ta)iNAS)2 z;mY6Z*0j#jwTnO)e<5>EV95vwSbYYpVfnCwT=(ICp>x0>QaWN&h7@I{Gr^W2A0~0< z^RZA%^b0;;5&;0I{>N{<^E*_X4w6`>b26Sn8&uGg(ulo`9nR!${$gX}9~1*R6K($x zyGEoaU0S+g;$&D?`OT&}ek&qd-?lExV;%>TgnOWDy4fZWBtF?f^D-L>zfrAfSM-jL zUgtm2-%xn4L9jzbeh6;Zr%{=#;!&@4~3d3(d1x!$8UAMG|eR9)?*>bE50rS;9 z8~sOyaZ0gC*upkB?XS12nxrH;Z=cV_NQ!=Fo7^xf=U^|IqO&{y;E6}#7gx-dWA0T! zs)_tiUgVIk6>)4=W5log`1p$mCk=fe)~_Yij#0jxOA^#~BMrkTUA5MFAMG;ovnQ!r zin>3nDJ4n7p10I4wZkiN=SniC0I?@#xpKk%5X$=|iN^^KbUNIthr=F|%*xExEJyY}_QWX5X?}kLZ8g zMVacv;y3?j6R+OBQ~Sy8^sFM0Pp5Ozf6n@*&;ah3QVwK&_(13FpS17re793XZyt3g z*IZK*xUfF`E``&0i9muY^b<}ci!~Bf-VV3(TY88Vh5>>*K(>Jt>>1O}YiWNV_l*Zm zk?OdHqGJH43g%<+Awog2<7MyCm*88O@00%UhL~=vfV|GGj{Doq@3fgEuBxWoEe` zH*yfmT9l9w#{3p1)Y?(qY5Q{jWheQ8?x0eDB>5mtKj6cwb94#O&l7zeMZU-Xl{?)6BZO@mqXfEn)v%0`B>jsiw4ZjqdrbSY#RC4igFm|?d_0lw z6=rnXRFG}C*@B}b?VNYEvv~*12e~ZzOx@oekQSE>z{bSOa9y)+AFeS#X@vBB>*bi#ZqUKGRVUm z=7DG0&s3Uqr0CI{zlE8kvUPE&j{^%Co4anxiLH<>^mX@{7<;DY&Z(jgarwsf{D22! z-RrM)wD@h@`}Fn(i1c!fSGeyEV?h1WHulF_>6&M5e6x**Y8pm5(GcXQ;~`GF>OaOsaf&D3L2srrbzIzwTJxO#V71KGRIjBUmT zp$+J>APShN-{h^=)QQXSDVxLlOv<4!%3X(kd2!Eu%SuFjx93%1L!l$im(L8qdfP6DeRqJ(93ze720cCUO9 z^x37su%5*hb`QvhGYC_%$M5w=qspFtF{g4J-}&pU`3*{F)v9{JxZ4DF1yiy5D^9+w zi1b^sPx9&>^n<5K^u=gSsHX1?qH&PVuSt~>sgxCMm>;YBW!?w#1VIsWfGO{il$lZl z22_4~6)6}4At%wH^00%wqbUV;v>h~x8%9AYaABvfLB!}HhjnrC5 ze0Z}0erWH1h&8=x0&xH$lS_L6bbzmU%aZX@Yfqc$c3ob&DBb8|iwe69O(@*Zub2*6 z#nS`~cf15N(jd14--%Gj)>nD@U_Qobcw=rVNfRQs-B*WnIr0N(FJ| zLHc21xm~FmD7_7Ww;J#D^rrOgc#g}#d;@n~Osf1+m5dA#TEd(+I>nU(GP@UTrzo7L z|I;P+@1`m>fCg4vNq7csCvyy7`rR5I3mQRo` zGp|kUqIh?*dP;qSqiSAIV$-N{&fTZ>dg*vmhfElsRZevF>D(4%WtaiNILuHuy>ho2 zBgCe71(mO%vAkupilrA9Blqw?9q=R%qQ96VoAT1H;H6p!tLXjc}(a;IK zhZ{+*InE#=SL z^Npc5pft+R&jY7riOcr68}w*}X(@=?B|r2B@y5tQM(Hf#ap`c{Vk{^i2g54IB1E#Y zl)PKm;G>bH#Xa*t;AzvHCMJ&$jG*^M9Xf1?~=`1_^;8&944a?So`Ih zr=>-8OA(h!!Rjnp);nb)mQn2aoPYwe38NehlLD%az@-i{EhiI6lNjy<682~BheZje zlYYR%&Gho^NMb*(!F}A;9G477KBoHj9Eiyx_}N)dBFf7;C6Gl<;A#v!>*-*{HM|5m z`1Ab6k?T)usgW$^xBi%u53(U|w61{@m1G+~J;``~Z-{|l@yP%vH9mR6Z-4w5=VL&( zA$lO)P4&2FcF@bsU%Zw0&u7HwimQdUg3q=Eces{NL58W9h1pXS<%3e%gd6z<3D7im z1~(gYn~n*tr>yG$`Dp5akFH`}+;9x_mIzh!vmXpAW5eU7sn$*q$MF-5j;03bRLMzg zYBi1)`P6t;s?>f#DE-QpCd)ddxO)jqrX|~I5?|-wf%)1;CYJ$28Tk9HjnsKsMCk1L zRZb$-22MK3`8JP0R>#2Q1a zv(RP6pU4d|DKR_1lcUO$nXQI`lBayW9yDarzXA<{|vi0Qtn4e?u08*%FV~6C8ix z*m3SRfJgTLJUN##<)Iuwu>)t=`wko<1XpJL&B6Kzr+gp+AW36*@gK*U?c|s9PU-K* z>F@1@EihwqPR9y$E6q0L-WNkJ7|p<;ho(x`orB5Eh^7|9O7*g;7bvjf^2w90j*IFfZt-U%05swIOqja z{*lxf;gQ9o?#*~TP^m_qC3;vTTvsn5E^cjr&+uSu@yScTvb7&P^8#{lGinZSls&J( zQ_q>=qu2lzpM)BC>ptZB(XJE5`n)9<}hs+hzfR0S8MK^>5i)Ej5uWF51hYr=MTD{Fe9ZQ9RA@!cX~2 zNA-V0_v$S5=ei}T`jgjUwkN@6slCo{l6M8S2!jT_ZKi+X?j1`PU%#RB4| zq0ze)JGE>&eePX%5HUiP%ikYGymJNGdOr+piFz?JR&l zkI@0*I?_e?*b}u-+xvG~Nn^O9PWr<;?>TcVEIr(fmD-8@jdY0FF2#0umB-Z+dLkhF zL2z98EsKiVLBiS{f~H?@lX84I)qsc$XXVq12;ZIrfgmsTvQnJHa|rf+GyKmfYG;A) z_(8lxkv}Cy9&>yn>{yWpc%{FZiT~`q{?B99O8B3}><jY#roxc0POHH1ah)Dn+HNz5LG3^OPn5Sa1q!3$Lh zS1F@)JC^CIG_Fp;7q=>1*d1w>Dlu?5nV&o#HO5wcSTk{h?qvoU4Xx9MyE3PqS z$?42hEhtR6w)YZpcXpgahs!{-KrEhlu?`m`&0guNIG%;ZsKv^!r%1mlZ%t|hT_Hs= zjK?RHZMJ?LHf^hJ`gY2UCWX;_JP#TJ(OMQBYw zNJkn%O&XJn`OpESFOz>hrgraqb%Vn9)!KLaUqRv!`Gu_zxteTalMgc%$h&G$LvQWQ z#U8(@9@U?uGrQ2gwIz~?Xtgb#wQfV9?NT%!tF8}=emp!HCq&AQNf2y@uur+v2~mt* z^vcc5sv;PZY{HZKgSYJ-cCuz2fhqk^-E#C{c16N5?~3S?DpYl6d|&w>o$9=>`rXge zfA|cWg6wbUfCtFNNg!p;cYixHWSCOW^KtmIrY7DgxvvefwpxxPIbZb}L z*j-)wQ`0FQejyJi*Q}-?d$w2X*rme4(cnLz{nSTb?T{bVhdcmLb%IwuHbd0|DPcce zL5a6P;kP=NNbpUSfp#FekswWgmM~w2UJ_YCHj1hM0bvaIQ0H&l`>Qy_HSI5gL;ZN= z6&4p@;41cP8`N}N&^Xq1es z>uc(|ju-5Nz-QpGgt#OE$iR)X$_tPn=f6b%Ia_^K05J9c3S$XXdQ=MpO;ottud6|w z+~SB)Mbi3`(Sdeu0l+hi+5iI67jk)!mE4Ia#|AY-n z+yanFBd3tic9LwepqA+%K{^En1**wyvwm$Yt#>-Q@}iZ}x#f-(LAD;{J=bmT>gy*h z_JY4YmBL+{5>imylJxBh_*kEfMfQr%I~8j`c8Y#Tq-uDi9$KQR^e#MD6a|Zd#`PKE z%8~OdS!>gzwl}Y|>B&BF{9xe%FR!QX{{lWeX2`$jRz>8MKb#Q<8}@HKv|3|)_w{D1jN>v*8 zGafWjTTh}qXQKQuP`I~Y2Fu&GEWhc(<3jbpDPDC{p>RGS)bCGYsK)?n>{0c~>kd9&+|#Rwg{sPApDI6G@`W!Y2p$I8Ct1;+KOw&p3Z#1UNl6^_#M2{N{f zX&#La#i2zS>z2?Dz#ri|uDrwR25j0l12p=v@6cyaH;=T_@y4S^)Zsm!n+dI4-o4qx zI4-43Xmuz)G&7AzKFa&nO!Ao-`pptDMsii&fU5MK2`nl630rga2iAy}?%8^KKn}co z$@6*lq*)F3LaNqYB9L~thSG;*oM~YbgRDWZWoj>_&ULmw&@|saH}$u(0h+VjPdHjz zQe5Q3o@SU-134-4pyT!F40By}MNLFhQ44I$;e79>!LaWldoJG=gX}JN2^lYWDO~R` z4+f+-vxYxn2$9d^(7c%t@kgI*R(C#?)7f#gW`~Tkn!RYfMBY| zOIiVV)jm<8O)l{IagXWrX+1WRCvDtCjgSlGyl=J|!rOZk#D`UV0?>%QM0`xVRH=_F zaOP^?nt#>B1-dA`SZcJt$>smVh9UqEA!D*m5NML#tcM7mG`r&2zQEvj5xdf&VMihs z;$T%I30sJDp{b)oXs$DU;=^0|k zd3ShV9#5F)Wv=69x3Zx`)s`b`K2to2u;ZZeV4DeLywJ`E0GG4Pu9d)THonSVmE6MH z7nWo>ZuA|9%@f5ai#n{)^mGbN%ZJXP?)urFWS&nV=UNe2ypl1Szis^6)+40&3k$z( z(+o{f7WJmr3AcLRL81|t+}}0oY~Jkl>nZXJN>rrm0!X}mZ)Oh=0z6AZb}13*Goa_R zQM*p#>34|Ck3No-RGJHaSl+_V&u-s*GEw%%+M1%Lub*qL3!YGu7#g5 zqwdOWmb5?{xHv<fY1XZ?5%{P1L9I1@cjF4|W>il35|>wv(l zla&xja|2V-);JlL(6 z(Kgn2#A9N645GoAF3|oD*q(FcKj9*&ACc8F-)~uA?E2+i^bCi*3I;(o8;G)8V&fTm zd=QdW>{$J|@>Tt#=oj^3V*W}iC~oYw0e%!GUMa4&Ry)TrJeqL+;jv2t`!nj$C^f=w7xaeFchgb-tA`? zaoGk8R@SYx0k49(+ni?pr7q9XE3ET% z6*kjyhNVsfpwAC{|bZD}+I?cEe_l#=kJm?mc3jH^t)@rphVwQh8U0J+Y>7 zAaU*m-=4=mplP7j8)Q?yg)8si)LR?i0_-QEJMTVbSZSmt<4+aTSJUs zFWnh!OE}(`n4~VdMKQa6K{+o=ydFsY^foz+bg~S)zx{mgH*3c(cPS~9dgC<2WP#_$ zNQXl1ZoKV`+qRWCPjt1}AARm)+g+~nSgIP(iBc>3)Fy=CB%3mtIi4E#c8&D2L^f~M zvgf6=UHb;n4Nc^>m9wM2Z$N$hzLzuYdu0WyAX^ex)E(at$w!Z`b6qQany=rhQhu5@ z48dWNlv`#hAA32nwbedsP}KsKBo0 zUh}Dhwt5pT-Xn5?nl#=X;RNoaK4S{T@cZEN75Lde@mlO7zux!F@#9-U!Czm_IxwHb z+nD&fKE7K$|A5EdWHeuxoEQSK<0L(FvYxula=7l9XCnYk9AX5cb`6qy`_De%ruY?R409vE-!ounuTmWkpzE)U@-k1r_8DUfV5n;wEnBQ!J_z!gC8Yc z3mMt5LjzPeUride3I9W_@aX0nzXtr15qo^=TYzLEcb?XdO)fZytcn&JvEw8B^+|%@ z5E|Of=7d*lfAfv><|i)FxF(VzSSN%gFvJh>wic&&aHIp>0s5@2Q&omB?BasEN*`^& z!s96CB{+rJ(ir(BjP<(#V0@7lGw)R=-S%>W*owSORLK!b()i_l5qoL2 z*Y{BUxYzfVvac94Q~!iLzs=vYUx=b>_jrMRPK8-9FJ*p*vB!0eg=kcTs3Mdg`O1i3 znVB-KXyQcZp-%LZ`crZLkI!;{DB1Muku11|+P6DTp)eFNKxuew_}^vabQV!jhCR|s zf)n#2%SZE&A0l|!1e~0+q$itDDq2YOpef84 zwc0X*cCf@;g^TKeGj&Dd?ECc;61}<&=CznIXE-S69tG6KBbdvVVlN$=A)w@u8oSyq zszC<1%c@#ZFr#k$s^1*ej_Z5tXicqP`E@gC^TMh@vaSFWz5HVQBh#4An4whyshq+0 z`Y4ILqCM*aWLS`~%knOJAe7R{ppWjDVsHA#jglm4E#y;^vpxigAJhn!U1qu2%yvCh z3$q%09hPZMRU*R?5W5apa>ecABl&?^`xoS|=}kkBFCaglLtbA(fo@M_v?Af+Sfu30 zeM(w#L#@_YX?lWtM|py4QY>Mx;;i$9erEOjuiI2JPN#-{^lVJ2#+cLvQ%5OX$piGS zgvS1k81*S%U;I54LJ^CK_OYhk{yD$h0QGnO_TaU~vs=J;OsJyny?m6=v7(_lAkkr9 zhZfIT4YJKm%5^b$=8t}Qv)q_WRNqe77QQSM>yWa_#`>z9*jyA-kyvX153&c%z zbP12JXJAc+d+FIFuzGoRd2@4)s4T69^i`@UgP=O@2t=NhhN>8O0JPU`F5lrX9uCE) zSeT9mAo{?})*GmL->l<_nOXBe+Un1fWEBNeXMqt`3)p4+_ETJN!Q6|dHn~20Qx+h1 zGU^D_@2ou~hx5yB2w*J%KBZ{@tR=$RNHM6Zj|$5FfGk`gfYr)a5b!N<_J;xTS$W7c zqu_YEB4og@=PyOE4tQh6wnONE#{<}*hi`x4X%zBZ_e9|;R&9$5VNib?_Hv9od}l`e z*|sa=gAeT4F-sx2A!%_3`aL4JIOL|#j*d`OE>)9{P0~oxU2yL@p3qvi$LXOf`P{%l zL^M?t6{6%!(Q7lz`q3-@Ox(+Z@vhbDlnd7Q;KHmW)9t3nu}v#~EaBqFdgKGR>9{LJ zaY5O>r^lLVdoionC3L7gXM4KFYFdzg>UB)Wpm$J{4RWC1_?4X3_{B=#3RCC5t6k`Z za5OzXaaNPY6T2P1G)lC%I4?`KDoB=q%#*2S1iIc@whk-LHag1%$-*gZ^}dEGd1I}2 zDjEV>893Xzi zkw6`{P%5}(#zzVlg7ok@FC2?GE}X4tTjSpB`r;#X0qg0uU@bKQuhlW&h!;N6QW<}x z2tF7@FIy3+4wMe?txXGw@8}#(lT>PFsbqKlQC5K^zfvo_d-xgNpKGsPdm` zH~#uwC^VcV0BjL&DZp|CLIAP$)YV^Mk0BuJAuSF zOfQ&oSLLQAM>xr2lbr`HwIg!q?rys9>1pmr#*DA`wpp8X${=Sm(+@(e zT0W<4-)1Y`g>iFtdZY~?!MX3(7hUU(2n$Br3+-6(bw6iu!u@A3wg}ahZ~nC#R8;r8 zp`j6^qvCynVT;qI4a`0(rY438;!iruIc*Ox4Rz+kXT9?r4bk5R1O2()Z;c|!X78^Y z?PeY49VnZb4ovWJUKXj~C0`FO?ng^pKS$$HI*qaBjwUZoo0FLIR90ZiabewlElcw? zi!Fi936{I;@)>-Q^Qyl&>~q2_>IJ9pfQzck@%4RSDwPMC69Yf@Zy(()qmY7zoUCF0 zm`N6hjc~255~amIq`jfxwfpoAW2M7hWtGH?bD;D629eUEBIC<*u0##RzQ?D6>|;Ja zE+7K;^HfLl>`gPt^%QU+fqqW-_Eo-ANd8_n`Z30^b5;<6ORaMBGUrly>gzR3dduEI z`jfA4z;b1!L1V31U?-LuiT;*ixA`OGS1CLhDXt>zB*USuiet+n$&EKz1 z33;p|Ff-!9)|xVVZXhnk_hhkNeBt*qVwV=Pip;i`mZF_8;W>B?)Ni0xGgHQyTu`Pk zYMe@-Sy#dmafqZ!42(@}@+tZU4cEp}%C0$W(42Gt`oZf>JxMN~c;D0hih zq~|Xil?^v7trJ?wt8mEW{`w12$1WEa7orZAM!(UQ){HYO>v`L;#v--V2B(q*7=|gg z*{sykTStbb!O@VV2RIu5R5&Of04&;-YX+WrERwSbN`k)y2ecql!no&FGJxP8kbWO1 zLGYp)SNy`P5D2j7~b7pLR2Ds+q_7l7vW*Jya?5k35Uu@_D z>%rC(v{#tG(QY*J-Raw>BvKbos`rpjmxu$VmH)#D^YOG9iOL;-F6oLAcn9&%gT&Lc zUM}-q2Sxnb*@2hlg>9h>7OecjPYF1}xAvAD;-igYMY&kn)q-z^cpa?&PeiK#U-V7n zX-E;4?!g44jm;EeIPs09MYzarOW|&I%E>(@W^-M`r(u6?3%s;6N{0QR+k0(Ertg#=kObHmk56S*%*z5MgTCp(r1KXvL~Q&0=;!AKtJTDv@<{qI^%HH z@EBMxt}6Uh`mwnlkV`y~F1@gY|9Ez@>_|A#SJW(suQ^iv*_o+9!Q)G02*6JkwcS}h z;iwCYD>Bz{=yK%F4PVkYymDRz#&Lmd34?8Kqig?cekss%pPrN53xoUuQ)(}V;F#`$0 zP#r5A9e?>@OL9xMNZ38B6x_KC7ceKBqVD%5#?HtgQ$M)ZU1e<1>p9vykz1d{+}!dy zk!90_kK(#7+kuytQ1QFFxLGXBI>L>UjOCp#X_Gz)*;TCM{;iS48k-_3ebxqDhnmsq zoanjCc8jx4q~ydVoKit8@T;1w+uQGE^J-0Q({HFAcpjyY5)aI(&%R0S^H>hXAv2ox z-_&i|Y)$!CB8b}q9Ne?wUvoDnSX%I$kVOgn9^*u}Ctc@ttbE>tpV9#Lg_@2PO&Jat z9xg;h?N%8*abup4ojo9M`2sHtEQXrxBiX4MCiiRO68IlT&s&Zu{G_F1rRIBaTKzy; zM3w_YqL5>1S{rM64r37feE`3mB&H0*ICtH^OP==}d9B)p{cYBeVpi99XLAL>>e^6D|Ch1dN&R;v=J<#i+;W_Xo zchzU?)(;SYd=AX7a}ZlCQFJ6H`TXp;Z%BjYgmRBV#;HeZq%!r^sq3TkKx1!`Mw2e! zVgjL%O&vcAN6-4{lU8x1TEddk_USNWANJh=;+=>*R#Z7TBTE=U_^A&h!K~iQ>_^UBg%wEKGnza8`3Ka}04|lec238_ z6W#^U6t(A9Xt8FD7QU;neU}0m6$|ucUu0v4%jpM~-WpJ{>{RDO4XZ+Otr4;~&Jv5Q z_S?dX|E(7t~?-EZ1xwH8`!;~+yx|w(VHOw9?7JB0% z>*UV)B=Y-9HS99>L}#X))L7K5srEHD^qS3G1q5pxV-q(NqUwt;*Xjj@Ntl7mtxOT#Ou#ROj3 zuiW%k%EaiTn#;=aW3tXyJ__wlYY1#$Ux4I}`<%+xb5H&^83Wm@?>kc^y$PnJh|mbozx@)}>~ zLCNPUy-wbk_R6T9rc7cd$A0aO?Gi3?quEjFCPG7>c?K+k_rQ#pVzU|>Y)8LY#V$n} z;E6g)An#Ji>uJR5+8KmNo@w)c=bNf_=LyVeV2$SC>*u}%i3M+Ol5N>^u{oN}fS#y%;y=@|fLr4b#D!Ze$xqnC3I@3ka^ z>VC~=7O>hgibc#9R$l`N&k&YYv$yHlERK|9nWF@|_f8P(ShcCSv$#5)Ty4slIV~l- zI2+w!Cv3z3LJcRm$R^x(p;YQos_#$J<7uqcQWj3+;6DU6lT?)Z;$G{z&R7-1OApy!k|v`$6vk=!TxIJ3Hg0@DzT+TQWNwZ?}|}*ftnH zx&0vfl~n|n`jm<9r{sH~p{s@vrV3i}$`40IA< z6OaYN*Kh*FUMx_QRTp3hw~B5U%B z?(E@g;uqBWL+Rf<;W9xO{yW1>>I@_>cM1x5RBn*^!COR?pS|w434@1k>vJ;)-6M!t zZ6$6UHeidRudG?~P1|Fy%vD#3HW=P6iYMeFhU6|xd0o96i39He3vEJxaKaUnaAa+p z^q9FL`wK3L`we2d0;M_YjN7QJqihK7Eb1D-TzSl2cz}UbU<>8D3()g~0@_08^Y-b( z`!0;4CAK+~&jBFc1V_V>8LN35p}KJ}@V--U(F@m{){cYUsVMpZo_@4OtSE=eZ3= zi(eO9>-h%nB<3oX|KyygBiC6jj-|+5CY|HZaItMQ>mfYPeCYv~lI~Zmo^DN_SkM4u z+30?s37?;3U`967hzsTK7Z3-L&QzA82Eyw_4eeucH~d{F&Yb-|@XUEMf5D|t#-FQU zNAAuUp8ZA&d7n!4_ZNa$!8>X|A20_cL2209)QR~-z#6e&dcbMK5H=1FZb&(>4+TN z6Rc}Ung2;QFE!i5f2Ur2L(S9gzdE6%i1IHXCnqbf3L{T6tAS<3=k_oN@x0f zwS;cq5}-kT(=v{U>|fTrDoz(ta_|fVB&7H!}&I1j& z&brA(48jO#EImqq69CMu%mL~;+y!#1Jq=v@1g{pzgT#i%H|Yx?3u#s1p?3!UW;q7@ zKUt2b3Mf4g6q*5iKB)MG3xY3{30KN4H|MKqeYM1kreA#v-t7!(ljW2dmF@SiT!Ugd zs2ot!=r`>5TJHuI1^Uh@c$J`uCn`4l*0D&Z+xwKZ(yqCrIGdWLYE}f7B7Jz|y3i2Bnq;*tk8#FhqX9VC8%e!|D z*L&r1cX!fv8%Z+WXt%o4sgEOb-jJQHP#K@-lIqk?`rO{NQng9z)w3falLJ8eO4{3Z ze?3Mb%&c!;Nf-J>^@;-=u#2Bi+O32{+Vpp>N<9~`v$(0nIm(^{d*3`Rccwy7En53k zw+varFGxK_$4j-5A=YLKj5izjY1@QuA1?DHPtO43$C6!I@0ViysCS1~!RvSo^Tdf)5MoA{kTx73{joOi(%iA?DOONbIz5$a zPdnVm_9p0oC*?5oGsTq(BUj+5W;Rg+7;U+u$d_PMaP^X-j=%%u?@<4n;esc%wRy7=OD?3Ne!sr@t2t+qte zDg#`1i%BLqRqE>7rczi2)>6dc-*=1kViHNX>`PcNg@K5e5Ek5%E4ilT>V`=4)-+nn z0OK|<$e|#ua46zsrE@T&`VC7NH!)*+bNB1Vb%!3?kXiTOrm-c}vL#_jV;uLC9DALGdsOsE6T+m4XV(ReNN~R zmLxtYd%p!956m>JB`i(-s(q1H4`bp~<&b$vXdfOUF@xoGOX%MOeRH1vb-Yyw`$H_IK&saYETWYNkR z3wWd*lUy+G;_3YeyPKimHots6yX?6>O#Aa=eGk-Y+>3am3yaJC%&2e%>QZVR2x3V00?W$(oVq zEw4|BLtj3fT;V}WKhI9oCI&6S-=Ugkt^^Kj4r0-*cWc)~$OmlKGC21MVTvA;w0iE2 z+NiDDiqPC++4&jk>U4gdm~?OX-BB*q_}#NAWPfvdW!WZ;5<+1DN#0EwTtGDV=!F=O z1yz#R>ON@Rd)xW?1sU81 z{>#)HE7%2N`B}G1yse!w^EA;#PtZJ5Dl&$4G4oEn>FPc_0~R?blT$k>5 z@mKX@neDG`4IC4J4b`Jpej7awcKz@5$(``%D&kUbCdl9UhC?L(O4-&x_ zY(5=Vw;BLy)rerqbQsv1I#$Y^7BrQQwM|xP6`t+>#F?QEKxm z23DT*^2O6hq5Zutg28Q3e=MP-TiUVP3i?GVE=z1mJLcvEM{-~(#(Mu~<8Qxr7(tx@ zREGEo>%+ST9oJs)^Vp$J*9GQv@eVeH%(H3M(gG&Cr5Ly~(7gPTdj^DR0<2%l{>5#; zfKLaKAQoFQ{T=)-2Q0>g_UnY{9Z#RlwG0OerJer7jFCHusu#Kn=cYPk7mgYD2J?K&bXWZiTCf0(DKvJk5_7iIBR6UbTSX@ja=GlE&UAD`)>8sxj{@OiGDyg-LI|Y_rIHyN)5^N zjNdfbtyYa)LHSy<+$gqm=)ZDJBIq7h_)>jxr+geqCz(5eYj{>SX)n#3qutromg1T* zJWIMu*l|(`hAJN#!SSttaxT?KnGmv44uB-oZRISKhCq|Y@HwZ$$V{O3Wvp3lVs_D1 zhP%VK5gqY&1a&>Wf2m6Q!l zh;(A|RSV`c%HQsXO-*8UhlbD6e*+9wNJ`su`+J;D@O2?J)_FXEu`$t~UdnTo_Sh0x zMNG0}{baf}Z}28N(v`iea?HRd6=)CC$%X%aN#AG!7%T{K$NFUKB5OksjwQJY=>xi2 z|A0!rkTn}jqIlhfX#m*O9x_lV~KuTelf!doVer@c4%J|cZJ-qn@|w7FR*yA z&?l5omLWtrq#j7^k4SUVGH;Ct2XTV6+e&cd)>D-?+lwo$ExQ^;5*`0!C??)M`(pp+ z;%%jK=_c0d(Iw}nH@9z*$s#!=y~d*O0mawHg3I6?;k$)!bYeznWtI5)b=ITLC!?Y- z=YxvzWDY0!*F61jbcSoax|^^6rz3gl@)4(!1=gX=m#)=Uc! z>%;(R|LFbc8Hx12KLq~Qr<-c2fxIC9dgTB81Y$0>ePWL`6u6q~IP49flh^3YjW1;I zJC0|}8WG->QpbEvHQ&N-t4clcPB2dtb!kCG@J|rz!cBjM!$GtMG4>Fs)Quqf%j$So>zQqC40!+r+HHKs`3fK)n zm}hL3E=0fDLl^1Q-+HeUus_rHd&oS$H+%a&`u7nkO_Y7M`tg{ZlYKnEempkkmnuVl zx?6I0Ftkie7H~aVhX%cE){mfXHb%y-ry8oIys$OALDd*)PSNShVS6Mw9u)BX=WF~( z^JKWtY}L^FDpF)(aZ^_(*v!@7w7%gSn47!_=UL}nBKK4j)O}JnrTZa+t4A)0%~n7s z=Jc)##wp++xIB4E*wu&p`SRM~vQB31s9o|IJ(3XMRP8%wbZZzbqX} z%3;R>XE$f&Zj{KES1(DSC!i#4IsqhS)uSyncXZIt1T!YLm$4G?)}Y)TMe{9jcnP9V zfuP9GAxN<<_SV;A`vwzF+gYC19a5OYrU8!Q8?84hj^VhM#6RQ!ld^w6PX0CxLG7lQ ziS3{F4fQ-)93fUVT*trAfBp0jL2@p7jgudeT~=b)^wBpSk`;!|c7Br~I_}yNBd_t;0L(-i~lCS7EqY}Cc`f@WZj%fYJa&#~k`8cg>?jCK;=zw+hS43!~lm$zqgt~x+Po9jQX|BVlQMdA4-Q6oRUi)7x zntr)r`*v_;O}W_Um%R6o^g8c@`LM`qshk^rjF<%pS+z+s;c@C9gWkQa$$d1qn zXrv1v6d{$psVxejgRIsh3S1K%=^f~^JKVFTLtJ;chswd*ytL))9>Hgd70NYzr_FY06&p8?{4Hj_lm)}f*JV2IKHB+V(`~|1j4&h! zURrGrW2t{YVtEWa`N4Qhj8uS6L+@_L0-pQ52WciIT)tc~g+nJvq(zfOWz03yh-$N) zwY^o$U&?O(mE+-ziM+xmM!}|#O=_UNHCq0j-!k#FHDycDAbm~sX-eD~MeoVrT+Wog zVbAxWG0EAdJDxvK2`P~MvYu^^wsY`oFy%#?DIW3|P_aQ)0^yzecW{A5xFA9}8^2aSwqWPYfdMoll^m+`{0b&tPTV=zEn?%{aIP zNjdl+6@0;jfE+jj3@?N6$-qA#!OMtiD*#U^=K(vU@}bh#|Lt7FxbSIqR$OZ7AIA{( zpS?~8tvaV1cWB6h9?sgrLJCj-a=Q)iS9w_gb4~pH?<}V7{_(jRY-8(4aV3;cY++!c z;SsU#n`73%JEMLjdQ$FhB^$k{xSB-o#_dCJ#OY1T<=39G<_l_fTvC5<(>2h85 zruTQb{{h{jBn9B0>_4E-B?`v3l&F3_tfP=Ljd{`%$(T@(JO2;JJ^6PvtD&-kuBrZ% zaI2K}%%yV|vmWcrkMAyA@%ALK3lz(nmu1MIi4U90PO1gxu&nF#8J?l(saiaq`I zg@*Hc@@n2jK}g+CM=+g&NOQB`%W*@Y1-})Ux(8bEGQn63&bc&`gKP}(oVS9c*?@^V%uvS z-yx$rX;L>|AAFTrv)I9G=4Y+n7`cpgoOkrS`T!yZ?c=5@NemCF@-dqy2r4Vf->Ml@ z7Bf4~L+n-}??982NDPphsTJGJkZ1*KJAb>cz!-Dc&wO*Wn&G9x7fVLId-A3wmB>h` z_`$b&iq4T0`B9~#`R_+7xSU>>UMl$vlN3&0p64U+yt6NHEyxVHw2za)pVU}In)z9# zOiRhcb5ehsxP5RfK5&b+ot8K=kHM(MW{`gBLY}z?2B6HbOvmd}E*;;0a0k`23|-0L zYyE_KvaITs5H#~nx^W3olOuI3(X;aw#jNc9YRVsdCgHWQX_a0nbx*Z>wd3va=GH$} zeOSsXt&N(RG$X96^+v1vWyIuZ!eDzyBfaEB~%s_uG_90y^U}UJ`jiYSHF`a zEO0VGM?YVl)))N*(qiPmDEJ~&;K&A(>3xN1@#yh4$){e(aV?AAF;npw_crWg0_Yru zjHz9(V;9J(I1i$F9k{Vizio<2Rqv^ z#cya_yIAd{D_h0u$a(dbTpwS?EW*=X1O%Y0l;6g&^}KJrHOBD*1MIG*mb}tLD|K>w zlXxK84>J;5aEn$V4q_gmWgC=s0iIhl-s|km2th$7Q2phJo zLW;Sf>5_Y@i3jzJ5RtAgfN5qAj2|bl1?FEl{*9IY%gp~Df2ttXV>9^}JW!4qTHf^6 z2TBk|M?B4x1g7Nr%XJa)?|aWew!L5)XCFb{Hd;H5T`X+mewnzwFJX9u0brX>@(+m4 zQZIk`)^W$J8C>Gd({$~xl%SMSgcIQ@F z8tsVnxj|Aq-6}nEXu}T%f`U4)bb~3%vy6qAwr31{rBy;BO{$Dqv=QFV5p&7G8i$-E zB@Q%y)m|#v{QTWvOaOMr9&3EV8}BaEKtqqO&CC~Qw#EwwYd@(t(!`gwivfNz;h-z$ zUN@k^!nQ}8o7Uq;Llh@#{e>08%g5LdGu$-j5l)+z2L!5t)F94{;1a%zr)6pAM}qOT ztbfUsT8*#=3W}94otvNNxX~Al)^tYP;bxQ%-A(dm&!2CHi{0v>BYvLd!2s7 z?ncG1HA`kr~#cyOaSuwgYsz>s=+iG54^@9 z_cr(x5b~j&t>zy6r#?;pUEAFDzqHL7agY_AX~=fJ+cjvMq<EA$5Eh^XWC; zq?hy+NxK{d-3(#am=|n$QB_A8YzEAqxxWRNJgP`vIz~nd+Z1sWV9oO65iZVgC{kpI z!MCc%3R}L#?_W4@|65~?2wLZ~KGQvFMFw>2>OX)1r+G|QED1UmL&ni}*EB})x56)6 z%-&DDYI5%Vz*y9v+E3Hw=|{r!tdo_!7A8C)iIWrrGU)4mwU2P^e4Di@oi*ik;Qb=A zBcdqSf}>PUYF-KFlvQtd8>2b9oiQp{gsXnv03({_jlEr2$^L@qwtEZHXPH@5*rUy^ zW1gIH$>(U-4A|FadeRD$UGLGu8`8pGx=Ph|>|VaDd3?FkuTVEv3r+j3iP^W8z0qW8 ztu^JHJ(4w7*jIZ9$O1R-s6c{Xb^CCV{iSN0n=N-=MZ>f6)bePWz}M(LJZU}+GkmF|)fknUKPE`goO$L` zulMJVg9Q+g$=vBs@5s^HKU-9xeQ(e~_1-mbTa?zPqmkkGst=>l-^|$>#+-DS*y)z4 zsiYYsN*kL(=K_WKD%cg{`Mknz@etx075D+QOv4@snd3>gdn2}a7CX?A-aUjk9lL>k z|0SO`B}^v-A>%)&zp-D*H0o666Vu7@?9!--kgPhOAdfpSd-ndlbD_)EmpFLFJm+p} zv)t>H)>+*e1sN@qMu0v74r^4%E5QtS!x$~dq3)7#|1tm7Rn?r)J2A}!{$oTl&-tBR z$0#M8oL>@B63-CYIX*RHpquU;NQvco+q0)Au*y+CZldKI+{}RNvG(0{3EtA0y&(xM zOV)wfqJ(zsGB>BpV9ACb!}#Tq$gUbvROwei6H|G^+ihj<%+@m4>2y|D{;3_nZHN<< zk-AFn`}I+2h^<%?8sM@w5Oh#7T=rMgY(P4iPNSn>SjmGgbBD2j^iKK5Ij^W67MmND z3_8|pDvAW$AtFMl=B{3FD>U-R#^Z+*Ec1iOStep@fghXkLQW?1=5 z!y7{LRC)8v%UzMo;0>Bp{0>Vqa9O(MK)+SVR&TsL=#?Rc>WOP+BTfOT*209=2IRoX zMLt3-`D4AME7NYto!}%{)Bqx}ZIF_LKN9*RchfS`%UqKC!_7F`a4)wC93IEI@98~1 zBthmWJz=0=k?KAlf7EU8Bd(9p+O|)gfA-y%j6Xx#x8}=4Q>pEHKnJ#ZI z4eZP5|r7kV9c10 z9XUX{&-Huk2=gpz5Z{F$nl4QP8--4uJ84PUr3NY!=TizcUov5qNCh7#l4g{UdAB!* zmw%@GqwjgI)OLyIxMi>zb>N^F5bq)q zRT`fLMB?#J`b;iZJpsEP8_4&b31pZ19$fu&yhcSn+>)J-#;#4l+jwpJq_fQZ(ZJ-& zT!ab$H0ZWdq{`kcxo(6ycnBs2w*R$y=)=qET%zNHZ8eHh_^MU!5zi*?WX#LvS21BVzYg&f2plxgH;I+4i|D*ubyKJr?VjXD ze#vKBV}G9?*VjNcb8xfS&_+D&b}zfmbt!Kad&E~3Dy+qTWA>vS4{P&&#S4fxUo_Hm zSsfaS@g`ey<$oeK4lT+a-7r*pa#-?8#l5~So$y7bKxg7g#GhtF!A+V6(7`gO?nRgC z8S~b>^gBE*va9&0z~G}s>wR%B1Zq8sZ$j0R5_aP7_$TDMj1zndB-?rFDQ*`(?&FLE z5p(3pAq=1bD{|(J&%PNr9P26U*q%*BBq*Mpg!6}U0}dzU(MS$Y@>X=MN^7j9OA%&5 z`ISZqiojcV5hd!x^=+B`~%DJ9ILwDorF~7mfE^))Ir1vaxFERiaU%nd;=(frxxK zErr4)hS?kD++yn%bK=fl-OABHLkHCcS6cq`h>+E%AZ-p|0=K@l!by}X-2)$=%6D`L zDSJ&lFrU^{L>KnBLYx_SoT93qoLkV#;?})`;cG?2j56{4UrKz516`UO0GiIC# zrb|Sw`{L>b?3vu^RiFn0ZmHH5FWm6_#|@#z>A7Ol89WkNwbP=cC0MPt%|X+o(qis( zSzM=AA&|k=rP|VzaMr@6&UQA?ETyZtwmCDYOdx4O`jd95#vk@4 zahQZ2WHn&hfv&+vZ`gcNQZ8qcw%aO@-gzrWtTWKQ)i<4u)Jl}?QXyzLl?v9~n zL>(jZub9KKN3tJ_js!k8*6T{_S=s#tK^g6N-*>wPscZvWQnB1N zcYtm=?IAh4WGP5)Vm;3+nH1G2tpFZk+Nz9dDTXZz*~9kV#1|F1D8?Rr>FYM?vy~jD zgVFiAZl&U_D=v)cdpUuE^;N3=FQpl{-B+Nwh2JG^U)xX>WA2_NsL;|&x*KY=giihC zi-aYVcXt$G(aR-ZqIjX9lK!bX{XM0JsjrONWjIoj=r04?M!sFRA zCG@F~tVy@&SKCB-9y@Fj&l;7ciQ`1G!U&4Y856f8^md6D(p&mk^r;UoQyEky=uv2d z-+a-EWp>i?4&%jAY56cpC7<2%sYa~YXW9>MD@9>OVP9d^VX*vn&d)z%@Ykr-Q{+jX zA6#lJg6H?$O|g zQ);!-f`^e=#4a{a$N6;vpo!*&o+t_9m+~sSLHodv$zJBUQ=jxQM2qN~Y)8`6Z#>2T zU}E43cQ?qfjWjwx&1#7E;T2)~w|$D7Y)+^%;ny6|a@ zeP7{9;xJzaJ?jj&_N>~Nz#~i7*tF#&x#{m{xJ?3oAf)KMKJ2GFKrqs5l8erwHFfBZ zYKBl84*CTex>3e|p$er{N5cv*j@!L1gLFeG&yw~r32FV@tpMd_PlPr6u@u`NPC=>M z3)-^$Qv59Sw`DbVq>~ldHV!@t$Va)(Au&pw16@l`j8kM@CM*$i)S_^+=aelgX9Oa_ zcpaV&7*EA{u@%0Y^2tvzew-3Ga@ix@()Na}fzWvuzwN4Cq6v3b(b~3Ju>>bpIT~&V!?klGnJejm;+bV-215uB`9l1z-M7PDFjAL-F=GB^)T<&BgYVova`2_j zzL&yqp^`hi9y!ZXZn;UN3{k@w7{NUtk+U+iQ=wrmzDEIk`a!kwtCTrX+-rfsg)!v(Q{V+A*`Axm0B}vk!5X>0x6|ax{zBc* z@QgwcQQsM(fV;$FJvr(=P;$Jg^~KaxEcl;5D-!_?GM0-BWO zkoWFSAJLR7M@>Duqp5E8UvD~-46_RFr55H^Vked+*1zy#t@ifcnt`I%a!No&x^!na zEqhmaA9V@>OJrkk$5<1pS<{-*O}#vo?8)*VAzj7kBKxqXmrz;3pVHyGpks}nDtn17GQ zNA>r6y}7m1$hrX%gj7ug6N+xV-%P$>${pZi8lzo; zxX0{~trSNjiP3kvR|9XO8we$2WyQhqtNJSL%(Xh|t=;C_Pk#}xOu3Ubna{z?CLTVF zNUlqJet7V^G`R(ooB()4?v7OrA3C~H21v63e=j8aWO0#&+B7SaO|0)<--2Tmvqjjc zxMp8uCr4XL$D;*&@@k^EX4T&$n_Ci4+ATN}c3d$X7%s zpZ6fbWA7LnxY5O&lCWj__2 z;xSzP=jnDhv_z)Zc#m9&B5q@_F?pH#eV;N96(!KR>~uR!z_m1*zU%gF{l@1ji*wf~ zYd^jp&N@(N`pvTBSXPbWfgSB?#3jtxM}sIb8#cjHX_q}y=AbXPT8p_;NrUT)5E>FD zQ%0p5sZoL#=(eWFdoLN%kTP#q&EtA|VE!GNhB<5sBSO#`qr#G$J^dx;!m7drlX7cT zE;BtrdekpuqRoPCbRIP%TQ=U(@;3$cERAlIJB=){hX0;s?dr_~LaG6JaPyG5Jwpww z{+{5~xUJ5gb6b(Et&%uSL^^)&?;p<-Y#ktZA-~W_^0Hy9j(28XO7*}LX@THpb-~l! zF$@6;AdAwfs@_ekvd8Tf?!BTOyePYO8C(;-^u02z&ddX?)lc|hqLy6bN=lCSeR(@R zkpngHjUjxb#vj>!lKe=bq{WbxKL+b9-W)j&K@RReBersOt{zyX@085&>r3e4D7yBF zhX(OqH-28Cq`U66YxrS$*A=hVMnBu4CJ}3Hw!X_nyVtB0DMt#mdNO4Ex_iLVbX{#3 znOQC>swm0}5Pgdn!FB3xOoYSfdrj?}N& zM6fr$ieu|&10M3|T@OGeZlO}!NL!|XT#SC>6n9Ya%tFvi^3@=Iv6d|5r)7m5`tN@# z(sBc42u%16$K;69wiU!`30gsyT_iFPXwh|AvP>lWr-b9&V8GBaI@R%O~u-U;V|g)|NKyu^bux>Hv(X<#+6pRUc*erp&fYlld2@P(Ma$LVY zDtGXk#F|{NP2R_vU~tk^7TG)jy=LN}L$4^E?Ya?&$q~3uPB3@;BH^khlqLsC7u6iR{BEb$b_s}7vyW}&wt3Z?Hm=hnt zn_7L#+DC-%28g$wJ-22cr}>2*W|--!SqMkww@qFc$$qIFZCFvP+^2Zu@aOT<_p~qP z`on}jwbS}e@1-4slq-`7zFSn)dsfWVbwluzzQ>_+@to75315&Yd+Ky;D2kYl0|<5{ z-*w31VaZm?!_|_x#J#O%bwknKz0cu?&rs;Tv)9Pal3lNrJh08GO=H|%eeW5Azm2?H3dIfkT_FlM9Ul z&yTOJvo9hY9>e(GJg@Lvu-hx=ocMD2SY%;A;VE;SZs9knrn^y|z@Yu?Y>?YG1!OZ6 z-`F-SIR|EFOVO!h2a&c@^0o~A$d*UQQobP6p^_9UAZ z9>t1^`BLVj-(k1yn})Z3ZrIO~?EkrGzmE=Rf7O71? Date: Sat, 8 Apr 2023 13:53:24 +1000 Subject: [PATCH 212/287] AP_Airspeed: rename UAVCAN drivers to DroneCAN --- .../AP_Airspeed/AP_Airspeed_DroneCAN.cpp | 197 ++++++++++++++++++ libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h | 68 ++++++ 2 files changed, 265 insertions(+) create mode 100644 libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp create mode 100644 libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp new file mode 100644 index 00000000000000..93fd090cfc5961 --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp @@ -0,0 +1,197 @@ +#include "AP_Airspeed_UAVCAN.h" + +#if AP_AIRSPEED_UAVCAN_ENABLED + +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define LOG_TAG "AirSpeed" + +AP_Airspeed_UAVCAN::DetectedModules AP_Airspeed_UAVCAN::_detected_modules[]; +HAL_Semaphore AP_Airspeed_UAVCAN::_sem_registry; + +// constructor +AP_Airspeed_UAVCAN::AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance) : + AP_Airspeed_Backend(_frontend, _instance) +{} + +void AP_Airspeed_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +{ + if (ap_dronecan == nullptr) { + return; + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("airspeed_sub"); + } + +#if AP_AIRSPEED_HYGROMETER_ENABLE + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("hygrometer_sub"); + } +#endif +} + +AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_Airspeed_UAVCAN* backend = nullptr; + + for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { + if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { + const auto bus_id = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, + _detected_modules[i].ap_dronecan->get_driver_index(), + _detected_modules[i].node_id, 0); + if (previous_devid != 0 && previous_devid != bus_id) { + // match with previous ID only + continue; + } + backend = new AP_Airspeed_UAVCAN(_frontend, _instance); + if (backend == nullptr) { + AP::can().log_text(AP_CANManager::LOG_INFO, + LOG_TAG, + "Failed register UAVCAN Airspeed Node %d on Bus %d\n", + _detected_modules[i].node_id, + _detected_modules[i].ap_dronecan->get_driver_index()); + } else { + _detected_modules[i].driver = backend; + AP::can().log_text(AP_CANManager::LOG_INFO, + LOG_TAG, + "Registered UAVCAN Airspeed Node %d on Bus %d\n", + _detected_modules[i].node_id, + _detected_modules[i].ap_dronecan->get_driver_index()); + backend->set_bus_id(bus_id); + } + break; + } + } + + return backend; +} + +AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) +{ + if (ap_dronecan == nullptr) { + return nullptr; + } + + for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { + if (_detected_modules[i].driver != nullptr && + _detected_modules[i].ap_dronecan == ap_dronecan && + _detected_modules[i].node_id == node_id ) { + return _detected_modules[i].driver; + } + } + + bool detected = false; + for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { + if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { + // detected + detected = true; + break; + } + } + + if (!detected) { + for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { + if (_detected_modules[i].ap_dronecan == nullptr) { + _detected_modules[i].ap_dronecan = ap_dronecan; + _detected_modules[i].node_id = node_id; + break; + } + } + } + + return nullptr; +} + +void AP_Airspeed_UAVCAN::handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + + if (driver != nullptr) { + WITH_SEMAPHORE(driver->_sem_airspeed); + driver->_pressure = msg.differential_pressure; + if (!isnan(msg.static_air_temperature) && + msg.static_air_temperature > 0) { + driver->_temperature = KELVIN_TO_C(msg.static_air_temperature); + driver->_have_temperature = true; + } + driver->_last_sample_time_ms = AP_HAL::millis(); + } +} + +#if AP_AIRSPEED_HYGROMETER_ENABLE +void AP_Airspeed_UAVCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + + if (driver != nullptr) { + WITH_SEMAPHORE(driver->_sem_airspeed); + driver->_hygrometer.temperature = KELVIN_TO_C(msg.temperature); + driver->_hygrometer.humidity = msg.humidity; + driver->_hygrometer.last_sample_ms = AP_HAL::millis(); + } +} +#endif // AP_AIRSPEED_HYGROMETER_ENABLE + +bool AP_Airspeed_UAVCAN::init() +{ + // always returns true + return true; +} + +bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure) +{ + WITH_SEMAPHORE(_sem_airspeed); + + if ((AP_HAL::millis() - _last_sample_time_ms) > 100) { + return false; + } + + pressure = _pressure; + + return true; +} + +bool AP_Airspeed_UAVCAN::get_temperature(float &temperature) +{ + if (!_have_temperature) { + return false; + } + WITH_SEMAPHORE(_sem_airspeed); + + if ((AP_HAL::millis() - _last_sample_time_ms) > 100) { + return false; + } + + temperature = _temperature; + + return true; +} + +#if AP_AIRSPEED_HYGROMETER_ENABLE +/* + return hygrometer data if available + */ +bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) +{ + if (_hygrometer.last_sample_ms == 0) { + return false; + } + WITH_SEMAPHORE(_sem_airspeed); + last_sample_ms = _hygrometer.last_sample_ms; + temperature = _hygrometer.temperature; + humidity = _hygrometer.humidity; + return true; +} +#endif // AP_AIRSPEED_HYGROMETER_ENABLE +#endif // AP_AIRSPEED_UAVCAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h new file mode 100644 index 00000000000000..3ccbdd7127ca5a --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h @@ -0,0 +1,68 @@ +#pragma once + +#include + +#ifndef AP_AIRSPEED_UAVCAN_ENABLED +#define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif + +#if AP_AIRSPEED_UAVCAN_ENABLED + +#include "AP_Airspeed_Backend.h" + +#include + +class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { +public: + AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance); + + bool init(void) override; + + // return the current differential_pressure in Pascal + bool get_differential_pressure(float &pressure) override; + + // temperature not available via analog backend + bool get_temperature(float &temperature) override; + +#if AP_AIRSPEED_HYGROMETER_ENABLE + // get hygrometer data + bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) override; +#endif + + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + + static AP_Airspeed_Backend* probe(AP_Airspeed &_fronted, uint8_t _instance, uint32_t previous_devid); + +private: + + static void handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg); + static void handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg); + + static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); + + float _pressure; // Pascal + float _temperature; // Celcius + uint32_t _last_sample_time_ms; + + // hygrometer data + struct { + float temperature; + float humidity; + uint32_t last_sample_ms; + } _hygrometer; + + HAL_Semaphore _sem_airspeed; + + // Module Detection Registry + static struct DetectedModules { + AP_DroneCAN* ap_dronecan; + uint8_t node_id; + AP_Airspeed_UAVCAN *driver; + } _detected_modules[AIRSPEED_MAX_SENSORS]; + + static HAL_Semaphore _sem_registry; + bool _have_temperature; +}; + + +#endif // AP_AIRSPEED_UAVCAN_ENABLED From 43eaf013ed04987fcaa78aa76aa5e20437e3539f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:53:24 +1000 Subject: [PATCH 213/287] AP_Baro: rename UAVCAN drivers to DroneCAN --- libraries/AP_Baro/AP_Baro_DroneCAN.cpp | 177 +++++++++++++++++++++++++ libraries/AP_Baro/AP_Baro_DroneCAN.h | 52 ++++++++ 2 files changed, 229 insertions(+) create mode 100644 libraries/AP_Baro/AP_Baro_DroneCAN.cpp create mode 100644 libraries/AP_Baro/AP_Baro_DroneCAN.h diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp new file mode 100644 index 00000000000000..b4c3db984596d0 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp @@ -0,0 +1,177 @@ +#include "AP_Baro_UAVCAN.h" + +#if AP_BARO_UAVCAN_ENABLED + +#include +#include +#include "AP_Baro_SITL.h" +#include + +extern const AP_HAL::HAL& hal; + +#define LOG_TAG "Baro" + +AP_Baro_UAVCAN::DetectedModules AP_Baro_UAVCAN::_detected_modules[]; +HAL_Semaphore AP_Baro_UAVCAN::_sem_registry; + +/* + constructor - registers instance at top Baro driver + */ +AP_Baro_UAVCAN::AP_Baro_UAVCAN(AP_Baro &baro) : + AP_Baro_Backend(baro) +{} + +void AP_Baro_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +{ + if (ap_dronecan == nullptr) { + return; + } + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("pressure_sub"); + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("temperature_sub"); + } +} + +AP_Baro_Backend* AP_Baro_UAVCAN::probe(AP_Baro &baro) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_Baro_UAVCAN* backend = nullptr; + for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { + if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { + backend = new AP_Baro_UAVCAN(baro); + if (backend == nullptr) { + AP::can().log_text(AP_CANManager::LOG_ERROR, + LOG_TAG, + "Failed register UAVCAN Baro Node %d on Bus %d\n", + _detected_modules[i].node_id, + _detected_modules[i].ap_dronecan->get_driver_index()); + } else { + _detected_modules[i].driver = backend; + backend->_pressure = 0; + backend->_pressure_count = 0; + backend->_ap_dronecan = _detected_modules[i].ap_dronecan; + backend->_node_id = _detected_modules[i].node_id; + + backend->_instance = backend->_frontend.register_sensor(); + backend->set_bus_id(backend->_instance, AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, + _detected_modules[i].ap_dronecan->get_driver_index(), + backend->_node_id, 0)); + + AP::can().log_text(AP_CANManager::LOG_INFO, + LOG_TAG, + "Registered UAVCAN Baro Node %d on Bus %d\n", + _detected_modules[i].node_id, + _detected_modules[i].ap_dronecan->get_driver_index()); + } + break; + } + } + return backend; +} + +AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new) +{ + if (ap_dronecan == nullptr) { + return nullptr; + } + for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { + if (_detected_modules[i].driver != nullptr && + _detected_modules[i].ap_dronecan == ap_dronecan && + _detected_modules[i].node_id == node_id) { + return _detected_modules[i].driver; + } + } + + if (create_new) { + bool already_detected = false; + //Check if there's an empty spot for possible registeration + for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { + if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { + //Already Detected + already_detected = true; + break; + } + } + if (!already_detected) { + for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { + if (_detected_modules[i].ap_dronecan == nullptr) { + _detected_modules[i].ap_dronecan = ap_dronecan; + _detected_modules[i].node_id = node_id; + break; + } + } + } + } + + return nullptr; +} + + +void AP_Baro_UAVCAN::_update_and_wrap_accumulator(float *accum, float val, uint8_t *count, const uint8_t max_count) +{ + *accum += val; + *count += 1; + if (*count == max_count) { + *count = max_count / 2; + *accum = *accum / 2; + } +} + +void AP_Baro_UAVCAN::handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg) +{ + AP_Baro_UAVCAN* driver; + { + WITH_SEMAPHORE(_sem_registry); + driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, true); + if (driver == nullptr) { + return; + } + } + { + WITH_SEMAPHORE(driver->_sem_baro); + _update_and_wrap_accumulator(&driver->_pressure, msg.static_pressure, &driver->_pressure_count, 32); + driver->new_pressure = true; + } +} + +void AP_Baro_UAVCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg) +{ + AP_Baro_UAVCAN* driver; + { + WITH_SEMAPHORE(_sem_registry); + driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, false); + if (driver == nullptr) { + return; + } + } + { + WITH_SEMAPHORE(driver->_sem_baro); + driver->_temperature = KELVIN_TO_C(msg.static_temperature); + } +} + +// Read the sensor +void AP_Baro_UAVCAN::update(void) +{ + float pressure = 0; + + WITH_SEMAPHORE(_sem_baro); + if (new_pressure) { + if (_pressure_count != 0) { + pressure = _pressure / _pressure_count; + _pressure_count = 0; + _pressure = 0; + } + _copy_to_frontend(_instance, pressure, _temperature); + + + _frontend.set_external_temperature(_temperature); + new_pressure = false; + } +} + +#endif // AP_BARO_UAVCAN_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.h b/libraries/AP_Baro/AP_Baro_DroneCAN.h new file mode 100644 index 00000000000000..c3fb700d252ba6 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.h @@ -0,0 +1,52 @@ +#pragma once + +#include "AP_Baro_Backend.h" + +#if AP_BARO_UAVCAN_ENABLED + +#include +#if AP_TEST_DRONECAN_DRIVERS +#include +#endif + +class AP_Baro_UAVCAN : public AP_Baro_Backend { +public: + AP_Baro_UAVCAN(AP_Baro &baro); + + void update() override; + + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static AP_Baro_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new); + static AP_Baro_Backend* probe(AP_Baro &baro); + + static void handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg); + static void handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg); +#if AP_TEST_DRONECAN_DRIVERS + void update_healthy_flag(uint8_t instance) override { _frontend.sensors[instance].healthy = !AP::sitl()->baro[instance].disable; }; +#endif +private: + + static void _update_and_wrap_accumulator(float *accum, float val, uint8_t *count, const uint8_t max_count); + + uint8_t _instance; + + bool new_pressure; + float _pressure; + float _temperature; + uint8_t _pressure_count; + HAL_Semaphore _sem_baro; + + AP_DroneCAN* _ap_dronecan; + uint8_t _node_id; + + // Module Detection Registry + static struct DetectedModules { + AP_DroneCAN* ap_dronecan; + uint8_t node_id; + AP_Baro_UAVCAN* driver; + } _detected_modules[BARO_MAX_DRIVERS]; + + static HAL_Semaphore _sem_registry; +}; + +#endif // AP_BARO_UAVCAN_ENABLED From 63e67db5167128ed3c5f59bdf8a57777b0e80a2d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:53:24 +1000 Subject: [PATCH 214/287] AP_BattMonitor: rename UAVCAN drivers to DroneCAN --- .../AP_BattMonitor_DroneCAN.cpp | 411 ++++++++++++++++++ .../AP_BattMonitor/AP_BattMonitor_DroneCAN.h | 115 +++++ 2 files changed, 526 insertions(+) create mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp create mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp new file mode 100644 index 00000000000000..434292f870dd0a --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -0,0 +1,411 @@ +#include "AP_BattMonitor_config.h" + +#if AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED + +#include +#include "AP_BattMonitor.h" +#include "AP_BattMonitor_UAVCAN.h" + +#include +#include +#include +#include +#include +#include + +#define LOG_TAG "BattMon" + +extern const AP_HAL::HAL& hal; + +const AP_Param::GroupInfo AP_BattMonitor_UAVCAN::var_info[] = { + + // @Param: CURR_MULT + // @DisplayName: Scales reported power monitor current + // @Description: Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications + // @Range: .1 10 + // @User: Advanced + AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_UAVCAN, _curr_mult, 1.0), + + // Param indexes must be between 30 and 39 to avoid conflict with other battery monitor param tables loaded by pointer + + AP_GROUPEND +}; + +/// Constructor +AP_BattMonitor_UAVCAN::AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params ¶ms) : + AP_BattMonitor_Backend(mon, mon_state, params), + _type(type) +{ + AP_Param::setup_object_defaults(this,var_info); + _state.var_info = var_info; + + // starts with not healthy + _state.healthy = false; +} + +void AP_BattMonitor_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +{ + if (ap_dronecan == nullptr) { + return; + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("battinfo_sub"); + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("battinfo_aux_sub"); + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("mppt_stream_sub"); + } +} + +AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id) +{ + if (ap_dronecan == nullptr) { + return nullptr; + } + for (uint8_t i = 0; i < AP::battery()._num_instances; i++) { + if (AP::battery().drivers[i] == nullptr || + AP::battery().get_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) { + continue; + } + AP_BattMonitor_UAVCAN* driver = (AP_BattMonitor_UAVCAN*)AP::battery().drivers[i]; + if (driver->_ap_dronecan == ap_dronecan && driver->_node_id == node_id && match_battery_id(i, battery_id)) { + return driver; + } + } + // find empty uavcan driver + for (uint8_t i = 0; i < AP::battery()._num_instances; i++) { + if (AP::battery().drivers[i] != nullptr && + AP::battery().get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && + match_battery_id(i, battery_id)) { + + AP_BattMonitor_UAVCAN* batmon = (AP_BattMonitor_UAVCAN*)AP::battery().drivers[i]; + if(batmon->_ap_dronecan != nullptr || batmon->_node_id != 0) { + continue; + } + batmon->_ap_dronecan = ap_dronecan; + batmon->_node_id = node_id; + batmon->_instance = i; + batmon->init(); + AP::can().log_text(AP_CANManager::LOG_INFO, + LOG_TAG, + "Registered BattMonitor Node %d on Bus %d\n", + node_id, + ap_dronecan->get_driver_index()); + return batmon; + } + } + return nullptr; +} + +void AP_BattMonitor_UAVCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg) +{ + update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct); + + WITH_SEMAPHORE(_sem_battmon); + _remaining_capacity_wh = msg.remaining_capacity_wh; + _full_charge_capacity_wh = msg.full_charge_capacity_wh; +} + +void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc) +{ + WITH_SEMAPHORE(_sem_battmon); + + _interim_state.voltage = voltage; + _interim_state.current_amps = _curr_mult * current; + _soc = soc; + + if (!isnan(temperature_K) && temperature_K > 0) { + // Temperature reported from battery in kelvin and stored internally in Celsius. + _interim_state.temperature = KELVIN_TO_C(temperature_K); + _interim_state.temperature_time = AP_HAL::millis(); + } + + const uint32_t tnow = AP_HAL::micros(); + + if (!_has_battery_info_aux || _mppt.is_detected) { + const uint32_t dt_us = tnow - _interim_state.last_time_micros; + + // update total current drawn since startup + update_consumed(_interim_state, dt_us); + } + + // record time + _interim_state.last_time_micros = tnow; + _interim_state.healthy = true; +} + +void AP_BattMonitor_UAVCAN::handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg) +{ + WITH_SEMAPHORE(_sem_battmon); + uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len); + float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage; + float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage; + + _cycle_count = msg.cycle_count; + for (uint8_t i = 0; i < cell_count; i++) { + _interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000; + } + _interim_state.is_powering_off = msg.is_powering_off; + _interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000; + _interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh; + _interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600); + _interim_state.has_time_remaining = true; + + _has_cell_voltages = true; + _has_time_remaining = true; + _has_consumed_energy = true; + _has_battery_info_aux = true; +} + +void AP_BattMonitor_UAVCAN::handle_mppt_stream(const mppt_Stream &msg) +{ + const bool use_input_value = option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value); + const float voltage = use_input_value ? msg.input_voltage : msg.output_voltage; + const float current = use_input_value ? msg.input_current : msg.output_current; + + // use an invalid soc so we use the library calculated one + const uint8_t soc = 127; + + // convert C to Kelvin + const float temperature_K = isnan(msg.temperature) ? 0 : C_TO_KELVIN(msg.temperature); + + update_interim_state(voltage, current, temperature_K, soc); + + if (!_mppt.is_detected) { + // this is the first time the mppt message has been received + // so set powered up state + _mppt.is_detected = true; + + // Boot/Power-up event + if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Boot)) { + mppt_set_powered_state(true); + } else if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Boot)) { + mppt_set_powered_state(false); + } + } + +#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG + if (_mppt.fault_flags != msg.fault_flags) { + mppt_report_faults(_instance, msg.fault_flags); + } +#endif + _mppt.fault_flags = msg.fault_flags; +} + +void AP_BattMonitor_UAVCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg) +{ + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); + if (driver == nullptr) { + return; + } + driver->handle_battery_info(msg); +} + +void AP_BattMonitor_UAVCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) +{ + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); + if (driver == nullptr) { + return; + } + driver->handle_battery_info_aux(msg); +} + +void AP_BattMonitor_UAVCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg) +{ + AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id); + if (driver == nullptr) { + return; + } + driver->handle_mppt_stream(msg); +} + +// read - read the voltage and current +void AP_BattMonitor_UAVCAN::read() +{ + uint32_t tnow = AP_HAL::micros(); + + // timeout after 5 seconds + if ((tnow - _interim_state.last_time_micros) > AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS) { + _interim_state.healthy = false; + } + // Copy over relevant states over to main state + WITH_SEMAPHORE(_sem_battmon); + _state.temperature = _interim_state.temperature; + _state.temperature_time = _interim_state.temperature_time; + _state.voltage = _interim_state.voltage; + _state.current_amps = _interim_state.current_amps; + _state.consumed_mah = _interim_state.consumed_mah; + _state.consumed_wh = _interim_state.consumed_wh; + _state.last_time_micros = _interim_state.last_time_micros; + _state.healthy = _interim_state.healthy; + _state.time_remaining = _interim_state.time_remaining; + _state.has_time_remaining = _interim_state.has_time_remaining; + _state.is_powering_off = _interim_state.is_powering_off; + memcpy(_state.cell_voltages.cells, _interim_state.cell_voltages.cells, sizeof(_state.cell_voltages)); + + _has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT; + + // check if MPPT should be powered on/off depending upon arming state + if (_mppt.is_detected) { + mppt_check_powered_state(); + } +} + +/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument +bool AP_BattMonitor_UAVCAN::capacity_remaining_pct(uint8_t &percentage) const +{ + if ((uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC)) || + _mppt.is_detected || + _soc == 127) { + // a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then + // the user can set the option to use current integration in the backend instead. + // SOC of 127 is used as an invalid SOC flag ie system configuration errors or SOC estimation unavailable + return AP_BattMonitor_Backend::capacity_remaining_pct(percentage); + } + + // the monitor must have current readings in order to estimate consumed_mah and be healthy + if (!has_current() || !_state.healthy) { + return false; + } + + percentage = _soc; + return true; +} + +/// get_cycle_count - return true if cycle count can be provided and fills in cycles argument +bool AP_BattMonitor_UAVCAN::get_cycle_count(uint16_t &cycles) const +{ + if (_has_battery_info_aux) { + cycles = _cycle_count; + return true; + } + return false; +} + +// request MPPT board to power on/off depending upon vehicle arming state as specified by BATT_OPTIONS +void AP_BattMonitor_UAVCAN::mppt_check_powered_state() +{ + if ((_mppt.powered_state_remote_ms != 0) && (AP_HAL::millis() - _mppt.powered_state_remote_ms >= 1000)) { + // there's already a set attempt that didnt' respond. Retry at 1Hz + mppt_set_powered_state(_mppt.powered_state); + } + + // check if vehicle armed state has changed + const bool vehicle_armed = hal.util->get_soft_armed(); + if ((!_mppt.vehicle_armed_last && vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Arm)) { + // arm event + mppt_set_powered_state(true); + } else if ((_mppt.vehicle_armed_last && !vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Disarm)) { + // disarm event + mppt_set_powered_state(false); + } + _mppt.vehicle_armed_last = vehicle_armed; +} + +// request MPPT board to power on or off +// power_on should be true to power on the MPPT, false to power off +// force should be true to force sending the state change request to the MPPT +void AP_BattMonitor_UAVCAN::mppt_set_powered_state(bool power_on) +{ + if (_ap_dronecan == nullptr || !_mppt.is_detected) { + return; + } + + _mppt.powered_state = power_on; + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: powering %s%s", (unsigned)_instance+1, _mppt.powered_state ? "ON" : "OFF", + (_mppt.powered_state_remote_ms == 0) ? "" : " Retry"); + + mppt_OutputEnableRequest request; + request.enable = _mppt.powered_state; + request.disable = !request.enable; + + if (mppt_outputenable_client == nullptr) { + mppt_outputenable_client = new Canard::Client{_ap_dronecan->get_canard_iface(), mppt_outputenable_res_cb}; + if (mppt_outputenable_client == nullptr) { + return; + } + } + mppt_outputenable_client->request(_node_id, request); +} + +// callback from outputEnable to verify it is enabled or disabled +void AP_BattMonitor_UAVCAN::handle_outputEnable_response(const CanardRxTransfer& transfer, const mppt_OutputEnableResponse& response) +{ + if (transfer.source_node_id != _node_id) { + // this response is not from the node we are looking for + return; + } + + if (response.enabled == _mppt.powered_state) { + // we got back what we expected it to be. We set it on, it now says it on (or vice versa). + // Clear the timer so we don't re-request + _mppt.powered_state_remote_ms = 0; + } +} + +#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG +// report changes in MPPT faults +void AP_BattMonitor_UAVCAN::mppt_report_faults(const uint8_t instance, const uint8_t fault_flags) +{ + // handle recovery + if (fault_flags == 0) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: OK", (unsigned)instance+1); + return; + } + + // send battery faults via text messages + for (uint8_t fault_bit=0x01; fault_bit <= 0x08; fault_bit <<= 1) { + // this loop is to generate multiple messages if there are multiple concurrent faults, but also run once if there are no faults + if ((fault_bit & fault_flags) != 0) { + const MPPT_FaultFlags err = (MPPT_FaultFlags)fault_bit; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: %s", (unsigned)instance+1, mppt_fault_string(err)); + } + } +} + +// returns string description of MPPT fault bit. Only handles single bit faults +const char* AP_BattMonitor_UAVCAN::mppt_fault_string(const MPPT_FaultFlags fault) +{ + switch (fault) { + case MPPT_FaultFlags::OVER_VOLTAGE: + return "over voltage"; + case MPPT_FaultFlags::UNDER_VOLTAGE: + return "under voltage"; + case MPPT_FaultFlags::OVER_CURRENT: + return "over current"; + case MPPT_FaultFlags::OVER_TEMPERATURE: + return "over temp"; + } + return "unknown"; +} +#endif + +// return mavlink fault bitmask (see MAV_BATTERY_FAULT enum) +uint32_t AP_BattMonitor_UAVCAN::get_mavlink_fault_bitmask() const +{ + // return immediately if not mppt or no faults + if (!_mppt.is_detected || (_mppt.fault_flags == 0)) { + return 0; + } + + // convert mppt fault bitmask to mavlink fault bitmask + uint32_t mav_fault_bitmask = 0; + if ((_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_VOLTAGE) || (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::UNDER_VOLTAGE)) { + mav_fault_bitmask |= MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE; + } + if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_CURRENT) { + mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_CURRENT; + } + if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_TEMPERATURE) { + mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_TEMPERATURE; + } + return mav_fault_bitmask; +} + +#endif // AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h new file mode 100644 index 00000000000000..22e4cfd170b6b6 --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h @@ -0,0 +1,115 @@ +#pragma once + +#include "AP_BattMonitor.h" +#include "AP_BattMonitor_Backend.h" +#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#include + +#define AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS 5000000 // sensor becomes unhealthy if no successful readings for 5 seconds + +#ifndef AP_BATTMONITOR_UAVCAN_MPPT_DEBUG +#define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 +#endif + +class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend +{ +public: + enum BattMonitor_UAVCAN_Type { + UAVCAN_BATTERY_INFO = 0 + }; + + /// Constructor + AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params ¶ms); + + static const struct AP_Param::GroupInfo var_info[]; + + void init() override {} + + /// Read the battery voltage and current. Should be called at 10hz + void read() override; + + /// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument + bool capacity_remaining_pct(uint8_t &percentage) const override; + + bool has_temperature() const override { return _has_temperature; } + + bool has_current() const override { return true; } + + bool has_consumed_energy() const override { return _has_consumed_energy; } + + bool has_time_remaining() const override { return _has_time_remaining; } + + bool has_cell_voltages() const override { return _has_cell_voltages; } + + bool get_cycle_count(uint16_t &cycles) const override; + + // return mavlink fault bitmask (see MAV_BATTERY_FAULT enum) + uint32_t get_mavlink_fault_bitmask() const override; + + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static AP_BattMonitor_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id); + static void handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg); + static void handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg); + static void handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg); + + void mppt_set_powered_state(bool power_on) override; + +private: + void handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg); + void handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg); + void update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc); + + static bool match_battery_id(uint8_t instance, uint8_t battery_id) { + // when serial number is negative, all batteries are accepted. Else, it must match + return (AP::battery().get_serial_number(instance) < 0) || (AP::battery().get_serial_number(instance) == (int32_t)battery_id); + } + + // MPPT related enums and methods + enum class MPPT_FaultFlags : uint8_t { + OVER_VOLTAGE = (1U<<0), + UNDER_VOLTAGE = (1U<<1), + OVER_CURRENT = (1U<<2), + OVER_TEMPERATURE = (1U<<3), + }; + void handle_mppt_stream(const mppt_Stream &msg); + void mppt_check_powered_state(); + +#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG + static void mppt_report_faults(const uint8_t instance, const uint8_t fault_flags); + static const char* mppt_fault_string(const MPPT_FaultFlags fault); +#endif + + AP_BattMonitor::BattMonitor_State _interim_state; + BattMonitor_UAVCAN_Type _type; + + HAL_Semaphore _sem_battmon; + + AP_DroneCAN* _ap_dronecan; + uint8_t _soc; + uint8_t _node_id; + uint16_t _cycle_count; + float _remaining_capacity_wh; + float _full_charge_capacity_wh; + bool _has_temperature; + bool _has_cell_voltages; + bool _has_time_remaining; + bool _has_consumed_energy; + bool _has_battery_info_aux; + uint8_t _instance; // instance of this battery monitor + + AP_Float _curr_mult; // scaling multiplier applied to current reports for adjustment + // MPPT variables + struct { + bool is_detected; // true if this UAVCAN device is a Packet Digital MPPT + bool powered_state; // true if the mppt is powered on, false if powered off + bool vehicle_armed_last; // latest vehicle armed state. used to detect changes and power on/off MPPT board + uint8_t fault_flags; // bits holding fault flags + uint32_t powered_state_remote_ms; // timestamp of when request was sent, zeroed on response. Used to retry + } _mppt; + + void handle_outputEnable_response(const CanardRxTransfer&, const mppt_OutputEnableResponse&); + + Canard::ObjCallback mppt_outputenable_res_cb{this, &AP_BattMonitor_UAVCAN::handle_outputEnable_response}; + Canard::Client *mppt_outputenable_client; +}; +#endif From 2e8ea6ac4716e04799e84b139376a981c0ab653c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:53:24 +1000 Subject: [PATCH 215/287] AP_Compass: rename UAVCAN drivers to DroneCAN --- libraries/AP_Compass/AP_Compass_DroneCAN.cpp | 208 +++++++++++++++++++ libraries/AP_Compass/AP_Compass_DroneCAN.h | 50 +++++ 2 files changed, 258 insertions(+) create mode 100644 libraries/AP_Compass/AP_Compass_DroneCAN.cpp create mode 100644 libraries/AP_Compass/AP_Compass_DroneCAN.h diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp new file mode 100644 index 00000000000000..7b0dcf0818e3b0 --- /dev/null +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp @@ -0,0 +1,208 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_Compass_UAVCAN.h" + +#if AP_COMPASS_UAVCAN_ENABLED + +#include + +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define LOG_TAG "COMPASS" + +AP_Compass_UAVCAN::DetectedModules AP_Compass_UAVCAN::_detected_modules[]; +HAL_Semaphore AP_Compass_UAVCAN::_sem_registry; + +AP_Compass_UAVCAN::AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid) + : _ap_dronecan(ap_dronecan) + , _node_id(node_id) + , _sensor_id(sensor_id) + , _devid(devid) +{ +} + +void AP_Compass_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +{ + if (ap_dronecan == nullptr) { + return; + } + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("mag_sub"); + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("mag2_sub"); + } +} + +AP_Compass_Backend* AP_Compass_UAVCAN::probe(uint8_t index) +{ + AP_Compass_UAVCAN* driver = nullptr; + if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) { + WITH_SEMAPHORE(_sem_registry); + // Register new Compass mode to a backend + driver = new AP_Compass_UAVCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].node_id, _detected_modules[index].sensor_id, _detected_modules[index].devid); + if (driver) { + if (!driver->init()) { + delete driver; + return nullptr; + } + _detected_modules[index].driver = driver; + AP::can().log_text(AP_CANManager::LOG_INFO, + LOG_TAG, + "Found Mag Node %d on Bus %d Sensor ID %d\n", + _detected_modules[index].node_id, + _detected_modules[index].ap_dronecan->get_driver_index(), + _detected_modules[index].sensor_id); +#if AP_TEST_DRONECAN_DRIVERS + // Scroll through the registered compasses, and set the offsets + if (driver->_compass.get_offsets(index).is_zero()) { + driver->_compass.set_offsets(index, AP::sitl()->mag_ofs[index]); + } + + // we want to simulate a calibrated compass by default, so set + // scale to 1 + AP_Param::set_default_by_name("COMPASS_SCALE", 1); + AP_Param::set_default_by_name("COMPASS_SCALE2", 1); + AP_Param::set_default_by_name("COMPASS_SCALE3", 1); + driver->save_dev_id(index); + driver->set_rotation(index, ROTATION_NONE); + + // make first compass external + driver->set_external(index, true); +#endif + } + } + return driver; +} + +bool AP_Compass_UAVCAN::init() +{ + // Adding 1 is necessary to allow backward compatibilty, where this field was set as 1 by default + if (!register_compass(_devid, _instance)) { + return false; + } + + set_dev_id(_instance, _devid); + set_external(_instance, true); + + AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_UAVCAN loaded\n\r"); + return true; +} + +AP_Compass_UAVCAN* AP_Compass_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id) +{ + if (ap_dronecan == nullptr) { + return nullptr; + } + for (uint8_t i=0; iget_driver_index(), + node_id, + sensor_id + 1); // we use sensor_id as devtype + break; + } + } + } + + struct DetectedModules tempslot; + // Sort based on the node_id, larger values first + // we do this, so that we have repeatable compass + // registration, especially in cases of extraneous + // CAN compass is connected. + for (uint8_t i = 1; i < COMPASS_MAX_BACKEND; i++) { + for (uint8_t j = i; j > 0; j--) { + if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) { + tempslot = _detected_modules[j]; + _detected_modules[j] = _detected_modules[j-1]; + _detected_modules[j-1] = tempslot; + } + } + } + return nullptr; +} + +void AP_Compass_UAVCAN::handle_mag_msg(const Vector3f &mag) +{ + Vector3f raw_field = mag * 1000.0; + + accumulate_sample(raw_field, _instance); +} + +void AP_Compass_UAVCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg) +{ + WITH_SEMAPHORE(_sem_registry); + + Vector3f mag_vector; + AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, 0); + if (driver != nullptr) { + mag_vector[0] = msg.magnetic_field_ga[0]; + mag_vector[1] = msg.magnetic_field_ga[1]; + mag_vector[2] = msg.magnetic_field_ga[2]; + driver->handle_mag_msg(mag_vector); + } +} + +void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg) +{ + WITH_SEMAPHORE(_sem_registry); + + Vector3f mag_vector; + uint8_t sensor_id = msg.sensor_id; + AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, sensor_id); + if (driver != nullptr) { + mag_vector[0] = msg.magnetic_field_ga[0]; + mag_vector[1] = msg.magnetic_field_ga[1]; + mag_vector[2] = msg.magnetic_field_ga[2]; + driver->handle_mag_msg(mag_vector); + } +} + +void AP_Compass_UAVCAN::read(void) +{ + drain_accumulated_samples(_instance); +} +#endif // AP_COMPASS_UAVCAN_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.h b/libraries/AP_Compass/AP_Compass_DroneCAN.h new file mode 100644 index 00000000000000..32f66768baa117 --- /dev/null +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.h @@ -0,0 +1,50 @@ +#pragma once + +#include "AP_Compass.h" + +#if AP_COMPASS_UAVCAN_ENABLED + +#include "AP_Compass_Backend.h" + +#include + +class AP_Compass_UAVCAN : public AP_Compass_Backend { +public: + AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid); + + void read(void) override; + + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static AP_Compass_Backend* probe(uint8_t index); + static uint32_t get_detected_devid(uint8_t index) { return _detected_modules[index].devid; } + static void handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg); + static void handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg); + +private: + bool init(); + + // callback for DroneCAN messages + void handle_mag_msg(const Vector3f &mag); + + static AP_Compass_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id); + + uint8_t _instance; + + AP_DroneCAN* _ap_dronecan; + uint8_t _node_id; + uint8_t _sensor_id; + uint32_t _devid; + + // Module Detection Registry + static struct DetectedModules { + AP_DroneCAN* ap_dronecan; + uint8_t node_id; + uint8_t sensor_id; + AP_Compass_UAVCAN *driver; + uint32_t devid; + } _detected_modules[COMPASS_MAX_BACKEND]; + + static HAL_Semaphore _sem_registry; +}; + +#endif // AP_COMPASS_UAVCAN_ENABLED From 9d37083ddf1ccfbe8bbf51c9b6f30f79eb9c77b0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:53:24 +1000 Subject: [PATCH 216/287] AP_DroneCAN: rename UAVCAN drivers to DroneCAN --- .../examples/DroneCAN_sniffer/README.md | 27 ++ .../DroneCAN_sniffer/UAVCAN_sniffer.cpp | 246 ++++++++++++++++++ .../examples/DroneCAN_sniffer/nobuild.txt | 0 .../examples/DroneCAN_sniffer/wscript | 21 ++ 4 files changed, 294 insertions(+) create mode 100644 libraries/AP_DroneCAN/examples/DroneCAN_sniffer/README.md create mode 100644 libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp create mode 100644 libraries/AP_DroneCAN/examples/DroneCAN_sniffer/nobuild.txt create mode 100644 libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/README.md b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/README.md new file mode 100644 index 00000000000000..44f3e1c5b4b53c --- /dev/null +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/README.md @@ -0,0 +1,27 @@ +This is a UAVCAN sniffer designed to run on an ArduPilot board. It can +be used to watch traffic on a UAVCAN bus, showing exactly what would +be received by another node. + +To build and upload for a Pixhawk style board run this: + +``` + ./waf configure --board fmuv3 + ./waf --target examples/UAVCAN_sniffer --upload +``` + +then connect on the USB console. You will see 1Hz packet stats like +this: + +``` +uavcan.equipment.air_data.StaticPressure: 29 +uavcan.equipment.air_data.StaticTemperature: 29 +uavcan.equipment.ahrs.MagneticFieldStrength: 20 +uavcan.protocol.NodeStatus: 6 +uavcan.equipment.gnss.Fix: 10 +uavcan.equipment.gnss.Auxiliary: 1 +uavcan.equipment.actuator.ArrayCommand: 45 +uavcan.equipment.esc.RawCommand: 368 +``` + +note that the code requires you to add new msg types you want to +see. Look for the MSG_CB() and START_CB() macros in the code diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp new file mode 100644 index 00000000000000..942404349b29c6 --- /dev/null +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp @@ -0,0 +1,246 @@ +/* + simple UAVCAN network sniffer as an ArduPilot firmware + */ +#include +#include + +#if HAL_ENABLE_LIBUAVCAN_DRIVERS + +#include + +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX +#include +#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include +#include +#endif + +void setup(); +void loop(); + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +#define UAVCAN_NODE_POOL_SIZE 8192 + +static uint8_t node_memory_pool[UAVCAN_NODE_POOL_SIZE]; + +#define debug_uavcan(fmt, args...) do { hal.console->printf(fmt, ##args); } while (0) + +class UAVCAN_sniffer { +public: + UAVCAN_sniffer(); + ~UAVCAN_sniffer(); + + void init(void); + void loop(void); + void print_stats(void); + +private: + uint8_t driver_index = 0; + + AP_CANManager can_mgr; +}; + +static struct { + const char *msg_name; + uint32_t count; +} counters[100]; + +static void count_msg(const char *name) +{ + for (uint16_t i=0; i *node_status_pub; +Canard::Server *node_info_srv; + +static void cb_GetNodeInfoRequest(const CanardRxTransfer &transfer, const uavcan_protocol_GetNodeInfoRequest& msg) +{ + if (node_info_srv == nullptr) { + return; + } + node_info_srv->respond(transfer, node_info); +} + +void UAVCAN_sniffer::init(void) +{ + const_cast (hal).can[driver_index] = new HAL_CANIface(driver_index); + + if (hal.can[driver_index] == nullptr) { + AP_HAL::panic("Couldn't allocate CANManager, something is very wrong"); + } + + hal.can[driver_index]->init(1000000, AP_HAL::CANIface::NormalMode); + + if (!hal.can[driver_index]->is_initialized()) { + debug_uavcan("Can not initialised\n"); + return; + } + _uavcan_iface_mgr = new CanardInterface{driver_index}; + + if (_uavcan_iface_mgr == nullptr) { + return; + } + + if (!_uavcan_iface_mgr->add_interface(hal.can[driver_index])) { + debug_uavcan("Failed to add iface"); + return; + } + + _uavcan_iface_mgr->init(node_memory_pool, sizeof(node_memory_pool), 9); + + node_status_pub = new Canard::Publisher{*_uavcan_iface_mgr}; + if (node_status_pub == nullptr) { + return; + } + + node_info_srv = new Canard::Server{*_uavcan_iface_mgr, *Canard::allocate_static_callback(cb_GetNodeInfoRequest)}; + if (node_info_srv == nullptr) { + return; + } + + node_info.name.len = snprintf((char*)node_info.name.data, sizeof(node_info.name.data), "org.ardupilot:%u", driver_index); + + node_info.software_version.major = AP_DRONECAN_SW_VERS_MAJOR; + node_info.software_version.minor = AP_DRONECAN_SW_VERS_MINOR; + + node_info.hardware_version.major = AP_DRONECAN_HW_VERS_MAJOR; + node_info.hardware_version.minor = AP_DRONECAN_HW_VERS_MINOR; + +#define START_CB(mtype, cbname) Canard::allocate_sub_static_callback(cb_ ## cbname,driver_index) + + START_CB(uavcan_protocol_NodeStatus, NodeStatus); + START_CB(uavcan_equipment_gnss_Fix2, Fix2); + START_CB(uavcan_equipment_gnss_Auxiliary, Auxiliary); + START_CB(uavcan_equipment_ahrs_MagneticFieldStrength, MagneticFieldStrength); + START_CB(uavcan_equipment_ahrs_MagneticFieldStrength2, MagneticFieldStrength2); + START_CB(uavcan_equipment_air_data_StaticPressure, StaticPressure); + START_CB(uavcan_equipment_air_data_StaticTemperature, StaticTemperature); + START_CB(uavcan_equipment_power_BatteryInfo, BatteryInfo); + START_CB(uavcan_equipment_actuator_ArrayCommand, ArrayCommand); + START_CB(uavcan_equipment_esc_RawCommand, RawCommand); + START_CB(uavcan_equipment_indication_LightsCommand, LightsCommand); + START_CB(com_hex_equipment_flow_Measurement, Measurement); + + debug_uavcan("UAVCAN: init done\n\r"); +} + +static void send_node_status() +{ + uavcan_protocol_NodeStatus msg; + msg.uptime_sec = AP_HAL::millis() / 1000; + msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; + msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; + msg.sub_mode = 0; + msg.vendor_specific_status_code = 0; + node_status_pub->broadcast(msg); +} + +uint32_t last_status_send = 0; +void UAVCAN_sniffer::loop(void) +{ + if (AP_HAL::millis() - last_status_send > 1000) { + last_status_send = AP_HAL::millis(); + send_node_status(); + } + _uavcan_iface_mgr->process(1); +} + +void UAVCAN_sniffer::print_stats(void) +{ + hal.console->printf("%lu\n", (unsigned long)AP_HAL::micros()); + for (uint16_t i=0;i<100;i++) { + if (counters[i].msg_name == nullptr) { + break; + } + hal.console->printf("%s: %u\n", counters[i].msg_name, unsigned(counters[i].count)); + counters[i].count = 0; + } + hal.console->printf("\n"); +} + +static UAVCAN_sniffer sniffer; + +UAVCAN_sniffer::UAVCAN_sniffer() +{} + +UAVCAN_sniffer::~UAVCAN_sniffer() +{ +} + +void setup(void) +{ + hal.scheduler->delay(2000); + hal.console->printf("Starting UAVCAN sniffer\n"); + sniffer.init(); +} + +void loop(void) +{ + sniffer.loop(); + static uint32_t last_print_ms; + uint32_t now = AP_HAL::millis(); + if (now - last_print_ms >= 1000) { + last_print_ms = now; + sniffer.print_stats(); + } + + // auto-reboot for --upload + if (hal.console->available() > 50) { + hal.console->printf("rebooting\n"); + hal.console->discard_input(); + hal.scheduler->reboot(false); + } + hal.console->discard_input(); +} + +AP_HAL_MAIN(); + +#else + +#include + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +static void loop() { } +static void setup() +{ + printf("Board not currently supported\n"); +} + +AP_HAL_MAIN(); +#endif diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/nobuild.txt b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/nobuild.txt new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript new file mode 100644 index 00000000000000..3e81beeee182a4 --- /dev/null +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript @@ -0,0 +1,21 @@ +#!/usr/bin/env python +# encoding: utf-8 +from waflib.TaskGen import after_method, before_method, feature + +def build(bld): + vehicle = bld.path.name + + bld.ap_stlib( + name=vehicle + '_libs', + ap_vehicle='UNKNOWN', + dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', + ap_libraries=bld.ap_common_vehicle_libraries() + [ + 'AP_OSD', + 'AP_RCMapper', + 'AP_Arming' + ], + ) + bld.ap_program( + program_groups=['tool'], + use=[vehicle + '_libs'], + ) From 258158b0bcd566c370fd69dc76596171b6fb7322 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:53:24 +1000 Subject: [PATCH 217/287] AP_GPS: rename UAVCAN drivers to DroneCAN --- libraries/AP_GPS/AP_GPS_DroneCAN.cpp | 848 +++++++++++++++++++++++++++ libraries/AP_GPS/AP_GPS_DroneCAN.h | 142 +++++ 2 files changed, 990 insertions(+) create mode 100644 libraries/AP_GPS/AP_GPS_DroneCAN.cpp create mode 100644 libraries/AP_GPS/AP_GPS_DroneCAN.h diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp new file mode 100644 index 00000000000000..8ac0ca6d6571ba --- /dev/null +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp @@ -0,0 +1,848 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +// +// UAVCAN GPS driver +// +#include + +#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#include "AP_GPS_UAVCAN.h" + +#include +#include +#include + +#include + +#include +#include + +#define GPS_PPS_EMULATION 0 + +extern const AP_HAL::HAL& hal; + +#define GPS_UAVCAN_DEBUGGING 0 + +#if GPS_UAVCAN_DEBUGGING +#if defined(HAL_BUILD_AP_PERIPH) + extern "C" { + void can_printf(const char *fmt, ...); + } + # define Debug(fmt, args ...) do {can_printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args);} while(0) +#else + # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0) +#endif +#else + # define Debug(fmt, args ...) +#endif + +#define LOG_TAG "GPS" + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#define NATIVE_TIME_OFFSET (AP_HAL::micros64() - AP_HAL::native_micros64()) +#else +#define NATIVE_TIME_OFFSET 0 +#endif +AP_GPS_UAVCAN::DetectedModules AP_GPS_UAVCAN::_detected_modules[]; +HAL_Semaphore AP_GPS_UAVCAN::_sem_registry; + +// Member Methods +AP_GPS_UAVCAN::AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role _role) : + AP_GPS_Backend(_gps, _state, nullptr), + interim_state(_state), + role(_role) +{ + param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_int, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); + param_float_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_float, bool, AP_DroneCAN*, const uint8_t, const char*, float &); + param_save_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_save_response, void, AP_DroneCAN*, const uint8_t, bool); +} + +AP_GPS_UAVCAN::~AP_GPS_UAVCAN() +{ + WITH_SEMAPHORE(_sem_registry); + + _detected_modules[_detected_module].driver = nullptr; + +#if GPS_MOVING_BASELINE + if (rtcm3_parser != nullptr) { + delete rtcm3_parser; + } +#endif +} + +void AP_GPS_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +{ + if (ap_dronecan == nullptr) { + return; + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_fix2_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_aux_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_heading_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_status_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("status_sub"); + } +#if GPS_MOVING_BASELINE + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_moving_baseline_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("moving_baseline_sub"); + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_relposheading_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("relposheading_sub"); + } +#endif +} + +AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) +{ + WITH_SEMAPHORE(_sem_registry); + int8_t found_match = -1, last_match = -1; + AP_GPS_UAVCAN* backend = nullptr; + bool bad_override_config = false; + for (int8_t i = GPS_MAX_RECEIVERS - 1; i >= 0; i--) { + if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { + if (_gps._override_node_id[_state.instance] != 0 && + _gps._override_node_id[_state.instance] != _detected_modules[i].node_id) { + continue; // This device doesn't match the correct node + } + last_match = found_match; + for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) { + if (_detected_modules[i].node_id == _gps._override_node_id[j] && + (j != _state.instance)) { + //wrong instance + found_match = -1; + break; + } + found_match = i; + } + + // Handle Duplicate overrides + for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) { + if (_gps._override_node_id[i] != 0 && (i != j) && + _gps._override_node_id[i] == _gps._override_node_id[j]) { + bad_override_config = true; + } + } + if (bad_override_config) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Same Node Id %lu set for multiple GPS", (unsigned long int)_gps._override_node_id[i].get()); + last_match = i; + } + + if (found_match == -1) { + found_match = last_match; + continue; + } + break; + } + } + + if (found_match == -1) { + return NULL; + } + // initialise the backend based on the UAVCAN Moving baseline selection + switch (_gps.get_type(_state.instance)) { + case AP_GPS::GPS_TYPE_UAVCAN: + backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_NORMAL); + break; +#if GPS_MOVING_BASELINE + case AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE: + backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_MB_BASE); + break; + case AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER: + backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_MB_ROVER); + break; +#endif + default: + return NULL; + } + if (backend == nullptr) { + AP::can().log_text(AP_CANManager::LOG_ERROR, + LOG_TAG, + "Failed to register UAVCAN GPS Node %d on Bus %d\n", + _detected_modules[found_match].node_id, + _detected_modules[found_match].ap_dronecan->get_driver_index()); + } else { + _detected_modules[found_match].driver = backend; + backend->_detected_module = found_match; + AP::can().log_text(AP_CANManager::LOG_INFO, + LOG_TAG, + "Registered UAVCAN GPS Node %d on Bus %d as instance %d\n", + _detected_modules[found_match].node_id, + _detected_modules[found_match].ap_dronecan->get_driver_index(), + _state.instance); + snprintf(backend->_name, ARRAY_SIZE(backend->_name), "UAVCAN%u-%u", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); + _detected_modules[found_match].instance = _state.instance; + for (uint8_t i=0; i < GPS_MAX_RECEIVERS; i++) { + if (_detected_modules[found_match].node_id == AP::gps()._node_id[i]) { + if (i == _state.instance) { + // Nothing to do here + break; + } + // else swap + uint8_t tmp = AP::gps()._node_id[_state.instance].get(); + AP::gps()._node_id[_state.instance].set_and_notify(_detected_modules[found_match].node_id); + AP::gps()._node_id[i].set_and_notify(tmp); + } + } +#if GPS_MOVING_BASELINE + if (backend->role == AP_GPS::GPS_ROLE_MB_BASE) { + backend->rtcm3_parser = new RTCM3_Parser; + if (backend->rtcm3_parser == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UAVCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); + } + } +#endif // GPS_MOVING_BASELINE + } + + return backend; +} + +bool AP_GPS_UAVCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_len) +{ + for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { + bool overriden_node_found = false; + bool bad_override_config = false; + if (AP::gps()._override_node_id[i] == 0) { + //anything goes + continue; + } + for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) { + if (AP::gps()._override_node_id[i] == AP::gps()._override_node_id[j] && (i != j)) { + bad_override_config = true; + break; + } + if (i == _detected_modules[j].instance && _detected_modules[j].driver) { + if (AP::gps()._override_node_id[i] == _detected_modules[j].node_id) { + overriden_node_found = true; + break; + } + } + } + if (bad_override_config) { + snprintf(failure_msg, failure_msg_len, "Same Node Id %lu set for multiple GPS", (unsigned long int)AP::gps()._override_node_id[i].get()); + return false; + } + + if (!overriden_node_found) { + snprintf(failure_msg, failure_msg_len, "Selected GPS Node %lu not set as instance %d", (unsigned long int)AP::gps()._override_node_id[i].get(), i + 1); + return false; + } + } + + return true; +} + +AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) +{ + if (ap_dronecan == nullptr) { + return nullptr; + } + + for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { + if (_detected_modules[i].driver != nullptr && + _detected_modules[i].ap_dronecan == ap_dronecan && + _detected_modules[i].node_id == node_id) { + return _detected_modules[i].driver; + } + } + + bool already_detected = false; + // Check if there's an empty spot for possible registeration + for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { + if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { + // Already Detected + already_detected = true; + break; + } + } + if (!already_detected) { + for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { + if (_detected_modules[i].ap_dronecan == nullptr) { + _detected_modules[i].ap_dronecan = ap_dronecan; + _detected_modules[i].node_id = node_id; + // Just set the Node ID in order of appearance + // This will be used to set select ids + AP::gps()._node_id[i].set_and_notify(node_id); + break; + } + } + } + struct DetectedModules tempslot; + // Sort based on the node_id, larger values first + // we do this, so that we have repeatable GPS + // registration + for (uint8_t i = 1; i < GPS_MAX_RECEIVERS; i++) { + for (uint8_t j = i; j > 0; j--) { + if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) { + tempslot = _detected_modules[j]; + _detected_modules[j] = _detected_modules[j-1]; + _detected_modules[j-1] = tempslot; + // also fix the _detected_module in the driver so that RTCM injection + // can determine if it has the bus to itself + if (_detected_modules[j].driver) { + _detected_modules[j].driver->_detected_module = j; + } + if (_detected_modules[j-1].driver) { + _detected_modules[j-1].driver->_detected_module = j-1; + } + } + } + } + return nullptr; +} + +/* + handle velocity element of message + */ +void AP_GPS_UAVCAN::handle_velocity(const float vx, const float vy, const float vz) +{ + if (!isnanf(vx)) { + const Vector3f vel(vx, vy, vz); + interim_state.velocity = vel; + velocity_to_speed_course(interim_state); + // assume we have vertical velocity if we ever get a non-zero Z velocity + if (!isnan(vel.z) && !is_zero(vel.z)) { + interim_state.have_vertical_velocity = true; + } else { + interim_state.have_vertical_velocity = state.have_vertical_velocity; + } + } else { + interim_state.have_vertical_velocity = false; + } +} + +void AP_GPS_UAVCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec) +{ + bool process = false; + seen_fix2 = true; + + WITH_SEMAPHORE(sem); + + if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX) { + interim_state.status = AP_GPS::GPS_Status::NO_FIX; + } else { + if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_TIME_ONLY) { + interim_state.status = AP_GPS::GPS_Status::NO_FIX; + } else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX) { + interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_2D; + process = true; + } else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX) { + interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D; + process = true; + } + + if (msg.gnss_time_standard == UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_UTC) { + uint64_t epoch_ms = msg.gnss_timestamp.usec; + if (epoch_ms != 0) { + epoch_ms /= 1000; + uint64_t gps_ms = epoch_ms - UNIX_OFFSET_MSEC; + interim_state.time_week = (uint16_t)(gps_ms / AP_MSEC_PER_WEEK); + interim_state.time_week_ms = (uint32_t)(gps_ms - (interim_state.time_week) * AP_MSEC_PER_WEEK); + } + } + + if (interim_state.status == AP_GPS::GPS_Status::GPS_OK_FIX_3D) { + if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS) { + interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS; + } else if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK) { + if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT) { + interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT; + } else if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED) { + interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED; + } + } + } + } + + if (process) { + Location loc = { }; + loc.lat = msg.latitude_deg_1e8 / 10; + loc.lng = msg.longitude_deg_1e8 / 10; + loc.alt = msg.height_msl_mm / 10; + interim_state.have_undulation = true; + interim_state.undulation = (msg.height_msl_mm - msg.height_ellipsoid_mm) * 0.001; + interim_state.location = loc; + + handle_velocity(msg.ned_velocity[0], msg.ned_velocity[1], msg.ned_velocity[2]); + + if (msg.covariance.len == 6) { + if (!isnanf(msg.covariance.data[0])) { + interim_state.horizontal_accuracy = sqrtf(msg.covariance.data[0]); + interim_state.have_horizontal_accuracy = true; + } else { + interim_state.have_horizontal_accuracy = false; + } + if (!isnanf(msg.covariance.data[2])) { + interim_state.vertical_accuracy = sqrtf(msg.covariance.data[2]); + interim_state.have_vertical_accuracy = true; + } else { + interim_state.have_vertical_accuracy = false; + } + if (!isnanf(msg.covariance.data[3]) && + !isnanf(msg.covariance.data[4]) && + !isnanf(msg.covariance.data[5])) { + interim_state.speed_accuracy = sqrtf((msg.covariance.data[3] + msg.covariance.data[4] + msg.covariance.data[5])/3); + interim_state.have_speed_accuracy = true; + } else { + interim_state.have_speed_accuracy = false; + } + } + + interim_state.num_sats = msg.sats_used; + } else { + interim_state.have_vertical_velocity = false; + interim_state.have_vertical_accuracy = false; + interim_state.have_horizontal_accuracy = false; + interim_state.have_speed_accuracy = false; + interim_state.num_sats = 0; + } + + if (!seen_aux) { + // if we haven't seen an Aux message then populate vdop and + // hdop from pdop. Some GPS modules don't provide the Aux message + interim_state.hdop = interim_state.vdop = msg.pdop * 100.0; + } + + if ((msg.timestamp.usec > msg.gnss_timestamp.usec) && (msg.gnss_timestamp.usec > 0)) { + // we have a valid timestamp based on gnss_timestamp timescale, we can use that to correct our gps message time + interim_state.last_corrected_gps_time_us = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, (timestamp_usec + NATIVE_TIME_OFFSET)); + interim_state.last_gps_time_ms = interim_state.last_corrected_gps_time_us/1000U; + interim_state.last_corrected_gps_time_us -= msg.timestamp.usec - msg.gnss_timestamp.usec; + // this is also the time the message was received on the UART on other end. + interim_state.corrected_timestamp_updated = true; + } else { + interim_state.last_gps_time_ms = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, timestamp_usec + NATIVE_TIME_OFFSET)/1000U; + } + +#if GPS_PPS_EMULATION + // Emulates a PPS signal, can be used to check how close are we to real GPS time + static virtual_timer_t timeout_vt; + hal.gpio->pinMode(51, 1); + auto handle_timeout = [](void *arg) + { + (void)arg; + //we are called from ISR context + chSysLockFromISR(); + hal.gpio->toggle(51); + chSysUnlockFromISR(); + }; + + static uint64_t next_toggle, last_toggle; + + next_toggle = (msg.timestamp.usec) + (1000000ULL - ((msg.timestamp.usec) % 1000000ULL)); + + next_toggle += jitter_correction.get_link_offset_usec(); + if (next_toggle != last_toggle) { + chVTSet(&timeout_vt, chTimeUS2I(next_toggle - AP_HAL::micros64()), handle_timeout, nullptr); + last_toggle = next_toggle; + } +#endif + + _new_data = true; + if (!seen_message) { + if (interim_state.status == AP_GPS::GPS_Status::NO_GPS) { + // the first time we see a fix message we change from + // NO_GPS to NO_FIX, indicating to user that a UAVCAN GPS + // has been seen + interim_state.status = AP_GPS::GPS_Status::NO_FIX; + } + seen_message = true; + } +} + +void AP_GPS_UAVCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg) +{ + WITH_SEMAPHORE(sem); + + if (!isnanf(msg.hdop)) { + seen_aux = true; + interim_state.hdop = msg.hdop * 100.0; + } + + if (!isnanf(msg.vdop)) { + seen_aux = true; + interim_state.vdop = msg.vdop * 100.0; + } +} + +void AP_GPS_UAVCAN::handle_heading_msg(const ardupilot_gnss_Heading& msg) +{ +#if GPS_MOVING_BASELINE + if (seen_relposheading && gps.mb_params[interim_state.instance].type.get() != 0) { + // we prefer to use the relposheading to get yaw as it allows + // the user to more easily control the relative antenna positions + return; + } +#endif + + WITH_SEMAPHORE(sem); + + if (interim_state.gps_yaw_configured == false) { + interim_state.gps_yaw_configured = msg.heading_valid; + } + + interim_state.have_gps_yaw = msg.heading_valid; + interim_state.gps_yaw = degrees(msg.heading_rad); + if (interim_state.have_gps_yaw) { + interim_state.gps_yaw_time_ms = AP_HAL::millis(); + } + + interim_state.have_gps_yaw_accuracy = msg.heading_accuracy_valid; + interim_state.gps_yaw_accuracy = degrees(msg.heading_accuracy_rad); +} + +void AP_GPS_UAVCAN::handle_status_msg(const ardupilot_gnss_Status& msg) +{ + WITH_SEMAPHORE(sem); + + seen_status = true; + + healthy = msg.healthy; + status_flags = msg.status; + if (error_code != msg.error_codes) { + AP::logger().Write_MessageF("GPS %d: error changed (0x%08x/0x%08x)", + (unsigned int)(state.instance + 1), + error_code, + msg.error_codes); + error_code = msg.error_codes; + } +} + +#if GPS_MOVING_BASELINE +/* + handle moving baseline data. + */ +void AP_GPS_UAVCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id) +{ + WITH_SEMAPHORE(sem); + if (role != AP_GPS::GPS_ROLE_MB_BASE) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Incorrect Role set for UAVCAN GPS, %d should be Base", node_id); + return; + } + + if (rtcm3_parser == nullptr) { + return; + } + for (int i=0; i < msg.data.len; i++) { + rtcm3_parser->read(msg.data.data[i]); + } +} + +/* + handle relposheading message +*/ +void AP_GPS_UAVCAN::handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id) +{ + WITH_SEMAPHORE(sem); + + interim_state.gps_yaw_configured = true; + seen_relposheading = true; + // push raw heading data to calculate moving baseline heading states + if (calculate_moving_base_yaw(interim_state, + msg.reported_heading_deg, + msg.relative_distance_m, + msg.relative_down_pos_m)) { + if (msg.reported_heading_acc_available) { + interim_state.gps_yaw_accuracy = msg.reported_heading_acc_deg; + } + interim_state.have_gps_yaw_accuracy = msg.reported_heading_acc_available; + } +} + +// support for retrieving RTCMv3 data from a moving baseline base +bool AP_GPS_UAVCAN::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) +{ + WITH_SEMAPHORE(sem); + if (rtcm3_parser != nullptr) { + len = rtcm3_parser->get_len(bytes); + return len > 0; + } + return false; +} + +// clear previous RTCM3 packet +void AP_GPS_UAVCAN::clear_RTCMV3(void) +{ + WITH_SEMAPHORE(sem); + if (rtcm3_parser != nullptr) { + rtcm3_parser->clear_packet(); + } +} + +#endif // GPS_MOVING_BASELINE + +void AP_GPS_UAVCAN::handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + if (driver != nullptr) { + driver->handle_fix2_msg(msg, transfer.timestamp_usec); + } +} + +void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + if (driver != nullptr) { + driver->handle_aux_msg(msg); + } +} + +void AP_GPS_UAVCAN::handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + if (driver != nullptr) { + driver->handle_heading_msg(msg); + } +} + +void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + if (driver != nullptr) { + driver->handle_status_msg(msg); + } +} + +#if GPS_MOVING_BASELINE +// Moving Baseline msg trampoline +void AP_GPS_UAVCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg) +{ + WITH_SEMAPHORE(_sem_registry); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + if (driver != nullptr) { + driver->handle_moving_baseline_msg(msg, transfer.source_node_id); + } +} + +// RelPosHeading msg trampoline +void AP_GPS_UAVCAN::handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg) +{ + WITH_SEMAPHORE(_sem_registry); + AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + if (driver != nullptr) { + driver->handle_relposheading_msg(msg, transfer.source_node_id); + } +} +#endif + +bool AP_GPS_UAVCAN::do_config() +{ + AP_DroneCAN *ap_dronecan = _detected_modules[_detected_module].ap_dronecan; + if (ap_dronecan == nullptr) { + return false; + } + uint8_t node_id = _detected_modules[_detected_module].node_id; + + switch(cfg_step) { + case STEP_SET_TYPE: + ap_dronecan->get_parameter_on_node(node_id, "GPS_TYPE", ¶m_int_cb); + break; + case STEP_SET_MB_CAN_TX: + if (role != AP_GPS::GPS_Role::GPS_ROLE_NORMAL) { + ap_dronecan->get_parameter_on_node(node_id, "GPS_MB_ONLY_PORT", ¶m_int_cb); + } else { + cfg_step++; + } + break; + case STEP_SAVE_AND_REBOOT: + if (requires_save_and_reboot) { + ap_dronecan->save_parameters_on_node(node_id, ¶m_save_cb); + } else { + cfg_step++; + } + break; + case STEP_FINISHED: + return true; + default: + break; + } + return false; +} + +// Consume new data and mark it received +bool AP_GPS_UAVCAN::read(void) +{ + if (gps._auto_config >= AP_GPS::GPS_AUTO_CONFIG_ENABLE_ALL) { + if (!do_config()) { + return false; + } + } + + WITH_SEMAPHORE(sem); + if (_new_data) { + _new_data = false; + + // the encoding of accuracies in UAVCAN can result in infinite + // values. These cause problems with blending. Use 1000m and 1000m/s instead + interim_state.horizontal_accuracy = MIN(interim_state.horizontal_accuracy, 1000.0); + interim_state.vertical_accuracy = MIN(interim_state.vertical_accuracy, 1000.0); + interim_state.speed_accuracy = MIN(interim_state.speed_accuracy, 1000.0); + + state = interim_state; + if (interim_state.last_corrected_gps_time_us) { + // If we were able to get a valid last_corrected_gps_time_us + // we have had a valid GPS message time, from which we calculate + // the time of week. + _last_itow_ms = interim_state.time_week_ms; + _have_itow = true; + } + return true; + } + if (!seen_message) { + // start with NO_GPS until we get first packet + state.status = AP_GPS::GPS_Status::NO_GPS; + } + + return false; +} + +bool AP_GPS_UAVCAN::is_healthy(void) const +{ + // if we don't have any health reports, assume it's healthy + if (!seen_status) { + return true; + } + return healthy; +} + +bool AP_GPS_UAVCAN::logging_healthy(void) const +{ + // if we don't have status, assume it's valid + if (!seen_status) { + return true; + } + + return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_LOGGING) != 0; +} + +bool AP_GPS_UAVCAN::is_configured(void) const +{ + // if we don't have status assume it's configured + if (!seen_status) { + return true; + } + + return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE) != 0; +} + +/* + handle RTCM data from MAVLink GPS_RTCM_DATA, forwarding it over MAVLink + */ +void AP_GPS_UAVCAN::inject_data(const uint8_t *data, uint16_t len) +{ + // we only handle this if we are the first UAVCAN GPS or we are + // using a different uavcan instance than the first GPS, as we + // send the data as broadcast on all UAVCAN devive ports and we + // don't want to send duplicates + if (_detected_module == 0 || + _detected_modules[_detected_module].ap_dronecan != _detected_modules[0].ap_dronecan) { + _detected_modules[_detected_module].ap_dronecan->send_RTCMStream(data, len); + } +} + +/* + handle param get/set response +*/ +bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, int32_t &value) +{ + Debug("AP_GPS_UAVCAN: param set/get response from %d %s %ld\n", node_id, name, value); + if (strcmp(name, "GPS_TYPE") == 0 && cfg_step == STEP_SET_TYPE) { + if (role == AP_GPS::GPS_ROLE_MB_BASE && value != AP_GPS::GPS_TYPE_UBLOX_RTK_BASE) { + value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_BASE; + requires_save_and_reboot = true; + return true; + } else if (role == AP_GPS::GPS_ROLE_MB_ROVER && value != AP_GPS::GPS_TYPE_UBLOX_RTK_ROVER) { + value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_ROVER; + requires_save_and_reboot = true; + return true; + } else { + cfg_step++; + } + } + + if (strcmp(name, "GPS_MB_ONLY_PORT") == 0 && cfg_step == STEP_SET_MB_CAN_TX) { + if (option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && !value) { + // set up so that another CAN port is used for the Moving Baseline Data + // setting this value will allow another CAN port to be used as dedicated + // line for the Moving Baseline Data + value = 1; + requires_save_and_reboot = true; + return true; + } else if (!option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && value) { + // set up so that all CAN ports are used for the Moving Baseline Data + value = 0; + requires_save_and_reboot = true; + return true; + } else { + cfg_step++; + } + } + return false; +} + +bool AP_GPS_UAVCAN::handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, float &value) +{ + Debug("AP_GPS_UAVCAN: param set/get response from %d %s %f\n", node_id, name, value); + return false; +} + +void AP_GPS_UAVCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success) +{ + Debug("AP_GPS_UAVCAN: param save response from %d %s\n", node_id, success ? "success" : "failure"); + + if (cfg_step != STEP_SAVE_AND_REBOOT) { + return; + } + + if (success) { + cfg_step++; + } + // Also send reboot command + // this is ok as we are sending from UAVCAN thread context + Debug("AP_GPS_UAVCAN: sending reboot command %d\n", node_id); + ap_dronecan->send_reboot_request(node_id); +} + +#if AP_DRONECAN_SEND_GPS +bool AP_GPS_UAVCAN::instance_exists(const AP_DroneCAN* ap_dronecan) +{ + for (uint8_t i=0; i. + */ + +// +// DroneCAN GPS driver +// +#pragma once + +#include +#include +#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#include "AP_GPS.h" +#include "GPS_Backend.h" +#include "RTCM3_Parser.h" +#include + +class AP_GPS_UAVCAN : public AP_GPS_Backend { +public: + AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role role); + ~AP_GPS_UAVCAN(); + + bool read() override; + + bool is_healthy(void) const override; + + bool logging_healthy(void) const override; + + bool is_configured(void) const override; + + const char *name() const override { return _name; } + + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static AP_GPS_Backend* probe(AP_GPS &_gps, AP_GPS::GPS_State &_state); + + static void handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg); + + static void handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg); + static void handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg); + static void handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg); +#if GPS_MOVING_BASELINE + static void handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg); + static void handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg); +#endif + static bool backends_healthy(char failure_msg[], uint16_t failure_msg_len); + void inject_data(const uint8_t *data, uint16_t len) override; + + bool get_error_codes(uint32_t &error_codes) const override { error_codes = error_code; return seen_status; }; + +#if GPS_MOVING_BASELINE + bool get_RTCMV3(const uint8_t *&data, uint16_t &len) override; + void clear_RTCMV3() override; +#endif + +#if AP_DRONECAN_SEND_GPS + static bool instance_exists(const AP_DroneCAN* ap_dronecan); +#endif + +private: + + bool param_configured = true; + enum config_step { + STEP_SET_TYPE = 0, + STEP_SET_MB_CAN_TX, + STEP_SAVE_AND_REBOOT, + STEP_FINISHED + }; + uint8_t cfg_step; + bool requires_save_and_reboot; + + // returns true once configuration has finished + bool do_config(void); + + void handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec); + void handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg); + void handle_heading_msg(const ardupilot_gnss_Heading& msg); + void handle_status_msg(const ardupilot_gnss_Status& msg); + void handle_velocity(const float vx, const float vy, const float vz); + +#if GPS_MOVING_BASELINE + void handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id); + void handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id); +#endif + + static bool take_registry(); + static void give_registry(); + static AP_GPS_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); + + bool _new_data; + AP_GPS::GPS_State interim_state; + + HAL_Semaphore sem; + + uint8_t _detected_module; + bool seen_message; + bool seen_fix2; + bool seen_aux; + bool seen_status; + bool seen_relposheading; + + bool healthy; + uint32_t status_flags; + uint32_t error_code; + char _name[15]; + + // Module Detection Registry + static struct DetectedModules { + AP_DroneCAN* ap_dronecan; + uint8_t node_id; + uint8_t instance; + AP_GPS_UAVCAN* driver; + } _detected_modules[GPS_MAX_RECEIVERS]; + + static HAL_Semaphore _sem_registry; + +#if GPS_MOVING_BASELINE + // RTCM3 parser for when in moving baseline base mode + RTCM3_Parser *rtcm3_parser; +#endif + // the role set from GPS_TYPE + AP_GPS::GPS_Role role; + + FUNCTOR_DECLARE(param_int_cb, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); + FUNCTOR_DECLARE(param_float_cb, bool, AP_DroneCAN*, const uint8_t, const char*, float &); + FUNCTOR_DECLARE(param_save_cb, void, AP_DroneCAN*, const uint8_t, bool); + + bool handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, int32_t &value); + bool handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, float &value); + void handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success); +}; +#endif From edc454fee35ba0846822d68fead115e9133efe7c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:53:24 +1000 Subject: [PATCH 218/287] AP_Notify: rename UAVCAN drivers to DroneCAN --- libraries/AP_Notify/DroneCAN_RGB_LED.cpp | 73 ++++++++++++++++++++++++ libraries/AP_Notify/DroneCAN_RGB_LED.h | 18 ++++++ 2 files changed, 91 insertions(+) create mode 100644 libraries/AP_Notify/DroneCAN_RGB_LED.cpp create mode 100644 libraries/AP_Notify/DroneCAN_RGB_LED.h diff --git a/libraries/AP_Notify/DroneCAN_RGB_LED.cpp b/libraries/AP_Notify/DroneCAN_RGB_LED.cpp new file mode 100644 index 00000000000000..f07a230f672c71 --- /dev/null +++ b/libraries/AP_Notify/DroneCAN_RGB_LED.cpp @@ -0,0 +1,73 @@ +/* + * Copyright (C) 2017 Emlid Ltd. All rights reserved. + * + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + */ +#include +#include + +#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#include "UAVCAN_RGB_LED.h" + +#include + +#include + +#define LED_OFF 0 +#define LED_FULL_BRIGHT 255 +#define LED_MEDIUM ((LED_FULL_BRIGHT / 5) * 4) +#define LED_DIM ((LED_FULL_BRIGHT / 5) * 2) + +UAVCAN_RGB_LED::UAVCAN_RGB_LED(uint8_t led_index) + : UAVCAN_RGB_LED(led_index, LED_OFF, + LED_FULL_BRIGHT, LED_MEDIUM, LED_DIM) +{ +} + +UAVCAN_RGB_LED::UAVCAN_RGB_LED(uint8_t led_index, uint8_t led_off, + uint8_t led_full, uint8_t led_medium, + uint8_t led_dim) + : RGBLed(led_off, led_full, led_medium, led_dim) + , _led_index(led_index) +{ +} + +bool UAVCAN_RGB_LED::init() +{ + const uint8_t can_num_drivers = AP::can().get_num_drivers(); + for (uint8_t i = 0; i < can_num_drivers; i++) { + AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); + if (uavcan != nullptr) { + return true; + } + } + // no UAVCAN drivers + return false; +} + + +bool UAVCAN_RGB_LED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) +{ + bool success = false; + uint8_t can_num_drivers = AP::can().get_num_drivers(); + + for (uint8_t i = 0; i < can_num_drivers; i++) { + AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); + if (uavcan != nullptr) { + success = uavcan->led_write(_led_index, red, green, blue) || success; + } + } + return success; +} +#endif diff --git a/libraries/AP_Notify/DroneCAN_RGB_LED.h b/libraries/AP_Notify/DroneCAN_RGB_LED.h new file mode 100644 index 00000000000000..ddb19eee2b3276 --- /dev/null +++ b/libraries/AP_Notify/DroneCAN_RGB_LED.h @@ -0,0 +1,18 @@ +#pragma once + +#include "RGBLed.h" + +class UAVCAN_RGB_LED: public RGBLed { +public: + UAVCAN_RGB_LED(uint8_t led_index, uint8_t led_off, uint8_t led_full, + uint8_t led_medium, uint8_t led_dim); + UAVCAN_RGB_LED(uint8_t led_index); + bool init() override; + +protected: + virtual bool hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) override; + +private: + uint8_t _led_index; +}; + From 01a32430f59bafcf4d4841d9a90e56ac1a11a89e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:53:24 +1000 Subject: [PATCH 219/287] AP_RangeFinder: rename UAVCAN drivers to DroneCAN --- .../AP_RangeFinder_DroneCAN.cpp | 164 ++++++++++++++++++ .../AP_RangeFinder/AP_RangeFinder_DroneCAN.h | 42 +++++ 2 files changed, 206 insertions(+) create mode 100644 libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp create mode 100644 libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp new file mode 100644 index 00000000000000..b9abe57194a38f --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -0,0 +1,164 @@ +#include "AP_RangeFinder_UAVCAN.h" + +#if AP_RANGEFINDER_UAVCAN_ENABLED + +#include +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0) + +//links the rangefinder uavcan message to this backend +void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +{ + if (ap_dronecan == nullptr) { + return; + } + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("measurement_sub"); + } +} + +//Method to find the backend relating to the node id +AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) +{ + if (ap_dronecan == nullptr) { + return nullptr; + } + AP_RangeFinder_UAVCAN* driver = nullptr; + RangeFinder &frontend = *AP::rangefinder(); + //Scan through the Rangefinder params to find UAVCAN RFND with matching address. + for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { + if ((RangeFinder::Type)frontend.params[i].type.get() == RangeFinder::Type::UAVCAN && + frontend.params[i].address == address) { + driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i]; + } + //Double check if the driver was initialised as UAVCAN Type + if (driver != nullptr && (driver->_backend_type == RangeFinder::Type::UAVCAN)) { + if (driver->_ap_dronecan == ap_dronecan && + driver->_node_id == node_id) { + return driver; + } else { + //we found a possible duplicate addressed sensor + //we return nothing in such scenario + return nullptr; + } + } + } + + if (create_new) { + for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { + if ((RangeFinder::Type)frontend.params[i].type.get() == RangeFinder::Type::UAVCAN && + frontend.params[i].address == address) { + WITH_SEMAPHORE(frontend.detect_sem); + if (frontend.drivers[i] != nullptr) { + //we probably initialised this driver as something else, reboot is required for setting + //it up as UAVCAN type + return nullptr; + } + frontend.drivers[i] = new AP_RangeFinder_UAVCAN(frontend.state[i], frontend.params[i]); + driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i]; + if (driver == nullptr) { + break; + } + gcs().send_text(MAV_SEVERITY_INFO, "RangeFinder[%u]: added UAVCAN node %u addr %u", + unsigned(i), unsigned(node_id), unsigned(address)); + //Assign node id and respective uavcan driver, for identification + if (driver->_ap_dronecan == nullptr) { + driver->_ap_dronecan = ap_dronecan; + driver->_node_id = node_id; + break; + } + } + } + } + + return driver; +} + +//Called from frontend to update with the readings received by handler +void AP_RangeFinder_UAVCAN::update() +{ + WITH_SEMAPHORE(_sem); + if ((AP_HAL::millis() - _last_reading_ms) > 500) { + //if data is older than 500ms, report NoData + set_status(RangeFinder::Status::NoData); + } else if (_status == RangeFinder::Status::Good && new_data) { + //copy over states + state.distance_m = _distance_cm * 0.01f; + state.last_reading_ms = _last_reading_ms; + update_status(); + new_data = false; + } else if (_status != RangeFinder::Status::Good) { + //handle additional states received by measurement handler + set_status(_status); + } +} + +//RangeFinder message handler +void AP_RangeFinder_UAVCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg) +{ + //fetch the matching uavcan driver, node id and sensor id backend instance + AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); + if (driver == nullptr) { + return; + } + WITH_SEMAPHORE(driver->_sem); + switch (msg.reading_type) { + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE: + { + //update the states in backend instance + driver->_distance_cm = msg.range*100.0f; + driver->_last_reading_ms = AP_HAL::millis(); + driver->_status = RangeFinder::Status::Good; + driver->new_data = true; + break; + } + //Additional states supported by RFND message + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_CLOSE: + { + driver->_last_reading_ms = AP_HAL::millis(); + driver->_status = RangeFinder::Status::OutOfRangeLow; + break; + } + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR: + { + driver->_last_reading_ms = AP_HAL::millis(); + driver->_status = RangeFinder::Status::OutOfRangeHigh; + break; + } + default: + { + break; + } + } + //copy over the sensor type of Rangefinder + switch (msg.sensor_type) { + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_SONAR: + { + driver->_sensor_type = MAV_DISTANCE_SENSOR_ULTRASOUND; + break; + } + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR: + { + driver->_sensor_type = MAV_DISTANCE_SENSOR_LASER; + break; + } + case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_RADAR: + { + driver->_sensor_type = MAV_DISTANCE_SENSOR_RADAR; + break; + } + default: + { + driver->_sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN; + break; + } + } +} + +#endif // AP_RANGEFINDER_UAVCAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h new file mode 100644 index 00000000000000..47cdca2284b4ed --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h @@ -0,0 +1,42 @@ +#pragma once + +#include "AP_RangeFinder_Backend.h" + +#ifndef AP_RANGEFINDER_UAVCAN_ENABLED +#define AP_RANGEFINDER_UAVCAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_UAVCAN_ENABLED + +#include + +class MeasurementCb; + +class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { +public: + //constructor - registers instance at top RangeFinder driver + using AP_RangeFinder_Backend::AP_RangeFinder_Backend; + + void update() override; + + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + static AP_RangeFinder_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); + static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); + + static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg); + +protected: + virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { + return _sensor_type; + } +private: + uint8_t _instance; + RangeFinder::Status _status; + uint16_t _distance_cm; + uint32_t _last_reading_ms; + AP_DroneCAN* _ap_dronecan; + uint8_t _node_id; + bool new_data; + MAV_DISTANCE_SENSOR _sensor_type; +}; +#endif // AP_RANGEFINDER_UAVCAN_ENABLED From 5188816274cb219cf5d08dad345f5396093b6e0c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:55:39 +1000 Subject: [PATCH 220/287] AP_Airspeed: update header references --- libraries/AP_Airspeed/AP_Airspeed.cpp | 2 +- .../AP_Airspeed/AP_Airspeed_DroneCAN.cpp | 2 +- libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp | 197 ------------------ libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h | 68 ------ 4 files changed, 2 insertions(+), 267 deletions(-) delete mode 100644 libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp delete mode 100644 libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 715a5261ca694d..3b67e92bb22f7f 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -45,7 +45,7 @@ #include "AP_Airspeed_analog.h" #include "AP_Airspeed_ASP5033.h" #include "AP_Airspeed_Backend.h" -#include "AP_Airspeed_UAVCAN.h" +#include "AP_Airspeed_DroneCAN.h" #include "AP_Airspeed_NMEA.h" #include "AP_Airspeed_MSP.h" #include "AP_Airspeed_SITL.h" diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp index 93fd090cfc5961..a015eb5c1a351f 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp @@ -1,4 +1,4 @@ -#include "AP_Airspeed_UAVCAN.h" +#include "AP_Airspeed_DroneCAN.h" #if AP_AIRSPEED_UAVCAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp deleted file mode 100644 index 93fd090cfc5961..00000000000000 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp +++ /dev/null @@ -1,197 +0,0 @@ -#include "AP_Airspeed_UAVCAN.h" - -#if AP_AIRSPEED_UAVCAN_ENABLED - -#include -#include -#include - -extern const AP_HAL::HAL& hal; - -#define LOG_TAG "AirSpeed" - -AP_Airspeed_UAVCAN::DetectedModules AP_Airspeed_UAVCAN::_detected_modules[]; -HAL_Semaphore AP_Airspeed_UAVCAN::_sem_registry; - -// constructor -AP_Airspeed_UAVCAN::AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance) : - AP_Airspeed_Backend(_frontend, _instance) -{} - -void AP_Airspeed_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) -{ - if (ap_dronecan == nullptr) { - return; - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("airspeed_sub"); - } - -#if AP_AIRSPEED_HYGROMETER_ENABLE - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("hygrometer_sub"); - } -#endif -} - -AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid) -{ - WITH_SEMAPHORE(_sem_registry); - - AP_Airspeed_UAVCAN* backend = nullptr; - - for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { - if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { - const auto bus_id = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, - _detected_modules[i].ap_dronecan->get_driver_index(), - _detected_modules[i].node_id, 0); - if (previous_devid != 0 && previous_devid != bus_id) { - // match with previous ID only - continue; - } - backend = new AP_Airspeed_UAVCAN(_frontend, _instance); - if (backend == nullptr) { - AP::can().log_text(AP_CANManager::LOG_INFO, - LOG_TAG, - "Failed register UAVCAN Airspeed Node %d on Bus %d\n", - _detected_modules[i].node_id, - _detected_modules[i].ap_dronecan->get_driver_index()); - } else { - _detected_modules[i].driver = backend; - AP::can().log_text(AP_CANManager::LOG_INFO, - LOG_TAG, - "Registered UAVCAN Airspeed Node %d on Bus %d\n", - _detected_modules[i].node_id, - _detected_modules[i].ap_dronecan->get_driver_index()); - backend->set_bus_id(bus_id); - } - break; - } - } - - return backend; -} - -AP_Airspeed_UAVCAN* AP_Airspeed_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) -{ - if (ap_dronecan == nullptr) { - return nullptr; - } - - for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { - if (_detected_modules[i].driver != nullptr && - _detected_modules[i].ap_dronecan == ap_dronecan && - _detected_modules[i].node_id == node_id ) { - return _detected_modules[i].driver; - } - } - - bool detected = false; - for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { - if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { - // detected - detected = true; - break; - } - } - - if (!detected) { - for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { - if (_detected_modules[i].ap_dronecan == nullptr) { - _detected_modules[i].ap_dronecan = ap_dronecan; - _detected_modules[i].node_id = node_id; - break; - } - } - } - - return nullptr; -} - -void AP_Airspeed_UAVCAN::handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg) -{ - WITH_SEMAPHORE(_sem_registry); - - AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); - - if (driver != nullptr) { - WITH_SEMAPHORE(driver->_sem_airspeed); - driver->_pressure = msg.differential_pressure; - if (!isnan(msg.static_air_temperature) && - msg.static_air_temperature > 0) { - driver->_temperature = KELVIN_TO_C(msg.static_air_temperature); - driver->_have_temperature = true; - } - driver->_last_sample_time_ms = AP_HAL::millis(); - } -} - -#if AP_AIRSPEED_HYGROMETER_ENABLE -void AP_Airspeed_UAVCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg) -{ - WITH_SEMAPHORE(_sem_registry); - - AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); - - if (driver != nullptr) { - WITH_SEMAPHORE(driver->_sem_airspeed); - driver->_hygrometer.temperature = KELVIN_TO_C(msg.temperature); - driver->_hygrometer.humidity = msg.humidity; - driver->_hygrometer.last_sample_ms = AP_HAL::millis(); - } -} -#endif // AP_AIRSPEED_HYGROMETER_ENABLE - -bool AP_Airspeed_UAVCAN::init() -{ - // always returns true - return true; -} - -bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure) -{ - WITH_SEMAPHORE(_sem_airspeed); - - if ((AP_HAL::millis() - _last_sample_time_ms) > 100) { - return false; - } - - pressure = _pressure; - - return true; -} - -bool AP_Airspeed_UAVCAN::get_temperature(float &temperature) -{ - if (!_have_temperature) { - return false; - } - WITH_SEMAPHORE(_sem_airspeed); - - if ((AP_HAL::millis() - _last_sample_time_ms) > 100) { - return false; - } - - temperature = _temperature; - - return true; -} - -#if AP_AIRSPEED_HYGROMETER_ENABLE -/* - return hygrometer data if available - */ -bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) -{ - if (_hygrometer.last_sample_ms == 0) { - return false; - } - WITH_SEMAPHORE(_sem_airspeed); - last_sample_ms = _hygrometer.last_sample_ms; - temperature = _hygrometer.temperature; - humidity = _hygrometer.humidity; - return true; -} -#endif // AP_AIRSPEED_HYGROMETER_ENABLE -#endif // AP_AIRSPEED_UAVCAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h deleted file mode 100644 index 3ccbdd7127ca5a..00000000000000 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h +++ /dev/null @@ -1,68 +0,0 @@ -#pragma once - -#include - -#ifndef AP_AIRSPEED_UAVCAN_ENABLED -#define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS -#endif - -#if AP_AIRSPEED_UAVCAN_ENABLED - -#include "AP_Airspeed_Backend.h" - -#include - -class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { -public: - AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance); - - bool init(void) override; - - // return the current differential_pressure in Pascal - bool get_differential_pressure(float &pressure) override; - - // temperature not available via analog backend - bool get_temperature(float &temperature) override; - -#if AP_AIRSPEED_HYGROMETER_ENABLE - // get hygrometer data - bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) override; -#endif - - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - - static AP_Airspeed_Backend* probe(AP_Airspeed &_fronted, uint8_t _instance, uint32_t previous_devid); - -private: - - static void handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg); - static void handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg); - - static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); - - float _pressure; // Pascal - float _temperature; // Celcius - uint32_t _last_sample_time_ms; - - // hygrometer data - struct { - float temperature; - float humidity; - uint32_t last_sample_ms; - } _hygrometer; - - HAL_Semaphore _sem_airspeed; - - // Module Detection Registry - static struct DetectedModules { - AP_DroneCAN* ap_dronecan; - uint8_t node_id; - AP_Airspeed_UAVCAN *driver; - } _detected_modules[AIRSPEED_MAX_SENSORS]; - - static HAL_Semaphore _sem_registry; - bool _have_temperature; -}; - - -#endif // AP_AIRSPEED_UAVCAN_ENABLED From 55b1e6d5d0df9a0d47004bb18f8371bace9e87cf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:55:39 +1000 Subject: [PATCH 221/287] AP_Baro: update header references --- libraries/AP_Baro/AP_Baro.cpp | 2 +- libraries/AP_Baro/AP_Baro_DroneCAN.cpp | 2 +- libraries/AP_Baro/AP_Baro_UAVCAN.cpp | 177 ------------------------- libraries/AP_Baro/AP_Baro_UAVCAN.h | 52 -------- 4 files changed, 2 insertions(+), 231 deletions(-) delete mode 100644 libraries/AP_Baro/AP_Baro_UAVCAN.cpp delete mode 100644 libraries/AP_Baro/AP_Baro_UAVCAN.h diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 9c1f3665d52801..394306b14820d0 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -43,7 +43,7 @@ #include "AP_Baro_DPS280.h" #include "AP_Baro_BMP388.h" #include "AP_Baro_Dummy.h" -#include "AP_Baro_UAVCAN.h" +#include "AP_Baro_DroneCAN.h" #include "AP_Baro_MSP.h" #include "AP_Baro_ExternalAHRS.h" #include "AP_Baro_ICP101XX.h" diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp index b4c3db984596d0..48bd565e875009 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp @@ -1,4 +1,4 @@ -#include "AP_Baro_UAVCAN.h" +#include "AP_Baro_DroneCAN.h" #if AP_BARO_UAVCAN_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp deleted file mode 100644 index b4c3db984596d0..00000000000000 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp +++ /dev/null @@ -1,177 +0,0 @@ -#include "AP_Baro_UAVCAN.h" - -#if AP_BARO_UAVCAN_ENABLED - -#include -#include -#include "AP_Baro_SITL.h" -#include - -extern const AP_HAL::HAL& hal; - -#define LOG_TAG "Baro" - -AP_Baro_UAVCAN::DetectedModules AP_Baro_UAVCAN::_detected_modules[]; -HAL_Semaphore AP_Baro_UAVCAN::_sem_registry; - -/* - constructor - registers instance at top Baro driver - */ -AP_Baro_UAVCAN::AP_Baro_UAVCAN(AP_Baro &baro) : - AP_Baro_Backend(baro) -{} - -void AP_Baro_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) -{ - if (ap_dronecan == nullptr) { - return; - } - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("pressure_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("temperature_sub"); - } -} - -AP_Baro_Backend* AP_Baro_UAVCAN::probe(AP_Baro &baro) -{ - WITH_SEMAPHORE(_sem_registry); - - AP_Baro_UAVCAN* backend = nullptr; - for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { - if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { - backend = new AP_Baro_UAVCAN(baro); - if (backend == nullptr) { - AP::can().log_text(AP_CANManager::LOG_ERROR, - LOG_TAG, - "Failed register UAVCAN Baro Node %d on Bus %d\n", - _detected_modules[i].node_id, - _detected_modules[i].ap_dronecan->get_driver_index()); - } else { - _detected_modules[i].driver = backend; - backend->_pressure = 0; - backend->_pressure_count = 0; - backend->_ap_dronecan = _detected_modules[i].ap_dronecan; - backend->_node_id = _detected_modules[i].node_id; - - backend->_instance = backend->_frontend.register_sensor(); - backend->set_bus_id(backend->_instance, AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, - _detected_modules[i].ap_dronecan->get_driver_index(), - backend->_node_id, 0)); - - AP::can().log_text(AP_CANManager::LOG_INFO, - LOG_TAG, - "Registered UAVCAN Baro Node %d on Bus %d\n", - _detected_modules[i].node_id, - _detected_modules[i].ap_dronecan->get_driver_index()); - } - break; - } - } - return backend; -} - -AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new) -{ - if (ap_dronecan == nullptr) { - return nullptr; - } - for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { - if (_detected_modules[i].driver != nullptr && - _detected_modules[i].ap_dronecan == ap_dronecan && - _detected_modules[i].node_id == node_id) { - return _detected_modules[i].driver; - } - } - - if (create_new) { - bool already_detected = false; - //Check if there's an empty spot for possible registeration - for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { - if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { - //Already Detected - already_detected = true; - break; - } - } - if (!already_detected) { - for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { - if (_detected_modules[i].ap_dronecan == nullptr) { - _detected_modules[i].ap_dronecan = ap_dronecan; - _detected_modules[i].node_id = node_id; - break; - } - } - } - } - - return nullptr; -} - - -void AP_Baro_UAVCAN::_update_and_wrap_accumulator(float *accum, float val, uint8_t *count, const uint8_t max_count) -{ - *accum += val; - *count += 1; - if (*count == max_count) { - *count = max_count / 2; - *accum = *accum / 2; - } -} - -void AP_Baro_UAVCAN::handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg) -{ - AP_Baro_UAVCAN* driver; - { - WITH_SEMAPHORE(_sem_registry); - driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, true); - if (driver == nullptr) { - return; - } - } - { - WITH_SEMAPHORE(driver->_sem_baro); - _update_and_wrap_accumulator(&driver->_pressure, msg.static_pressure, &driver->_pressure_count, 32); - driver->new_pressure = true; - } -} - -void AP_Baro_UAVCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg) -{ - AP_Baro_UAVCAN* driver; - { - WITH_SEMAPHORE(_sem_registry); - driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, false); - if (driver == nullptr) { - return; - } - } - { - WITH_SEMAPHORE(driver->_sem_baro); - driver->_temperature = KELVIN_TO_C(msg.static_temperature); - } -} - -// Read the sensor -void AP_Baro_UAVCAN::update(void) -{ - float pressure = 0; - - WITH_SEMAPHORE(_sem_baro); - if (new_pressure) { - if (_pressure_count != 0) { - pressure = _pressure / _pressure_count; - _pressure_count = 0; - _pressure = 0; - } - _copy_to_frontend(_instance, pressure, _temperature); - - - _frontend.set_external_temperature(_temperature); - new_pressure = false; - } -} - -#endif // AP_BARO_UAVCAN_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.h b/libraries/AP_Baro/AP_Baro_UAVCAN.h deleted file mode 100644 index c3fb700d252ba6..00000000000000 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once - -#include "AP_Baro_Backend.h" - -#if AP_BARO_UAVCAN_ENABLED - -#include -#if AP_TEST_DRONECAN_DRIVERS -#include -#endif - -class AP_Baro_UAVCAN : public AP_Baro_Backend { -public: - AP_Baro_UAVCAN(AP_Baro &baro); - - void update() override; - - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_Baro_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new); - static AP_Baro_Backend* probe(AP_Baro &baro); - - static void handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg); - static void handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg); -#if AP_TEST_DRONECAN_DRIVERS - void update_healthy_flag(uint8_t instance) override { _frontend.sensors[instance].healthy = !AP::sitl()->baro[instance].disable; }; -#endif -private: - - static void _update_and_wrap_accumulator(float *accum, float val, uint8_t *count, const uint8_t max_count); - - uint8_t _instance; - - bool new_pressure; - float _pressure; - float _temperature; - uint8_t _pressure_count; - HAL_Semaphore _sem_baro; - - AP_DroneCAN* _ap_dronecan; - uint8_t _node_id; - - // Module Detection Registry - static struct DetectedModules { - AP_DroneCAN* ap_dronecan; - uint8_t node_id; - AP_Baro_UAVCAN* driver; - } _detected_modules[BARO_MAX_DRIVERS]; - - static HAL_Semaphore _sem_registry; -}; - -#endif // AP_BARO_UAVCAN_ENABLED From 017543f6e60556126038cd284497c228b3f018be Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:55:39 +1000 Subject: [PATCH 222/287] AP_BattMonitor: update header references --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 20 +- .../AP_BattMonitor_DroneCAN.cpp | 2 +- .../AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp | 411 ------------------ .../AP_BattMonitor/AP_BattMonitor_UAVCAN.h | 115 ----- 4 files changed, 11 insertions(+), 537 deletions(-) delete mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp delete mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index f03ce3f6e0c289..a86d534779d113 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -24,7 +24,7 @@ #include #if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "AP_BattMonitor_UAVCAN.h" +#include "AP_BattMonitor_DroneCAN.h" #endif #include @@ -52,7 +52,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: _ // @Path: AP_BattMonitor_Sum.cpp // @Group: _ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: _ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: _ @@ -71,7 +71,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: 2_ // @Path: AP_BattMonitor_Sum.cpp // @Group: 2_ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: 2_ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: 2_ @@ -91,7 +91,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: 3_ // @Path: AP_BattMonitor_Sum.cpp // @Group: 3_ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: 3_ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: 3_ @@ -111,7 +111,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: 4_ // @Path: AP_BattMonitor_Sum.cpp // @Group: 4_ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: 4_ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: 4_ @@ -131,7 +131,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: 5_ // @Path: AP_BattMonitor_Sum.cpp // @Group: 5_ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: 5_ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: 5_ @@ -151,7 +151,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: 6_ // @Path: AP_BattMonitor_Sum.cpp // @Group: 6_ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: 6_ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: 6_ @@ -171,7 +171,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: 7_ // @Path: AP_BattMonitor_Sum.cpp // @Group: 7_ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: 7_ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: 7_ @@ -191,7 +191,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: 8_ // @Path: AP_BattMonitor_Sum.cpp // @Group: 8_ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: 8_ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: 8_ @@ -211,7 +211,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Group: 9_ // @Path: AP_BattMonitor_Sum.cpp // @Group: 9_ - // @Path: AP_BattMonitor_UAVCAN.cpp + // @Path: AP_BattMonitor_DroneCAN.cpp // @Group: 9_ // @Path: AP_BattMonitor_FuelLevel_Analog.cpp // @Group: 9_ diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index 434292f870dd0a..49aad641ec819e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -4,7 +4,7 @@ #include #include "AP_BattMonitor.h" -#include "AP_BattMonitor_UAVCAN.h" +#include "AP_BattMonitor_DroneCAN.h" #include #include diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp deleted file mode 100644 index 434292f870dd0a..00000000000000 --- a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp +++ /dev/null @@ -1,411 +0,0 @@ -#include "AP_BattMonitor_config.h" - -#if AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED - -#include -#include "AP_BattMonitor.h" -#include "AP_BattMonitor_UAVCAN.h" - -#include -#include -#include -#include -#include -#include - -#define LOG_TAG "BattMon" - -extern const AP_HAL::HAL& hal; - -const AP_Param::GroupInfo AP_BattMonitor_UAVCAN::var_info[] = { - - // @Param: CURR_MULT - // @DisplayName: Scales reported power monitor current - // @Description: Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications - // @Range: .1 10 - // @User: Advanced - AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_UAVCAN, _curr_mult, 1.0), - - // Param indexes must be between 30 and 39 to avoid conflict with other battery monitor param tables loaded by pointer - - AP_GROUPEND -}; - -/// Constructor -AP_BattMonitor_UAVCAN::AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params ¶ms) : - AP_BattMonitor_Backend(mon, mon_state, params), - _type(type) -{ - AP_Param::setup_object_defaults(this,var_info); - _state.var_info = var_info; - - // starts with not healthy - _state.healthy = false; -} - -void AP_BattMonitor_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) -{ - if (ap_dronecan == nullptr) { - return; - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("battinfo_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("battinfo_aux_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("mppt_stream_sub"); - } -} - -AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id) -{ - if (ap_dronecan == nullptr) { - return nullptr; - } - for (uint8_t i = 0; i < AP::battery()._num_instances; i++) { - if (AP::battery().drivers[i] == nullptr || - AP::battery().get_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) { - continue; - } - AP_BattMonitor_UAVCAN* driver = (AP_BattMonitor_UAVCAN*)AP::battery().drivers[i]; - if (driver->_ap_dronecan == ap_dronecan && driver->_node_id == node_id && match_battery_id(i, battery_id)) { - return driver; - } - } - // find empty uavcan driver - for (uint8_t i = 0; i < AP::battery()._num_instances; i++) { - if (AP::battery().drivers[i] != nullptr && - AP::battery().get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && - match_battery_id(i, battery_id)) { - - AP_BattMonitor_UAVCAN* batmon = (AP_BattMonitor_UAVCAN*)AP::battery().drivers[i]; - if(batmon->_ap_dronecan != nullptr || batmon->_node_id != 0) { - continue; - } - batmon->_ap_dronecan = ap_dronecan; - batmon->_node_id = node_id; - batmon->_instance = i; - batmon->init(); - AP::can().log_text(AP_CANManager::LOG_INFO, - LOG_TAG, - "Registered BattMonitor Node %d on Bus %d\n", - node_id, - ap_dronecan->get_driver_index()); - return batmon; - } - } - return nullptr; -} - -void AP_BattMonitor_UAVCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg) -{ - update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct); - - WITH_SEMAPHORE(_sem_battmon); - _remaining_capacity_wh = msg.remaining_capacity_wh; - _full_charge_capacity_wh = msg.full_charge_capacity_wh; -} - -void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc) -{ - WITH_SEMAPHORE(_sem_battmon); - - _interim_state.voltage = voltage; - _interim_state.current_amps = _curr_mult * current; - _soc = soc; - - if (!isnan(temperature_K) && temperature_K > 0) { - // Temperature reported from battery in kelvin and stored internally in Celsius. - _interim_state.temperature = KELVIN_TO_C(temperature_K); - _interim_state.temperature_time = AP_HAL::millis(); - } - - const uint32_t tnow = AP_HAL::micros(); - - if (!_has_battery_info_aux || _mppt.is_detected) { - const uint32_t dt_us = tnow - _interim_state.last_time_micros; - - // update total current drawn since startup - update_consumed(_interim_state, dt_us); - } - - // record time - _interim_state.last_time_micros = tnow; - _interim_state.healthy = true; -} - -void AP_BattMonitor_UAVCAN::handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg) -{ - WITH_SEMAPHORE(_sem_battmon); - uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len); - float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage; - float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage; - - _cycle_count = msg.cycle_count; - for (uint8_t i = 0; i < cell_count; i++) { - _interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000; - } - _interim_state.is_powering_off = msg.is_powering_off; - _interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000; - _interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh; - _interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600); - _interim_state.has_time_remaining = true; - - _has_cell_voltages = true; - _has_time_remaining = true; - _has_consumed_energy = true; - _has_battery_info_aux = true; -} - -void AP_BattMonitor_UAVCAN::handle_mppt_stream(const mppt_Stream &msg) -{ - const bool use_input_value = option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value); - const float voltage = use_input_value ? msg.input_voltage : msg.output_voltage; - const float current = use_input_value ? msg.input_current : msg.output_current; - - // use an invalid soc so we use the library calculated one - const uint8_t soc = 127; - - // convert C to Kelvin - const float temperature_K = isnan(msg.temperature) ? 0 : C_TO_KELVIN(msg.temperature); - - update_interim_state(voltage, current, temperature_K, soc); - - if (!_mppt.is_detected) { - // this is the first time the mppt message has been received - // so set powered up state - _mppt.is_detected = true; - - // Boot/Power-up event - if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Boot)) { - mppt_set_powered_state(true); - } else if (option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Boot)) { - mppt_set_powered_state(false); - } - } - -#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG - if (_mppt.fault_flags != msg.fault_flags) { - mppt_report_faults(_instance, msg.fault_flags); - } -#endif - _mppt.fault_flags = msg.fault_flags; -} - -void AP_BattMonitor_UAVCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg) -{ - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); - if (driver == nullptr) { - return; - } - driver->handle_battery_info(msg); -} - -void AP_BattMonitor_UAVCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) -{ - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); - if (driver == nullptr) { - return; - } - driver->handle_battery_info_aux(msg); -} - -void AP_BattMonitor_UAVCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg) -{ - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id); - if (driver == nullptr) { - return; - } - driver->handle_mppt_stream(msg); -} - -// read - read the voltage and current -void AP_BattMonitor_UAVCAN::read() -{ - uint32_t tnow = AP_HAL::micros(); - - // timeout after 5 seconds - if ((tnow - _interim_state.last_time_micros) > AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS) { - _interim_state.healthy = false; - } - // Copy over relevant states over to main state - WITH_SEMAPHORE(_sem_battmon); - _state.temperature = _interim_state.temperature; - _state.temperature_time = _interim_state.temperature_time; - _state.voltage = _interim_state.voltage; - _state.current_amps = _interim_state.current_amps; - _state.consumed_mah = _interim_state.consumed_mah; - _state.consumed_wh = _interim_state.consumed_wh; - _state.last_time_micros = _interim_state.last_time_micros; - _state.healthy = _interim_state.healthy; - _state.time_remaining = _interim_state.time_remaining; - _state.has_time_remaining = _interim_state.has_time_remaining; - _state.is_powering_off = _interim_state.is_powering_off; - memcpy(_state.cell_voltages.cells, _interim_state.cell_voltages.cells, sizeof(_state.cell_voltages)); - - _has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT; - - // check if MPPT should be powered on/off depending upon arming state - if (_mppt.is_detected) { - mppt_check_powered_state(); - } -} - -/// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument -bool AP_BattMonitor_UAVCAN::capacity_remaining_pct(uint8_t &percentage) const -{ - if ((uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC)) || - _mppt.is_detected || - _soc == 127) { - // a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then - // the user can set the option to use current integration in the backend instead. - // SOC of 127 is used as an invalid SOC flag ie system configuration errors or SOC estimation unavailable - return AP_BattMonitor_Backend::capacity_remaining_pct(percentage); - } - - // the monitor must have current readings in order to estimate consumed_mah and be healthy - if (!has_current() || !_state.healthy) { - return false; - } - - percentage = _soc; - return true; -} - -/// get_cycle_count - return true if cycle count can be provided and fills in cycles argument -bool AP_BattMonitor_UAVCAN::get_cycle_count(uint16_t &cycles) const -{ - if (_has_battery_info_aux) { - cycles = _cycle_count; - return true; - } - return false; -} - -// request MPPT board to power on/off depending upon vehicle arming state as specified by BATT_OPTIONS -void AP_BattMonitor_UAVCAN::mppt_check_powered_state() -{ - if ((_mppt.powered_state_remote_ms != 0) && (AP_HAL::millis() - _mppt.powered_state_remote_ms >= 1000)) { - // there's already a set attempt that didnt' respond. Retry at 1Hz - mppt_set_powered_state(_mppt.powered_state); - } - - // check if vehicle armed state has changed - const bool vehicle_armed = hal.util->get_soft_armed(); - if ((!_mppt.vehicle_armed_last && vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_On_At_Arm)) { - // arm event - mppt_set_powered_state(true); - } else if ((_mppt.vehicle_armed_last && !vehicle_armed) && option_is_set(AP_BattMonitor_Params::Options::MPPT_Power_Off_At_Disarm)) { - // disarm event - mppt_set_powered_state(false); - } - _mppt.vehicle_armed_last = vehicle_armed; -} - -// request MPPT board to power on or off -// power_on should be true to power on the MPPT, false to power off -// force should be true to force sending the state change request to the MPPT -void AP_BattMonitor_UAVCAN::mppt_set_powered_state(bool power_on) -{ - if (_ap_dronecan == nullptr || !_mppt.is_detected) { - return; - } - - _mppt.powered_state = power_on; - - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: powering %s%s", (unsigned)_instance+1, _mppt.powered_state ? "ON" : "OFF", - (_mppt.powered_state_remote_ms == 0) ? "" : " Retry"); - - mppt_OutputEnableRequest request; - request.enable = _mppt.powered_state; - request.disable = !request.enable; - - if (mppt_outputenable_client == nullptr) { - mppt_outputenable_client = new Canard::Client{_ap_dronecan->get_canard_iface(), mppt_outputenable_res_cb}; - if (mppt_outputenable_client == nullptr) { - return; - } - } - mppt_outputenable_client->request(_node_id, request); -} - -// callback from outputEnable to verify it is enabled or disabled -void AP_BattMonitor_UAVCAN::handle_outputEnable_response(const CanardRxTransfer& transfer, const mppt_OutputEnableResponse& response) -{ - if (transfer.source_node_id != _node_id) { - // this response is not from the node we are looking for - return; - } - - if (response.enabled == _mppt.powered_state) { - // we got back what we expected it to be. We set it on, it now says it on (or vice versa). - // Clear the timer so we don't re-request - _mppt.powered_state_remote_ms = 0; - } -} - -#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG -// report changes in MPPT faults -void AP_BattMonitor_UAVCAN::mppt_report_faults(const uint8_t instance, const uint8_t fault_flags) -{ - // handle recovery - if (fault_flags == 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: OK", (unsigned)instance+1); - return; - } - - // send battery faults via text messages - for (uint8_t fault_bit=0x01; fault_bit <= 0x08; fault_bit <<= 1) { - // this loop is to generate multiple messages if there are multiple concurrent faults, but also run once if there are no faults - if ((fault_bit & fault_flags) != 0) { - const MPPT_FaultFlags err = (MPPT_FaultFlags)fault_bit; - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Battery %u: %s", (unsigned)instance+1, mppt_fault_string(err)); - } - } -} - -// returns string description of MPPT fault bit. Only handles single bit faults -const char* AP_BattMonitor_UAVCAN::mppt_fault_string(const MPPT_FaultFlags fault) -{ - switch (fault) { - case MPPT_FaultFlags::OVER_VOLTAGE: - return "over voltage"; - case MPPT_FaultFlags::UNDER_VOLTAGE: - return "under voltage"; - case MPPT_FaultFlags::OVER_CURRENT: - return "over current"; - case MPPT_FaultFlags::OVER_TEMPERATURE: - return "over temp"; - } - return "unknown"; -} -#endif - -// return mavlink fault bitmask (see MAV_BATTERY_FAULT enum) -uint32_t AP_BattMonitor_UAVCAN::get_mavlink_fault_bitmask() const -{ - // return immediately if not mppt or no faults - if (!_mppt.is_detected || (_mppt.fault_flags == 0)) { - return 0; - } - - // convert mppt fault bitmask to mavlink fault bitmask - uint32_t mav_fault_bitmask = 0; - if ((_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_VOLTAGE) || (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::UNDER_VOLTAGE)) { - mav_fault_bitmask |= MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE; - } - if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_CURRENT) { - mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_CURRENT; - } - if (_mppt.fault_flags & (uint8_t)MPPT_FaultFlags::OVER_TEMPERATURE) { - mav_fault_bitmask |= MAV_BATTERY_FAULT_OVER_TEMPERATURE; - } - return mav_fault_bitmask; -} - -#endif // AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h deleted file mode 100644 index 22e4cfd170b6b6..00000000000000 --- a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.h +++ /dev/null @@ -1,115 +0,0 @@ -#pragma once - -#include "AP_BattMonitor.h" -#include "AP_BattMonitor_Backend.h" -#if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include - -#define AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS 5000000 // sensor becomes unhealthy if no successful readings for 5 seconds - -#ifndef AP_BATTMONITOR_UAVCAN_MPPT_DEBUG -#define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 -#endif - -class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend -{ -public: - enum BattMonitor_UAVCAN_Type { - UAVCAN_BATTERY_INFO = 0 - }; - - /// Constructor - AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params ¶ms); - - static const struct AP_Param::GroupInfo var_info[]; - - void init() override {} - - /// Read the battery voltage and current. Should be called at 10hz - void read() override; - - /// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument - bool capacity_remaining_pct(uint8_t &percentage) const override; - - bool has_temperature() const override { return _has_temperature; } - - bool has_current() const override { return true; } - - bool has_consumed_energy() const override { return _has_consumed_energy; } - - bool has_time_remaining() const override { return _has_time_remaining; } - - bool has_cell_voltages() const override { return _has_cell_voltages; } - - bool get_cycle_count(uint16_t &cycles) const override; - - // return mavlink fault bitmask (see MAV_BATTERY_FAULT enum) - uint32_t get_mavlink_fault_bitmask() const override; - - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_BattMonitor_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id); - static void handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg); - static void handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg); - static void handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg); - - void mppt_set_powered_state(bool power_on) override; - -private: - void handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg); - void handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg); - void update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc); - - static bool match_battery_id(uint8_t instance, uint8_t battery_id) { - // when serial number is negative, all batteries are accepted. Else, it must match - return (AP::battery().get_serial_number(instance) < 0) || (AP::battery().get_serial_number(instance) == (int32_t)battery_id); - } - - // MPPT related enums and methods - enum class MPPT_FaultFlags : uint8_t { - OVER_VOLTAGE = (1U<<0), - UNDER_VOLTAGE = (1U<<1), - OVER_CURRENT = (1U<<2), - OVER_TEMPERATURE = (1U<<3), - }; - void handle_mppt_stream(const mppt_Stream &msg); - void mppt_check_powered_state(); - -#if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG - static void mppt_report_faults(const uint8_t instance, const uint8_t fault_flags); - static const char* mppt_fault_string(const MPPT_FaultFlags fault); -#endif - - AP_BattMonitor::BattMonitor_State _interim_state; - BattMonitor_UAVCAN_Type _type; - - HAL_Semaphore _sem_battmon; - - AP_DroneCAN* _ap_dronecan; - uint8_t _soc; - uint8_t _node_id; - uint16_t _cycle_count; - float _remaining_capacity_wh; - float _full_charge_capacity_wh; - bool _has_temperature; - bool _has_cell_voltages; - bool _has_time_remaining; - bool _has_consumed_energy; - bool _has_battery_info_aux; - uint8_t _instance; // instance of this battery monitor - - AP_Float _curr_mult; // scaling multiplier applied to current reports for adjustment - // MPPT variables - struct { - bool is_detected; // true if this UAVCAN device is a Packet Digital MPPT - bool powered_state; // true if the mppt is powered on, false if powered off - bool vehicle_armed_last; // latest vehicle armed state. used to detect changes and power on/off MPPT board - uint8_t fault_flags; // bits holding fault flags - uint32_t powered_state_remote_ms; // timestamp of when request was sent, zeroed on response. Used to retry - } _mppt; - - void handle_outputEnable_response(const CanardRxTransfer&, const mppt_OutputEnableResponse&); - - Canard::ObjCallback mppt_outputenable_res_cb{this, &AP_BattMonitor_UAVCAN::handle_outputEnable_response}; - Canard::Client *mppt_outputenable_client; -}; -#endif From 992409328fd1d72dee6b3d115cd654908dea572b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:55:40 +1000 Subject: [PATCH 223/287] AP_Compass: update header references --- libraries/AP_Compass/AP_Compass.cpp | 2 +- libraries/AP_Compass/AP_Compass_DroneCAN.cpp | 2 +- libraries/AP_Compass/AP_Compass_UAVCAN.cpp | 208 ------------------- libraries/AP_Compass/AP_Compass_UAVCAN.h | 50 ----- 4 files changed, 2 insertions(+), 260 deletions(-) delete mode 100644 libraries/AP_Compass/AP_Compass_UAVCAN.cpp delete mode 100644 libraries/AP_Compass/AP_Compass_UAVCAN.h diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 4456927f83e815..f805ec097d062e 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -25,7 +25,7 @@ #include "AP_Compass_AK09916.h" #include "AP_Compass_QMC5883L.h" #if AP_COMPASS_UAVCAN_ENABLED -#include "AP_Compass_UAVCAN.h" +#include "AP_Compass_DroneCAN.h" #endif #include "AP_Compass_MMC3416.h" #include "AP_Compass_MMC5xx3.h" diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp index 7b0dcf0818e3b0..d034ea87997456 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ -#include "AP_Compass_UAVCAN.h" +#include "AP_Compass_DroneCAN.h" #if AP_COMPASS_UAVCAN_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_UAVCAN.cpp b/libraries/AP_Compass/AP_Compass_UAVCAN.cpp deleted file mode 100644 index 7b0dcf0818e3b0..00000000000000 --- a/libraries/AP_Compass/AP_Compass_UAVCAN.cpp +++ /dev/null @@ -1,208 +0,0 @@ -/* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#include "AP_Compass_UAVCAN.h" - -#if AP_COMPASS_UAVCAN_ENABLED - -#include - -#include -#include -#include -#include - -extern const AP_HAL::HAL& hal; - -#define LOG_TAG "COMPASS" - -AP_Compass_UAVCAN::DetectedModules AP_Compass_UAVCAN::_detected_modules[]; -HAL_Semaphore AP_Compass_UAVCAN::_sem_registry; - -AP_Compass_UAVCAN::AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid) - : _ap_dronecan(ap_dronecan) - , _node_id(node_id) - , _sensor_id(sensor_id) - , _devid(devid) -{ -} - -void AP_Compass_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) -{ - if (ap_dronecan == nullptr) { - return; - } - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("mag_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_magnetic_field_2, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("mag2_sub"); - } -} - -AP_Compass_Backend* AP_Compass_UAVCAN::probe(uint8_t index) -{ - AP_Compass_UAVCAN* driver = nullptr; - if (!_detected_modules[index].driver && _detected_modules[index].ap_dronecan) { - WITH_SEMAPHORE(_sem_registry); - // Register new Compass mode to a backend - driver = new AP_Compass_UAVCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].node_id, _detected_modules[index].sensor_id, _detected_modules[index].devid); - if (driver) { - if (!driver->init()) { - delete driver; - return nullptr; - } - _detected_modules[index].driver = driver; - AP::can().log_text(AP_CANManager::LOG_INFO, - LOG_TAG, - "Found Mag Node %d on Bus %d Sensor ID %d\n", - _detected_modules[index].node_id, - _detected_modules[index].ap_dronecan->get_driver_index(), - _detected_modules[index].sensor_id); -#if AP_TEST_DRONECAN_DRIVERS - // Scroll through the registered compasses, and set the offsets - if (driver->_compass.get_offsets(index).is_zero()) { - driver->_compass.set_offsets(index, AP::sitl()->mag_ofs[index]); - } - - // we want to simulate a calibrated compass by default, so set - // scale to 1 - AP_Param::set_default_by_name("COMPASS_SCALE", 1); - AP_Param::set_default_by_name("COMPASS_SCALE2", 1); - AP_Param::set_default_by_name("COMPASS_SCALE3", 1); - driver->save_dev_id(index); - driver->set_rotation(index, ROTATION_NONE); - - // make first compass external - driver->set_external(index, true); -#endif - } - } - return driver; -} - -bool AP_Compass_UAVCAN::init() -{ - // Adding 1 is necessary to allow backward compatibilty, where this field was set as 1 by default - if (!register_compass(_devid, _instance)) { - return false; - } - - set_dev_id(_instance, _devid); - set_external(_instance, true); - - AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_UAVCAN loaded\n\r"); - return true; -} - -AP_Compass_UAVCAN* AP_Compass_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id) -{ - if (ap_dronecan == nullptr) { - return nullptr; - } - for (uint8_t i=0; iget_driver_index(), - node_id, - sensor_id + 1); // we use sensor_id as devtype - break; - } - } - } - - struct DetectedModules tempslot; - // Sort based on the node_id, larger values first - // we do this, so that we have repeatable compass - // registration, especially in cases of extraneous - // CAN compass is connected. - for (uint8_t i = 1; i < COMPASS_MAX_BACKEND; i++) { - for (uint8_t j = i; j > 0; j--) { - if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) { - tempslot = _detected_modules[j]; - _detected_modules[j] = _detected_modules[j-1]; - _detected_modules[j-1] = tempslot; - } - } - } - return nullptr; -} - -void AP_Compass_UAVCAN::handle_mag_msg(const Vector3f &mag) -{ - Vector3f raw_field = mag * 1000.0; - - accumulate_sample(raw_field, _instance); -} - -void AP_Compass_UAVCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg) -{ - WITH_SEMAPHORE(_sem_registry); - - Vector3f mag_vector; - AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, 0); - if (driver != nullptr) { - mag_vector[0] = msg.magnetic_field_ga[0]; - mag_vector[1] = msg.magnetic_field_ga[1]; - mag_vector[2] = msg.magnetic_field_ga[2]; - driver->handle_mag_msg(mag_vector); - } -} - -void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg) -{ - WITH_SEMAPHORE(_sem_registry); - - Vector3f mag_vector; - uint8_t sensor_id = msg.sensor_id; - AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, sensor_id); - if (driver != nullptr) { - mag_vector[0] = msg.magnetic_field_ga[0]; - mag_vector[1] = msg.magnetic_field_ga[1]; - mag_vector[2] = msg.magnetic_field_ga[2]; - driver->handle_mag_msg(mag_vector); - } -} - -void AP_Compass_UAVCAN::read(void) -{ - drain_accumulated_samples(_instance); -} -#endif // AP_COMPASS_UAVCAN_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_UAVCAN.h b/libraries/AP_Compass/AP_Compass_UAVCAN.h deleted file mode 100644 index 32f66768baa117..00000000000000 --- a/libraries/AP_Compass/AP_Compass_UAVCAN.h +++ /dev/null @@ -1,50 +0,0 @@ -#pragma once - -#include "AP_Compass.h" - -#if AP_COMPASS_UAVCAN_ENABLED - -#include "AP_Compass_Backend.h" - -#include - -class AP_Compass_UAVCAN : public AP_Compass_Backend { -public: - AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid); - - void read(void) override; - - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_Compass_Backend* probe(uint8_t index); - static uint32_t get_detected_devid(uint8_t index) { return _detected_modules[index].devid; } - static void handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg); - static void handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg); - -private: - bool init(); - - // callback for DroneCAN messages - void handle_mag_msg(const Vector3f &mag); - - static AP_Compass_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id); - - uint8_t _instance; - - AP_DroneCAN* _ap_dronecan; - uint8_t _node_id; - uint8_t _sensor_id; - uint32_t _devid; - - // Module Detection Registry - static struct DetectedModules { - AP_DroneCAN* ap_dronecan; - uint8_t node_id; - uint8_t sensor_id; - AP_Compass_UAVCAN *driver; - uint32_t devid; - } _detected_modules[COMPASS_MAX_BACKEND]; - - static HAL_Semaphore _sem_registry; -}; - -#endif // AP_COMPASS_UAVCAN_ENABLED From 60beb288eeae02e016e505012a91ea521b739a4b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:55:40 +1000 Subject: [PATCH 224/287] AP_DroneCAN: update header references --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 20 +- .../examples/UAVCAN_sniffer/README.md | 27 -- .../UAVCAN_sniffer/UAVCAN_sniffer.cpp | 246 ------------------ .../examples/UAVCAN_sniffer/nobuild.txt | 0 .../examples/UAVCAN_sniffer/wscript | 21 -- 5 files changed, 10 insertions(+), 304 deletions(-) delete mode 100644 libraries/AP_DroneCAN/examples/UAVCAN_sniffer/README.md delete mode 100644 libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp delete mode 100644 libraries/AP_DroneCAN/examples/UAVCAN_sniffer/nobuild.txt delete mode 100644 libraries/AP_DroneCAN/examples/UAVCAN_sniffer/wscript diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 7a3651ce142fef..52782823b90086 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -26,19 +26,19 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include -#include +#include #include -#include +#include #include -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/README.md b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/README.md deleted file mode 100644 index 44f3e1c5b4b53c..00000000000000 --- a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/README.md +++ /dev/null @@ -1,27 +0,0 @@ -This is a UAVCAN sniffer designed to run on an ArduPilot board. It can -be used to watch traffic on a UAVCAN bus, showing exactly what would -be received by another node. - -To build and upload for a Pixhawk style board run this: - -``` - ./waf configure --board fmuv3 - ./waf --target examples/UAVCAN_sniffer --upload -``` - -then connect on the USB console. You will see 1Hz packet stats like -this: - -``` -uavcan.equipment.air_data.StaticPressure: 29 -uavcan.equipment.air_data.StaticTemperature: 29 -uavcan.equipment.ahrs.MagneticFieldStrength: 20 -uavcan.protocol.NodeStatus: 6 -uavcan.equipment.gnss.Fix: 10 -uavcan.equipment.gnss.Auxiliary: 1 -uavcan.equipment.actuator.ArrayCommand: 45 -uavcan.equipment.esc.RawCommand: 368 -``` - -note that the code requires you to add new msg types you want to -see. Look for the MSG_CB() and START_CB() macros in the code diff --git a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp deleted file mode 100644 index 942404349b29c6..00000000000000 --- a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp +++ /dev/null @@ -1,246 +0,0 @@ -/* - simple UAVCAN network sniffer as an ArduPilot firmware - */ -#include -#include - -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - -#include - -#include - -#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX -#include -#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL -#include -#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -#include -#include -#endif - -void setup(); -void loop(); - -const AP_HAL::HAL& hal = AP_HAL::get_HAL(); - -#define UAVCAN_NODE_POOL_SIZE 8192 - -static uint8_t node_memory_pool[UAVCAN_NODE_POOL_SIZE]; - -#define debug_uavcan(fmt, args...) do { hal.console->printf(fmt, ##args); } while (0) - -class UAVCAN_sniffer { -public: - UAVCAN_sniffer(); - ~UAVCAN_sniffer(); - - void init(void); - void loop(void); - void print_stats(void); - -private: - uint8_t driver_index = 0; - - AP_CANManager can_mgr; -}; - -static struct { - const char *msg_name; - uint32_t count; -} counters[100]; - -static void count_msg(const char *name) -{ - for (uint16_t i=0; i *node_status_pub; -Canard::Server *node_info_srv; - -static void cb_GetNodeInfoRequest(const CanardRxTransfer &transfer, const uavcan_protocol_GetNodeInfoRequest& msg) -{ - if (node_info_srv == nullptr) { - return; - } - node_info_srv->respond(transfer, node_info); -} - -void UAVCAN_sniffer::init(void) -{ - const_cast (hal).can[driver_index] = new HAL_CANIface(driver_index); - - if (hal.can[driver_index] == nullptr) { - AP_HAL::panic("Couldn't allocate CANManager, something is very wrong"); - } - - hal.can[driver_index]->init(1000000, AP_HAL::CANIface::NormalMode); - - if (!hal.can[driver_index]->is_initialized()) { - debug_uavcan("Can not initialised\n"); - return; - } - _uavcan_iface_mgr = new CanardInterface{driver_index}; - - if (_uavcan_iface_mgr == nullptr) { - return; - } - - if (!_uavcan_iface_mgr->add_interface(hal.can[driver_index])) { - debug_uavcan("Failed to add iface"); - return; - } - - _uavcan_iface_mgr->init(node_memory_pool, sizeof(node_memory_pool), 9); - - node_status_pub = new Canard::Publisher{*_uavcan_iface_mgr}; - if (node_status_pub == nullptr) { - return; - } - - node_info_srv = new Canard::Server{*_uavcan_iface_mgr, *Canard::allocate_static_callback(cb_GetNodeInfoRequest)}; - if (node_info_srv == nullptr) { - return; - } - - node_info.name.len = snprintf((char*)node_info.name.data, sizeof(node_info.name.data), "org.ardupilot:%u", driver_index); - - node_info.software_version.major = AP_DRONECAN_SW_VERS_MAJOR; - node_info.software_version.minor = AP_DRONECAN_SW_VERS_MINOR; - - node_info.hardware_version.major = AP_DRONECAN_HW_VERS_MAJOR; - node_info.hardware_version.minor = AP_DRONECAN_HW_VERS_MINOR; - -#define START_CB(mtype, cbname) Canard::allocate_sub_static_callback(cb_ ## cbname,driver_index) - - START_CB(uavcan_protocol_NodeStatus, NodeStatus); - START_CB(uavcan_equipment_gnss_Fix2, Fix2); - START_CB(uavcan_equipment_gnss_Auxiliary, Auxiliary); - START_CB(uavcan_equipment_ahrs_MagneticFieldStrength, MagneticFieldStrength); - START_CB(uavcan_equipment_ahrs_MagneticFieldStrength2, MagneticFieldStrength2); - START_CB(uavcan_equipment_air_data_StaticPressure, StaticPressure); - START_CB(uavcan_equipment_air_data_StaticTemperature, StaticTemperature); - START_CB(uavcan_equipment_power_BatteryInfo, BatteryInfo); - START_CB(uavcan_equipment_actuator_ArrayCommand, ArrayCommand); - START_CB(uavcan_equipment_esc_RawCommand, RawCommand); - START_CB(uavcan_equipment_indication_LightsCommand, LightsCommand); - START_CB(com_hex_equipment_flow_Measurement, Measurement); - - debug_uavcan("UAVCAN: init done\n\r"); -} - -static void send_node_status() -{ - uavcan_protocol_NodeStatus msg; - msg.uptime_sec = AP_HAL::millis() / 1000; - msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; - msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; - msg.sub_mode = 0; - msg.vendor_specific_status_code = 0; - node_status_pub->broadcast(msg); -} - -uint32_t last_status_send = 0; -void UAVCAN_sniffer::loop(void) -{ - if (AP_HAL::millis() - last_status_send > 1000) { - last_status_send = AP_HAL::millis(); - send_node_status(); - } - _uavcan_iface_mgr->process(1); -} - -void UAVCAN_sniffer::print_stats(void) -{ - hal.console->printf("%lu\n", (unsigned long)AP_HAL::micros()); - for (uint16_t i=0;i<100;i++) { - if (counters[i].msg_name == nullptr) { - break; - } - hal.console->printf("%s: %u\n", counters[i].msg_name, unsigned(counters[i].count)); - counters[i].count = 0; - } - hal.console->printf("\n"); -} - -static UAVCAN_sniffer sniffer; - -UAVCAN_sniffer::UAVCAN_sniffer() -{} - -UAVCAN_sniffer::~UAVCAN_sniffer() -{ -} - -void setup(void) -{ - hal.scheduler->delay(2000); - hal.console->printf("Starting UAVCAN sniffer\n"); - sniffer.init(); -} - -void loop(void) -{ - sniffer.loop(); - static uint32_t last_print_ms; - uint32_t now = AP_HAL::millis(); - if (now - last_print_ms >= 1000) { - last_print_ms = now; - sniffer.print_stats(); - } - - // auto-reboot for --upload - if (hal.console->available() > 50) { - hal.console->printf("rebooting\n"); - hal.console->discard_input(); - hal.scheduler->reboot(false); - } - hal.console->discard_input(); -} - -AP_HAL_MAIN(); - -#else - -#include - -const AP_HAL::HAL& hal = AP_HAL::get_HAL(); - -static void loop() { } -static void setup() -{ - printf("Board not currently supported\n"); -} - -AP_HAL_MAIN(); -#endif diff --git a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/nobuild.txt b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/nobuild.txt deleted file mode 100644 index e69de29bb2d1d6..00000000000000 diff --git a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/wscript b/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/wscript deleted file mode 100644 index 3e81beeee182a4..00000000000000 --- a/libraries/AP_DroneCAN/examples/UAVCAN_sniffer/wscript +++ /dev/null @@ -1,21 +0,0 @@ -#!/usr/bin/env python -# encoding: utf-8 -from waflib.TaskGen import after_method, before_method, feature - -def build(bld): - vehicle = bld.path.name - - bld.ap_stlib( - name=vehicle + '_libs', - ap_vehicle='UNKNOWN', - dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', - ap_libraries=bld.ap_common_vehicle_libraries() + [ - 'AP_OSD', - 'AP_RCMapper', - 'AP_Arming' - ], - ) - bld.ap_program( - program_groups=['tool'], - use=[vehicle + '_libs'], - ) From 5952eb1249cf575dbd339d302536e647bf24c226 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:55:40 +1000 Subject: [PATCH 225/287] AP_GPS: update header references --- libraries/AP_GPS/AP_GPS.cpp | 2 +- libraries/AP_GPS/AP_GPS_DroneCAN.cpp | 2 +- libraries/AP_GPS/AP_GPS_UAVCAN.cpp | 848 --------------------------- libraries/AP_GPS/AP_GPS_UAVCAN.h | 142 ----- 4 files changed, 2 insertions(+), 992 deletions(-) delete mode 100644 libraries/AP_GPS/AP_GPS_UAVCAN.cpp delete mode 100644 libraries/AP_GPS/AP_GPS_UAVCAN.h diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index d54ab189105945..9508ec1ce391fe 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -44,7 +44,7 @@ #if HAL_ENABLE_LIBUAVCAN_DRIVERS #include #include -#include "AP_GPS_UAVCAN.h" +#include "AP_GPS_DroneCAN.h" #endif #include diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp index 8ac0ca6d6571ba..bf4c7c1d6e5edd 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp @@ -19,7 +19,7 @@ #include #if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "AP_GPS_UAVCAN.h" +#include "AP_GPS_DroneCAN.h" #include #include diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp deleted file mode 100644 index 8ac0ca6d6571ba..00000000000000 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp +++ /dev/null @@ -1,848 +0,0 @@ -/* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -// -// UAVCAN GPS driver -// -#include - -#if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "AP_GPS_UAVCAN.h" - -#include -#include -#include - -#include - -#include -#include - -#define GPS_PPS_EMULATION 0 - -extern const AP_HAL::HAL& hal; - -#define GPS_UAVCAN_DEBUGGING 0 - -#if GPS_UAVCAN_DEBUGGING -#if defined(HAL_BUILD_AP_PERIPH) - extern "C" { - void can_printf(const char *fmt, ...); - } - # define Debug(fmt, args ...) do {can_printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args);} while(0) -#else - # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0) -#endif -#else - # define Debug(fmt, args ...) -#endif - -#define LOG_TAG "GPS" - -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL -#define NATIVE_TIME_OFFSET (AP_HAL::micros64() - AP_HAL::native_micros64()) -#else -#define NATIVE_TIME_OFFSET 0 -#endif -AP_GPS_UAVCAN::DetectedModules AP_GPS_UAVCAN::_detected_modules[]; -HAL_Semaphore AP_GPS_UAVCAN::_sem_registry; - -// Member Methods -AP_GPS_UAVCAN::AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role _role) : - AP_GPS_Backend(_gps, _state, nullptr), - interim_state(_state), - role(_role) -{ - param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_int, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); - param_float_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_float, bool, AP_DroneCAN*, const uint8_t, const char*, float &); - param_save_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_save_response, void, AP_DroneCAN*, const uint8_t, bool); -} - -AP_GPS_UAVCAN::~AP_GPS_UAVCAN() -{ - WITH_SEMAPHORE(_sem_registry); - - _detected_modules[_detected_module].driver = nullptr; - -#if GPS_MOVING_BASELINE - if (rtcm3_parser != nullptr) { - delete rtcm3_parser; - } -#endif -} - -void AP_GPS_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) -{ - if (ap_dronecan == nullptr) { - return; - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_fix2_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_aux_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_heading_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_status_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("status_sub"); - } -#if GPS_MOVING_BASELINE - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_moving_baseline_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("moving_baseline_sub"); - } - - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_relposheading_msg_trampoline, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("relposheading_sub"); - } -#endif -} - -AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) -{ - WITH_SEMAPHORE(_sem_registry); - int8_t found_match = -1, last_match = -1; - AP_GPS_UAVCAN* backend = nullptr; - bool bad_override_config = false; - for (int8_t i = GPS_MAX_RECEIVERS - 1; i >= 0; i--) { - if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { - if (_gps._override_node_id[_state.instance] != 0 && - _gps._override_node_id[_state.instance] != _detected_modules[i].node_id) { - continue; // This device doesn't match the correct node - } - last_match = found_match; - for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) { - if (_detected_modules[i].node_id == _gps._override_node_id[j] && - (j != _state.instance)) { - //wrong instance - found_match = -1; - break; - } - found_match = i; - } - - // Handle Duplicate overrides - for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) { - if (_gps._override_node_id[i] != 0 && (i != j) && - _gps._override_node_id[i] == _gps._override_node_id[j]) { - bad_override_config = true; - } - } - if (bad_override_config) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Same Node Id %lu set for multiple GPS", (unsigned long int)_gps._override_node_id[i].get()); - last_match = i; - } - - if (found_match == -1) { - found_match = last_match; - continue; - } - break; - } - } - - if (found_match == -1) { - return NULL; - } - // initialise the backend based on the UAVCAN Moving baseline selection - switch (_gps.get_type(_state.instance)) { - case AP_GPS::GPS_TYPE_UAVCAN: - backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_NORMAL); - break; -#if GPS_MOVING_BASELINE - case AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE: - backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_MB_BASE); - break; - case AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER: - backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_MB_ROVER); - break; -#endif - default: - return NULL; - } - if (backend == nullptr) { - AP::can().log_text(AP_CANManager::LOG_ERROR, - LOG_TAG, - "Failed to register UAVCAN GPS Node %d on Bus %d\n", - _detected_modules[found_match].node_id, - _detected_modules[found_match].ap_dronecan->get_driver_index()); - } else { - _detected_modules[found_match].driver = backend; - backend->_detected_module = found_match; - AP::can().log_text(AP_CANManager::LOG_INFO, - LOG_TAG, - "Registered UAVCAN GPS Node %d on Bus %d as instance %d\n", - _detected_modules[found_match].node_id, - _detected_modules[found_match].ap_dronecan->get_driver_index(), - _state.instance); - snprintf(backend->_name, ARRAY_SIZE(backend->_name), "UAVCAN%u-%u", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); - _detected_modules[found_match].instance = _state.instance; - for (uint8_t i=0; i < GPS_MAX_RECEIVERS; i++) { - if (_detected_modules[found_match].node_id == AP::gps()._node_id[i]) { - if (i == _state.instance) { - // Nothing to do here - break; - } - // else swap - uint8_t tmp = AP::gps()._node_id[_state.instance].get(); - AP::gps()._node_id[_state.instance].set_and_notify(_detected_modules[found_match].node_id); - AP::gps()._node_id[i].set_and_notify(tmp); - } - } -#if GPS_MOVING_BASELINE - if (backend->role == AP_GPS::GPS_ROLE_MB_BASE) { - backend->rtcm3_parser = new RTCM3_Parser; - if (backend->rtcm3_parser == nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UAVCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); - } - } -#endif // GPS_MOVING_BASELINE - } - - return backend; -} - -bool AP_GPS_UAVCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_len) -{ - for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { - bool overriden_node_found = false; - bool bad_override_config = false; - if (AP::gps()._override_node_id[i] == 0) { - //anything goes - continue; - } - for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) { - if (AP::gps()._override_node_id[i] == AP::gps()._override_node_id[j] && (i != j)) { - bad_override_config = true; - break; - } - if (i == _detected_modules[j].instance && _detected_modules[j].driver) { - if (AP::gps()._override_node_id[i] == _detected_modules[j].node_id) { - overriden_node_found = true; - break; - } - } - } - if (bad_override_config) { - snprintf(failure_msg, failure_msg_len, "Same Node Id %lu set for multiple GPS", (unsigned long int)AP::gps()._override_node_id[i].get()); - return false; - } - - if (!overriden_node_found) { - snprintf(failure_msg, failure_msg_len, "Selected GPS Node %lu not set as instance %d", (unsigned long int)AP::gps()._override_node_id[i].get(), i + 1); - return false; - } - } - - return true; -} - -AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) -{ - if (ap_dronecan == nullptr) { - return nullptr; - } - - for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { - if (_detected_modules[i].driver != nullptr && - _detected_modules[i].ap_dronecan == ap_dronecan && - _detected_modules[i].node_id == node_id) { - return _detected_modules[i].driver; - } - } - - bool already_detected = false; - // Check if there's an empty spot for possible registeration - for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { - if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { - // Already Detected - already_detected = true; - break; - } - } - if (!already_detected) { - for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { - if (_detected_modules[i].ap_dronecan == nullptr) { - _detected_modules[i].ap_dronecan = ap_dronecan; - _detected_modules[i].node_id = node_id; - // Just set the Node ID in order of appearance - // This will be used to set select ids - AP::gps()._node_id[i].set_and_notify(node_id); - break; - } - } - } - struct DetectedModules tempslot; - // Sort based on the node_id, larger values first - // we do this, so that we have repeatable GPS - // registration - for (uint8_t i = 1; i < GPS_MAX_RECEIVERS; i++) { - for (uint8_t j = i; j > 0; j--) { - if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) { - tempslot = _detected_modules[j]; - _detected_modules[j] = _detected_modules[j-1]; - _detected_modules[j-1] = tempslot; - // also fix the _detected_module in the driver so that RTCM injection - // can determine if it has the bus to itself - if (_detected_modules[j].driver) { - _detected_modules[j].driver->_detected_module = j; - } - if (_detected_modules[j-1].driver) { - _detected_modules[j-1].driver->_detected_module = j-1; - } - } - } - } - return nullptr; -} - -/* - handle velocity element of message - */ -void AP_GPS_UAVCAN::handle_velocity(const float vx, const float vy, const float vz) -{ - if (!isnanf(vx)) { - const Vector3f vel(vx, vy, vz); - interim_state.velocity = vel; - velocity_to_speed_course(interim_state); - // assume we have vertical velocity if we ever get a non-zero Z velocity - if (!isnan(vel.z) && !is_zero(vel.z)) { - interim_state.have_vertical_velocity = true; - } else { - interim_state.have_vertical_velocity = state.have_vertical_velocity; - } - } else { - interim_state.have_vertical_velocity = false; - } -} - -void AP_GPS_UAVCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec) -{ - bool process = false; - seen_fix2 = true; - - WITH_SEMAPHORE(sem); - - if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX) { - interim_state.status = AP_GPS::GPS_Status::NO_FIX; - } else { - if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_TIME_ONLY) { - interim_state.status = AP_GPS::GPS_Status::NO_FIX; - } else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX) { - interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_2D; - process = true; - } else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX) { - interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D; - process = true; - } - - if (msg.gnss_time_standard == UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_UTC) { - uint64_t epoch_ms = msg.gnss_timestamp.usec; - if (epoch_ms != 0) { - epoch_ms /= 1000; - uint64_t gps_ms = epoch_ms - UNIX_OFFSET_MSEC; - interim_state.time_week = (uint16_t)(gps_ms / AP_MSEC_PER_WEEK); - interim_state.time_week_ms = (uint32_t)(gps_ms - (interim_state.time_week) * AP_MSEC_PER_WEEK); - } - } - - if (interim_state.status == AP_GPS::GPS_Status::GPS_OK_FIX_3D) { - if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS) { - interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS; - } else if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK) { - if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT) { - interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT; - } else if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED) { - interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED; - } - } - } - } - - if (process) { - Location loc = { }; - loc.lat = msg.latitude_deg_1e8 / 10; - loc.lng = msg.longitude_deg_1e8 / 10; - loc.alt = msg.height_msl_mm / 10; - interim_state.have_undulation = true; - interim_state.undulation = (msg.height_msl_mm - msg.height_ellipsoid_mm) * 0.001; - interim_state.location = loc; - - handle_velocity(msg.ned_velocity[0], msg.ned_velocity[1], msg.ned_velocity[2]); - - if (msg.covariance.len == 6) { - if (!isnanf(msg.covariance.data[0])) { - interim_state.horizontal_accuracy = sqrtf(msg.covariance.data[0]); - interim_state.have_horizontal_accuracy = true; - } else { - interim_state.have_horizontal_accuracy = false; - } - if (!isnanf(msg.covariance.data[2])) { - interim_state.vertical_accuracy = sqrtf(msg.covariance.data[2]); - interim_state.have_vertical_accuracy = true; - } else { - interim_state.have_vertical_accuracy = false; - } - if (!isnanf(msg.covariance.data[3]) && - !isnanf(msg.covariance.data[4]) && - !isnanf(msg.covariance.data[5])) { - interim_state.speed_accuracy = sqrtf((msg.covariance.data[3] + msg.covariance.data[4] + msg.covariance.data[5])/3); - interim_state.have_speed_accuracy = true; - } else { - interim_state.have_speed_accuracy = false; - } - } - - interim_state.num_sats = msg.sats_used; - } else { - interim_state.have_vertical_velocity = false; - interim_state.have_vertical_accuracy = false; - interim_state.have_horizontal_accuracy = false; - interim_state.have_speed_accuracy = false; - interim_state.num_sats = 0; - } - - if (!seen_aux) { - // if we haven't seen an Aux message then populate vdop and - // hdop from pdop. Some GPS modules don't provide the Aux message - interim_state.hdop = interim_state.vdop = msg.pdop * 100.0; - } - - if ((msg.timestamp.usec > msg.gnss_timestamp.usec) && (msg.gnss_timestamp.usec > 0)) { - // we have a valid timestamp based on gnss_timestamp timescale, we can use that to correct our gps message time - interim_state.last_corrected_gps_time_us = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, (timestamp_usec + NATIVE_TIME_OFFSET)); - interim_state.last_gps_time_ms = interim_state.last_corrected_gps_time_us/1000U; - interim_state.last_corrected_gps_time_us -= msg.timestamp.usec - msg.gnss_timestamp.usec; - // this is also the time the message was received on the UART on other end. - interim_state.corrected_timestamp_updated = true; - } else { - interim_state.last_gps_time_ms = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, timestamp_usec + NATIVE_TIME_OFFSET)/1000U; - } - -#if GPS_PPS_EMULATION - // Emulates a PPS signal, can be used to check how close are we to real GPS time - static virtual_timer_t timeout_vt; - hal.gpio->pinMode(51, 1); - auto handle_timeout = [](void *arg) - { - (void)arg; - //we are called from ISR context - chSysLockFromISR(); - hal.gpio->toggle(51); - chSysUnlockFromISR(); - }; - - static uint64_t next_toggle, last_toggle; - - next_toggle = (msg.timestamp.usec) + (1000000ULL - ((msg.timestamp.usec) % 1000000ULL)); - - next_toggle += jitter_correction.get_link_offset_usec(); - if (next_toggle != last_toggle) { - chVTSet(&timeout_vt, chTimeUS2I(next_toggle - AP_HAL::micros64()), handle_timeout, nullptr); - last_toggle = next_toggle; - } -#endif - - _new_data = true; - if (!seen_message) { - if (interim_state.status == AP_GPS::GPS_Status::NO_GPS) { - // the first time we see a fix message we change from - // NO_GPS to NO_FIX, indicating to user that a UAVCAN GPS - // has been seen - interim_state.status = AP_GPS::GPS_Status::NO_FIX; - } - seen_message = true; - } -} - -void AP_GPS_UAVCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg) -{ - WITH_SEMAPHORE(sem); - - if (!isnanf(msg.hdop)) { - seen_aux = true; - interim_state.hdop = msg.hdop * 100.0; - } - - if (!isnanf(msg.vdop)) { - seen_aux = true; - interim_state.vdop = msg.vdop * 100.0; - } -} - -void AP_GPS_UAVCAN::handle_heading_msg(const ardupilot_gnss_Heading& msg) -{ -#if GPS_MOVING_BASELINE - if (seen_relposheading && gps.mb_params[interim_state.instance].type.get() != 0) { - // we prefer to use the relposheading to get yaw as it allows - // the user to more easily control the relative antenna positions - return; - } -#endif - - WITH_SEMAPHORE(sem); - - if (interim_state.gps_yaw_configured == false) { - interim_state.gps_yaw_configured = msg.heading_valid; - } - - interim_state.have_gps_yaw = msg.heading_valid; - interim_state.gps_yaw = degrees(msg.heading_rad); - if (interim_state.have_gps_yaw) { - interim_state.gps_yaw_time_ms = AP_HAL::millis(); - } - - interim_state.have_gps_yaw_accuracy = msg.heading_accuracy_valid; - interim_state.gps_yaw_accuracy = degrees(msg.heading_accuracy_rad); -} - -void AP_GPS_UAVCAN::handle_status_msg(const ardupilot_gnss_Status& msg) -{ - WITH_SEMAPHORE(sem); - - seen_status = true; - - healthy = msg.healthy; - status_flags = msg.status; - if (error_code != msg.error_codes) { - AP::logger().Write_MessageF("GPS %d: error changed (0x%08x/0x%08x)", - (unsigned int)(state.instance + 1), - error_code, - msg.error_codes); - error_code = msg.error_codes; - } -} - -#if GPS_MOVING_BASELINE -/* - handle moving baseline data. - */ -void AP_GPS_UAVCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id) -{ - WITH_SEMAPHORE(sem); - if (role != AP_GPS::GPS_ROLE_MB_BASE) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Incorrect Role set for UAVCAN GPS, %d should be Base", node_id); - return; - } - - if (rtcm3_parser == nullptr) { - return; - } - for (int i=0; i < msg.data.len; i++) { - rtcm3_parser->read(msg.data.data[i]); - } -} - -/* - handle relposheading message -*/ -void AP_GPS_UAVCAN::handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id) -{ - WITH_SEMAPHORE(sem); - - interim_state.gps_yaw_configured = true; - seen_relposheading = true; - // push raw heading data to calculate moving baseline heading states - if (calculate_moving_base_yaw(interim_state, - msg.reported_heading_deg, - msg.relative_distance_m, - msg.relative_down_pos_m)) { - if (msg.reported_heading_acc_available) { - interim_state.gps_yaw_accuracy = msg.reported_heading_acc_deg; - } - interim_state.have_gps_yaw_accuracy = msg.reported_heading_acc_available; - } -} - -// support for retrieving RTCMv3 data from a moving baseline base -bool AP_GPS_UAVCAN::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) -{ - WITH_SEMAPHORE(sem); - if (rtcm3_parser != nullptr) { - len = rtcm3_parser->get_len(bytes); - return len > 0; - } - return false; -} - -// clear previous RTCM3 packet -void AP_GPS_UAVCAN::clear_RTCMV3(void) -{ - WITH_SEMAPHORE(sem); - if (rtcm3_parser != nullptr) { - rtcm3_parser->clear_packet(); - } -} - -#endif // GPS_MOVING_BASELINE - -void AP_GPS_UAVCAN::handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg) -{ - WITH_SEMAPHORE(_sem_registry); - - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); - if (driver != nullptr) { - driver->handle_fix2_msg(msg, transfer.timestamp_usec); - } -} - -void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg) -{ - WITH_SEMAPHORE(_sem_registry); - - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); - if (driver != nullptr) { - driver->handle_aux_msg(msg); - } -} - -void AP_GPS_UAVCAN::handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg) -{ - WITH_SEMAPHORE(_sem_registry); - - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); - if (driver != nullptr) { - driver->handle_heading_msg(msg); - } -} - -void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg) -{ - WITH_SEMAPHORE(_sem_registry); - - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); - if (driver != nullptr) { - driver->handle_status_msg(msg); - } -} - -#if GPS_MOVING_BASELINE -// Moving Baseline msg trampoline -void AP_GPS_UAVCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg) -{ - WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); - if (driver != nullptr) { - driver->handle_moving_baseline_msg(msg, transfer.source_node_id); - } -} - -// RelPosHeading msg trampoline -void AP_GPS_UAVCAN::handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg) -{ - WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); - if (driver != nullptr) { - driver->handle_relposheading_msg(msg, transfer.source_node_id); - } -} -#endif - -bool AP_GPS_UAVCAN::do_config() -{ - AP_DroneCAN *ap_dronecan = _detected_modules[_detected_module].ap_dronecan; - if (ap_dronecan == nullptr) { - return false; - } - uint8_t node_id = _detected_modules[_detected_module].node_id; - - switch(cfg_step) { - case STEP_SET_TYPE: - ap_dronecan->get_parameter_on_node(node_id, "GPS_TYPE", ¶m_int_cb); - break; - case STEP_SET_MB_CAN_TX: - if (role != AP_GPS::GPS_Role::GPS_ROLE_NORMAL) { - ap_dronecan->get_parameter_on_node(node_id, "GPS_MB_ONLY_PORT", ¶m_int_cb); - } else { - cfg_step++; - } - break; - case STEP_SAVE_AND_REBOOT: - if (requires_save_and_reboot) { - ap_dronecan->save_parameters_on_node(node_id, ¶m_save_cb); - } else { - cfg_step++; - } - break; - case STEP_FINISHED: - return true; - default: - break; - } - return false; -} - -// Consume new data and mark it received -bool AP_GPS_UAVCAN::read(void) -{ - if (gps._auto_config >= AP_GPS::GPS_AUTO_CONFIG_ENABLE_ALL) { - if (!do_config()) { - return false; - } - } - - WITH_SEMAPHORE(sem); - if (_new_data) { - _new_data = false; - - // the encoding of accuracies in UAVCAN can result in infinite - // values. These cause problems with blending. Use 1000m and 1000m/s instead - interim_state.horizontal_accuracy = MIN(interim_state.horizontal_accuracy, 1000.0); - interim_state.vertical_accuracy = MIN(interim_state.vertical_accuracy, 1000.0); - interim_state.speed_accuracy = MIN(interim_state.speed_accuracy, 1000.0); - - state = interim_state; - if (interim_state.last_corrected_gps_time_us) { - // If we were able to get a valid last_corrected_gps_time_us - // we have had a valid GPS message time, from which we calculate - // the time of week. - _last_itow_ms = interim_state.time_week_ms; - _have_itow = true; - } - return true; - } - if (!seen_message) { - // start with NO_GPS until we get first packet - state.status = AP_GPS::GPS_Status::NO_GPS; - } - - return false; -} - -bool AP_GPS_UAVCAN::is_healthy(void) const -{ - // if we don't have any health reports, assume it's healthy - if (!seen_status) { - return true; - } - return healthy; -} - -bool AP_GPS_UAVCAN::logging_healthy(void) const -{ - // if we don't have status, assume it's valid - if (!seen_status) { - return true; - } - - return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_LOGGING) != 0; -} - -bool AP_GPS_UAVCAN::is_configured(void) const -{ - // if we don't have status assume it's configured - if (!seen_status) { - return true; - } - - return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE) != 0; -} - -/* - handle RTCM data from MAVLink GPS_RTCM_DATA, forwarding it over MAVLink - */ -void AP_GPS_UAVCAN::inject_data(const uint8_t *data, uint16_t len) -{ - // we only handle this if we are the first UAVCAN GPS or we are - // using a different uavcan instance than the first GPS, as we - // send the data as broadcast on all UAVCAN devive ports and we - // don't want to send duplicates - if (_detected_module == 0 || - _detected_modules[_detected_module].ap_dronecan != _detected_modules[0].ap_dronecan) { - _detected_modules[_detected_module].ap_dronecan->send_RTCMStream(data, len); - } -} - -/* - handle param get/set response -*/ -bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, int32_t &value) -{ - Debug("AP_GPS_UAVCAN: param set/get response from %d %s %ld\n", node_id, name, value); - if (strcmp(name, "GPS_TYPE") == 0 && cfg_step == STEP_SET_TYPE) { - if (role == AP_GPS::GPS_ROLE_MB_BASE && value != AP_GPS::GPS_TYPE_UBLOX_RTK_BASE) { - value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_BASE; - requires_save_and_reboot = true; - return true; - } else if (role == AP_GPS::GPS_ROLE_MB_ROVER && value != AP_GPS::GPS_TYPE_UBLOX_RTK_ROVER) { - value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_ROVER; - requires_save_and_reboot = true; - return true; - } else { - cfg_step++; - } - } - - if (strcmp(name, "GPS_MB_ONLY_PORT") == 0 && cfg_step == STEP_SET_MB_CAN_TX) { - if (option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && !value) { - // set up so that another CAN port is used for the Moving Baseline Data - // setting this value will allow another CAN port to be used as dedicated - // line for the Moving Baseline Data - value = 1; - requires_save_and_reboot = true; - return true; - } else if (!option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && value) { - // set up so that all CAN ports are used for the Moving Baseline Data - value = 0; - requires_save_and_reboot = true; - return true; - } else { - cfg_step++; - } - } - return false; -} - -bool AP_GPS_UAVCAN::handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, float &value) -{ - Debug("AP_GPS_UAVCAN: param set/get response from %d %s %f\n", node_id, name, value); - return false; -} - -void AP_GPS_UAVCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success) -{ - Debug("AP_GPS_UAVCAN: param save response from %d %s\n", node_id, success ? "success" : "failure"); - - if (cfg_step != STEP_SAVE_AND_REBOOT) { - return; - } - - if (success) { - cfg_step++; - } - // Also send reboot command - // this is ok as we are sending from UAVCAN thread context - Debug("AP_GPS_UAVCAN: sending reboot command %d\n", node_id); - ap_dronecan->send_reboot_request(node_id); -} - -#if AP_DRONECAN_SEND_GPS -bool AP_GPS_UAVCAN::instance_exists(const AP_DroneCAN* ap_dronecan) -{ - for (uint8_t i=0; i. - */ - -// -// DroneCAN GPS driver -// -#pragma once - -#include -#include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "AP_GPS.h" -#include "GPS_Backend.h" -#include "RTCM3_Parser.h" -#include - -class AP_GPS_UAVCAN : public AP_GPS_Backend { -public: - AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role role); - ~AP_GPS_UAVCAN(); - - bool read() override; - - bool is_healthy(void) const override; - - bool logging_healthy(void) const override; - - bool is_configured(void) const override; - - const char *name() const override { return _name; } - - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_GPS_Backend* probe(AP_GPS &_gps, AP_GPS::GPS_State &_state); - - static void handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg); - - static void handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg); - static void handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg); - static void handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg); -#if GPS_MOVING_BASELINE - static void handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg); - static void handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg); -#endif - static bool backends_healthy(char failure_msg[], uint16_t failure_msg_len); - void inject_data(const uint8_t *data, uint16_t len) override; - - bool get_error_codes(uint32_t &error_codes) const override { error_codes = error_code; return seen_status; }; - -#if GPS_MOVING_BASELINE - bool get_RTCMV3(const uint8_t *&data, uint16_t &len) override; - void clear_RTCMV3() override; -#endif - -#if AP_DRONECAN_SEND_GPS - static bool instance_exists(const AP_DroneCAN* ap_dronecan); -#endif - -private: - - bool param_configured = true; - enum config_step { - STEP_SET_TYPE = 0, - STEP_SET_MB_CAN_TX, - STEP_SAVE_AND_REBOOT, - STEP_FINISHED - }; - uint8_t cfg_step; - bool requires_save_and_reboot; - - // returns true once configuration has finished - bool do_config(void); - - void handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec); - void handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg); - void handle_heading_msg(const ardupilot_gnss_Heading& msg); - void handle_status_msg(const ardupilot_gnss_Status& msg); - void handle_velocity(const float vx, const float vy, const float vz); - -#if GPS_MOVING_BASELINE - void handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id); - void handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id); -#endif - - static bool take_registry(); - static void give_registry(); - static AP_GPS_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); - - bool _new_data; - AP_GPS::GPS_State interim_state; - - HAL_Semaphore sem; - - uint8_t _detected_module; - bool seen_message; - bool seen_fix2; - bool seen_aux; - bool seen_status; - bool seen_relposheading; - - bool healthy; - uint32_t status_flags; - uint32_t error_code; - char _name[15]; - - // Module Detection Registry - static struct DetectedModules { - AP_DroneCAN* ap_dronecan; - uint8_t node_id; - uint8_t instance; - AP_GPS_UAVCAN* driver; - } _detected_modules[GPS_MAX_RECEIVERS]; - - static HAL_Semaphore _sem_registry; - -#if GPS_MOVING_BASELINE - // RTCM3 parser for when in moving baseline base mode - RTCM3_Parser *rtcm3_parser; -#endif - // the role set from GPS_TYPE - AP_GPS::GPS_Role role; - - FUNCTOR_DECLARE(param_int_cb, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); - FUNCTOR_DECLARE(param_float_cb, bool, AP_DroneCAN*, const uint8_t, const char*, float &); - FUNCTOR_DECLARE(param_save_cb, void, AP_DroneCAN*, const uint8_t, bool); - - bool handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, int32_t &value); - bool handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, float &value); - void handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success); -}; -#endif From a6d0738d8035c995523ea295fe3422c3e6564eb8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:55:40 +1000 Subject: [PATCH 226/287] AP_Notify: update header references --- libraries/AP_Notify/UAVCAN_RGB_LED.cpp | 73 -------------------------- libraries/AP_Notify/UAVCAN_RGB_LED.h | 18 ------- 2 files changed, 91 deletions(-) delete mode 100644 libraries/AP_Notify/UAVCAN_RGB_LED.cpp delete mode 100644 libraries/AP_Notify/UAVCAN_RGB_LED.h diff --git a/libraries/AP_Notify/UAVCAN_RGB_LED.cpp b/libraries/AP_Notify/UAVCAN_RGB_LED.cpp deleted file mode 100644 index f07a230f672c71..00000000000000 --- a/libraries/AP_Notify/UAVCAN_RGB_LED.cpp +++ /dev/null @@ -1,73 +0,0 @@ -/* - * Copyright (C) 2017 Emlid Ltd. All rights reserved. - * - * This file is free software: you can redistribute it and/or modify it - * under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program. If not, see . - */ -#include -#include - -#if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "UAVCAN_RGB_LED.h" - -#include - -#include - -#define LED_OFF 0 -#define LED_FULL_BRIGHT 255 -#define LED_MEDIUM ((LED_FULL_BRIGHT / 5) * 4) -#define LED_DIM ((LED_FULL_BRIGHT / 5) * 2) - -UAVCAN_RGB_LED::UAVCAN_RGB_LED(uint8_t led_index) - : UAVCAN_RGB_LED(led_index, LED_OFF, - LED_FULL_BRIGHT, LED_MEDIUM, LED_DIM) -{ -} - -UAVCAN_RGB_LED::UAVCAN_RGB_LED(uint8_t led_index, uint8_t led_off, - uint8_t led_full, uint8_t led_medium, - uint8_t led_dim) - : RGBLed(led_off, led_full, led_medium, led_dim) - , _led_index(led_index) -{ -} - -bool UAVCAN_RGB_LED::init() -{ - const uint8_t can_num_drivers = AP::can().get_num_drivers(); - for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); - if (uavcan != nullptr) { - return true; - } - } - // no UAVCAN drivers - return false; -} - - -bool UAVCAN_RGB_LED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) -{ - bool success = false; - uint8_t can_num_drivers = AP::can().get_num_drivers(); - - for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); - if (uavcan != nullptr) { - success = uavcan->led_write(_led_index, red, green, blue) || success; - } - } - return success; -} -#endif diff --git a/libraries/AP_Notify/UAVCAN_RGB_LED.h b/libraries/AP_Notify/UAVCAN_RGB_LED.h deleted file mode 100644 index ddb19eee2b3276..00000000000000 --- a/libraries/AP_Notify/UAVCAN_RGB_LED.h +++ /dev/null @@ -1,18 +0,0 @@ -#pragma once - -#include "RGBLed.h" - -class UAVCAN_RGB_LED: public RGBLed { -public: - UAVCAN_RGB_LED(uint8_t led_index, uint8_t led_off, uint8_t led_full, - uint8_t led_medium, uint8_t led_dim); - UAVCAN_RGB_LED(uint8_t led_index); - bool init() override; - -protected: - virtual bool hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) override; - -private: - uint8_t _led_index; -}; - From f7a52557f645f3aab4c6d826e863c5013cd3c8f8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:55:40 +1000 Subject: [PATCH 227/287] AP_RangeFinder: update header references --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 2 +- .../AP_RangeFinder_DroneCAN.cpp | 2 +- .../AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp | 164 ------------------ .../AP_RangeFinder/AP_RangeFinder_UAVCAN.h | 42 ----- 4 files changed, 2 insertions(+), 208 deletions(-) delete mode 100644 libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp delete mode 100644 libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 977c5af6306ab6..139e50ea584cb9 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -44,7 +44,7 @@ #include "AP_RangeFinder_HC_SR04.h" #include "AP_RangeFinder_Bebop.h" #include "AP_RangeFinder_BLPing.h" -#include "AP_RangeFinder_UAVCAN.h" +#include "AP_RangeFinder_DroneCAN.h" #include "AP_RangeFinder_Lanbao.h" #include "AP_RangeFinder_LeddarVu8.h" #include "AP_RangeFinder_SITL.h" diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp index b9abe57194a38f..10e6d97291bd03 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -1,4 +1,4 @@ -#include "AP_RangeFinder_UAVCAN.h" +#include "AP_RangeFinder_DroneCAN.h" #if AP_RANGEFINDER_UAVCAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp deleted file mode 100644 index b9abe57194a38f..00000000000000 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp +++ /dev/null @@ -1,164 +0,0 @@ -#include "AP_RangeFinder_UAVCAN.h" - -#if AP_RANGEFINDER_UAVCAN_ENABLED - -#include -#include -#include -#include -#include - -extern const AP_HAL::HAL& hal; - -#define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0) - -//links the rangefinder uavcan message to this backend -void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) -{ - if (ap_dronecan == nullptr) { - return; - } - if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_measurement, ap_dronecan->get_driver_index()) == nullptr) { - AP_BoardConfig::allocation_error("measurement_sub"); - } -} - -//Method to find the backend relating to the node id -AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) -{ - if (ap_dronecan == nullptr) { - return nullptr; - } - AP_RangeFinder_UAVCAN* driver = nullptr; - RangeFinder &frontend = *AP::rangefinder(); - //Scan through the Rangefinder params to find UAVCAN RFND with matching address. - for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { - if ((RangeFinder::Type)frontend.params[i].type.get() == RangeFinder::Type::UAVCAN && - frontend.params[i].address == address) { - driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i]; - } - //Double check if the driver was initialised as UAVCAN Type - if (driver != nullptr && (driver->_backend_type == RangeFinder::Type::UAVCAN)) { - if (driver->_ap_dronecan == ap_dronecan && - driver->_node_id == node_id) { - return driver; - } else { - //we found a possible duplicate addressed sensor - //we return nothing in such scenario - return nullptr; - } - } - } - - if (create_new) { - for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { - if ((RangeFinder::Type)frontend.params[i].type.get() == RangeFinder::Type::UAVCAN && - frontend.params[i].address == address) { - WITH_SEMAPHORE(frontend.detect_sem); - if (frontend.drivers[i] != nullptr) { - //we probably initialised this driver as something else, reboot is required for setting - //it up as UAVCAN type - return nullptr; - } - frontend.drivers[i] = new AP_RangeFinder_UAVCAN(frontend.state[i], frontend.params[i]); - driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i]; - if (driver == nullptr) { - break; - } - gcs().send_text(MAV_SEVERITY_INFO, "RangeFinder[%u]: added UAVCAN node %u addr %u", - unsigned(i), unsigned(node_id), unsigned(address)); - //Assign node id and respective uavcan driver, for identification - if (driver->_ap_dronecan == nullptr) { - driver->_ap_dronecan = ap_dronecan; - driver->_node_id = node_id; - break; - } - } - } - } - - return driver; -} - -//Called from frontend to update with the readings received by handler -void AP_RangeFinder_UAVCAN::update() -{ - WITH_SEMAPHORE(_sem); - if ((AP_HAL::millis() - _last_reading_ms) > 500) { - //if data is older than 500ms, report NoData - set_status(RangeFinder::Status::NoData); - } else if (_status == RangeFinder::Status::Good && new_data) { - //copy over states - state.distance_m = _distance_cm * 0.01f; - state.last_reading_ms = _last_reading_ms; - update_status(); - new_data = false; - } else if (_status != RangeFinder::Status::Good) { - //handle additional states received by measurement handler - set_status(_status); - } -} - -//RangeFinder message handler -void AP_RangeFinder_UAVCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg) -{ - //fetch the matching uavcan driver, node id and sensor id backend instance - AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); - if (driver == nullptr) { - return; - } - WITH_SEMAPHORE(driver->_sem); - switch (msg.reading_type) { - case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE: - { - //update the states in backend instance - driver->_distance_cm = msg.range*100.0f; - driver->_last_reading_ms = AP_HAL::millis(); - driver->_status = RangeFinder::Status::Good; - driver->new_data = true; - break; - } - //Additional states supported by RFND message - case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_CLOSE: - { - driver->_last_reading_ms = AP_HAL::millis(); - driver->_status = RangeFinder::Status::OutOfRangeLow; - break; - } - case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR: - { - driver->_last_reading_ms = AP_HAL::millis(); - driver->_status = RangeFinder::Status::OutOfRangeHigh; - break; - } - default: - { - break; - } - } - //copy over the sensor type of Rangefinder - switch (msg.sensor_type) { - case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_SONAR: - { - driver->_sensor_type = MAV_DISTANCE_SENSOR_ULTRASOUND; - break; - } - case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR: - { - driver->_sensor_type = MAV_DISTANCE_SENSOR_LASER; - break; - } - case UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_RADAR: - { - driver->_sensor_type = MAV_DISTANCE_SENSOR_RADAR; - break; - } - default: - { - driver->_sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN; - break; - } - } -} - -#endif // AP_RANGEFINDER_UAVCAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h deleted file mode 100644 index 47cdca2284b4ed..00000000000000 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h +++ /dev/null @@ -1,42 +0,0 @@ -#pragma once - -#include "AP_RangeFinder_Backend.h" - -#ifndef AP_RANGEFINDER_UAVCAN_ENABLED -#define AP_RANGEFINDER_UAVCAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) -#endif - -#if AP_RANGEFINDER_UAVCAN_ENABLED - -#include - -class MeasurementCb; - -class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { -public: - //constructor - registers instance at top RangeFinder driver - using AP_RangeFinder_Backend::AP_RangeFinder_Backend; - - void update() override; - - static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_RangeFinder_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); - static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); - - static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg); - -protected: - virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { - return _sensor_type; - } -private: - uint8_t _instance; - RangeFinder::Status _status; - uint16_t _distance_cm; - uint32_t _last_reading_ms; - AP_DroneCAN* _ap_dronecan; - uint8_t _node_id; - bool new_data; - MAV_DISTANCE_SENSOR _sensor_type; -}; -#endif // AP_RANGEFINDER_UAVCAN_ENABLED From d2882c79de08b4f1edf9f231b01588b6d4dbcb07 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:58:12 +1000 Subject: [PATCH 228/287] AP_Airspeed: change UAVCAN_ENABLED to DRONECAN_ENABLED --- libraries/AP_Airspeed/AP_Airspeed.cpp | 6 +++--- libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp | 4 ++-- libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h | 8 ++++---- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 3b67e92bb22f7f..4eb7156b65dfd8 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -415,7 +415,7 @@ void AP_Airspeed::allocate() #endif break; case TYPE_UAVCAN: -#if AP_AIRSPEED_UAVCAN_ENABLED +#if AP_AIRSPEED_DRONECAN_ENABLED sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i, uint32_t(param[i].bus_id.get())); #endif break; @@ -442,7 +442,7 @@ void AP_Airspeed::allocate() } } -#if AP_AIRSPEED_UAVCAN_ENABLED +#if AP_AIRSPEED_DRONECAN_ENABLED // we need a 2nd pass for DroneCAN sensors so we can match order by DEVID // the 2nd pass accepts any devid for (uint8_t i=0; i #include @@ -194,4 +194,4 @@ bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &tempera return true; } #endif // AP_AIRSPEED_HYGROMETER_ENABLE -#endif // AP_AIRSPEED_UAVCAN_ENABLED +#endif // AP_AIRSPEED_DRONECAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h index 3ccbdd7127ca5a..dd06f1633f062d 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h @@ -2,11 +2,11 @@ #include -#ifndef AP_AIRSPEED_UAVCAN_ENABLED -#define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS +#ifndef AP_AIRSPEED_DRONECAN_ENABLED +#define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS #endif -#if AP_AIRSPEED_UAVCAN_ENABLED +#if AP_AIRSPEED_DRONECAN_ENABLED #include "AP_Airspeed_Backend.h" @@ -65,4 +65,4 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { }; -#endif // AP_AIRSPEED_UAVCAN_ENABLED +#endif // AP_AIRSPEED_DRONECAN_ENABLED From 8d21ef71d31225933d00fc97b94dea921c697eb8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:58:12 +1000 Subject: [PATCH 229/287] AP_Baro: change UAVCAN_ENABLED to DRONECAN_ENABLED --- libraries/AP_Baro/AP_Baro.cpp | 2 +- libraries/AP_Baro/AP_Baro_DroneCAN.cpp | 4 ++-- libraries/AP_Baro/AP_Baro_DroneCAN.h | 4 ++-- libraries/AP_Baro/AP_Baro_config.h | 4 ++-- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 394306b14820d0..2a16f2675cf841 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -613,7 +613,7 @@ void AP_Baro::init(void) #endif #endif -#if AP_BARO_UAVCAN_ENABLED +#if AP_BARO_DRONECAN_ENABLED // Detect UAVCAN Modules, try as many times as there are driver slots for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { ADD_BACKEND(AP_Baro_UAVCAN::probe(*this)); diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp index 48bd565e875009..a5ce108db6880f 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp @@ -1,6 +1,6 @@ #include "AP_Baro_DroneCAN.h" -#if AP_BARO_UAVCAN_ENABLED +#if AP_BARO_DRONECAN_ENABLED #include #include @@ -174,4 +174,4 @@ void AP_Baro_UAVCAN::update(void) } } -#endif // AP_BARO_UAVCAN_ENABLED +#endif // AP_BARO_DRONECAN_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.h b/libraries/AP_Baro/AP_Baro_DroneCAN.h index c3fb700d252ba6..fdf6c535688049 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.h +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.h @@ -2,7 +2,7 @@ #include "AP_Baro_Backend.h" -#if AP_BARO_UAVCAN_ENABLED +#if AP_BARO_DRONECAN_ENABLED #include #if AP_TEST_DRONECAN_DRIVERS @@ -49,4 +49,4 @@ class AP_Baro_UAVCAN : public AP_Baro_Backend { static HAL_Semaphore _sem_registry; }; -#endif // AP_BARO_UAVCAN_ENABLED +#endif // AP_BARO_DRONECAN_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_config.h b/libraries/AP_Baro/AP_Baro_config.h index 87df55266b0fc7..83d85a8ead8187 100644 --- a/libraries/AP_Baro/AP_Baro_config.h +++ b/libraries/AP_Baro/AP_Baro_config.h @@ -77,6 +77,6 @@ #define AP_BARO_SPL06_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED #endif -#ifndef AP_BARO_UAVCAN_ENABLED -#define AP_BARO_UAVCAN_ENABLED (AP_BARO_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) +#ifndef AP_BARO_DRONECAN_ENABLED +#define AP_BARO_DRONECAN_ENABLED (AP_BARO_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) #endif From dc40e1e7c395a0ac573e893ddd6dda0f376074d7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:58:13 +1000 Subject: [PATCH 230/287] AP_Compass: change UAVCAN_ENABLED to DRONECAN_ENABLED --- libraries/AP_Compass/AP_Compass.cpp | 10 +++++----- libraries/AP_Compass/AP_Compass.h | 2 +- libraries/AP_Compass/AP_Compass_DroneCAN.cpp | 4 ++-- libraries/AP_Compass/AP_Compass_DroneCAN.h | 4 ++-- libraries/AP_Compass/AP_Compass_config.h | 4 ++-- 5 files changed, 12 insertions(+), 12 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index f805ec097d062e..19364bd969ee7d 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -24,7 +24,7 @@ #include "AP_Compass_LIS3MDL.h" #include "AP_Compass_AK09916.h" #include "AP_Compass_QMC5883L.h" -#if AP_COMPASS_UAVCAN_ENABLED +#if AP_COMPASS_DRONECAN_ENABLED #include "AP_Compass_DroneCAN.h" #endif #include "AP_Compass_MMC3416.h" @@ -1449,7 +1449,7 @@ void Compass::_detect_backends(void) #endif -#if AP_COMPASS_UAVCAN_ENABLED +#if AP_COMPASS_DRONECAN_ENABLED if (_driver_enabled(DRIVER_UAVCAN)) { for (uint8_t i=0; i 0 } -#endif // AP_COMPASS_UAVCAN_ENABLED +#endif // AP_COMPASS_DRONECAN_ENABLED if (_backend_count == 0 || _compass_count == 0) { @@ -1608,7 +1608,7 @@ void Compass::_reset_compass_id() void Compass::_detect_runtime(void) { -#if AP_COMPASS_UAVCAN_ENABLED +#if AP_COMPASS_DRONECAN_ENABLED if (!available()) { return; } @@ -1632,7 +1632,7 @@ Compass::_detect_runtime(void) CHECK_UNREG_LIMIT_RETURN; } } -#endif // AP_COMPASS_UAVCAN_ENABLED +#endif // AP_COMPASS_DRONECAN_ENABLED } bool diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index cae86595cab0bc..53d760404d07e9 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -453,7 +453,7 @@ friend class AP_Compass_Backend; #if AP_COMPASS_MMC3416_ENABLED DRIVER_MMC3416 =9, #endif -#if AP_COMPASS_UAVCAN_ENABLED +#if AP_COMPASS_DRONECAN_ENABLED DRIVER_UAVCAN =11, #endif #if AP_COMPASS_QMC5883L_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp index d034ea87997456..8103332e778e77 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp @@ -15,7 +15,7 @@ #include "AP_Compass_DroneCAN.h" -#if AP_COMPASS_UAVCAN_ENABLED +#if AP_COMPASS_DRONECAN_ENABLED #include @@ -205,4 +205,4 @@ void AP_Compass_UAVCAN::read(void) { drain_accumulated_samples(_instance); } -#endif // AP_COMPASS_UAVCAN_ENABLED +#endif // AP_COMPASS_DRONECAN_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.h b/libraries/AP_Compass/AP_Compass_DroneCAN.h index 32f66768baa117..e068fb4f2fc57b 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.h +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.h @@ -2,7 +2,7 @@ #include "AP_Compass.h" -#if AP_COMPASS_UAVCAN_ENABLED +#if AP_COMPASS_DRONECAN_ENABLED #include "AP_Compass_Backend.h" @@ -47,4 +47,4 @@ class AP_Compass_UAVCAN : public AP_Compass_Backend { static HAL_Semaphore _sem_registry; }; -#endif // AP_COMPASS_UAVCAN_ENABLED +#endif // AP_COMPASS_DRONECAN_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_config.h b/libraries/AP_Compass/AP_Compass_config.h index 58d1bf95e46c36..830b84c81ef2ad 100644 --- a/libraries/AP_Compass/AP_Compass_config.h +++ b/libraries/AP_Compass/AP_Compass_config.h @@ -25,8 +25,8 @@ #define AP_COMPASS_SITL_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED) #endif -#ifndef AP_COMPASS_UAVCAN_ENABLED -#define AP_COMPASS_UAVCAN_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) +#ifndef AP_COMPASS_DRONECAN_ENABLED +#define AP_COMPASS_DRONECAN_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) #endif // i2c-based compasses: From 607d4eed02c9955983605df53e3fc19ccd5e5323 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:58:13 +1000 Subject: [PATCH 231/287] AP_DroneCAN: change UAVCAN_ENABLED to DRONECAN_ENABLED --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 52782823b90086..e14fcc09a94278 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -235,20 +235,20 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) // Roundup all subscribers from supported drivers AP_GPS_UAVCAN::subscribe_msgs(this); -#if AP_COMPASS_UAVCAN_ENABLED +#if AP_COMPASS_DRONECAN_ENABLED AP_Compass_UAVCAN::subscribe_msgs(this); #endif -#if AP_BARO_UAVCAN_ENABLED +#if AP_BARO_DRONECAN_ENABLED AP_Baro_UAVCAN::subscribe_msgs(this); #endif AP_BattMonitor_UAVCAN::subscribe_msgs(this); -#if AP_AIRSPEED_UAVCAN_ENABLED +#if AP_AIRSPEED_DRONECAN_ENABLED AP_Airspeed_UAVCAN::subscribe_msgs(this); #endif #if AP_OPTICALFLOW_HEREFLOW_ENABLED AP_OpticalFlow_HereFlow::subscribe_msgs(this); #endif -#if AP_RANGEFINDER_UAVCAN_ENABLED +#if AP_RANGEFINDER_DRONECAN_ENABLED AP_RangeFinder_UAVCAN::subscribe_msgs(this); #endif #if AP_EFI_DRONECAN_ENABLED From 9d5815ce7bd169120d9fad79c32459bc1bb584e4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:58:13 +1000 Subject: [PATCH 232/287] AP_HAL_ChibiOS: change UAVCAN_ENABLED to DRONECAN_ENABLED --- libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc index 3201ff23e4e0d4..4eec0f9917e19e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc @@ -7,4 +7,4 @@ define AP_AIRSPEED_MS5525_ENABLED 1 define AP_AIRSPEED_SDP3X_ENABLED 1 define AP_AIRSPEED_NMEA_ENABLED 1 # additional checks for vehicle type in .cpp -define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS +define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS From 7b1337adafd187a7f4183982bd3a22f8a9bb2b06 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:58:13 +1000 Subject: [PATCH 233/287] AP_RangeFinder: change UAVCAN_ENABLED to DRONECAN_ENABLED --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 2 +- libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp | 4 ++-- libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h | 8 ++++---- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 139e50ea584cb9..ce2be113c2cd15 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -488,7 +488,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) break; case Type::UAVCAN: -#if AP_RANGEFINDER_UAVCAN_ENABLED +#if AP_RANGEFINDER_DRONECAN_ENABLED /* the UAVCAN driver gets created when we first receive a measurement. We take the instance slot now, even if we don't diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp index 10e6d97291bd03..cec61be979e9eb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -1,6 +1,6 @@ #include "AP_RangeFinder_DroneCAN.h" -#if AP_RANGEFINDER_UAVCAN_ENABLED +#if AP_RANGEFINDER_DRONECAN_ENABLED #include #include @@ -161,4 +161,4 @@ void AP_RangeFinder_UAVCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const C } } -#endif // AP_RANGEFINDER_UAVCAN_ENABLED +#endif // AP_RANGEFINDER_DRONECAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h index 47cdca2284b4ed..5b08bdc16f5b12 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h @@ -2,11 +2,11 @@ #include "AP_RangeFinder_Backend.h" -#ifndef AP_RANGEFINDER_UAVCAN_ENABLED -#define AP_RANGEFINDER_UAVCAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#ifndef AP_RANGEFINDER_DRONECAN_ENABLED +#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) #endif -#if AP_RANGEFINDER_UAVCAN_ENABLED +#if AP_RANGEFINDER_DRONECAN_ENABLED #include @@ -39,4 +39,4 @@ class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { bool new_data; MAV_DISTANCE_SENSOR _sensor_type; }; -#endif // AP_RANGEFINDER_UAVCAN_ENABLED +#endif // AP_RANGEFINDER_DRONECAN_ENABLED From b322a7a1fed881a8ac30c560eb7b7b0898f0df1c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 13:58:13 +1000 Subject: [PATCH 234/287] Tools: change UAVCAN_ENABLED to DRONECAN_ENABLED --- Tools/scripts/build_options.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 6d7dd9f022d624..4973c1fa00c0f8 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -145,7 +145,7 @@ def __init__(self, Feature('Compass', 'MMC5XX3', 'AP_COMPASS_MMC5XX3_ENABLED', 'Enable MMC5XX3 compasses', 1, None), Feature('Compass', 'QMC5883L', 'AP_COMPASS_QMC5883L_ENABLED', 'Enable QMC5883L compasses', 1, None), Feature('Compass', 'RM3100', 'AP_COMPASS_RM3100_ENABLED', 'Enable RM3100 compasses', 1, None), - Feature('Compass', 'UAVCAN_COMPASS', 'AP_COMPASS_UAVCAN_ENABLED', 'Enable UAVCAN compasses', 0, None), + Feature('Compass', 'UAVCAN_COMPASS', 'AP_COMPASS_DRONECAN_ENABLED', 'Enable UAVCAN compasses', 0, None), Feature('Gimbal', 'MOUNT', 'HAL_MOUNT_ENABLED', 'Enable Mount', 0, None), Feature('Gimbal', 'ALEXMOS', 'HAL_MOUNT_ALEXMOS_ENABLED', 'Enable Alexmos Gimbal', 0, "MOUNT"), @@ -202,7 +202,7 @@ def __init__(self, # Feature('Rangefinder', 'RANGEFINDER_SIM', 'AP_RANGEFINDER_SIM_ENABLED', "Enable Rangefinder - SIM", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_TRI2C', 'AP_RANGEFINDER_TRI2C_ENABLED', "Enable Rangefinder - TeraRangerI2C", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_TR_SERIAL', 'AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED', "Enable Rangefinder - TeraRanger Serial", 0, "RANGEFINDER"), # NOQA: E501 - Feature('Rangefinder', 'RANGEFINDER_UAVCAN', 'AP_RANGEFINDER_UAVCAN_ENABLED', "Enable Rangefinder - UAVCAN", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_UAVCAN', 'AP_RANGEFINDER_DRONECAN_ENABLED', "Enable Rangefinder - UAVCAN", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_USD1_CAN', 'AP_RANGEFINDER_USD1_CAN_ENABLED', "Enable Rangefinder - USD1 (CAN)", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_USD1_SERIAL', 'AP_RANGEFINDER_USD1_SERIAL_ENABLED', "Enable Rangefinder - USD1 (SERIAL)", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_VL53L0X', 'AP_RANGEFINDER_VL53L0X_ENABLED', "Enable Rangefinder - VL53L0X", 0, "RANGEFINDER"), # NOQA: E501 @@ -231,7 +231,7 @@ def __init__(self, Feature('Sensors', 'MS56XX', 'AP_BARO_MS56XX_ENABLED', 'Enable MS56XX Barometric Sensor', 1, None), Feature('Sensors', 'MSP_BARO', 'AP_BARO_MSP_ENABLED', 'Enable MSP Barometric Sensor', 0, 'MSP'), Feature('Sensors', 'SPL06', 'AP_BARO_SPL06_ENABLED', 'Enable SPL06 Barometric Sensor', 1, None), - Feature('Sensors', 'UAVCAN_BARO', 'AP_BARO_UAVCAN_ENABLED', 'Enable UAVCAN Barometric Sensor', 0, None), + Feature('Sensors', 'UAVCAN_BARO', 'AP_BARO_DRONECAN_ENABLED', 'Enable UAVCAN Barometric Sensor', 0, None), Feature('Sensors', 'ICP101XX', 'AP_BARO_ICP101XX_ENABLED', 'Enable ICP101XX Barometric Sensor', 0, None), Feature('Sensors', 'ICP201XX', 'AP_BARO_ICP201XX_ENABLED', 'Enable ICP201XX Barometric Sensor', 0, None), @@ -278,7 +278,7 @@ def __init__(self, Feature('Airspeed Drivers', 'MSP_AIRSPEED', 'AP_AIRSPEED_MSP_ENABLED', 'ENABLE MSP AIRSPEED', 0, 'AIRSPEED,MSP,OSD'), Feature('Airspeed Drivers', 'NMEA_AIRSPEED', 'AP_AIRSPEED_NMEA_ENABLED', 'ENABLE NMEA AIRSPEED', 0, 'AIRSPEED'), Feature('Airspeed Drivers', 'SDP3X', 'AP_AIRSPEED_SDP3X_ENABLED', 'ENABLE SDP3X AIRSPEED', 0, 'AIRSPEED'), - Feature('Airspeed Drivers', 'UAVCAN_ASPD', 'AP_AIRSPEED_UAVCAN_ENABLED', 'ENABLE UAVCAN AIRSPEED', 0, 'AIRSPEED'), # NOQA: E501 + Feature('Airspeed Drivers', 'UAVCAN_ASPD', 'AP_AIRSPEED_DRONECAN_ENABLED', 'ENABLE UAVCAN AIRSPEED', 0, 'AIRSPEED'), # NOQA: E501 Feature('Actuators', 'Volz', 'AP_VOLZ_ENABLED', 'Enable Volz Protocol', 0, None), Feature('Actuators', 'Volz_DroneCAN', 'AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', 'Enable Volz DroneCAN Feedback', 0, None), From 6912b0db9e6c8cd9b6a773f38b4267617ffd465f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 235/287] AP_Airspeed: rename more variables, types and defines --- libraries/AP_Airspeed/AP_Airspeed.cpp | 4 +-- .../AP_Airspeed/AP_Airspeed_DroneCAN.cpp | 32 +++++++++---------- libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h | 10 +++--- 3 files changed, 23 insertions(+), 23 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 4eb7156b65dfd8..a3d97e30c05385 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -416,7 +416,7 @@ void AP_Airspeed::allocate() break; case TYPE_UAVCAN: #if AP_AIRSPEED_DRONECAN_ENABLED - sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i, uint32_t(param[i].bus_id.get())); + sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, uint32_t(param[i].bus_id.get())); #endif break; case TYPE_NMEA_WATER: @@ -447,7 +447,7 @@ void AP_Airspeed::allocate() // the 2nd pass accepts any devid for (uint8_t i=0; i_sem_airspeed); @@ -128,11 +128,11 @@ void AP_Airspeed_UAVCAN::handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardR } #if AP_AIRSPEED_HYGROMETER_ENABLE -void AP_Airspeed_UAVCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg) +void AP_Airspeed_DroneCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg) { WITH_SEMAPHORE(_sem_registry); - AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_Airspeed_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { WITH_SEMAPHORE(driver->_sem_airspeed); @@ -143,13 +143,13 @@ void AP_Airspeed_UAVCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const Canar } #endif // AP_AIRSPEED_HYGROMETER_ENABLE -bool AP_Airspeed_UAVCAN::init() +bool AP_Airspeed_DroneCAN::init() { // always returns true return true; } -bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure) +bool AP_Airspeed_DroneCAN::get_differential_pressure(float &pressure) { WITH_SEMAPHORE(_sem_airspeed); @@ -162,7 +162,7 @@ bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure) return true; } -bool AP_Airspeed_UAVCAN::get_temperature(float &temperature) +bool AP_Airspeed_DroneCAN::get_temperature(float &temperature) { if (!_have_temperature) { return false; @@ -182,7 +182,7 @@ bool AP_Airspeed_UAVCAN::get_temperature(float &temperature) /* return hygrometer data if available */ -bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) +bool AP_Airspeed_DroneCAN::get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) { if (_hygrometer.last_sample_ms == 0) { return false; diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h index dd06f1633f062d..fb15a8e9229344 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h @@ -3,7 +3,7 @@ #include #ifndef AP_AIRSPEED_DRONECAN_ENABLED -#define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS +#define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS #endif #if AP_AIRSPEED_DRONECAN_ENABLED @@ -12,9 +12,9 @@ #include -class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { +class AP_Airspeed_DroneCAN : public AP_Airspeed_Backend { public: - AP_Airspeed_UAVCAN(AP_Airspeed &_frontend, uint8_t _instance); + AP_Airspeed_DroneCAN(AP_Airspeed &_frontend, uint8_t _instance); bool init(void) override; @@ -38,7 +38,7 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { static void handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg); static void handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg); - static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); + static AP_Airspeed_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); float _pressure; // Pascal float _temperature; // Celcius @@ -57,7 +57,7 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { static struct DetectedModules { AP_DroneCAN* ap_dronecan; uint8_t node_id; - AP_Airspeed_UAVCAN *driver; + AP_Airspeed_DroneCAN *driver; } _detected_modules[AIRSPEED_MAX_SENSORS]; static HAL_Semaphore _sem_registry; From 116e456d359189e05397e27b38f696200bc68d9c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 236/287] AP_Arming: rename more variables, types and defines --- libraries/AP_Arming/AP_Arming.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index a74d50b2badc0d..d53a3b9fd4a276 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -1173,9 +1173,9 @@ bool AP_Arming::can_checks(bool report) #endif break; } - case AP_CANManager::Driver_Type_UAVCAN: + case AP_CANManager::Driver_Type_DroneCAN: { -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_uavcan(i); if (ap_dronecan != nullptr && !ap_dronecan->prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) { check_failed(ARMING_CHECK_SYSTEM, report, "UAVCAN: %s", fail_msg); From 0e1927fc35032b2ca4ac1f3a3deee1e2b91f3963 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 237/287] AP_Baro: rename more variables, types and defines --- libraries/AP_Baro/AP_Baro.cpp | 2 +- libraries/AP_Baro/AP_Baro.h | 2 +- libraries/AP_Baro/AP_Baro_DroneCAN.cpp | 28 +++++++++++++------------- libraries/AP_Baro/AP_Baro_DroneCAN.h | 8 ++++---- libraries/AP_Baro/AP_Baro_config.h | 2 +- 5 files changed, 21 insertions(+), 21 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 2a16f2675cf841..ef39507cc3c6e5 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -616,7 +616,7 @@ void AP_Baro::init(void) #if AP_BARO_DRONECAN_ENABLED // Detect UAVCAN Modules, try as many times as there are driver slots for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { - ADD_BACKEND(AP_Baro_UAVCAN::probe(*this)); + ADD_BACKEND(AP_Baro_DroneCAN::probe(*this)); } #endif diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index d61a43b9b1d478..ba76b23419c949 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -28,7 +28,7 @@ class AP_Baro { friend class AP_Baro_Backend; friend class AP_Baro_SITL; // for access to sensors[] - friend class AP_Baro_UAVCAN; // for access to sensors[] + friend class AP_Baro_DroneCAN; // for access to sensors[] public: AP_Baro(); diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp index a5ce108db6880f..eb0cdecce9e6a5 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp @@ -11,17 +11,17 @@ extern const AP_HAL::HAL& hal; #define LOG_TAG "Baro" -AP_Baro_UAVCAN::DetectedModules AP_Baro_UAVCAN::_detected_modules[]; -HAL_Semaphore AP_Baro_UAVCAN::_sem_registry; +AP_Baro_DroneCAN::DetectedModules AP_Baro_DroneCAN::_detected_modules[]; +HAL_Semaphore AP_Baro_DroneCAN::_sem_registry; /* constructor - registers instance at top Baro driver */ -AP_Baro_UAVCAN::AP_Baro_UAVCAN(AP_Baro &baro) : +AP_Baro_DroneCAN::AP_Baro_DroneCAN(AP_Baro &baro) : AP_Baro_Backend(baro) {} -void AP_Baro_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +void AP_Baro_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { if (ap_dronecan == nullptr) { return; @@ -35,14 +35,14 @@ void AP_Baro_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) } } -AP_Baro_Backend* AP_Baro_UAVCAN::probe(AP_Baro &baro) +AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro) { WITH_SEMAPHORE(_sem_registry); - AP_Baro_UAVCAN* backend = nullptr; + AP_Baro_DroneCAN* backend = nullptr; for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { - backend = new AP_Baro_UAVCAN(baro); + backend = new AP_Baro_DroneCAN(baro); if (backend == nullptr) { AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, @@ -73,7 +73,7 @@ AP_Baro_Backend* AP_Baro_UAVCAN::probe(AP_Baro &baro) return backend; } -AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new) +AP_Baro_DroneCAN* AP_Baro_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new) { if (ap_dronecan == nullptr) { return nullptr; @@ -111,7 +111,7 @@ AP_Baro_UAVCAN* AP_Baro_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uin } -void AP_Baro_UAVCAN::_update_and_wrap_accumulator(float *accum, float val, uint8_t *count, const uint8_t max_count) +void AP_Baro_DroneCAN::_update_and_wrap_accumulator(float *accum, float val, uint8_t *count, const uint8_t max_count) { *accum += val; *count += 1; @@ -121,9 +121,9 @@ void AP_Baro_UAVCAN::_update_and_wrap_accumulator(float *accum, float val, uint8 } } -void AP_Baro_UAVCAN::handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg) +void AP_Baro_DroneCAN::handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg) { - AP_Baro_UAVCAN* driver; + AP_Baro_DroneCAN* driver; { WITH_SEMAPHORE(_sem_registry); driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, true); @@ -138,9 +138,9 @@ void AP_Baro_UAVCAN::handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTra } } -void AP_Baro_UAVCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg) +void AP_Baro_DroneCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticTemperature &msg) { - AP_Baro_UAVCAN* driver; + AP_Baro_DroneCAN* driver; { WITH_SEMAPHORE(_sem_registry); driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, false); @@ -155,7 +155,7 @@ void AP_Baro_UAVCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const CanardRx } // Read the sensor -void AP_Baro_UAVCAN::update(void) +void AP_Baro_DroneCAN::update(void) { float pressure = 0; diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.h b/libraries/AP_Baro/AP_Baro_DroneCAN.h index fdf6c535688049..19278c28e715a0 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.h +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.h @@ -9,14 +9,14 @@ #include #endif -class AP_Baro_UAVCAN : public AP_Baro_Backend { +class AP_Baro_DroneCAN : public AP_Baro_Backend { public: - AP_Baro_UAVCAN(AP_Baro &baro); + AP_Baro_DroneCAN(AP_Baro &baro); void update() override; static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_Baro_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new); + static AP_Baro_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new); static AP_Baro_Backend* probe(AP_Baro &baro); static void handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg); @@ -43,7 +43,7 @@ class AP_Baro_UAVCAN : public AP_Baro_Backend { static struct DetectedModules { AP_DroneCAN* ap_dronecan; uint8_t node_id; - AP_Baro_UAVCAN* driver; + AP_Baro_DroneCAN* driver; } _detected_modules[BARO_MAX_DRIVERS]; static HAL_Semaphore _sem_registry; diff --git a/libraries/AP_Baro/AP_Baro_config.h b/libraries/AP_Baro/AP_Baro_config.h index 83d85a8ead8187..981baf6684816c 100644 --- a/libraries/AP_Baro/AP_Baro_config.h +++ b/libraries/AP_Baro/AP_Baro_config.h @@ -78,5 +78,5 @@ #endif #ifndef AP_BARO_DRONECAN_ENABLED -#define AP_BARO_DRONECAN_ENABLED (AP_BARO_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) +#define AP_BARO_DRONECAN_ENABLED (AP_BARO_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS) #endif From 11a2f5ed9c6e61263c09fd425e9f656e6b070b69 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 238/287] AP_BattMonitor: rename more variables, types and defines --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 4 +- libraries/AP_BattMonitor/AP_BattMonitor.h | 4 +- .../AP_BattMonitor_DroneCAN.cpp | 52 +++++++++---------- .../AP_BattMonitor/AP_BattMonitor_DroneCAN.h | 14 ++--- .../AP_BattMonitor/AP_BattMonitor_config.h | 2 +- 5 files changed, 38 insertions(+), 38 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index a86d534779d113..c2880d24e6eb74 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -23,7 +23,7 @@ #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include "AP_BattMonitor_DroneCAN.h" #endif @@ -312,7 +312,7 @@ AP_BattMonitor::init() break; case Type::UAVCAN_BatteryInfo: #if AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED - drivers[instance] = new AP_BattMonitor_UAVCAN(*this, state[instance], AP_BattMonitor_UAVCAN::UAVCAN_BATTERY_INFO, _params[instance]); + drivers[instance] = new AP_BattMonitor_DroneCAN(*this, state[instance], AP_BattMonitor_DroneCAN::UAVCAN_BATTERY_INFO, _params[instance]); #endif break; case Type::BLHeliESC: diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index 6b04bd9fef62c4..93987634cdc846 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -37,7 +37,7 @@ class AP_BattMonitor_SMBus_Solo; class AP_BattMonitor_SMBus_Generic; class AP_BattMonitor_SMBus_Maxell; class AP_BattMonitor_SMBus_Rotoye; -class AP_BattMonitor_UAVCAN; +class AP_BattMonitor_DroneCAN; class AP_BattMonitor_Generator; class AP_BattMonitor_INA2XX; class AP_BattMonitor_INA239; @@ -56,7 +56,7 @@ class AP_BattMonitor friend class AP_BattMonitor_SMBus_Generic; friend class AP_BattMonitor_SMBus_Maxell; friend class AP_BattMonitor_SMBus_Rotoye; - friend class AP_BattMonitor_UAVCAN; + friend class AP_BattMonitor_DroneCAN; friend class AP_BattMonitor_Sum; friend class AP_BattMonitor_FuelFlow; friend class AP_BattMonitor_FuelLevel_PWM; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index 49aad641ec819e..d44fdda40239c9 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -17,14 +17,14 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_BattMonitor_UAVCAN::var_info[] = { +const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = { // @Param: CURR_MULT // @DisplayName: Scales reported power monitor current // @Description: Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications // @Range: .1 10 // @User: Advanced - AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_UAVCAN, _curr_mult, 1.0), + AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_DroneCAN, _curr_mult, 1.0), // Param indexes must be between 30 and 39 to avoid conflict with other battery monitor param tables loaded by pointer @@ -32,7 +32,7 @@ const AP_Param::GroupInfo AP_BattMonitor_UAVCAN::var_info[] = { }; /// Constructor -AP_BattMonitor_UAVCAN::AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params ¶ms) : +AP_BattMonitor_DroneCAN::AP_BattMonitor_DroneCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_DroneCAN_Type type, AP_BattMonitor_Params ¶ms) : AP_BattMonitor_Backend(mon, mon_state, params), _type(type) { @@ -43,7 +43,7 @@ AP_BattMonitor_UAVCAN::AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor _state.healthy = false; } -void AP_BattMonitor_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +void AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { if (ap_dronecan == nullptr) { return; @@ -62,7 +62,7 @@ void AP_BattMonitor_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) } } -AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id) +AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id) { if (ap_dronecan == nullptr) { return nullptr; @@ -72,7 +72,7 @@ AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap AP::battery().get_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) { continue; } - AP_BattMonitor_UAVCAN* driver = (AP_BattMonitor_UAVCAN*)AP::battery().drivers[i]; + AP_BattMonitor_DroneCAN* driver = (AP_BattMonitor_DroneCAN*)AP::battery().drivers[i]; if (driver->_ap_dronecan == ap_dronecan && driver->_node_id == node_id && match_battery_id(i, battery_id)) { return driver; } @@ -83,7 +83,7 @@ AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap AP::battery().get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && match_battery_id(i, battery_id)) { - AP_BattMonitor_UAVCAN* batmon = (AP_BattMonitor_UAVCAN*)AP::battery().drivers[i]; + AP_BattMonitor_DroneCAN* batmon = (AP_BattMonitor_DroneCAN*)AP::battery().drivers[i]; if(batmon->_ap_dronecan != nullptr || batmon->_node_id != 0) { continue; } @@ -102,7 +102,7 @@ AP_BattMonitor_UAVCAN* AP_BattMonitor_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap return nullptr; } -void AP_BattMonitor_UAVCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg) +void AP_BattMonitor_DroneCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg) { update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct); @@ -111,7 +111,7 @@ void AP_BattMonitor_UAVCAN::handle_battery_info(const uavcan_equipment_power_Bat _full_charge_capacity_wh = msg.full_charge_capacity_wh; } -void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc) +void AP_BattMonitor_DroneCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc) { WITH_SEMAPHORE(_sem_battmon); @@ -139,7 +139,7 @@ void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const floa _interim_state.healthy = true; } -void AP_BattMonitor_UAVCAN::handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg) +void AP_BattMonitor_DroneCAN::handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg) { WITH_SEMAPHORE(_sem_battmon); uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len); @@ -162,7 +162,7 @@ void AP_BattMonitor_UAVCAN::handle_battery_info_aux(const ardupilot_equipment_po _has_battery_info_aux = true; } -void AP_BattMonitor_UAVCAN::handle_mppt_stream(const mppt_Stream &msg) +void AP_BattMonitor_DroneCAN::handle_mppt_stream(const mppt_Stream &msg) { const bool use_input_value = option_is_set(AP_BattMonitor_Params::Options::MPPT_Use_Input_Value); const float voltage = use_input_value ? msg.input_voltage : msg.output_voltage; @@ -197,27 +197,27 @@ void AP_BattMonitor_UAVCAN::handle_mppt_stream(const mppt_Stream &msg) _mppt.fault_flags = msg.fault_flags; } -void AP_BattMonitor_UAVCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg) +void AP_BattMonitor_DroneCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); + AP_BattMonitor_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); if (driver == nullptr) { return; } driver->handle_battery_info(msg); } -void AP_BattMonitor_UAVCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) +void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); + AP_BattMonitor_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); if (driver == nullptr) { return; } driver->handle_battery_info_aux(msg); } -void AP_BattMonitor_UAVCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg) +void AP_BattMonitor_DroneCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg) { - AP_BattMonitor_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id); + AP_BattMonitor_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id); if (driver == nullptr) { return; } @@ -225,7 +225,7 @@ void AP_BattMonitor_UAVCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronec } // read - read the voltage and current -void AP_BattMonitor_UAVCAN::read() +void AP_BattMonitor_DroneCAN::read() { uint32_t tnow = AP_HAL::micros(); @@ -257,7 +257,7 @@ void AP_BattMonitor_UAVCAN::read() } /// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument -bool AP_BattMonitor_UAVCAN::capacity_remaining_pct(uint8_t &percentage) const +bool AP_BattMonitor_DroneCAN::capacity_remaining_pct(uint8_t &percentage) const { if ((uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC)) || _mppt.is_detected || @@ -278,7 +278,7 @@ bool AP_BattMonitor_UAVCAN::capacity_remaining_pct(uint8_t &percentage) const } /// get_cycle_count - return true if cycle count can be provided and fills in cycles argument -bool AP_BattMonitor_UAVCAN::get_cycle_count(uint16_t &cycles) const +bool AP_BattMonitor_DroneCAN::get_cycle_count(uint16_t &cycles) const { if (_has_battery_info_aux) { cycles = _cycle_count; @@ -288,7 +288,7 @@ bool AP_BattMonitor_UAVCAN::get_cycle_count(uint16_t &cycles) const } // request MPPT board to power on/off depending upon vehicle arming state as specified by BATT_OPTIONS -void AP_BattMonitor_UAVCAN::mppt_check_powered_state() +void AP_BattMonitor_DroneCAN::mppt_check_powered_state() { if ((_mppt.powered_state_remote_ms != 0) && (AP_HAL::millis() - _mppt.powered_state_remote_ms >= 1000)) { // there's already a set attempt that didnt' respond. Retry at 1Hz @@ -310,7 +310,7 @@ void AP_BattMonitor_UAVCAN::mppt_check_powered_state() // request MPPT board to power on or off // power_on should be true to power on the MPPT, false to power off // force should be true to force sending the state change request to the MPPT -void AP_BattMonitor_UAVCAN::mppt_set_powered_state(bool power_on) +void AP_BattMonitor_DroneCAN::mppt_set_powered_state(bool power_on) { if (_ap_dronecan == nullptr || !_mppt.is_detected) { return; @@ -335,7 +335,7 @@ void AP_BattMonitor_UAVCAN::mppt_set_powered_state(bool power_on) } // callback from outputEnable to verify it is enabled or disabled -void AP_BattMonitor_UAVCAN::handle_outputEnable_response(const CanardRxTransfer& transfer, const mppt_OutputEnableResponse& response) +void AP_BattMonitor_DroneCAN::handle_outputEnable_response(const CanardRxTransfer& transfer, const mppt_OutputEnableResponse& response) { if (transfer.source_node_id != _node_id) { // this response is not from the node we are looking for @@ -351,7 +351,7 @@ void AP_BattMonitor_UAVCAN::handle_outputEnable_response(const CanardRxTransfer& #if AP_BATTMONITOR_UAVCAN_MPPT_DEBUG // report changes in MPPT faults -void AP_BattMonitor_UAVCAN::mppt_report_faults(const uint8_t instance, const uint8_t fault_flags) +void AP_BattMonitor_DroneCAN::mppt_report_faults(const uint8_t instance, const uint8_t fault_flags) { // handle recovery if (fault_flags == 0) { @@ -370,7 +370,7 @@ void AP_BattMonitor_UAVCAN::mppt_report_faults(const uint8_t instance, const uin } // returns string description of MPPT fault bit. Only handles single bit faults -const char* AP_BattMonitor_UAVCAN::mppt_fault_string(const MPPT_FaultFlags fault) +const char* AP_BattMonitor_DroneCAN::mppt_fault_string(const MPPT_FaultFlags fault) { switch (fault) { case MPPT_FaultFlags::OVER_VOLTAGE: @@ -387,7 +387,7 @@ const char* AP_BattMonitor_UAVCAN::mppt_fault_string(const MPPT_FaultFlags fault #endif // return mavlink fault bitmask (see MAV_BATTERY_FAULT enum) -uint32_t AP_BattMonitor_UAVCAN::get_mavlink_fault_bitmask() const +uint32_t AP_BattMonitor_DroneCAN::get_mavlink_fault_bitmask() const { // return immediately if not mppt or no faults if (!_mppt.is_detected || (_mppt.fault_flags == 0)) { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h index 22e4cfd170b6b6..6d09200072217c 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h @@ -2,7 +2,7 @@ #include "AP_BattMonitor.h" #include "AP_BattMonitor_Backend.h" -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include #define AP_BATTMONITOR_UAVCAN_TIMEOUT_MICROS 5000000 // sensor becomes unhealthy if no successful readings for 5 seconds @@ -11,15 +11,15 @@ #define AP_BATTMONITOR_UAVCAN_MPPT_DEBUG 0 #endif -class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend +class AP_BattMonitor_DroneCAN : public AP_BattMonitor_Backend { public: - enum BattMonitor_UAVCAN_Type { + enum BattMonitor_DroneCAN_Type { UAVCAN_BATTERY_INFO = 0 }; /// Constructor - AP_BattMonitor_UAVCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_UAVCAN_Type type, AP_BattMonitor_Params ¶ms); + AP_BattMonitor_DroneCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_DroneCAN_Type type, AP_BattMonitor_Params ¶ms); static const struct AP_Param::GroupInfo var_info[]; @@ -47,7 +47,7 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend uint32_t get_mavlink_fault_bitmask() const override; static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_BattMonitor_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id); + static AP_BattMonitor_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id); static void handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg); static void handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg); static void handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg); @@ -80,7 +80,7 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend #endif AP_BattMonitor::BattMonitor_State _interim_state; - BattMonitor_UAVCAN_Type _type; + BattMonitor_DroneCAN_Type _type; HAL_Semaphore _sem_battmon; @@ -109,7 +109,7 @@ class AP_BattMonitor_UAVCAN : public AP_BattMonitor_Backend void handle_outputEnable_response(const CanardRxTransfer&, const mppt_OutputEnableResponse&); - Canard::ObjCallback mppt_outputenable_res_cb{this, &AP_BattMonitor_UAVCAN::handle_outputEnable_response}; + Canard::ObjCallback mppt_outputenable_res_cb{this, &AP_BattMonitor_DroneCAN::handle_outputEnable_response}; Canard::Client *mppt_outputenable_client; }; #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_config.h b/libraries/AP_BattMonitor/AP_BattMonitor_config.h index 4856281e0193b4..1a020bee26fe2b 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_config.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_config.h @@ -31,7 +31,7 @@ #endif #ifndef AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED -#define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS +#define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS #endif #ifndef AP_BATTERY_FUELFLOW_ENABLED From 33df480f87cd3d313bb5635f8a75e8a103752321 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 239/287] AP_CANManager: rename more variables, types and defines --- libraries/AP_CANManager/AP_CANDriver.cpp | 4 ++-- libraries/AP_CANManager/AP_CANManager.cpp | 6 +++--- libraries/AP_CANManager/AP_CANManager.h | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_CANManager/AP_CANDriver.cpp b/libraries/AP_CANManager/AP_CANDriver.cpp index 0a2b9a197cbcab..150c66f3c718df 100644 --- a/libraries/AP_CANManager/AP_CANDriver.cpp +++ b/libraries/AP_CANManager/AP_CANDriver.cpp @@ -34,9 +34,9 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = { // @Values: 0:Disabled,1:DroneCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN,10:Scripting,11:Benewake,12:Scripting2 // @User: Advanced // @RebootRequired: True - AP_GROUPINFO("PROTOCOL", 1, AP_CANManager::CANDriver_Params, _driver_type, AP_CANManager::Driver_Type_UAVCAN), + AP_GROUPINFO("PROTOCOL", 1, AP_CANManager::CANDriver_Params, _driver_type, AP_CANManager::Driver_Type_DroneCAN), -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS // @Group: UC_ // @Path: ../AP_DroneCAN/AP_DroneCAN.cpp AP_SUBGROUPPTR(_uavcan, "UC_", 2, AP_CANManager::CANDriver_Params, AP_DroneCAN), diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index a43e8b50fa3fcb..00aeaa4da8cffe 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -203,8 +203,8 @@ void AP_CANManager::init() } // Allocate the set type of Driver -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - if (drv_type[drv_num] == Driver_Type_UAVCAN) { +#if HAL_ENABLE_DRONECAN_DRIVERS + if (drv_type[drv_num] == Driver_Type_DroneCAN) { _drivers[drv_num] = _drv_param[drv_num]._uavcan = new AP_DroneCAN(drv_num); if (_drivers[drv_num] == nullptr) { @@ -288,7 +288,7 @@ void AP_CANManager::init() { WITH_SEMAPHORE(_sem); for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) { - if ((Driver_Type) _drv_param[i]._driver_type.get() == Driver_Type_UAVCAN) { + if ((Driver_Type) _drv_param[i]._driver_type.get() == Driver_Type_DroneCAN) { _drivers[i] = _drv_param[i]._uavcan = new AP_DroneCAN(i); if (_drivers[i] == nullptr) { diff --git a/libraries/AP_CANManager/AP_CANManager.h b/libraries/AP_CANManager/AP_CANManager.h index 5b04384a8a71c8..8c350261415ee7 100644 --- a/libraries/AP_CANManager/AP_CANManager.h +++ b/libraries/AP_CANManager/AP_CANManager.h @@ -58,7 +58,7 @@ class AP_CANManager enum Driver_Type : uint8_t { Driver_Type_None = 0, - Driver_Type_UAVCAN = 1, + Driver_Type_DroneCAN = 1, // 2 was KDECAN -- do not re-use // 3 was ToshibaCAN -- do not re-use Driver_Type_PiccoloCAN = 4, From e469ed9bd75ca2188973ce05e08c7ecbbf652ba9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 240/287] AP_Compass: rename more variables, types and defines --- libraries/AP_Compass/AP_Compass.cpp | 8 ++--- libraries/AP_Compass/AP_Compass_DroneCAN.cpp | 32 ++++++++++---------- libraries/AP_Compass/AP_Compass_DroneCAN.h | 8 ++--- libraries/AP_Compass/AP_Compass_config.h | 2 +- 4 files changed, 25 insertions(+), 25 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 19364bd969ee7d..f2c9e48c5045c7 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -1452,7 +1452,7 @@ void Compass::_detect_backends(void) #if AP_COMPASS_DRONECAN_ENABLED if (_driver_enabled(DRIVER_UAVCAN)) { for (uint8_t i=0; iinit()) { delete driver; @@ -94,7 +94,7 @@ AP_Compass_Backend* AP_Compass_UAVCAN::probe(uint8_t index) return driver; } -bool AP_Compass_UAVCAN::init() +bool AP_Compass_DroneCAN::init() { // Adding 1 is necessary to allow backward compatibilty, where this field was set as 1 by default if (!register_compass(_devid, _instance)) { @@ -104,11 +104,11 @@ bool AP_Compass_UAVCAN::init() set_dev_id(_instance, _devid); set_external(_instance, true); - AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_UAVCAN loaded\n\r"); + AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "AP_Compass_DroneCAN loaded\n\r"); return true; } -AP_Compass_UAVCAN* AP_Compass_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id) +AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id) { if (ap_dronecan == nullptr) { return nullptr; @@ -165,19 +165,19 @@ AP_Compass_UAVCAN* AP_Compass_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_droneca return nullptr; } -void AP_Compass_UAVCAN::handle_mag_msg(const Vector3f &mag) +void AP_Compass_DroneCAN::handle_mag_msg(const Vector3f &mag) { Vector3f raw_field = mag * 1000.0; accumulate_sample(raw_field, _instance); } -void AP_Compass_UAVCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg) +void AP_Compass_DroneCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength& msg) { WITH_SEMAPHORE(_sem_registry); Vector3f mag_vector; - AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, 0); + AP_Compass_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, 0); if (driver != nullptr) { mag_vector[0] = msg.magnetic_field_ga[0]; mag_vector[1] = msg.magnetic_field_ga[1]; @@ -186,13 +186,13 @@ void AP_Compass_UAVCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const Ca } } -void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg) +void AP_Compass_DroneCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_ahrs_MagneticFieldStrength2 &msg) { WITH_SEMAPHORE(_sem_registry); Vector3f mag_vector; uint8_t sensor_id = msg.sensor_id; - AP_Compass_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, sensor_id); + AP_Compass_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, sensor_id); if (driver != nullptr) { mag_vector[0] = msg.magnetic_field_ga[0]; mag_vector[1] = msg.magnetic_field_ga[1]; @@ -201,7 +201,7 @@ void AP_Compass_UAVCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, const } } -void AP_Compass_UAVCAN::read(void) +void AP_Compass_DroneCAN::read(void) { drain_accumulated_samples(_instance); } diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.h b/libraries/AP_Compass/AP_Compass_DroneCAN.h index e068fb4f2fc57b..45edf3853747f4 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.h +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.h @@ -8,9 +8,9 @@ #include -class AP_Compass_UAVCAN : public AP_Compass_Backend { +class AP_Compass_DroneCAN : public AP_Compass_Backend { public: - AP_Compass_UAVCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid); + AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid); void read(void) override; @@ -26,7 +26,7 @@ class AP_Compass_UAVCAN : public AP_Compass_Backend { // callback for DroneCAN messages void handle_mag_msg(const Vector3f &mag); - static AP_Compass_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id); + static AP_Compass_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id); uint8_t _instance; @@ -40,7 +40,7 @@ class AP_Compass_UAVCAN : public AP_Compass_Backend { AP_DroneCAN* ap_dronecan; uint8_t node_id; uint8_t sensor_id; - AP_Compass_UAVCAN *driver; + AP_Compass_DroneCAN *driver; uint32_t devid; } _detected_modules[COMPASS_MAX_BACKEND]; diff --git a/libraries/AP_Compass/AP_Compass_config.h b/libraries/AP_Compass/AP_Compass_config.h index 830b84c81ef2ad..72ae8a411c9c9e 100644 --- a/libraries/AP_Compass/AP_Compass_config.h +++ b/libraries/AP_Compass/AP_Compass_config.h @@ -26,7 +26,7 @@ #endif #ifndef AP_COMPASS_DRONECAN_ENABLED -#define AP_COMPASS_DRONECAN_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) +#define AP_COMPASS_DRONECAN_ENABLED (AP_COMPASS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS) #endif // i2c-based compasses: From 9261f89e39260b2cd54fee5bc4083758162597c2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 241/287] AP_DroneCAN: rename more variables, types and defines --- libraries/AP_DroneCAN/AP_Canard_iface.cpp | 4 ++-- libraries/AP_DroneCAN/AP_Canard_iface.h | 4 ++-- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 18 +++++++++--------- libraries/AP_DroneCAN/AP_DroneCAN.h | 6 +++--- .../AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp | 2 +- libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h | 2 +- .../DroneCAN_sniffer/UAVCAN_sniffer.cpp | 2 +- 7 files changed, 19 insertions(+), 19 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index d3a9c63e478235..8f302e1c0fb4d9 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -1,7 +1,7 @@ #include "AP_Canard_iface.h" #include #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include #include extern const AP_HAL::HAL& hal; @@ -309,4 +309,4 @@ bool CanardInterface::add_interface(AP_HAL::CANIface *can_iface) num_ifaces++; return true; } -#endif // #if HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif // #if HAL_ENABLE_DRONECAN_DRIVERS diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.h b/libraries/AP_DroneCAN/AP_Canard_iface.h index 37638dffd98077..21a9b8eea4881c 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.h +++ b/libraries/AP_DroneCAN/AP_Canard_iface.h @@ -1,6 +1,6 @@ #pragma once #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include class AP_DroneCAN; @@ -65,4 +65,4 @@ class CanardInterface : public Canard::Interface { bool initialized; HAL_Semaphore _sem; }; -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS \ No newline at end of file +#endif // HAL_ENABLE_DRONECAN_DRIVERS \ No newline at end of file diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index e14fcc09a94278..1c04de8c99cf6a 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -18,7 +18,7 @@ #include #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include "AP_DroneCAN.h" #include @@ -172,7 +172,7 @@ AP_DroneCAN::~AP_DroneCAN() AP_DroneCAN *AP_DroneCAN::get_uavcan(uint8_t driver_index) { if (driver_index >= AP::can().get_num_drivers() || - AP::can().get_driver_type(driver_index) != AP_CANManager::Driver_Type_UAVCAN) { + AP::can().get_driver_type(driver_index) != AP_CANManager::Driver_Type_DroneCAN) { return nullptr; } return static_cast(AP::can().get_driver(driver_index)); @@ -234,22 +234,22 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) } // Roundup all subscribers from supported drivers - AP_GPS_UAVCAN::subscribe_msgs(this); + AP_GPS_DroneCAN::subscribe_msgs(this); #if AP_COMPASS_DRONECAN_ENABLED - AP_Compass_UAVCAN::subscribe_msgs(this); + AP_Compass_DroneCAN::subscribe_msgs(this); #endif #if AP_BARO_DRONECAN_ENABLED - AP_Baro_UAVCAN::subscribe_msgs(this); + AP_Baro_DroneCAN::subscribe_msgs(this); #endif - AP_BattMonitor_UAVCAN::subscribe_msgs(this); + AP_BattMonitor_DroneCAN::subscribe_msgs(this); #if AP_AIRSPEED_DRONECAN_ENABLED - AP_Airspeed_UAVCAN::subscribe_msgs(this); + AP_Airspeed_DroneCAN::subscribe_msgs(this); #endif #if AP_OPTICALFLOW_HEREFLOW_ENABLED AP_OpticalFlow_HereFlow::subscribe_msgs(this); #endif #if AP_RANGEFINDER_DRONECAN_ENABLED - AP_RangeFinder_UAVCAN::subscribe_msgs(this); + AP_RangeFinder_DroneCAN::subscribe_msgs(this); #endif #if AP_EFI_DRONECAN_ENABLED AP_EFI_DroneCAN::subscribe_msgs(this); @@ -383,7 +383,7 @@ void AP_DroneCAN::loop(void) #endif #if AP_DRONECAN_SEND_GPS - if (option_is_set(AP_DroneCAN::Options::SEND_GNSS) && !AP_GPS_UAVCAN::instance_exists(this)) { + if (option_is_set(AP_DroneCAN::Options::SEND_GNSS) && !AP_GPS_DroneCAN::instance_exists(this)) { // send if enabled and this interface/driver is not used by the AP_GPS driver gnss_send_fix(); gnss_send_yaw(); diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index f736cf10cce227..50ca8d5db8a3d1 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -18,7 +18,7 @@ #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include "AP_Canard_iface.h" #include @@ -230,7 +230,7 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { } _buzzer; #if AP_DRONECAN_SEND_GPS - // send GNSS Fix and yaw, same thing AP_GPS_UAVCAN would receive + // send GNSS Fix and yaw, same thing AP_GPS_DroneCAN would receive void gnss_send_fix(); void gnss_send_yaw(); @@ -329,4 +329,4 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { void handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req); }; -#endif // #if HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif // #if HAL_ENABLE_DRONECAN_DRIVERS diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index 0a703b7d2029bb..3333931983888f 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -18,7 +18,7 @@ #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include "AP_DroneCAN_DNA_Server.h" #include "AP_DroneCAN.h" diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h index 8ceab48d1a9259..4dba03b5e3dee4 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h @@ -2,7 +2,7 @@ #include #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include #include #include diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp index 942404349b29c6..8a4700963cc0e4 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp @@ -4,7 +4,7 @@ #include #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include From 5e52175399238e4bbd515647247ab1877006e9ae Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 242/287] AP_EFI: rename more variables, types and defines --- libraries/AP_EFI/AP_EFI_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_EFI/AP_EFI_config.h b/libraries/AP_EFI/AP_EFI_config.h index 0552d781a3c9f4..a880817073c45d 100644 --- a/libraries/AP_EFI/AP_EFI_config.h +++ b/libraries/AP_EFI/AP_EFI_config.h @@ -16,7 +16,7 @@ #endif #ifndef AP_EFI_DRONECAN_ENABLED -#define AP_EFI_DRONECAN_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS +#define AP_EFI_DRONECAN_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS #endif #ifndef AP_EFI_NWPWU_ENABLED From 645fd82507b617ef5aa2ba53768a0725b4713c64 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 243/287] AP_GPS: rename more variables, types and defines --- libraries/AP_GPS/AP_GPS.cpp | 14 ++-- libraries/AP_GPS/AP_GPS.h | 4 +- libraries/AP_GPS/AP_GPS_DroneCAN.cpp | 104 +++++++++++++-------------- libraries/AP_GPS/AP_GPS_DroneCAN.h | 12 ++-- 4 files changed, 67 insertions(+), 67 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 9508ec1ce391fe..d78191f8761dec 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -41,7 +41,7 @@ #include "AP_GPS_SITL.h" #endif -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include #include #include "AP_GPS_DroneCAN.h" @@ -384,7 +384,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { AP_GROUPINFO("_PRIMARY", 27, AP_GPS, _primary, 0), #endif -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS // @Param: _CAN_NODEID1 // @DisplayName: GPS Node ID 1 // @Description: GPS Node id for first-discovered GPS. @@ -413,7 +413,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @User: Advanced AP_GROUPINFO("2_CAN_OVRIDE", 31, AP_GPS, _override_node_id[1], 0), #endif // GPS_MAX_RECEIVERS > 1 -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif // HAL_ENABLE_DRONECAN_DRIVERS AP_GROUPEND }; @@ -706,9 +706,9 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) case GPS_TYPE_UAVCAN: case GPS_TYPE_UAVCAN_RTK_BASE: case GPS_TYPE_UAVCAN_RTK_ROVER: -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS dstate->auto_detected_baud = false; // specified, not detected - return AP_GPS_UAVCAN::probe(*this, state[instance]); + return AP_GPS_DroneCAN::probe(*this, state[instance]); #endif return nullptr; // We don't do anything here if UAVCAN is not supported #if HAL_MSP_GPS_ENABLED @@ -2119,11 +2119,11 @@ bool AP_GPS::prepare_for_arming(void) { bool AP_GPS::backends_healthy(char failure_msg[], uint16_t failure_msg_len) { for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS if (_type[i] == GPS_TYPE_UAVCAN || _type[i] == GPS_TYPE_UAVCAN_RTK_BASE || _type[i] == GPS_TYPE_UAVCAN_RTK_ROVER) { - if (!AP_GPS_UAVCAN::backends_healthy(failure_msg, failure_msg_len)) { + if (!AP_GPS_DroneCAN::backends_healthy(failure_msg, failure_msg_len)) { return false; } } diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 25c138a0fba6e7..96013c72fec1d1 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -86,7 +86,7 @@ class AP_GPS friend class AP_GPS_SIRF; friend class AP_GPS_UBLOX; friend class AP_GPS_Backend; - friend class AP_GPS_UAVCAN; + friend class AP_GPS_DroneCAN; public: AP_GPS(); @@ -593,7 +593,7 @@ class AP_GPS AP_Float _blend_tc; AP_Int16 _driver_options; AP_Int8 _primary; -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS AP_Int32 _node_id[GPS_MAX_RECEIVERS]; AP_Int32 _override_node_id[GPS_MAX_RECEIVERS]; #endif diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp index bf4c7c1d6e5edd..4d6def5d87fd71 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp @@ -18,7 +18,7 @@ // #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include "AP_GPS_DroneCAN.h" #include @@ -56,21 +56,21 @@ extern const AP_HAL::HAL& hal; #else #define NATIVE_TIME_OFFSET 0 #endif -AP_GPS_UAVCAN::DetectedModules AP_GPS_UAVCAN::_detected_modules[]; -HAL_Semaphore AP_GPS_UAVCAN::_sem_registry; +AP_GPS_DroneCAN::DetectedModules AP_GPS_DroneCAN::_detected_modules[]; +HAL_Semaphore AP_GPS_DroneCAN::_sem_registry; // Member Methods -AP_GPS_UAVCAN::AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role _role) : +AP_GPS_DroneCAN::AP_GPS_DroneCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role _role) : AP_GPS_Backend(_gps, _state, nullptr), interim_state(_state), role(_role) { - param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_int, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); - param_float_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_float, bool, AP_DroneCAN*, const uint8_t, const char*, float &); - param_save_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_save_response, void, AP_DroneCAN*, const uint8_t, bool); + param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_get_set_response_int, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); + param_float_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_get_set_response_float, bool, AP_DroneCAN*, const uint8_t, const char*, float &); + param_save_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_save_response, void, AP_DroneCAN*, const uint8_t, bool); } -AP_GPS_UAVCAN::~AP_GPS_UAVCAN() +AP_GPS_DroneCAN::~AP_GPS_DroneCAN() { WITH_SEMAPHORE(_sem_registry); @@ -83,7 +83,7 @@ AP_GPS_UAVCAN::~AP_GPS_UAVCAN() #endif } -void AP_GPS_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +void AP_GPS_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { if (ap_dronecan == nullptr) { return; @@ -115,11 +115,11 @@ void AP_GPS_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) #endif } -AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) +AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) { WITH_SEMAPHORE(_sem_registry); int8_t found_match = -1, last_match = -1; - AP_GPS_UAVCAN* backend = nullptr; + AP_GPS_DroneCAN* backend = nullptr; bool bad_override_config = false; for (int8_t i = GPS_MAX_RECEIVERS - 1; i >= 0; i--) { if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) { @@ -164,14 +164,14 @@ AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) // initialise the backend based on the UAVCAN Moving baseline selection switch (_gps.get_type(_state.instance)) { case AP_GPS::GPS_TYPE_UAVCAN: - backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_NORMAL); + backend = new AP_GPS_DroneCAN(_gps, _state, AP_GPS::GPS_ROLE_NORMAL); break; #if GPS_MOVING_BASELINE case AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE: - backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_MB_BASE); + backend = new AP_GPS_DroneCAN(_gps, _state, AP_GPS::GPS_ROLE_MB_BASE); break; case AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER: - backend = new AP_GPS_UAVCAN(_gps, _state, AP_GPS::GPS_ROLE_MB_ROVER); + backend = new AP_GPS_DroneCAN(_gps, _state, AP_GPS::GPS_ROLE_MB_ROVER); break; #endif default: @@ -219,7 +219,7 @@ AP_GPS_Backend* AP_GPS_UAVCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) return backend; } -bool AP_GPS_UAVCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_len) +bool AP_GPS_DroneCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_len) { for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { bool overriden_node_found = false; @@ -254,7 +254,7 @@ bool AP_GPS_UAVCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_le return true; } -AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) +AP_GPS_DroneCAN* AP_GPS_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) { if (ap_dronecan == nullptr) { return nullptr; @@ -316,7 +316,7 @@ AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8 /* handle velocity element of message */ -void AP_GPS_UAVCAN::handle_velocity(const float vx, const float vy, const float vz) +void AP_GPS_DroneCAN::handle_velocity(const float vx, const float vy, const float vz) { if (!isnanf(vx)) { const Vector3f vel(vx, vy, vz); @@ -333,7 +333,7 @@ void AP_GPS_UAVCAN::handle_velocity(const float vx, const float vy, const float } } -void AP_GPS_UAVCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec) +void AP_GPS_DroneCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec) { bool process = false; seen_fix2 = true; @@ -472,7 +472,7 @@ void AP_GPS_UAVCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint6 } } -void AP_GPS_UAVCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg) +void AP_GPS_DroneCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg) { WITH_SEMAPHORE(sem); @@ -487,7 +487,7 @@ void AP_GPS_UAVCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg) } } -void AP_GPS_UAVCAN::handle_heading_msg(const ardupilot_gnss_Heading& msg) +void AP_GPS_DroneCAN::handle_heading_msg(const ardupilot_gnss_Heading& msg) { #if GPS_MOVING_BASELINE if (seen_relposheading && gps.mb_params[interim_state.instance].type.get() != 0) { @@ -513,7 +513,7 @@ void AP_GPS_UAVCAN::handle_heading_msg(const ardupilot_gnss_Heading& msg) interim_state.gps_yaw_accuracy = degrees(msg.heading_accuracy_rad); } -void AP_GPS_UAVCAN::handle_status_msg(const ardupilot_gnss_Status& msg) +void AP_GPS_DroneCAN::handle_status_msg(const ardupilot_gnss_Status& msg) { WITH_SEMAPHORE(sem); @@ -534,7 +534,7 @@ void AP_GPS_UAVCAN::handle_status_msg(const ardupilot_gnss_Status& msg) /* handle moving baseline data. */ -void AP_GPS_UAVCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id) +void AP_GPS_DroneCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id) { WITH_SEMAPHORE(sem); if (role != AP_GPS::GPS_ROLE_MB_BASE) { @@ -553,7 +553,7 @@ void AP_GPS_UAVCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBaseli /* handle relposheading message */ -void AP_GPS_UAVCAN::handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id) +void AP_GPS_DroneCAN::handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id) { WITH_SEMAPHORE(sem); @@ -572,7 +572,7 @@ void AP_GPS_UAVCAN::handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& } // support for retrieving RTCMv3 data from a moving baseline base -bool AP_GPS_UAVCAN::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) +bool AP_GPS_DroneCAN::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) { WITH_SEMAPHORE(sem); if (rtcm3_parser != nullptr) { @@ -583,7 +583,7 @@ bool AP_GPS_UAVCAN::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) } // clear previous RTCM3 packet -void AP_GPS_UAVCAN::clear_RTCMV3(void) +void AP_GPS_DroneCAN::clear_RTCMV3(void) { WITH_SEMAPHORE(sem); if (rtcm3_parser != nullptr) { @@ -593,41 +593,41 @@ void AP_GPS_UAVCAN::clear_RTCMV3(void) #endif // GPS_MOVING_BASELINE -void AP_GPS_UAVCAN::handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg) +void AP_GPS_DroneCAN::handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_fix2_msg(msg, transfer.timestamp_usec); } } -void AP_GPS_UAVCAN::handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg) +void AP_GPS_DroneCAN::handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_aux_msg(msg); } } -void AP_GPS_UAVCAN::handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg) +void AP_GPS_DroneCAN::handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_heading_msg(msg); } } -void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg) +void AP_GPS_DroneCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_status_msg(msg); } @@ -635,27 +635,27 @@ void AP_GPS_UAVCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const #if GPS_MOVING_BASELINE // Moving Baseline msg trampoline -void AP_GPS_UAVCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg) +void AP_GPS_DroneCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_moving_baseline_msg(msg, transfer.source_node_id); } } // RelPosHeading msg trampoline -void AP_GPS_UAVCAN::handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg) +void AP_GPS_DroneCAN::handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_relposheading_msg(msg, transfer.source_node_id); } } #endif -bool AP_GPS_UAVCAN::do_config() +bool AP_GPS_DroneCAN::do_config() { AP_DroneCAN *ap_dronecan = _detected_modules[_detected_module].ap_dronecan; if (ap_dronecan == nullptr) { @@ -690,7 +690,7 @@ bool AP_GPS_UAVCAN::do_config() } // Consume new data and mark it received -bool AP_GPS_UAVCAN::read(void) +bool AP_GPS_DroneCAN::read(void) { if (gps._auto_config >= AP_GPS::GPS_AUTO_CONFIG_ENABLE_ALL) { if (!do_config()) { @@ -726,7 +726,7 @@ bool AP_GPS_UAVCAN::read(void) return false; } -bool AP_GPS_UAVCAN::is_healthy(void) const +bool AP_GPS_DroneCAN::is_healthy(void) const { // if we don't have any health reports, assume it's healthy if (!seen_status) { @@ -735,7 +735,7 @@ bool AP_GPS_UAVCAN::is_healthy(void) const return healthy; } -bool AP_GPS_UAVCAN::logging_healthy(void) const +bool AP_GPS_DroneCAN::logging_healthy(void) const { // if we don't have status, assume it's valid if (!seen_status) { @@ -745,7 +745,7 @@ bool AP_GPS_UAVCAN::logging_healthy(void) const return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_LOGGING) != 0; } -bool AP_GPS_UAVCAN::is_configured(void) const +bool AP_GPS_DroneCAN::is_configured(void) const { // if we don't have status assume it's configured if (!seen_status) { @@ -758,7 +758,7 @@ bool AP_GPS_UAVCAN::is_configured(void) const /* handle RTCM data from MAVLink GPS_RTCM_DATA, forwarding it over MAVLink */ -void AP_GPS_UAVCAN::inject_data(const uint8_t *data, uint16_t len) +void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len) { // we only handle this if we are the first UAVCAN GPS or we are // using a different uavcan instance than the first GPS, as we @@ -773,9 +773,9 @@ void AP_GPS_UAVCAN::inject_data(const uint8_t *data, uint16_t len) /* handle param get/set response */ -bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, int32_t &value) +bool AP_GPS_DroneCAN::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, int32_t &value) { - Debug("AP_GPS_UAVCAN: param set/get response from %d %s %ld\n", node_id, name, value); + Debug("AP_GPS_DroneCAN: param set/get response from %d %s %ld\n", node_id, name, value); if (strcmp(name, "GPS_TYPE") == 0 && cfg_step == STEP_SET_TYPE) { if (role == AP_GPS::GPS_ROLE_MB_BASE && value != AP_GPS::GPS_TYPE_UBLOX_RTK_BASE) { value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_BASE; @@ -810,15 +810,15 @@ bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, return false; } -bool AP_GPS_UAVCAN::handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, float &value) +bool AP_GPS_DroneCAN::handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, float &value) { - Debug("AP_GPS_UAVCAN: param set/get response from %d %s %f\n", node_id, name, value); + Debug("AP_GPS_DroneCAN: param set/get response from %d %s %f\n", node_id, name, value); return false; } -void AP_GPS_UAVCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success) +void AP_GPS_DroneCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success) { - Debug("AP_GPS_UAVCAN: param save response from %d %s\n", node_id, success ? "success" : "failure"); + Debug("AP_GPS_DroneCAN: param save response from %d %s\n", node_id, success ? "success" : "failure"); if (cfg_step != STEP_SAVE_AND_REBOOT) { return; @@ -829,12 +829,12 @@ void AP_GPS_UAVCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const u } // Also send reboot command // this is ok as we are sending from UAVCAN thread context - Debug("AP_GPS_UAVCAN: sending reboot command %d\n", node_id); + Debug("AP_GPS_DroneCAN: sending reboot command %d\n", node_id); ap_dronecan->send_reboot_request(node_id); } #if AP_DRONECAN_SEND_GPS -bool AP_GPS_UAVCAN::instance_exists(const AP_DroneCAN* ap_dronecan) +bool AP_GPS_DroneCAN::instance_exists(const AP_DroneCAN* ap_dronecan) { for (uint8_t i=0; i #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include "AP_GPS.h" #include "GPS_Backend.h" #include "RTCM3_Parser.h" #include -class AP_GPS_UAVCAN : public AP_GPS_Backend { +class AP_GPS_DroneCAN : public AP_GPS_Backend { public: - AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role role); - ~AP_GPS_UAVCAN(); + AP_GPS_DroneCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role role); + ~AP_GPS_DroneCAN(); bool read() override; @@ -95,7 +95,7 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { static bool take_registry(); static void give_registry(); - static AP_GPS_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); + static AP_GPS_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); bool _new_data; AP_GPS::GPS_State interim_state; @@ -119,7 +119,7 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { AP_DroneCAN* ap_dronecan; uint8_t node_id; uint8_t instance; - AP_GPS_UAVCAN* driver; + AP_GPS_DroneCAN* driver; } _detected_modules[GPS_MAX_RECEIVERS]; static HAL_Semaphore _sem_registry; From 3f47d4c71c9f2424da23dc217162f8405d086175 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 244/287] AP_HAL_ChibiOS: rename more variables, types and defines --- libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat | 4 ++-- libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat index e99f50662bd33f..7b7644417c0e16 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat @@ -142,8 +142,8 @@ PD2 SDMMC1_CMD SDMMC1 define BOARD_SER1_RTSCTS_DEFAULT 0 define HAL_OS_FATFS_IO 1 -define HAL_WITH_UAVCAN 1 -env HAL_WITH_UAVCAN 1 +define HAL_WITH_DRONECAN 1 +env HAL_WITH_DRONECAN 1 define HAL_PICCOLO_CAN_ENABLE 0 define AP_CAN_SLCAN_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc index 4eec0f9917e19e..1770d8587866f0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc @@ -7,4 +7,4 @@ define AP_AIRSPEED_MS5525_ENABLED 1 define AP_AIRSPEED_SDP3X_ENABLED 1 define AP_AIRSPEED_NMEA_ENABLED 1 # additional checks for vehicle type in .cpp -define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS +define AP_AIRSPEED_DRONECAN_ENABLED HAL_ENABLE_DRONECAN_DRIVERS From 5d6b7b04d83a1ad48d8d074038e5b7a25e1f1dc4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 245/287] AP_HAL: rename more variables, types and defines --- libraries/AP_HAL/AP_HAL_Boards.h | 4 ++-- libraries/AP_HAL/board/esp32.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 2a3706ad034d72..d6159d7e45d529 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -218,8 +218,8 @@ #define HAL_CANMANAGER_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS > 0) #endif -#ifndef HAL_ENABLE_LIBUAVCAN_DRIVERS -#define HAL_ENABLE_LIBUAVCAN_DRIVERS HAL_CANMANAGER_ENABLED +#ifndef HAL_ENABLE_DRONECAN_DRIVERS +#define HAL_ENABLE_DRONECAN_DRIVERS HAL_CANMANAGER_ENABLED #endif #ifndef AP_TEST_DRONECAN_DRIVERS diff --git a/libraries/AP_HAL/board/esp32.h b/libraries/AP_HAL/board/esp32.h index 8be292c0d633c0..560920fc09c8b9 100644 --- a/libraries/AP_HAL/board/esp32.h +++ b/libraries/AP_HAL/board/esp32.h @@ -13,7 +13,7 @@ #define HAL_BOARD_NAME "ESP32" #define HAL_CPU_CLASS HAL_CPU_CLASS_150 -#define HAL_WITH_UAVCAN 0 +#define HAL_WITH_DRONECAN 0 #define HAL_HAVE_SAFETY_SWITCH 0 #define HAL_HAVE_BOARD_VOLTAGE 0 #define HAL_HAVE_SERVO_VOLTAGE 0 From 05d5b56bfa700a3607927a03ab43f30e8aea79a8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 246/287] AP_Notify: rename more variables, types and defines --- libraries/AP_Notify/AP_Notify.cpp | 12 ++++++------ libraries/AP_Notify/AP_Notify.h | 2 +- libraries/AP_Notify/DroneCAN_RGB_LED.cpp | 14 +++++++------- libraries/AP_Notify/DroneCAN_RGB_LED.h | 6 +++--- libraries/AP_Notify/MMLPlayer.cpp | 2 +- 5 files changed, 18 insertions(+), 18 deletions(-) diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index b3b3b28cac09cb..3a2319b12c528f 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -32,7 +32,7 @@ #include "DiscreteRGBLed.h" #include "DiscoLED.h" #include "Led_Sysfs.h" -#include "UAVCAN_RGB_LED.h" +#include "DroneCAN_RGB_LED.h" #include "SITL_SFML_LED.h" #include #include "AP_BoardLED2.h" @@ -79,7 +79,7 @@ AP_Notify *AP_Notify::_singleton; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE #define BUILD_DEFAULT_LED_TYPE (Notify_LED_Board | I2C_LEDS |\ - Notify_LED_UAVCAN) + Notify_LED_DroneCAN) #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET || \ @@ -347,10 +347,10 @@ void AP_Notify::add_backends(void) } #endif break; - case Notify_LED_UAVCAN: -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - ADD_BACKEND(new UAVCAN_RGB_LED(0)); -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS + case Notify_LED_DroneCAN: +#if HAL_ENABLE_DRONECAN_DRIVERS + ADD_BACKEND(new DroneCAN_RGB_LED(0)); +#endif // HAL_ENABLE_DRONECAN_DRIVERS break; case Notify_LED_Scripting: diff --git a/libraries/AP_Notify/AP_Notify.h b/libraries/AP_Notify/AP_Notify.h index 55f296994beffc..08cbd462cc9d4c 100644 --- a/libraries/AP_Notify/AP_Notify.h +++ b/libraries/AP_Notify/AP_Notify.h @@ -69,7 +69,7 @@ class AP_Notify Notify_LED_PCA9685LED_I2C_External = (1 << 3), // External PCA9685_I2C #endif Notify_LED_OreoLED = (1 << 4), // Oreo - Notify_LED_UAVCAN = (1 << 5), // UAVCAN RGB LED + Notify_LED_DroneCAN = (1 << 5), // UAVCAN RGB LED #if AP_NOTIFY_NCP5623_ENABLED Notify_LED_NCP5623_I2C_External = (1 << 6), // External NCP5623 Notify_LED_NCP5623_I2C_Internal = (1 << 7), // Internal NCP5623 diff --git a/libraries/AP_Notify/DroneCAN_RGB_LED.cpp b/libraries/AP_Notify/DroneCAN_RGB_LED.cpp index f07a230f672c71..e56bf791ecfad6 100644 --- a/libraries/AP_Notify/DroneCAN_RGB_LED.cpp +++ b/libraries/AP_Notify/DroneCAN_RGB_LED.cpp @@ -17,8 +17,8 @@ #include #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS -#include "UAVCAN_RGB_LED.h" +#if HAL_ENABLE_DRONECAN_DRIVERS +#include "DroneCAN_RGB_LED.h" #include @@ -29,13 +29,13 @@ #define LED_MEDIUM ((LED_FULL_BRIGHT / 5) * 4) #define LED_DIM ((LED_FULL_BRIGHT / 5) * 2) -UAVCAN_RGB_LED::UAVCAN_RGB_LED(uint8_t led_index) - : UAVCAN_RGB_LED(led_index, LED_OFF, +DroneCAN_RGB_LED::DroneCAN_RGB_LED(uint8_t led_index) + : DroneCAN_RGB_LED(led_index, LED_OFF, LED_FULL_BRIGHT, LED_MEDIUM, LED_DIM) { } -UAVCAN_RGB_LED::UAVCAN_RGB_LED(uint8_t led_index, uint8_t led_off, +DroneCAN_RGB_LED::DroneCAN_RGB_LED(uint8_t led_index, uint8_t led_off, uint8_t led_full, uint8_t led_medium, uint8_t led_dim) : RGBLed(led_off, led_full, led_medium, led_dim) @@ -43,7 +43,7 @@ UAVCAN_RGB_LED::UAVCAN_RGB_LED(uint8_t led_index, uint8_t led_off, { } -bool UAVCAN_RGB_LED::init() +bool DroneCAN_RGB_LED::init() { const uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { @@ -57,7 +57,7 @@ bool UAVCAN_RGB_LED::init() } -bool UAVCAN_RGB_LED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) +bool DroneCAN_RGB_LED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) { bool success = false; uint8_t can_num_drivers = AP::can().get_num_drivers(); diff --git a/libraries/AP_Notify/DroneCAN_RGB_LED.h b/libraries/AP_Notify/DroneCAN_RGB_LED.h index ddb19eee2b3276..e2c2d10f645a10 100644 --- a/libraries/AP_Notify/DroneCAN_RGB_LED.h +++ b/libraries/AP_Notify/DroneCAN_RGB_LED.h @@ -2,11 +2,11 @@ #include "RGBLed.h" -class UAVCAN_RGB_LED: public RGBLed { +class DroneCAN_RGB_LED: public RGBLed { public: - UAVCAN_RGB_LED(uint8_t led_index, uint8_t led_off, uint8_t led_full, + DroneCAN_RGB_LED(uint8_t led_index, uint8_t led_off, uint8_t led_full, uint8_t led_medium, uint8_t led_dim); - UAVCAN_RGB_LED(uint8_t led_index); + DroneCAN_RGB_LED(uint8_t led_index); bool init() override; protected: diff --git a/libraries/AP_Notify/MMLPlayer.cpp b/libraries/AP_Notify/MMLPlayer.cpp index 7cb2aac3e34d66..705253f98e733c 100644 --- a/libraries/AP_Notify/MMLPlayer.cpp +++ b/libraries/AP_Notify/MMLPlayer.cpp @@ -64,7 +64,7 @@ void MMLPlayer::start_note(float duration, float frequency, float volume) _note_duration_us = duration*1e6; hal.util->toneAlarm_set_buzzer_tone(frequency, volume, _note_duration_us/1000U); -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS // support CAN buzzers too uint8_t can_num_drivers = AP::can().get_num_drivers(); From 84020035537a7660ddce73445cf19c996c139f7a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 247/287] AP_OpenDroneID: rename more variables, types and defines --- libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp b/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp index 30887b9da53943..9928f0e9d427b3 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID_DroneCAN.cpp @@ -22,7 +22,7 @@ #include -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS #include static Canard::Publisher* dc_location[HAL_MAX_CAN_PROTOCOL_DRIVERS]; @@ -239,5 +239,5 @@ void AP_OpenDroneID::set_arm_status(mavlink_open_drone_id_arm_status_t &status) last_arm_status_ms = AP_HAL::millis(); } -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif // HAL_ENABLE_DRONECAN_DRIVERS #endif // AP_OPENDRONEID_ENABLED From d1d7cdfb5232657632f65d91e95f9e9be2995124 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 248/287] AP_OpticalFlow: rename more variables, types and defines --- libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h index 145d8754481f3d..fa340584ff2f2a 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h @@ -3,7 +3,7 @@ #include "AP_OpticalFlow.h" #ifndef AP_OPTICALFLOW_HEREFLOW_ENABLED -#define AP_OPTICALFLOW_HEREFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) +#define AP_OPTICALFLOW_HEREFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS) #endif #if AP_OPTICALFLOW_HEREFLOW_ENABLED From 70b04a22f082da1173a7ac41fdb88e43d63286d1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 249/287] AP_Proximity: rename more variables, types and defines --- libraries/AP_Proximity/AP_Proximity_DroneCAN.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h index aa85f7169b5d93..ea5fa409d43e36 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h @@ -5,7 +5,7 @@ #include #ifndef AP_PROXIMITY_DRONECAN_ENABLED -#define AP_PROXIMITY_DRONECAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && HAL_PROXIMITY_ENABLED) +#define AP_PROXIMITY_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS && HAL_PROXIMITY_ENABLED) #endif #if AP_PROXIMITY_DRONECAN_ENABLED From 83114f4c745a39732e755c6a16ccb4548b171056 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:10 +1000 Subject: [PATCH 250/287] AP_RangeFinder: rename more variables, types and defines --- libraries/AP_RangeFinder/AP_RangeFinder.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp | 18 +++++++++--------- .../AP_RangeFinder/AP_RangeFinder_DroneCAN.h | 6 +++--- 3 files changed, 13 insertions(+), 13 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index 29231548ed1671..3a66a5aa6de502 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -57,7 +57,7 @@ class RangeFinder { friend class AP_RangeFinder_Backend; //UAVCAN drivers are initialised in the Backend, hence list of drivers is needed there. - friend class AP_RangeFinder_UAVCAN; + friend class AP_RangeFinder_DroneCAN; public: RangeFinder(); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp index cec61be979e9eb..712b92bca821fb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -13,7 +13,7 @@ extern const AP_HAL::HAL& hal; #define debug_range_finder_uavcan(level_debug, can_driver, fmt, args...) do { if ((level_debug) <= AP::can().get_debug_level_driver(can_driver)) { hal.console->printf(fmt, ##args); }} while (0) //links the rangefinder uavcan message to this backend -void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +void AP_RangeFinder_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { if (ap_dronecan == nullptr) { return; @@ -24,18 +24,18 @@ void AP_RangeFinder_UAVCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) } //Method to find the backend relating to the node id -AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) +AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) { if (ap_dronecan == nullptr) { return nullptr; } - AP_RangeFinder_UAVCAN* driver = nullptr; + AP_RangeFinder_DroneCAN* driver = nullptr; RangeFinder &frontend = *AP::rangefinder(); //Scan through the Rangefinder params to find UAVCAN RFND with matching address. for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { if ((RangeFinder::Type)frontend.params[i].type.get() == RangeFinder::Type::UAVCAN && frontend.params[i].address == address) { - driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i]; + driver = (AP_RangeFinder_DroneCAN*)frontend.drivers[i]; } //Double check if the driver was initialised as UAVCAN Type if (driver != nullptr && (driver->_backend_type == RangeFinder::Type::UAVCAN)) { @@ -60,8 +60,8 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap //it up as UAVCAN type return nullptr; } - frontend.drivers[i] = new AP_RangeFinder_UAVCAN(frontend.state[i], frontend.params[i]); - driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i]; + frontend.drivers[i] = new AP_RangeFinder_DroneCAN(frontend.state[i], frontend.params[i]); + driver = (AP_RangeFinder_DroneCAN*)frontend.drivers[i]; if (driver == nullptr) { break; } @@ -81,7 +81,7 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_DroneCAN* ap } //Called from frontend to update with the readings received by handler -void AP_RangeFinder_UAVCAN::update() +void AP_RangeFinder_DroneCAN::update() { WITH_SEMAPHORE(_sem); if ((AP_HAL::millis() - _last_reading_ms) > 500) { @@ -100,10 +100,10 @@ void AP_RangeFinder_UAVCAN::update() } //RangeFinder message handler -void AP_RangeFinder_UAVCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg) +void AP_RangeFinder_DroneCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg) { //fetch the matching uavcan driver, node id and sensor id backend instance - AP_RangeFinder_UAVCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); + AP_RangeFinder_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); if (driver == nullptr) { return; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h index 5b08bdc16f5b12..80778b82adad3d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h @@ -3,7 +3,7 @@ #include "AP_RangeFinder_Backend.h" #ifndef AP_RANGEFINDER_DRONECAN_ENABLED -#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_LIBUAVCAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) #endif #if AP_RANGEFINDER_DRONECAN_ENABLED @@ -12,7 +12,7 @@ class MeasurementCb; -class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { +class AP_RangeFinder_DroneCAN : public AP_RangeFinder_Backend { public: //constructor - registers instance at top RangeFinder driver using AP_RangeFinder_Backend::AP_RangeFinder_Backend; @@ -20,7 +20,7 @@ class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { void update() override; static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_RangeFinder_UAVCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); + static AP_RangeFinder_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg); From 2119d6bfc9d86c9b63d2018c8febbe1a35f2f84b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:11 +1000 Subject: [PATCH 251/287] GCS_MAVLink: rename more variables, types and defines --- libraries/GCS_MAVLink/GCS_Common.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index f282c54c0687b5..94e26f7f8c19e1 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4391,7 +4391,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_can(const mavlink_command_long_ case AP_CANManager::Driver_Type_PiccoloCAN: // TODO - Run PiccoloCAN pre-flight checks here break; - case AP_CANManager::Driver_Type_UAVCAN: + case AP_CANManager::Driver_Type_DroneCAN: case AP_CANManager::Driver_Type_None: default: break; From 9e31757b249bdc906dc4f3321a3b68550ba930cc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:11 +1000 Subject: [PATCH 252/287] SRV_Channel: rename more variables, types and defines --- libraries/SRV_Channel/SRV_Channels.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channels.cpp b/libraries/SRV_Channel/SRV_Channels.cpp index b6489e1b9393b2..b9bbe6ffcf006d 100644 --- a/libraries/SRV_Channel/SRV_Channels.cpp +++ b/libraries/SRV_Channel/SRV_Channels.cpp @@ -534,12 +534,12 @@ void SRV_Channels::push() fetteconwire_ptr->update(); #endif -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if HAL_ENABLE_DRONECAN_DRIVERS // push outputs to CAN uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { switch (AP::can().get_driver_type(i)) { - case AP_CANManager::Driver_Type_UAVCAN: { + case AP_CANManager::Driver_Type_DroneCAN: { AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_uavcan(i); if (ap_dronecan == nullptr) { continue; From c7231240c854867c9094c8707633e09271a50f10 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:09:11 +1000 Subject: [PATCH 253/287] Tools: rename more variables, types and defines --- Tools/AP_Periph/Parameters.cpp | 6 +++--- Tools/AP_Periph/can.cpp | 8 ++++---- Tools/scripts/extract_features.py | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 613fcd235c82ad..8ac1666808099c 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -102,7 +102,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN // @User: Advanced // @RebootRequired: True - GARRAY(can_protocol, 0, "CAN_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN), + GARRAY(can_protocol, 0, "CAN_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN), // @Param: CAN2_BAUDRATE // @DisplayName: Bitrate of CAN2 interface @@ -118,7 +118,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN // @User: Advanced // @RebootRequired: True - GARRAY(can_protocol, 1, "CAN2_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN), + GARRAY(can_protocol, 1, "CAN2_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN), #endif #if HAL_NUM_CAN_IFACES >= 3 @@ -136,7 +136,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN // @User: Advanced // @RebootRequired: True - GARRAY(can_protocol, 2, "CAN3_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN), + GARRAY(can_protocol, 2, "CAN3_PROTOCOL", AP_CANManager::Driver_Type_DroneCAN), #endif #if HAL_CANFD_SUPPORTED diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index b8a206b46ce914..1c340a9e12b28f 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1197,7 +1197,7 @@ static void processTx(void) } #endif #if HAL_NUM_CAN_IFACES >= 2 - if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_UAVCAN) { + if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_DroneCAN) { continue; } #endif @@ -1229,7 +1229,7 @@ static void processRx(void) continue; } #if HAL_NUM_CAN_IFACES >= 2 - if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_UAVCAN) { + if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_DroneCAN) { continue; } #endif @@ -1485,12 +1485,12 @@ void AP_Periph_FW::can_start() #if AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz && HAL_NUM_CAN_IFACES >= 2 bool has_uavcan_at_1MHz = false; for (uint8_t i=0; i.*)::update',), ('GPS_MOVING_BASELINE', r'AP_GPS_Backend::calculate_moving_base_yaw\b',), - ('AP_DRONECAN_SEND_GPS', r'AP_GPS_UAVCAN::instance_exists\b',), + ('AP_DRONECAN_SEND_GPS', r'AP_GPS_DroneCAN::instance_exists\b',), ('HAL_WITH_DSP', r'AP_HAL::DSP::find_peaks\b',), ('HAL_GYROFFT_ENABLED', r'AP_GyroFFT::AP_GyroFFT\b',), From 5b45a4060a9c9d25495ccdfe3cc5b56ac5146964 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:13:44 +1000 Subject: [PATCH 254/287] AP_CANManager: cleanup more defines and classes --- libraries/AP_CANManager/AP_CANTester.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_CANManager/AP_CANTester.h b/libraries/AP_CANManager/AP_CANTester.h index c93ba0649fe375..6fb07c761847c3 100644 --- a/libraries/AP_CANManager/AP_CANTester.h +++ b/libraries/AP_CANManager/AP_CANTester.h @@ -96,7 +96,7 @@ class CANTester : public AP_CANDriver // Classes required for UAVCAN Test class RaiiSynchronizer {}; - uavcan::PoolAllocator _node_allocator; + uavcan::PoolAllocator _node_allocator; HAL_EventHandle _event_handle; AP_Int8 _test_driver_index; From 3129cae87527130917cb2e4fbc5c4ef5cd4cf699 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:13:44 +1000 Subject: [PATCH 255/287] AP_DroneCAN: cleanup more defines and classes --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 8 +++--- .../DroneCAN_sniffer/UAVCAN_sniffer.cpp | 28 +++++++++---------- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 1c04de8c99cf6a..b99eed1ea98d8e 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -53,11 +53,11 @@ extern const AP_HAL::HAL& hal; // setup default pool size -#ifndef UAVCAN_NODE_POOL_SIZE +#ifndef DRONECAN_NODE_POOL_SIZE #if HAL_CANFD_SUPPORTED -#define UAVCAN_NODE_POOL_SIZE 16384 +#define DRONECAN_NODE_POOL_SIZE 16384 #else -#define UAVCAN_NODE_POOL_SIZE 8192 +#define DRONECAN_NODE_POOL_SIZE 8192 #endif #endif @@ -141,7 +141,7 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Description: Amount of memory in bytes to allocate for the DroneCAN memory pool. More memory is needed for higher CAN bus loads // @Range: 1024 16384 // @User: Advanced - AP_GROUPINFO("POOL", 8, AP_DroneCAN, _pool_size, UAVCAN_NODE_POOL_SIZE), + AP_GROUPINFO("POOL", 8, AP_DroneCAN, _pool_size, DRONECAN_NODE_POOL_SIZE), AP_GROUPEND }; diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp index 8a4700963cc0e4..3e36e8e7a0b06d 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp @@ -1,5 +1,5 @@ /* - simple UAVCAN network sniffer as an ArduPilot firmware + simple DroneCAN network sniffer as an ArduPilot firmware */ #include #include @@ -24,16 +24,16 @@ void loop(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); -#define UAVCAN_NODE_POOL_SIZE 8192 +#define DRONECAN_NODE_POOL_SIZE 8192 -static uint8_t node_memory_pool[UAVCAN_NODE_POOL_SIZE]; +static uint8_t node_memory_pool[DRONECAN_NODE_POOL_SIZE]; #define debug_uavcan(fmt, args...) do { hal.console->printf(fmt, ##args); } while (0) -class UAVCAN_sniffer { +class DroneCAN_sniffer { public: - UAVCAN_sniffer(); - ~UAVCAN_sniffer(); + DroneCAN_sniffer(); + ~DroneCAN_sniffer(); void init(void); void loop(void); @@ -96,7 +96,7 @@ static void cb_GetNodeInfoRequest(const CanardRxTransfer &transfer, const uavcan node_info_srv->respond(transfer, node_info); } -void UAVCAN_sniffer::init(void) +void DroneCAN_sniffer::init(void) { const_cast (hal).can[driver_index] = new HAL_CANIface(driver_index); @@ -156,7 +156,7 @@ void UAVCAN_sniffer::init(void) START_CB(uavcan_equipment_indication_LightsCommand, LightsCommand); START_CB(com_hex_equipment_flow_Measurement, Measurement); - debug_uavcan("UAVCAN: init done\n\r"); + debug_uavcan("DroneCAN: init done\n\r"); } static void send_node_status() @@ -171,7 +171,7 @@ static void send_node_status() } uint32_t last_status_send = 0; -void UAVCAN_sniffer::loop(void) +void DroneCAN_sniffer::loop(void) { if (AP_HAL::millis() - last_status_send > 1000) { last_status_send = AP_HAL::millis(); @@ -180,7 +180,7 @@ void UAVCAN_sniffer::loop(void) _uavcan_iface_mgr->process(1); } -void UAVCAN_sniffer::print_stats(void) +void DroneCAN_sniffer::print_stats(void) { hal.console->printf("%lu\n", (unsigned long)AP_HAL::micros()); for (uint16_t i=0;i<100;i++) { @@ -193,19 +193,19 @@ void UAVCAN_sniffer::print_stats(void) hal.console->printf("\n"); } -static UAVCAN_sniffer sniffer; +static DroneCAN_sniffer sniffer; -UAVCAN_sniffer::UAVCAN_sniffer() +DroneCAN_sniffer::DroneCAN_sniffer() {} -UAVCAN_sniffer::~UAVCAN_sniffer() +DroneCAN_sniffer::~DroneCAN_sniffer() { } void setup(void) { hal.scheduler->delay(2000); - hal.console->printf("Starting UAVCAN sniffer\n"); + hal.console->printf("Starting DroneCAN sniffer\n"); sniffer.init(); } From 78862a334eb2eab89676183500c10e0f69ebd4c6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:13:44 +1000 Subject: [PATCH 256/287] AP_HAL_ChibiOS: cleanup more defines and classes --- libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat index 8addf44a7f33cb..985bc0cbd13949 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat @@ -82,7 +82,7 @@ PB9 CAN1_TX CAN1 PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) # reduce memory usage -define UAVCAN_NODE_POOL_SIZE 1024 +define DRONECAN_NODE_POOL_SIZE 1024 # --------------------- UARTs --------------------------- From c53e5eaafce7fa7524baf84c5553e5291f2bc12d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:13:44 +1000 Subject: [PATCH 257/287] Tools: cleanup more defines and classes --- Tools/ardupilotwaf/boards.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 5c56156a9a844e..8054b1b49cb7af 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -643,8 +643,6 @@ def configure_env(self, cfg, env): if self.with_can: cfg.define('HAL_NUM_CAN_IFACES', 2) - cfg.define('UAVCAN_EXCEPTIONS', 0) - cfg.define('UAVCAN_SUPPORT_CANFD', 1) env.DEFINES.update(CANARD_MULTI_IFACE=1, CANARD_IFACE_ALL = 0x3, CANARD_ENABLE_CANFD = 1) @@ -1177,8 +1175,6 @@ def configure_env(self, cfg, env): if self.with_can and cfg.options.board == 'linux': cfg.env.HAL_NUM_CAN_IFACES = 2 cfg.define('HAL_NUM_CAN_IFACES', 2) - cfg.define('UAVCAN_EXCEPTIONS', 0) - cfg.define('UAVCAN_SUPPORT_CANFD', 1) cfg.define('HAL_CANFD_SUPPORTED', 1) cfg.define('CANARD_ENABLE_CANFD', 1) From 20436ef5277d81ac0da4bef15f5ee1e7faa68e10 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 258/287] AP_Airspeed: text messages and more defines --- libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp | 10 +++++----- libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp index 9224ff9afd3917..2f312fe7884efa 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp @@ -54,14 +54,14 @@ AP_Airspeed_Backend* AP_Airspeed_DroneCAN::probe(AP_Airspeed &_frontend, uint8_t if (backend == nullptr) { AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, - "Failed register UAVCAN Airspeed Node %d on Bus %d\n", + "Failed register DroneCAN Airspeed Node %d on Bus %d\n", _detected_modules[i].node_id, _detected_modules[i].ap_dronecan->get_driver_index()); } else { _detected_modules[i].driver = backend; AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, - "Registered UAVCAN Airspeed Node %d on Bus %d\n", + "Registered DroneCAN Airspeed Node %d on Bus %d\n", _detected_modules[i].node_id, _detected_modules[i].ap_dronecan->get_driver_index()); backend->set_bus_id(bus_id); @@ -73,7 +73,7 @@ AP_Airspeed_Backend* AP_Airspeed_DroneCAN::probe(AP_Airspeed &_frontend, uint8_t return backend; } -AP_Airspeed_DroneCAN* AP_Airspeed_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) +AP_Airspeed_DroneCAN* AP_Airspeed_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) { if (ap_dronecan == nullptr) { return nullptr; @@ -113,7 +113,7 @@ void AP_Airspeed_DroneCAN::handle_airspeed(AP_DroneCAN *ap_dronecan, const Canar { WITH_SEMAPHORE(_sem_registry); - AP_Airspeed_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_Airspeed_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { WITH_SEMAPHORE(driver->_sem_airspeed); @@ -132,7 +132,7 @@ void AP_Airspeed_DroneCAN::handle_hygrometer(AP_DroneCAN *ap_dronecan, const Can { WITH_SEMAPHORE(_sem_registry); - AP_Airspeed_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_Airspeed_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { WITH_SEMAPHORE(driver->_sem_airspeed); diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h index fb15a8e9229344..ce34cd8c700f30 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h @@ -38,7 +38,7 @@ class AP_Airspeed_DroneCAN : public AP_Airspeed_Backend { static void handle_airspeed(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_RawAirData &msg); static void handle_hygrometer(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_hygrometer_Hygrometer &msg); - static AP_Airspeed_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); + static AP_Airspeed_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); float _pressure; // Pascal float _temperature; // Celcius From 4e161bab5eb7865353ccad05f5b798340a90a382 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 259/287] AP_Arming: text messages and more defines --- libraries/AP_Arming/AP_Arming.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index d53a3b9fd4a276..55079c3ba44e84 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -1176,9 +1176,9 @@ bool AP_Arming::can_checks(bool report) case AP_CANManager::Driver_Type_DroneCAN: { #if HAL_ENABLE_DRONECAN_DRIVERS - AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_uavcan(i); + AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_dronecan(i); if (ap_dronecan != nullptr && !ap_dronecan->prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) { - check_failed(ARMING_CHECK_SYSTEM, report, "UAVCAN: %s", fail_msg); + check_failed(ARMING_CHECK_SYSTEM, report, "DroneCAN: %s", fail_msg); return false; } #endif From 70a7115312eafa6e01d74eba1efbb033baadd264 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 260/287] AP_Baro: text messages and more defines --- libraries/AP_Baro/AP_Baro_DroneCAN.cpp | 10 +++++----- libraries/AP_Baro/AP_Baro_DroneCAN.h | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp index eb0cdecce9e6a5..ee1ee9e427ba91 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp @@ -46,7 +46,7 @@ AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro) if (backend == nullptr) { AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, - "Failed register UAVCAN Baro Node %d on Bus %d\n", + "Failed register DroneCAN Baro Node %d on Bus %d\n", _detected_modules[i].node_id, _detected_modules[i].ap_dronecan->get_driver_index()); } else { @@ -63,7 +63,7 @@ AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro) AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, - "Registered UAVCAN Baro Node %d on Bus %d\n", + "Registered DroneCAN Baro Node %d on Bus %d\n", _detected_modules[i].node_id, _detected_modules[i].ap_dronecan->get_driver_index()); } @@ -73,7 +73,7 @@ AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro) return backend; } -AP_Baro_DroneCAN* AP_Baro_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new) +AP_Baro_DroneCAN* AP_Baro_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new) { if (ap_dronecan == nullptr) { return nullptr; @@ -126,7 +126,7 @@ void AP_Baro_DroneCAN::handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxT AP_Baro_DroneCAN* driver; { WITH_SEMAPHORE(_sem_registry); - driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, true); + driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, true); if (driver == nullptr) { return; } @@ -143,7 +143,7 @@ void AP_Baro_DroneCAN::handle_temperature(AP_DroneCAN *ap_dronecan, const Canard AP_Baro_DroneCAN* driver; { WITH_SEMAPHORE(_sem_registry); - driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, false); + driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, false); if (driver == nullptr) { return; } diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.h b/libraries/AP_Baro/AP_Baro_DroneCAN.h index 19278c28e715a0..3040b97ab6b36b 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.h +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.h @@ -16,7 +16,7 @@ class AP_Baro_DroneCAN : public AP_Baro_Backend { void update() override; static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_Baro_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new); + static AP_Baro_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new); static AP_Baro_Backend* probe(AP_Baro &baro); static void handle_pressure(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_air_data_StaticPressure &msg); From ab8049f8e9828913282d56d8e9e7313936f242dd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 261/287] AP_BattMonitor: text messages and more defines --- libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp | 8 ++++---- libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index d44fdda40239c9..6b30aee470d2dc 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -62,7 +62,7 @@ void AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) } } -AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id) +AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id) { if (ap_dronecan == nullptr) { return nullptr; @@ -199,7 +199,7 @@ void AP_BattMonitor_DroneCAN::handle_mppt_stream(const mppt_Stream &msg) void AP_BattMonitor_DroneCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg) { - AP_BattMonitor_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); + AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); if (driver == nullptr) { return; } @@ -208,7 +208,7 @@ void AP_BattMonitor_DroneCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dro void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) { - AP_BattMonitor_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); + AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); if (driver == nullptr) { return; } @@ -217,7 +217,7 @@ void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap void AP_BattMonitor_DroneCAN::handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg) { - AP_BattMonitor_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id); + AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, transfer.source_node_id); if (driver == nullptr) { return; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h index 6d09200072217c..9c5c56bb73b527 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h @@ -47,7 +47,7 @@ class AP_BattMonitor_DroneCAN : public AP_BattMonitor_Backend uint32_t get_mavlink_fault_bitmask() const override; static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_BattMonitor_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id); + static AP_BattMonitor_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id); static void handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg); static void handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg); static void handle_mppt_stream_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const mppt_Stream &msg); From 44a0f502fe0c877f1242183faf081997c3087e92 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 262/287] AP_CANManager: text messages and more defines --- libraries/AP_CANManager/AP_CANTester.cpp | 26 ++++++++++++------------ 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/libraries/AP_CANManager/AP_CANTester.cpp b/libraries/AP_CANManager/AP_CANTester.cpp index 05617dcfa7e69e..15abf98de86db4 100644 --- a/libraries/AP_CANManager/AP_CANTester.cpp +++ b/libraries/AP_CANManager/AP_CANTester.cpp @@ -182,14 +182,14 @@ void CANTester::main_thread() break; case CANTester::TEST_UAVCAN_DNA: if (_can_ifaces[1] == nullptr) { - gcs().send_text(MAV_SEVERITY_ALERT, "********Running UAVCAN DNA Test********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********Running DroneCAN DNA Test********"); if (test_uavcan_dna()) { - gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN DNA Test Pass********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********DroneCAN DNA Test Pass********"); } else { - gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN DNA Test Fail********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********DroneCAN DNA Test Fail********"); } } else { - gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for UAVCAN_DNA_TEST"); + gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for DroneCAN_DNA_TEST"); } break; case CANTester::TEST_KDE_CAN: @@ -206,23 +206,23 @@ void CANTester::main_thread() break; case CANTester::TEST_UAVCAN_ESC: if (_can_ifaces[1] == nullptr) { - gcs().send_text(MAV_SEVERITY_ALERT, "********Running UAVCAN ESC Test********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********Running DroneCAN ESC Test********"); if (test_uavcan_esc(false)) { - gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN ESC Test Pass********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********DroneCAN ESC Test Pass********"); } else { - gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN ESC Test Fail********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********DroneCAN ESC Test Fail********"); } } else { - gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for UAVCAN_ESC_TEST"); + gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for DroneCAN_ESC_TEST"); } break; case CANTester::TEST_UAVCAN_FD_ESC: if (_can_ifaces[1] == nullptr) { - gcs().send_text(MAV_SEVERITY_ALERT, "********Running UAVCAN FD ESC Test********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********Running DroneCAN FD ESC Test********"); if (test_uavcan_esc(true)) { - gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN FD ESC Test Pass********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********DroneCAN FD ESC Test Pass********"); } else { - gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN FD ESC Test Fail********"); + gcs().send_text(MAV_SEVERITY_ALERT, "********DroneCAN FD ESC Test Fail********"); } } else { gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for UAVCAN_FD_ESC_TEST"); @@ -417,7 +417,7 @@ bool CANTester::test_busoff_recovery() } /***************************************** - * UAVCAN DNA Test * + * DroneCAN DNA Test * * ***************************************/ bool CANTester::test_uavcan_dna() @@ -542,7 +542,7 @@ bool CANTester::run_kdecan_enumeration(bool start_stop) } /*********************************************** - * UAVCAN ESC * + * DroneCAN ESC * * *********************************************/ #define NUM_ESCS 4 From ba450fa08bbda9d114bc6e31fd8862cda3de12d1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 263/287] AP_Compass: text messages and more defines --- libraries/AP_Compass/AP_Compass_DroneCAN.cpp | 6 +++--- libraries/AP_Compass/AP_Compass_DroneCAN.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp index 9f0150596e7f0a..fb35e62ccbad55 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp @@ -108,7 +108,7 @@ bool AP_Compass_DroneCAN::init() return true; } -AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id) +AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id) { if (ap_dronecan == nullptr) { return nullptr; @@ -177,7 +177,7 @@ void AP_Compass_DroneCAN::handle_magnetic_field(AP_DroneCAN *ap_dronecan, const WITH_SEMAPHORE(_sem_registry); Vector3f mag_vector; - AP_Compass_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, 0); + AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, 0); if (driver != nullptr) { mag_vector[0] = msg.magnetic_field_ga[0]; mag_vector[1] = msg.magnetic_field_ga[1]; @@ -192,7 +192,7 @@ void AP_Compass_DroneCAN::handle_magnetic_field_2(AP_DroneCAN *ap_dronecan, cons Vector3f mag_vector; uint8_t sensor_id = msg.sensor_id; - AP_Compass_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, sensor_id); + AP_Compass_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, sensor_id); if (driver != nullptr) { mag_vector[0] = msg.magnetic_field_ga[0]; mag_vector[1] = msg.magnetic_field_ga[1]; diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.h b/libraries/AP_Compass/AP_Compass_DroneCAN.h index 45edf3853747f4..61f677454ed680 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.h +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.h @@ -26,7 +26,7 @@ class AP_Compass_DroneCAN : public AP_Compass_Backend { // callback for DroneCAN messages void handle_mag_msg(const Vector3f &mag); - static AP_Compass_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id); + static AP_Compass_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id); uint8_t _instance; From e811cf86ebc6096df480b96e92bce8d0d81766d8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 264/287] AP_DroneCAN: text messages and more defines --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 72 +++++++++---------- libraries/AP_DroneCAN/AP_DroneCAN.h | 8 +-- .../AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp | 6 +- .../DroneCAN_sniffer/UAVCAN_sniffer.cpp | 8 +-- 4 files changed, 47 insertions(+), 47 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index b99eed1ea98d8e..74d5e29c1052d3 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -62,9 +62,9 @@ extern const AP_HAL::HAL& hal; #endif #if HAL_CANFD_SUPPORTED -#define UAVCAN_STACK_SIZE 8192 +#define DRONECAN_STACK_SIZE 8192 #else -#define UAVCAN_STACK_SIZE 4096 +#define DRONECAN_STACK_SIZE 4096 #endif #ifndef AP_DRONECAN_VOLZ_FEEDBACK_ENABLED @@ -75,9 +75,9 @@ extern const AP_HAL::HAL& hal; #include #endif -#define debug_uavcan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "UAVCAN", fmt, ##args); } while (0) +#define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0) -// Translation of all messages from UAVCAN structures into AP structures is done +// Translation of all messages from DroneCAN structures into AP structures is done // in AP_DroneCAN and not in corresponding drivers. // The overhead of including definitions of DSDL is very high and it is best to // concentrate in one place. @@ -85,23 +85,23 @@ extern const AP_HAL::HAL& hal; // table of user settable CAN bus parameters const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Param: NODE - // @DisplayName: UAVCAN node that is used for this network - // @Description: UAVCAN node should be set implicitly + // @DisplayName: DroneCAN node that is used for this network + // @Description: DroneCAN node should be set implicitly // @Range: 1 250 // @User: Advanced AP_GROUPINFO("NODE", 1, AP_DroneCAN, _dronecan_node, 10), // @Param: SRV_BM - // @DisplayName: Output channels to be transmitted as servo over UAVCAN - // @Description: Bitmask with one set for channel to be transmitted as a servo command over UAVCAN + // @DisplayName: Output channels to be transmitted as servo over DroneCAN + // @Description: Bitmask with one set for channel to be transmitted as a servo command over DroneCAN // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15, 15: Servo 16, 16: Servo 17, 17: Servo 18, 18: Servo 19, 19: Servo 20, 20: Servo 21, 21: Servo 22, 22: Servo 23, 23: Servo 24, 24: Servo 25, 25: Servo 26, 26: Servo 27, 27: Servo 28, 28: Servo 29, 29: Servo 30, 30: Servo 31, 31: Servo 32 // @User: Advanced AP_GROUPINFO("SRV_BM", 2, AP_DroneCAN, _servo_bm, 0), // @Param: ESC_BM - // @DisplayName: Output channels to be transmitted as ESC over UAVCAN - // @Description: Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN + // @DisplayName: Output channels to be transmitted as ESC over DroneCAN + // @Description: Bitmask with one set for channel to be transmitted as a ESC command over DroneCAN // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32 // @User: Advanced AP_GROUPINFO("ESC_BM", 3, AP_DroneCAN, _esc_bm, 0), @@ -115,7 +115,7 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { AP_GROUPINFO("SRV_RT", 4, AP_DroneCAN, _servo_rate_hz, 50), // @Param: OPTION - // @DisplayName: UAVCAN options + // @DisplayName: DroneCAN options // @Description: Option flags // @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy,4:SendServoAsPWM,5:SendGNSS // @User: Advanced @@ -157,19 +157,19 @@ _dna_server(*this) { AP_Param::setup_object_defaults(this, var_info); - for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) { + for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) { _SRV_conf[i].esc_pending = false; _SRV_conf[i].servo_pending = false; } - debug_uavcan(AP_CANManager::LOG_INFO, "AP_DroneCAN constructed\n\r"); + debug_dronecan(AP_CANManager::LOG_INFO, "AP_DroneCAN constructed\n\r"); } AP_DroneCAN::~AP_DroneCAN() { } -AP_DroneCAN *AP_DroneCAN::get_uavcan(uint8_t driver_index) +AP_DroneCAN *AP_DroneCAN::get_dronecan(uint8_t driver_index) { if (driver_index >= AP::can().get_num_drivers() || AP::can().get_driver_type(driver_index) != AP_CANManager::Driver_Type_DroneCAN) { @@ -181,7 +181,7 @@ AP_DroneCAN *AP_DroneCAN::get_uavcan(uint8_t driver_index) bool AP_DroneCAN::add_interface(AP_HAL::CANIface* can_iface) { if (!canard_iface.add_interface(can_iface)) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: can't add UAVCAN interface\n\r"); + debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: can't add DroneCAN interface\n\r"); return false; } return true; @@ -190,11 +190,11 @@ bool AP_DroneCAN::add_interface(AP_HAL::CANIface* can_iface) void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) { if (driver_index != _driver_index) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: init called with wrong driver_index"); + debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: init called with wrong driver_index"); return; } if (_initialized) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: init called more than once\n\r"); + debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: init called more than once\n\r"); return; } @@ -216,7 +216,7 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) mem_pool = new uint32_t[_pool_size/sizeof(uint32_t)]; if (mem_pool == nullptr) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: Failed to allocate memory pool\n\r"); + debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: Failed to allocate memory pool\n\r"); return; } canard_iface.init(mem_pool, (_pool_size/sizeof(uint32_t))*sizeof(uint32_t), _dronecan_node); @@ -229,7 +229,7 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) //Start Servers if (!_dna_server.init(unique_id, uid_len, _dronecan_node)) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: Failed to start DNA Server\n\r"); + debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: Failed to start DNA Server\n\r"); return; } @@ -321,15 +321,15 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) canard_iface.process(1000); } - snprintf(_thread_name, sizeof(_thread_name), "uavcan_%u", driver_index); + snprintf(_thread_name, sizeof(_thread_name), "dronecan_%u", driver_index); - if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_DroneCAN::loop, void), _thread_name, UAVCAN_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_CAN, 0)) { - debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't create thread\n\r"); + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_DroneCAN::loop, void), _thread_name, DRONECAN_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_CAN, 0)) { + debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: couldn't create thread\n\r"); return; } _initialized = true; - debug_uavcan(AP_CANManager::LOG_INFO, "UAVCAN: init done\n\r"); + debug_dronecan(AP_CANManager::LOG_INFO, "DroneCAN: init done\n\r"); } void AP_DroneCAN::loop(void) @@ -353,7 +353,7 @@ void AP_DroneCAN::loop(void) _SRV_last_send_us = now; SRV_send_actuator(); sent_servos = true; - for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) { + for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) { _SRV_conf[i].servo_pending = false; } } @@ -364,7 +364,7 @@ void AP_DroneCAN::loop(void) SRV_send_esc(); } - for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) { + for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) { _SRV_conf[i].esc_pending = false; } } @@ -429,14 +429,14 @@ void AP_DroneCAN::SRV_send_actuator(void) uavcan_equipment_actuator_ArrayCommand msg; uint8_t i; - // UAVCAN can hold maximum of 15 commands in one frame - for (i = 0; starting_servo < UAVCAN_SRV_NUMBER && i < 15; starting_servo++) { + // DroneCAN can hold maximum of 15 commands in one frame + for (i = 0; starting_servo < DRONECAN_SRV_NUMBER && i < 15; starting_servo++) { uavcan_equipment_actuator_Command cmd; /* * Servo output uses a range of 1000-2000 PWM for scaling. * This converts output PWM from [1000:2000] range to [-1:1] range that - * is passed to servo as unitless type via UAVCAN. + * is passed to servo as unitless type via DroneCAN. * This approach allows for MIN/TRIM/MAX values to be used fully on * autopilot side and for servo it should have the setup to provide maximum * physically possible throws at [-1:1] limits. @@ -484,10 +484,10 @@ void AP_DroneCAN::SRV_send_esc(void) WITH_SEMAPHORE(SRV_sem); // esc offset allows for efficient packing of higher ESC numbers in RawCommand - const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, UAVCAN_SRV_NUMBER); + const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, DRONECAN_SRV_NUMBER); // find out how many esc we have enabled and if they are active at all - for (uint8_t i = esc_offset; i < UAVCAN_SRV_NUMBER; i++) { + for (uint8_t i = esc_offset; i < DRONECAN_SRV_NUMBER; i++) { if ((((uint32_t) 1) << i) & _esc_bm) { max_esc_num = i + 1; if (_SRV_conf[i].esc_pending) { @@ -528,7 +528,7 @@ void AP_DroneCAN::SRV_push_servos() { WITH_SEMAPHORE(SRV_sem); - for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) { + for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) { // Check if this channels has any function assigned if (SRV_Channels::channel_function(i) >= SRV_Channel::k_none) { _SRV_conf[i].pulse = SRV_Channels::srv_channel(i)->get_output_pwm(); @@ -935,7 +935,7 @@ void AP_DroneCAN::safety_state_send() } /* - send RTCMStream packet on all active UAVCAN drivers + send RTCMStream packet on all active DroneCAN drivers */ void AP_DroneCAN::send_RTCMStream(const uint8_t *data, uint32_t len) { @@ -1078,7 +1078,7 @@ void AP_DroneCAN::handle_actuator_status_Volz(AP_DroneCAN* ap_dronecan, uint8_t void AP_DroneCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg) { #if HAL_WITH_ESC_TELEM - const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, UAVCAN_SRV_NUMBER); + const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, DRONECAN_SRV_NUMBER); const uint8_t esc_index = msg.esc_index + esc_offset; if (!is_esc_data_index_valid(esc_index)) { @@ -1100,8 +1100,8 @@ void AP_DroneCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavc } bool AP_DroneCAN::is_esc_data_index_valid(const uint8_t index) { - if (index > UAVCAN_SRV_NUMBER) { - // printf("UAVCAN: invalid esc index: %d. max index allowed: %d\n\r", index, UAVCAN_SRV_NUMBER); + if (index > DRONECAN_SRV_NUMBER) { + // printf("DroneCAN: invalid esc index: %d. max index allowed: %d\n\r", index, DRONECAN_SRV_NUMBER); return false; } return true; @@ -1277,7 +1277,7 @@ void AP_DroneCAN::handle_param_save_response(const CanardRxTransfer& transfer, c } // Send Reboot command -// Note: Do not call this from outside UAVCAN thread context, +// Note: Do not call this from outside DroneCAN thread context, // THIS IS NOT A THREAD SAFE API! void AP_DroneCAN::send_reboot_request(uint8_t node_id) { diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index 50ca8d5db8a3d1..a2df3a8263fbd2 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -35,8 +35,8 @@ #include #include -#ifndef UAVCAN_SRV_NUMBER -#define UAVCAN_SRV_NUMBER NUM_SERVO_CHANNELS +#ifndef DRONECAN_SRV_NUMBER +#define DRONECAN_SRV_NUMBER NUM_SERVO_CHANNELS #endif #ifndef AP_DRONECAN_SEND_GPS @@ -63,7 +63,7 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { static const struct AP_Param::GroupInfo var_info[]; // Return uavcan from @driver_index or nullptr if it's not ready or doesn't exist - static AP_DroneCAN *get_uavcan(uint8_t driver_index); + static AP_DroneCAN *get_dronecan(uint8_t driver_index); bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const; void init(uint8_t driver_index, bool enable_filters) override; @@ -192,7 +192,7 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { uint16_t pulse; bool esc_pending; bool servo_pending; - } _SRV_conf[UAVCAN_SRV_NUMBER]; + } _SRV_conf[DRONECAN_SRV_NUMBER]; uint32_t _esc_send_count; uint32_t _srv_send_count; diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index 3333931983888f..d20a728bd007e8 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -34,7 +34,7 @@ extern const AP_HAL::HAL& hal; #define NODEDATA_MAGIC_LEN 2 #define MAX_NODE_ID 125 -#define debug_uavcan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "UAVCAN", fmt, ##args); } while (0) +#define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0) AP_DroneCAN_DNA_Server::AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan) : _ap_dronecan(ap_dronecan), @@ -520,11 +520,11 @@ void AP_DroneCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer, } if (rcvd_unique_id_offset) { - debug_uavcan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting Followup part! %u\n", + debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting Followup part! %u\n", (long int)AP_HAL::millis(), unsigned((now - last_alloc_msg_ms))); } else { - debug_uavcan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting First part! %u\n", + debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting First part! %u\n", (long int)AP_HAL::millis(), unsigned((now - last_alloc_msg_ms))); } diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp index 3e36e8e7a0b06d..7f09bc2c3313d1 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp @@ -28,7 +28,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static uint8_t node_memory_pool[DRONECAN_NODE_POOL_SIZE]; -#define debug_uavcan(fmt, args...) do { hal.console->printf(fmt, ##args); } while (0) +#define debug_dronecan(fmt, args...) do { hal.console->printf(fmt, ##args); } while (0) class DroneCAN_sniffer { public: @@ -107,7 +107,7 @@ void DroneCAN_sniffer::init(void) hal.can[driver_index]->init(1000000, AP_HAL::CANIface::NormalMode); if (!hal.can[driver_index]->is_initialized()) { - debug_uavcan("Can not initialised\n"); + debug_dronecan("Can not initialised\n"); return; } _uavcan_iface_mgr = new CanardInterface{driver_index}; @@ -117,7 +117,7 @@ void DroneCAN_sniffer::init(void) } if (!_uavcan_iface_mgr->add_interface(hal.can[driver_index])) { - debug_uavcan("Failed to add iface"); + debug_dronecan("Failed to add iface"); return; } @@ -156,7 +156,7 @@ void DroneCAN_sniffer::init(void) START_CB(uavcan_equipment_indication_LightsCommand, LightsCommand); START_CB(com_hex_equipment_flow_Measurement, Measurement); - debug_uavcan("DroneCAN: init done\n\r"); + debug_dronecan("DroneCAN: init done\n\r"); } static void send_node_status() From 9fe63ca2d4f3b985d4cfebbb02ad4353a07b3b15 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 265/287] AP_EFI: text messages and more defines --- libraries/AP_EFI/AP_EFI_Backend.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_EFI/AP_EFI_Backend.h b/libraries/AP_EFI/AP_EFI_Backend.h index 9506c7ff091b10..3f637dba3f441d 100644 --- a/libraries/AP_EFI/AP_EFI_Backend.h +++ b/libraries/AP_EFI/AP_EFI_Backend.h @@ -42,7 +42,7 @@ class AP_EFI_Backend { // Internal state for this driver (before copying to frontend) EFI_State internal_state; - int8_t get_uavcan_node_id(void) const; + int8_t get_dronecan_node_id(void) const; float get_coef1(void) const; float get_coef2(void) const; float get_ecu_fuel_density(void) const; From 834831bfeb8f576ac92893f24a1e19c001227e14 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 266/287] AP_GPS: text messages and more defines --- libraries/AP_GPS/AP_GPS_DroneCAN.cpp | 34 ++++++++++++++-------------- libraries/AP_GPS/AP_GPS_DroneCAN.h | 2 +- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp index 4d6def5d87fd71..83ca20ec1f3cc6 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp @@ -180,7 +180,7 @@ AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) if (backend == nullptr) { AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, - "Failed to register UAVCAN GPS Node %d on Bus %d\n", + "Failed to register DroneCAN GPS Node %d on Bus %d\n", _detected_modules[found_match].node_id, _detected_modules[found_match].ap_dronecan->get_driver_index()); } else { @@ -188,11 +188,11 @@ AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) backend->_detected_module = found_match; AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, - "Registered UAVCAN GPS Node %d on Bus %d as instance %d\n", + "Registered DroneCAN GPS Node %d on Bus %d as instance %d\n", _detected_modules[found_match].node_id, _detected_modules[found_match].ap_dronecan->get_driver_index(), _state.instance); - snprintf(backend->_name, ARRAY_SIZE(backend->_name), "UAVCAN%u-%u", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); + snprintf(backend->_name, ARRAY_SIZE(backend->_name), "DroneCAN%u-%u", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); _detected_modules[found_match].instance = _state.instance; for (uint8_t i=0; i < GPS_MAX_RECEIVERS; i++) { if (_detected_modules[found_match].node_id == AP::gps()._node_id[i]) { @@ -210,7 +210,7 @@ AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state) if (backend->role == AP_GPS::GPS_ROLE_MB_BASE) { backend->rtcm3_parser = new RTCM3_Parser; if (backend->rtcm3_parser == nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UAVCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DroneCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id); } } #endif // GPS_MOVING_BASELINE @@ -254,7 +254,7 @@ bool AP_GPS_DroneCAN::backends_healthy(char failure_msg[], uint16_t failure_msg_ return true; } -AP_GPS_DroneCAN* AP_GPS_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) +AP_GPS_DroneCAN* AP_GPS_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) { if (ap_dronecan == nullptr) { return nullptr; @@ -464,7 +464,7 @@ void AP_GPS_DroneCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uin if (!seen_message) { if (interim_state.status == AP_GPS::GPS_Status::NO_GPS) { // the first time we see a fix message we change from - // NO_GPS to NO_FIX, indicating to user that a UAVCAN GPS + // NO_GPS to NO_FIX, indicating to user that a DroneCAN GPS // has been seen interim_state.status = AP_GPS::GPS_Status::NO_FIX; } @@ -538,7 +538,7 @@ void AP_GPS_DroneCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBase { WITH_SEMAPHORE(sem); if (role != AP_GPS::GPS_ROLE_MB_BASE) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Incorrect Role set for UAVCAN GPS, %d should be Base", node_id); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Incorrect Role set for DroneCAN GPS, %d should be Base", node_id); return; } @@ -597,7 +597,7 @@ void AP_GPS_DroneCAN::handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const { WITH_SEMAPHORE(_sem_registry); - AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_fix2_msg(msg, transfer.timestamp_usec); } @@ -607,7 +607,7 @@ void AP_GPS_DroneCAN::handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const { WITH_SEMAPHORE(_sem_registry); - AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_aux_msg(msg); } @@ -617,7 +617,7 @@ void AP_GPS_DroneCAN::handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, co { WITH_SEMAPHORE(_sem_registry); - AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_heading_msg(msg); } @@ -627,7 +627,7 @@ void AP_GPS_DroneCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, con { WITH_SEMAPHORE(_sem_registry); - AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_status_msg(msg); } @@ -638,7 +638,7 @@ void AP_GPS_DroneCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, con void AP_GPS_DroneCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_moving_baseline_msg(msg, transfer.source_node_id); } @@ -648,7 +648,7 @@ void AP_GPS_DroneCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dron void AP_GPS_DroneCAN::handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg) { WITH_SEMAPHORE(_sem_registry); - AP_GPS_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id); + AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); if (driver != nullptr) { driver->handle_relposheading_msg(msg, transfer.source_node_id); } @@ -702,7 +702,7 @@ bool AP_GPS_DroneCAN::read(void) if (_new_data) { _new_data = false; - // the encoding of accuracies in UAVCAN can result in infinite + // the encoding of accuracies in DroneCAN can result in infinite // values. These cause problems with blending. Use 1000m and 1000m/s instead interim_state.horizontal_accuracy = MIN(interim_state.horizontal_accuracy, 1000.0); interim_state.vertical_accuracy = MIN(interim_state.vertical_accuracy, 1000.0); @@ -760,9 +760,9 @@ bool AP_GPS_DroneCAN::is_configured(void) const */ void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len) { - // we only handle this if we are the first UAVCAN GPS or we are + // we only handle this if we are the first DroneCAN GPS or we are // using a different uavcan instance than the first GPS, as we - // send the data as broadcast on all UAVCAN devive ports and we + // send the data as broadcast on all DroneCAN devive ports and we // don't want to send duplicates if (_detected_module == 0 || _detected_modules[_detected_module].ap_dronecan != _detected_modules[0].ap_dronecan) { @@ -828,7 +828,7 @@ void AP_GPS_DroneCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const cfg_step++; } // Also send reboot command - // this is ok as we are sending from UAVCAN thread context + // this is ok as we are sending from DroneCAN thread context Debug("AP_GPS_DroneCAN: sending reboot command %d\n", node_id); ap_dronecan->send_reboot_request(node_id); } diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.h b/libraries/AP_GPS/AP_GPS_DroneCAN.h index 100a405c601d18..f4627cc11bb0cf 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.h +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.h @@ -95,7 +95,7 @@ class AP_GPS_DroneCAN : public AP_GPS_Backend { static bool take_registry(); static void give_registry(); - static AP_GPS_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); + static AP_GPS_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); bool _new_data; AP_GPS::GPS_State interim_state; From d3dde1eb1421e528e32850e5cb450242058582e6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 267/287] AP_Gripper: text messages and more defines --- libraries/AP_Gripper/AP_Gripper_EPM.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Gripper/AP_Gripper_EPM.cpp b/libraries/AP_Gripper/AP_Gripper_EPM.cpp index 574d6ff99c2969..5b55219c3a24e4 100644 --- a/libraries/AP_Gripper/AP_Gripper_EPM.cpp +++ b/libraries/AP_Gripper/AP_Gripper_EPM.cpp @@ -32,7 +32,7 @@ void AP_Gripper_EPM::init_gripper() #ifdef UAVCAN_NODE_FILE _uavcan_fd = ::open(UAVCAN_NODE_FILE, O_CLOEXEC); // https://ardupilot.org/dev/docs/learning-ardupilot-uarts-and-the-console.html - ::printf("EPM: UAVCAN fd %d\n", _uavcan_fd); + ::printf("EPM: DroneCAN fd %d\n", _uavcan_fd); #endif // initialise the EPM to the neutral position From 4a2ad024949129ece634915cc7dd3f318c321304 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 268/287] AP_Notify: text messages and more defines --- libraries/AP_Notify/DroneCAN_RGB_LED.cpp | 4 ++-- libraries/AP_Notify/MMLPlayer.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Notify/DroneCAN_RGB_LED.cpp b/libraries/AP_Notify/DroneCAN_RGB_LED.cpp index e56bf791ecfad6..069f23d5b14b5c 100644 --- a/libraries/AP_Notify/DroneCAN_RGB_LED.cpp +++ b/libraries/AP_Notify/DroneCAN_RGB_LED.cpp @@ -47,7 +47,7 @@ bool DroneCAN_RGB_LED::init() { const uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); + AP_DroneCAN *uavcan = AP_DroneCAN::get_dronecan(i); if (uavcan != nullptr) { return true; } @@ -63,7 +63,7 @@ bool DroneCAN_RGB_LED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); + AP_DroneCAN *uavcan = AP_DroneCAN::get_dronecan(i); if (uavcan != nullptr) { success = uavcan->led_write(_led_index, red, green, blue) || success; } diff --git a/libraries/AP_Notify/MMLPlayer.cpp b/libraries/AP_Notify/MMLPlayer.cpp index 705253f98e733c..7bde0a03eb45fa 100644 --- a/libraries/AP_Notify/MMLPlayer.cpp +++ b/libraries/AP_Notify/MMLPlayer.cpp @@ -69,7 +69,7 @@ void MMLPlayer::start_note(float duration, float frequency, float volume) uint8_t can_num_drivers = AP::can().get_num_drivers(); for (uint8_t i = 0; i < can_num_drivers; i++) { - AP_DroneCAN *uavcan = AP_DroneCAN::get_uavcan(i); + AP_DroneCAN *uavcan = AP_DroneCAN::get_dronecan(i); if (uavcan != nullptr && (AP::notify().get_buzzer_types() & AP_Notify::Notify_Buzz_UAVCAN)) { uavcan->set_buzzer_tone(frequency, _note_duration_us*1.0e-6); From 00b9833facfa0a07508c8c40cf4a80ebb3361baf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 269/287] AP_Proximity: text messages and more defines --- libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp | 4 ++-- libraries/AP_Proximity/AP_Proximity_DroneCAN.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp index a12a075c5c59b3..b5b3e8265ab69f 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.cpp @@ -44,7 +44,7 @@ void AP_Proximity_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) } //Method to find the backend relating to the node id -AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) +AP_Proximity_DroneCAN* AP_Proximity_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) { if (ap_dronecan == nullptr) { return nullptr; @@ -157,7 +157,7 @@ float AP_Proximity_DroneCAN::distance_min() const void AP_Proximity_DroneCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_proximity_sensor_Proximity &msg) { //fetch the matching DroneCAN driver, node id and sensor id backend instance - AP_Proximity_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); + AP_Proximity_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); if (driver == nullptr) { return; } diff --git a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h index ea5fa409d43e36..a5c3c731d17dea 100644 --- a/libraries/AP_Proximity/AP_Proximity_DroneCAN.h +++ b/libraries/AP_Proximity/AP_Proximity_DroneCAN.h @@ -24,7 +24,7 @@ class AP_Proximity_DroneCAN : public AP_Proximity_Backend float distance_min() const override; - static AP_Proximity_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); + static AP_Proximity_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); static void subscribe_msgs(AP_DroneCAN* ap_dronecan); From 1d5bf5a58ac493959410bb0381800452d54400de Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 270/287] AP_RangeFinder: text messages and more defines --- libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp | 6 +++--- libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp index 712b92bca821fb..19cc404e48083e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -24,7 +24,7 @@ void AP_RangeFinder_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) } //Method to find the backend relating to the node id -AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) +AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new) { if (ap_dronecan == nullptr) { return nullptr; @@ -65,7 +65,7 @@ AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_uavcan_backend(AP_DroneCAN if (driver == nullptr) { break; } - gcs().send_text(MAV_SEVERITY_INFO, "RangeFinder[%u]: added UAVCAN node %u addr %u", + gcs().send_text(MAV_SEVERITY_INFO, "RangeFinder[%u]: added DroneCAN node %u addr %u", unsigned(i), unsigned(node_id), unsigned(address)); //Assign node id and respective uavcan driver, for identification if (driver->_ap_dronecan == nullptr) { @@ -103,7 +103,7 @@ void AP_RangeFinder_DroneCAN::update() void AP_RangeFinder_DroneCAN::handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg) { //fetch the matching uavcan driver, node id and sensor id backend instance - AP_RangeFinder_DroneCAN* driver = get_uavcan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); + AP_RangeFinder_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.sensor_id, true); if (driver == nullptr) { return; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h index 80778b82adad3d..62b01782def333 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h @@ -20,7 +20,7 @@ class AP_RangeFinder_DroneCAN : public AP_RangeFinder_Backend { void update() override; static void subscribe_msgs(AP_DroneCAN* ap_dronecan); - static AP_RangeFinder_DroneCAN* get_uavcan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); + static AP_RangeFinder_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t address, bool create_new); static AP_RangeFinder_Backend* detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg); From 6b268173ddd9ba393390aa8d76ab263af07a91fa Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 271/287] SRV_Channel: text messages and more defines --- libraries/SRV_Channel/SRV_Channels.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SRV_Channel/SRV_Channels.cpp b/libraries/SRV_Channel/SRV_Channels.cpp index b9bbe6ffcf006d..8279740e2fe8f0 100644 --- a/libraries/SRV_Channel/SRV_Channels.cpp +++ b/libraries/SRV_Channel/SRV_Channels.cpp @@ -540,7 +540,7 @@ void SRV_Channels::push() for (uint8_t i = 0; i < can_num_drivers; i++) { switch (AP::can().get_driver_type(i)) { case AP_CANManager::Driver_Type_DroneCAN: { - AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_uavcan(i); + AP_DroneCAN *ap_dronecan = AP_DroneCAN::get_dronecan(i); if (ap_dronecan == nullptr) { continue; } From 402de293d68b0e0bde8a8e84380231793012becf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:27:51 +1000 Subject: [PATCH 272/287] Tools: text messages and more defines --- Tools/ardupilotwaf/boards.py | 3 --- Tools/ardupilotwaf/chibios.py | 5 ----- Tools/autotest/arducopter.py | 8 ++++---- Tools/autotest/web-firmware/index.html | 2 +- Tools/scripts/build_options.py | 8 ++++---- Tools/scripts/decode_devid.py | 8 ++++---- 6 files changed, 13 insertions(+), 21 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 8054b1b49cb7af..d8dae5af9f46da 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -439,9 +439,6 @@ def configure_env(self, cfg, env): ) env.DEFINES.update( - UAVCAN_CPP_VERSION = 'UAVCAN_CPP03', - UAVCAN_NO_ASSERTIONS = 1, - UAVCAN_NULLPTR = 'nullptr', DRONECAN_CXX_WRAPPERS = 1, USE_USER_HELPERS = 1, CANARD_ENABLE_DEADLINE = 1, diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 67920c4c3f5c6f..2c7d35bbc43205 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -450,11 +450,6 @@ def setup_canmgr_build(cfg): ] env.CFLAGS += ['-DHAL_CAN_IFACES=2'] - env.DEFINES += [ - 'UAVCAN_CPP_VERSION=UAVCAN_CPP03', - 'UAVCAN_NO_ASSERTIONS=1', - 'UAVCAN_NULLPTR=nullptr' - ] if not env.AP_PERIPH: env.DEFINES += [ 'DRONECAN_CXX_WRAPPERS=1', diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 8cf4ea09b411d5..4729468177267f 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -2591,8 +2591,8 @@ def CANGPSCopterMission(self): self.reboot_sitl() # Test UAVCAN GPS ordering working - gps1_det_text = self.wait_text("GPS 1: specified as UAVCAN.*", regex=True, check_context=True) - gps2_det_text = self.wait_text("GPS 2: specified as UAVCAN.*", regex=True, check_context=True) + gps1_det_text = self.wait_text("GPS 1: specified as DroneCAN.*", regex=True, check_context=True) + gps2_det_text = self.wait_text("GPS 2: specified as DroneCAN.*", regex=True, check_context=True) gps1_nodeid = int(gps1_det_text.split('-')[1]) gps2_nodeid = int(gps2_det_text.split('-')[1]) if gps1_nodeid is None or gps2_nodeid is None: @@ -2622,11 +2622,11 @@ def CANGPSCopterMission(self): gps1_det_text = None gps2_det_text = None try: - gps1_det_text = self.wait_text("GPS 1: specified as UAVCAN.*", regex=True, check_context=True) + gps1_det_text = self.wait_text("GPS 1: specified as DroneCAN.*", regex=True, check_context=True) except AutoTestTimeoutException: pass try: - gps2_det_text = self.wait_text("GPS 2: specified as UAVCAN.*", regex=True, check_context=True) + gps2_det_text = self.wait_text("GPS 2: specified as DroneCAN.*", regex=True, check_context=True) except AutoTestTimeoutException: pass diff --git a/Tools/autotest/web-firmware/index.html b/Tools/autotest/web-firmware/index.html index af07270203cf8b..cd23bd958170c6 100644 --- a/Tools/autotest/web-firmware/index.html +++ b/Tools/autotest/web-firmware/index.html @@ -97,7 +97,7 @@

Firmwares

CompanionCompanion - Companion Computer example code and Images

AP_PeriphAP_Periph - UAVCAN Peripheral Firmware

+ alt="AP_Periph">AP_Periph - DroneCAN Peripheral Firmware

FilterToolFilterTool - Filter Analysis Tool

diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 4973c1fa00c0f8..1b40d75316c46b 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -145,7 +145,7 @@ def __init__(self, Feature('Compass', 'MMC5XX3', 'AP_COMPASS_MMC5XX3_ENABLED', 'Enable MMC5XX3 compasses', 1, None), Feature('Compass', 'QMC5883L', 'AP_COMPASS_QMC5883L_ENABLED', 'Enable QMC5883L compasses', 1, None), Feature('Compass', 'RM3100', 'AP_COMPASS_RM3100_ENABLED', 'Enable RM3100 compasses', 1, None), - Feature('Compass', 'UAVCAN_COMPASS', 'AP_COMPASS_DRONECAN_ENABLED', 'Enable UAVCAN compasses', 0, None), + Feature('Compass', 'DRONECAN_COMPASS', 'AP_COMPASS_DRONECAN_ENABLED', 'Enable DroneCAN compasses', 0, None), Feature('Gimbal', 'MOUNT', 'HAL_MOUNT_ENABLED', 'Enable Mount', 0, None), Feature('Gimbal', 'ALEXMOS', 'HAL_MOUNT_ALEXMOS_ENABLED', 'Enable Alexmos Gimbal', 0, "MOUNT"), @@ -202,7 +202,7 @@ def __init__(self, # Feature('Rangefinder', 'RANGEFINDER_SIM', 'AP_RANGEFINDER_SIM_ENABLED', "Enable Rangefinder - SIM", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_TRI2C', 'AP_RANGEFINDER_TRI2C_ENABLED', "Enable Rangefinder - TeraRangerI2C", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_TR_SERIAL', 'AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED', "Enable Rangefinder - TeraRanger Serial", 0, "RANGEFINDER"), # NOQA: E501 - Feature('Rangefinder', 'RANGEFINDER_UAVCAN', 'AP_RANGEFINDER_DRONECAN_ENABLED', "Enable Rangefinder - UAVCAN", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_DRONECAN', 'AP_RANGEFINDER_DRONECAN_ENABLED', "Enable Rangefinder - DroneCAN", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_USD1_CAN', 'AP_RANGEFINDER_USD1_CAN_ENABLED', "Enable Rangefinder - USD1 (CAN)", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_USD1_SERIAL', 'AP_RANGEFINDER_USD1_SERIAL_ENABLED', "Enable Rangefinder - USD1 (SERIAL)", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_VL53L0X', 'AP_RANGEFINDER_VL53L0X_ENABLED', "Enable Rangefinder - VL53L0X", 0, "RANGEFINDER"), # NOQA: E501 @@ -231,7 +231,7 @@ def __init__(self, Feature('Sensors', 'MS56XX', 'AP_BARO_MS56XX_ENABLED', 'Enable MS56XX Barometric Sensor', 1, None), Feature('Sensors', 'MSP_BARO', 'AP_BARO_MSP_ENABLED', 'Enable MSP Barometric Sensor', 0, 'MSP'), Feature('Sensors', 'SPL06', 'AP_BARO_SPL06_ENABLED', 'Enable SPL06 Barometric Sensor', 1, None), - Feature('Sensors', 'UAVCAN_BARO', 'AP_BARO_DRONECAN_ENABLED', 'Enable UAVCAN Barometric Sensor', 0, None), + Feature('Sensors', 'DRONECAN_BARO', 'AP_BARO_DRONECAN_ENABLED', 'Enable DroneCAN Barometric Sensor', 0, None), Feature('Sensors', 'ICP101XX', 'AP_BARO_ICP101XX_ENABLED', 'Enable ICP101XX Barometric Sensor', 0, None), Feature('Sensors', 'ICP201XX', 'AP_BARO_ICP201XX_ENABLED', 'Enable ICP201XX Barometric Sensor', 0, None), @@ -278,7 +278,7 @@ def __init__(self, Feature('Airspeed Drivers', 'MSP_AIRSPEED', 'AP_AIRSPEED_MSP_ENABLED', 'ENABLE MSP AIRSPEED', 0, 'AIRSPEED,MSP,OSD'), Feature('Airspeed Drivers', 'NMEA_AIRSPEED', 'AP_AIRSPEED_NMEA_ENABLED', 'ENABLE NMEA AIRSPEED', 0, 'AIRSPEED'), Feature('Airspeed Drivers', 'SDP3X', 'AP_AIRSPEED_SDP3X_ENABLED', 'ENABLE SDP3X AIRSPEED', 0, 'AIRSPEED'), - Feature('Airspeed Drivers', 'UAVCAN_ASPD', 'AP_AIRSPEED_DRONECAN_ENABLED', 'ENABLE UAVCAN AIRSPEED', 0, 'AIRSPEED'), # NOQA: E501 + Feature('Airspeed Drivers', 'DRONECAN_ASPD', 'AP_AIRSPEED_DRONECAN_ENABLED', 'ENABLE DroneCAN AIRSPEED', 0, 'AIRSPEED'), # NOQA: E501 Feature('Actuators', 'Volz', 'AP_VOLZ_ENABLED', 'Enable Volz Protocol', 0, None), Feature('Actuators', 'Volz_DroneCAN', 'AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', 'Enable Volz DroneCAN Feedback', 0, None), diff --git a/Tools/scripts/decode_devid.py b/Tools/scripts/decode_devid.py index 15b574306bf65b..4d79b9d063d362 100755 --- a/Tools/scripts/decode_devid.py +++ b/Tools/scripts/decode_devid.py @@ -38,7 +38,7 @@ def num(s): bustypes = { 1: "I2C", 2: "SPI", - 3: "UAVCAN", + 3: "DRONECAN", 4: "SITL", 5: "MSP", 6: "SERIAL", @@ -114,7 +114,7 @@ def num(s): 0x0A : "DEVTYPE_BARO_LPS2XH", 0x0B : "DEVTYPE_BARO_MS5611", 0x0C : "DEVTYPE_BARO_SPL06", - 0x0D : "DEVTYPE_BARO_UAVCAN", + 0x0D : "DEVTYPE_BARO_DRONECAN", 0x0E : "DEVTYPE_BARO_MSP", 0x0F : "DEVTYPE_BARO_ICP101XX", 0x10 : "DEVTYPE_BARO_ICP201XX", @@ -131,7 +131,7 @@ def num(s): 0x04 : "DEVTYPE_AIRSPEED_DLVR", 0x05 : "DEVTYPE_AIRSPEED_MSP", 0x06 : "DEVTYPE_AIRSPEED_SDP3X", - 0x07 : "DEVTYPE_AIRSPEED_UAVCAN", + 0x07 : "DEVTYPE_AIRSPEED_DRONECAN", 0x08 : "DEVTYPE_AIRSPEED_ANALOG", 0x09 : "DEVTYPE_AIRSPEED_NMEA", 0x0A : "DEVTYPE_AIRSPEED_ASP5033", @@ -152,7 +152,7 @@ def num(s): decoded_devname = airspeed_types.get(devtype, "UNKNOWN") if bus_type == 3: - #uavcan devtype represents sensor_id + #dronecan devtype represents sensor_id print("bus_type:%s(%u) bus:%u address:%u(0x%x) sensor_id:%u(0x%x) %s" % ( bustypes.get(bus_type,"UNKNOWN"), bus_type, bus, address, address, devtype-1, devtype-1, decoded_devname)) From f6fa35a1f7764b8c00692ee33227df7fa313a08c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:42:41 +1000 Subject: [PATCH 273/287] AP_GPS: fixed name length --- libraries/AP_GPS/AP_GPS_DroneCAN.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.h b/libraries/AP_GPS/AP_GPS_DroneCAN.h index f4627cc11bb0cf..9e2968ecd27af6 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.h +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.h @@ -112,7 +112,7 @@ class AP_GPS_DroneCAN : public AP_GPS_Backend { bool healthy; uint32_t status_flags; uint32_t error_code; - char _name[15]; + char _name[16]; // Module Detection Registry static struct DetectedModules { From 6f3c1dcd2b833cf0f6466ce892371e0ee21c4555 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Apr 2023 14:46:29 +1000 Subject: [PATCH 274/287] AP_DroneCAN: rename sniffer cpp --- .../DroneCAN_sniffer/{UAVCAN_sniffer.cpp => DroneCAN_sniffer.cpp} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename libraries/AP_DroneCAN/examples/DroneCAN_sniffer/{UAVCAN_sniffer.cpp => DroneCAN_sniffer.cpp} (100%) diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp similarity index 100% rename from libraries/AP_DroneCAN/examples/DroneCAN_sniffer/UAVCAN_sniffer.cpp rename to libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp From 5c3d464754c1be40fdaffed355a59a27e033cdc2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 22 Mar 2023 16:04:28 +1100 Subject: [PATCH 275/287] waf: support extra C and C++ flags on a per library basis --- Tools/ardupilotwaf/ap_library.py | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/Tools/ardupilotwaf/ap_library.py b/Tools/ardupilotwaf/ap_library.py index d8fdd4c05ca10a..9c7b42f7749890 100644 --- a/Tools/ardupilotwaf/ap_library.py +++ b/Tools/ardupilotwaf/ap_library.py @@ -239,6 +239,25 @@ def __str__(self): def keyword(self): return 'Checking included headers' +def custom_flags_check(tgen): + ''' + check for tasks marked as having custom cpp or c flags + a library can do this by setting AP_LIB_EXTRA_CXXFLAGS and AP_LIB_EXTRA_CFLAGS + + For example add this is the configure section of the library, using AP_DDS as an example: + + cfg.env.AP_LIB_EXTRA_CXXFLAGS['AP_DDS'] = ['-DSOME_CXX_FLAG'] + cfg.env.AP_LIB_EXTRA_CFLAGS['AP_DDS'] = ['-DSOME_C_FLAG'] + ''' + if not tgen.name.startswith("objs/"): + return + libname = tgen.name[5:] + if libname in tgen.env.AP_LIB_EXTRA_CXXFLAGS: + tgen.env.CXXFLAGS.extend(tgen.env.AP_LIB_EXTRA_CXXFLAGS[libname]) + if libname in tgen.env.AP_LIB_EXTRA_CFLAGS: + tgen.env.CFLAGS.extend(tgen.env.AP_LIB_EXTRA_CFLAGS[libname]) + + def double_precision_check(tasks): '''check for tasks marked as double precision''' @@ -284,6 +303,7 @@ def ap_library_register_for_check(self): if not hasattr(self, 'compiled_tasks'): return + custom_flags_check(self) double_precision_check(self.compiled_tasks) if self.env.ENABLE_ONVIF: gsoap_library_check(self.bld, self.compiled_tasks) @@ -298,4 +318,6 @@ def ap_library_register_for_check(self): def configure(cfg): cfg.env.AP_LIBRARIES_OBJECTS_KW = dict() cfg.env.AP_LIB_EXTRA_SOURCES = dict() + cfg.env.AP_LIB_EXTRA_CXXFLAGS = dict() + cfg.env.AP_LIB_EXTRA_CFLAGS = dict() cfg.env.DOUBLE_PRECISION_SOURCES = dict() From aab771d3802c56ffebe3190c0a554b36ec153323 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 17:39:19 +1000 Subject: [PATCH 276/287] AP_HAL_ChibiOS: use AP_BEACON_ENABLED instead of BEACON_ENABLED --- libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc | 3 +++ libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc index 0bcda34f3957cd..25b624026771ca 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc @@ -61,3 +61,6 @@ define AP_CAMERA_SERVO_ENABLED AP_CAMERA_ENABLED # no SLCAN on these boards (use can-over-mavlink if required) define AP_CAN_SLCAN_ENABLED 0 + +# no beacon support on minimized boards: +define AP_BEACON_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat index 99c17ffc6df97b..ef7814bd6d0fbb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat @@ -73,7 +73,7 @@ define AP_AIRSPEED_ENABLED 0 define AP_BEACON_ENABLED 0 define AP_OPTICALFLOW_ENABLED 0 define AP_FRSKY_TELEM_ENABLED 0 -define BEACON_ENABLED 0 +define AP_BEACON_ENABLED 0 define GPS_MOVING_BASELINE 0 define HAL_ADSB_SAGETECH_ENABLED 0 define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED 0 From 3eae09596660ee0fdebabdac3c492476762d316c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 17:39:19 +1000 Subject: [PATCH 277/287] ArduCopter: use AP_BEACON_ENABLED instead of BEACON_ENABLED --- ArduCopter/APM_Config.h | 1 - ArduCopter/Copter.cpp | 4 ++-- ArduCopter/Copter.h | 4 ++-- ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/Parameters.h | 2 +- ArduCopter/config.h | 7 ------- ArduCopter/system.cpp | 2 +- 7 files changed, 8 insertions(+), 16 deletions(-) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index d9c8f7afdcdca7..bdd901706b50de 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -9,7 +9,6 @@ //#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles //#define PARACHUTE DISABLED // disable parachute release to save 1k of flash //#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands -//#define BEACON_ENABLED DISABLED // disable beacon support //#define STATS_ENABLED DISABLED // disable statistics support //#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support //#define MODE_AUTO_ENABLED DISABLED // disable auto mode support diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index bb80d616ad5e51..1241b5f9b2336d 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -165,7 +165,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if HAL_PROXIMITY_ENABLED SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50, 36), #endif -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED SCHED_TASK_CLASS(AP_Beacon, &copter.g2.beacon, update, 400, 50, 39), #endif SCHED_TASK(update_altitude, 10, 100, 42), @@ -550,7 +550,7 @@ void Copter::ten_hz_logging_loop() #if HAL_PROXIMITY_ENABLED g2.proximity.log(); // Write proximity sensor distances #endif -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED g2.beacon.log(); #endif } diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 425e419cfc1cf8..bde520ce01befe 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -100,8 +100,8 @@ #include "AP_Rally.h" // Rally point library #include "AP_Arming.h" -// libraries which are dependent on #defines in defines.h and/or config.h -#if BEACON_ENABLED == ENABLED +#include +#if AP_BEACON_ENABLED #include #endif diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 71ef92699fafb3..579a1baa446504 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -776,7 +776,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0), -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED // @Group: BCN // @Path: ../libraries/AP_Beacon/AP_Beacon.cpp AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon), @@ -1225,7 +1225,7 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = { */ ParametersG2::ParametersG2(void) : temp_calibration() // this doesn't actually need constructing, but removing it here is problematic syntax-wise -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED , beacon() #endif #if HAL_PROXIMITY_ENABLED diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 22fcee3432c576..15f719224c585e 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -525,7 +525,7 @@ class ParametersG2 { // temperature calibration handling AP_TempCalibration temp_calibration; -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED // beacon (non-GPS positioning) library AP_Beacon beacon; #endif diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 9900d7e39b5361..a260b6cba4ec67 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -288,13 +288,6 @@ # define MODE_AUTOROTATE_ENABLED DISABLED #endif -////////////////////////////////////////////////////////////////////////////// - -// Beacon support - support for local positioning systems -#ifndef BEACON_ENABLED -# define BEACON_ENABLED !HAL_MINIMIZE_FEATURES -#endif - ////////////////////////////////////////////////////////////////////////////// // RADIO CONFIGURATION ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 499c552a5882ca..4e1527e2fc569f 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -159,7 +159,7 @@ void Copter::init_ardupilot() g2.proximity.init(); #endif -#if BEACON_ENABLED == ENABLED +#if AP_BEACON_ENABLED // init beacons used for non-gps position estimation g2.beacon.init(); #endif From f2cc1c501b492f2aec863b4fab84289955b087b0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 17:39:19 +1000 Subject: [PATCH 278/287] Tools: use AP_BEACON_ENABLED instead of BEACON_ENABLED --- Tools/scripts/build_options.py | 2 +- Tools/scripts/extract_features.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 1b40d75316c46b..b2ed18e10c3d52 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -247,7 +247,7 @@ def __init__(self, Feature('Sensors', 'TEMP_MCP9600', 'AP_TEMPERATURE_SENSOR_MCP9600_ENABLED', 'Enable Temp Sensor - MCP9600', 0, "TEMP"), Feature('Sensors', 'AIRSPEED', 'AP_AIRSPEED_ENABLED', 'Enable Airspeed Sensors', 1, None), # Default to enabled to not annoy Plane users # NOQA: E501 - Feature('Sensors', 'BEACON', 'BEACON_ENABLED', 'Enable Beacon', 0, None), + Feature('Sensors', 'BEACON', 'AP_BEACON_ENABLED', 'Enable Beacon', 0, None), Feature('Sensors', 'GPS_MOVING_BASELINE', 'GPS_MOVING_BASELINE', 'Enable GPS Moving Baseline', 0, None), Feature('Other', 'GyroFFT', 'HAL_GYROFFT_ENABLED', 'Enable In-Flight Gyro FFT calculations', 0, None), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 4278ff58a8a13b..cf6e64cc764a72 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -58,7 +58,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_TEMPERATURE_SENSOR_ENABLED', 'AP_TemperatureSensor::AP_TemperatureSensor',), ('AP_TEMPERATURE_SENSOR_{type}_ENABLED', 'AP_TemperatureSensor_(?P.*)::update',), - ('BEACON_ENABLED', 'AP_Beacon::AP_Beacon',), + ('AP_BEACON_ENABLED', 'AP_Beacon::AP_Beacon',), ('HAL_TORQEEDO_ENABLED', 'AP_Torqeedo::AP_Torqeedo'), ('HAL_NAVEKF3_AVAILABLE', 'NavEKF3::NavEKF3',), From ff21f86a9c14e97f673d59768207efd5f72b0fc3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 18:54:09 +1000 Subject: [PATCH 279/287] Rover: use AP_BEACON_ENABLED instead of BEACON_ENABLED --- Rover/Parameters.cpp | 4 ++++ Rover/Parameters.h | 2 ++ Rover/Rover.cpp | 4 ++++ Rover/system.cpp | 2 ++ 4 files changed, 12 insertions(+) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 89738d9caedd36..792e50153461d6 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -425,9 +425,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe), #endif +#if AP_BEACON_ENABLED // @Group: BCN // @Path: ../libraries/AP_Beacon/AP_Beacon.cpp AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon), +#endif // 7 was used by AP_VisualOdometry @@ -730,7 +732,9 @@ ParametersG2::ParametersG2(void) #if ADVANCED_FAILSAFE == ENABLED afs(), #endif +#if AP_BEACON_ENABLED beacon(), +#endif motors(rover.ServoRelayEvents, wheel_rate_control), wheel_rate_control(wheel_encoder), attitude_control(), diff --git a/Rover/Parameters.h b/Rover/Parameters.h index 83f718b91e8c3f..3c3040ce5304bb 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -312,7 +312,9 @@ class ParametersG2 { AP_AdvancedFailsafe_Rover afs; #endif +#if AP_BEACON_ENABLED AP_Beacon beacon; +#endif // Motor library AP_MotorsUGV motors; diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index f264315234b883..2ef70f1c9e9868 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -80,7 +80,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK(set_servos, 400, 200, 15), SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300, 18), SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200, 21), +#if AP_BEACON_ENABLED SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200, 24), +#endif #if HAL_PROXIMITY_ENABLED SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200, 27), #endif @@ -377,7 +379,9 @@ void Rover::update_logging1(void) if (should_log(MASK_LOG_THR)) { Log_Write_Throttle(); +#if AP_BEACON_ENABLED g2.beacon.log(); +#endif } if (should_log(MASK_LOG_NTUN)) { diff --git a/Rover/system.cpp b/Rover/system.cpp index 78e4107254ded5..bd6ed6b1ccf68e 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -75,8 +75,10 @@ void Rover::init_ardupilot() g2.proximity.init(); #endif +#if AP_BEACON_ENABLED // init beacons used for non-gps position estimation g2.beacon.init(); +#endif // and baro for EKF barometer.set_log_baro_bit(MASK_LOG_IMU); From 4f355f7c8b82577d48a271b9c082f6033d0a3d0d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Apr 2023 23:25:21 +1000 Subject: [PATCH 280/287] AC_Avoidance: correct compilation when fence and beacon compiled out --- libraries/AC_Avoidance/AC_Avoid.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 0e402fc543e0a3..7b2e5fdf20f490 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -126,9 +126,11 @@ void AC_Avoid::adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desir { // Only horizontal component needed for most fences, since fences are 2D Vector2f desired_velocity_xy_cms{desired_vel_cms.x, desired_vel_cms.y}; - + +#if AP_FENCE_ENABLED || AP_BEACON_ENABLED // limit acceleration const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX); +#endif // maximum component of desired backup velocity in each quadrant Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel; From 89a13308017757f16037e6638d025668a8b14bae Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 1 Aug 2022 11:02:23 +1000 Subject: [PATCH 281/287] AP_Airspeed: reuse airspeed backend contructor in more backends ... and clean out some unused includes --- libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp | 5 ----- libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h | 3 ++- libraries/AP_Airspeed/AP_Airspeed_MS4525.h | 1 - libraries/AP_Airspeed/AP_Airspeed_MS5525.h | 1 - libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp | 7 ------- libraries/AP_Airspeed/AP_Airspeed_NMEA.h | 3 ++- libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp | 5 ----- libraries/AP_Airspeed/AP_Airspeed_SDP3X.h | 5 ++--- libraries/AP_Airspeed/AP_Airspeed_analog.h | 1 - 9 files changed, 6 insertions(+), 25 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp index 2f312fe7884efa..4b5db8bd0e1f42 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp @@ -13,11 +13,6 @@ extern const AP_HAL::HAL& hal; AP_Airspeed_DroneCAN::DetectedModules AP_Airspeed_DroneCAN::_detected_modules[]; HAL_Semaphore AP_Airspeed_DroneCAN::_sem_registry; -// constructor -AP_Airspeed_DroneCAN::AP_Airspeed_DroneCAN(AP_Airspeed &_frontend, uint8_t _instance) : - AP_Airspeed_Backend(_frontend, _instance) -{} - void AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) { if (ap_dronecan == nullptr) { diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h index ce34cd8c700f30..cc2484d27d8284 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.h @@ -14,7 +14,8 @@ class AP_Airspeed_DroneCAN : public AP_Airspeed_Backend { public: - AP_Airspeed_DroneCAN(AP_Airspeed &_frontend, uint8_t _instance); + + using AP_Airspeed_Backend::AP_Airspeed_Backend; bool init(void) override; diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS4525.h b/libraries/AP_Airspeed/AP_Airspeed_MS4525.h index 64ea04fb76913c..70e30b127e0860 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS4525.h +++ b/libraries/AP_Airspeed/AP_Airspeed_MS4525.h @@ -27,7 +27,6 @@ */ #include -#include #include #include #include diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS5525.h b/libraries/AP_Airspeed/AP_Airspeed_MS5525.h index afa7d448c422cf..0bcb74a2d85e16 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS5525.h +++ b/libraries/AP_Airspeed/AP_Airspeed_MS5525.h @@ -27,7 +27,6 @@ #if AP_AIRSPEED_MS5525_ENABLED #include -#include #include #include #include diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp index d085e5bd99e728..3da9c968e2f829 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp @@ -30,13 +30,6 @@ #define TIMEOUT_MS 2000 -extern const AP_HAL::HAL &hal; - -AP_Airspeed_NMEA::AP_Airspeed_NMEA(AP_Airspeed &_frontend, uint8_t _instance) : - AP_Airspeed_Backend(_frontend, _instance) -{ -} - bool AP_Airspeed_NMEA::init() { const AP_SerialManager& serial_manager = AP::serialmanager(); diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.h b/libraries/AP_Airspeed/AP_Airspeed_NMEA.h index 480637799f63bf..264f1c651dca0e 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.h +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.h @@ -15,7 +15,8 @@ class AP_Airspeed_NMEA : public AP_Airspeed_Backend { public: - AP_Airspeed_NMEA(AP_Airspeed &frontend, uint8_t _instance); + + using AP_Airspeed_Backend::AP_Airspeed_Backend; // probe and initialise the sensor bool init(void) override; diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp index 616e634c8aac23..e68fc3cd210f06 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp @@ -42,11 +42,6 @@ extern const AP_HAL::HAL &hal; -AP_Airspeed_SDP3X::AP_Airspeed_SDP3X(AP_Airspeed &_frontend, uint8_t _instance) : - AP_Airspeed_Backend(_frontend, _instance) -{ -} - /* send a 16 bit command code */ diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h index 6669cd1751c42b..01b652f17fc3e9 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h @@ -27,7 +27,6 @@ */ #include -#include #include #include #include @@ -42,8 +41,8 @@ class AP_Airspeed_SDP3X : public AP_Airspeed_Backend { public: - AP_Airspeed_SDP3X(AP_Airspeed &frontend, uint8_t _instance); - ~AP_Airspeed_SDP3X(void) {} + + using AP_Airspeed_Backend::AP_Airspeed_Backend; // probe and initialise the sensor bool init() override; diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.h b/libraries/AP_Airspeed/AP_Airspeed_analog.h index 3ee890db48198e..94908436925501 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.h +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.h @@ -9,7 +9,6 @@ #if AP_AIRSPEED_ANALOG_ENABLED #include -#include #include "AP_Airspeed_Backend.h" From 9179bce1caf6b1e2b5cf3c2a006b22654155f37a Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Wed, 5 Apr 2023 07:13:07 -0300 Subject: [PATCH 282/287] SITL: initialize battery at 0V --- libraries/SITL/SIM_Aircraft.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 87deaec30ed1a0..0a4d5768932cba 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -176,7 +176,7 @@ class Aircraft { Vector3f accel_body{0.0f, 0.0f, -GRAVITY_MSS}; // m/s/s NED, body frame float airspeed; // m/s, apparent airspeed float airspeed_pitot; // m/s, apparent airspeed, as seen by fwd pitot tube - float battery_voltage = -1.0f; + float battery_voltage = 0.0f; float battery_current; float local_ground_level; // ground level at local position bool lock_step_scheduled; From 0f1253b3938bd1c228a4d40eeeff6749ecd03954 Mon Sep 17 00:00:00 2001 From: Wu Date: Mon, 13 Feb 2023 11:41:52 +0800 Subject: [PATCH 283/287] AP_InertialSensor: the accel fast-sampling rate of MPU6500 is 4k,not 1k --- libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp index f62913071ca383..e103f6ee9d2f1c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp @@ -894,7 +894,7 @@ void AP_InertialSensor_Invensense::_set_filter_register(void) _gyro_backend_rate_hz *= fast_sampling_rate; // calculate rate we will be giving accel samples to the backend - if (_mpu_type >= Invensense_MPU9250) { + if (_mpu_type >= Invensense_MPU6500) { _accel_fifo_downsample_rate = MAX(4 / fast_sampling_rate, 1); _accel_backend_rate_hz *= MIN(fast_sampling_rate, 4); } else { From 6934a638a13ebfa3bcedd5ae6d1f956f57f154af Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 7 Apr 2023 09:51:54 +0900 Subject: [PATCH 284/287] AP_Scripting: Viewpro driver setup instruction fix --- libraries/AP_Scripting/drivers/mount-viewpro-driver.lua | 2 +- libraries/AP_Scripting/drivers/mount-viewpro-driver.md | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua index cc7ce6a042c717..68c17332da85b1 100644 --- a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua @@ -6,7 +6,7 @@ Set SERIALx_PROTOCOL = 28 (Scripting) where "x" corresponds to the serial port connected to the gimbal Set SCR_ENABLE = 1 to enable scripting and reboot the autopilot Set MNT1_TYPE = 9 (Scripting) to enable the mount/gimbal scripting driver - Set CAM_TRIGG_TYPE = 3 (Mount) to enable the camera driver + Set CAM1_TYPE = 4 (Mount) to enable the camera driver Set RCx_OPTION = 300 (Scripting1) to allow real-time selection of the video feed and camera control Copy this script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot Set VIEP_CAM_SWLOW, VIEP_CAM_SWMID, VIEP_CAM_SWHIGH to which cameras are controlled by the auxiliary switch diff --git a/libraries/AP_Scripting/drivers/mount-viewpro-driver.md b/libraries/AP_Scripting/drivers/mount-viewpro-driver.md index 6f941ac38c14a7..1c2f3609388dd2 100644 --- a/libraries/AP_Scripting/drivers/mount-viewpro-driver.md +++ b/libraries/AP_Scripting/drivers/mount-viewpro-driver.md @@ -2,12 +2,13 @@ Viewpro gimbal driver lua script -How to use +# How To Use + Connect gimbal UART to one of the autopilot's serial ports Set SERIALx_PROTOCOL = 28 (Scripting) where "x" corresponds to the serial port connected to the gimbal Set SCR_ENABLE = 1 to enable scripting and reboot the autopilot Set MNT1_TYPE = 9 (Scripting) to enable the mount/gimbal scripting driver - Set CAM_TRIGG_TYPE = 3 (Mount) to enable camera control using the mount driver + Set CAM1_TYPE = 4 (Mount) to enable camera control using the mount driver Set RCx_OPTION = 300 (Scripting1) to allow real-time selection of the video feed and camera control Copy this script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot Set VIEP_CAM_SWLOW, VIEP_CAM_SWMID, VIEP_CAM_SWHIGH to which cameras are controlled by the auxiliary switch From af64de341217967dd71d4e004002afc593255605 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 11 Apr 2023 17:11:37 +0900 Subject: [PATCH 285/287] AP_Scripting: mount-viewpro driver gets param desc --- .../drivers/mount-viewpro-driver.lua | 40 +++++++++++++++++++ 1 file changed, 40 insertions(+) diff --git a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua index 68c17332da85b1..a1e3b1e8dd52f7 100644 --- a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua @@ -41,10 +41,50 @@ assert(param:add_param(PARAM_TABLE_KEY, 5, "ZOOM_SPEED", 7), "could not add VIEP -- bind parameters to variables local MNT1_TYPE = Parameter("MNT1_TYPE") -- should be 9:Scripting + +--[[ + // @Param: VIEP_DEBUG + // @DisplayName: ViewPro debug + // @Description: ViewPro debug + // @Values: 0:Disabled, 1:Enabled, 2:Enabled including attitude reporting + // @User: Advanced +--]] local VIEP_DEBUG = Parameter("VIEP_DEBUG") -- debug level. 0:disabled 1:enabled 2:enabled with attitude reporting + +--[[ + // @Param: VIEP_CAM_SWLOW + // @DisplayName: ViewPro Camera For Switch Low + // @Description: Camera selection when switch is in low position + // @Values: 0:No change in camera selection, 1:EO1, 2:IR thermal, 3:EO1 + IR Picture-in-picture, 4:IR + EO1 Picture-in-picture, 5:Fusion, 6:IR1 13mm, 7:IR2 52mm + // @User: Standard +--]] local VIEP_CAM_SWLOW = Parameter("VIEP_CAM_SWLOW") -- RC swith low position's camera selection + +--[[ + // @Param: VIEP_CAM_SWMID + // @DisplayName: ViewPro Camera For Switch Mid + // @Description: Camera selection when switch is in middle position + // @Values: 0:No change in camera selection, 1:EO1, 2:IR thermal, 3:EO1 + IR Picture-in-picture, 4:IR + EO1 Picture-in-picture, 5:Fusion, 6:IR1 13mm, 7:IR2 52mm + // @User: Standard +--]] local VIEP_CAM_SWMID = Parameter("VIEP_CAM_SWMID") -- RC swith middle position's camera selection + +--[[ + // @Param: VIEP_CAM_SWHIGH + // @DisplayName: ViewPro Camera For Switch High + // @Description: Camera selection when switch is in high position + // @Values: 0:No change in camera selection, 1:EO1, 2:IR thermal, 3:EO1 + IR Picture-in-picture, 4:IR + EO1 Picture-in-picture, 5:Fusion, 6:IR1 13mm, 7:IR2 52mm + // @User: Standard +--]] local VIEP_CAM_SWHIGH = Parameter("VIEP_CAM_SWHIGH") -- RC swith high position's camera selection + +--[[ + // @Param: VIEP_ZOOM_SPEED + // @DisplayName: ViewPro Zoom Speed + // @Description: ViewPro Zoom Speed. Higher numbers result in faster zooming + // @Range: 0 7 + // @User: Standard +--]] local VIEP_ZOOM_SPEED = Parameter("VIEP_ZOOM_SPEED") -- zoom speed from 0 (slow) to 7 (fast) -- global definitions From 078778de30fb94099cbded23e00f48102c8ce781 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 20 Mar 2023 14:08:10 +0000 Subject: [PATCH 286/287] AP_HAL_ChibiOS: hwdef for MatekF405-TE/VTOL including bdshot --- .../hwdef/MatekF405-TE-bdshot/hwdef-bl.dat | 1 + .../hwdef/MatekF405-TE-bdshot/hwdef.dat | 17 +++++++++++++++++ 2 files changed, 18 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000000..581d05154ec2d2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef-bl.dat @@ -0,0 +1 @@ +include ../MatekF405-TE/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef.dat new file mode 100644 index 00000000000000..aea8d620fed48e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE-bdshot/hwdef.dat @@ -0,0 +1,17 @@ +# hw definition file for MATEK F405 VTOL + +include ../MatekF405-TE/hwdef.dat + +undef PC9 PC8 PB15 PA8 PB11 PB10 PB3 PA15 + +# --------------------- PWM ----------------------- +PC9 TIM8_CH4 TIM8 PWM(1) GPIO(50) BIDIR +PC8 TIM8_CH3 TIM8 PWM(2) GPIO(51) +PB15 TIM12_CH2 TIM12 PWM(3) GPIO(52) NODMA +PA8 TIM1_CH1 TIM1 PWM(4) GPIO(53) BIDIR +PB11 TIM2_CH4 TIM2 PWM(5) GPIO(54) +PB10 TIM2_CH3 TIM2 PWM(6) GPIO(55) BIDIR +PB3 TIM2_CH2 TIM2 PWM(7) GPIO(56) BIDIR +PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57) + +DMA_PRIORITY TIM8* TIM1* From db7fad0acaee98dc6e00d725a0535ef184f03819 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 20 Mar 2023 14:09:18 +0000 Subject: [PATCH 287/287] bootloaders: bootloaders for MatekF405-TE/VTOL-bdshot --- Tools/bootloaders/MatekF405-TE-bdshot_bl.bin | Bin 0 -> 15932 bytes Tools/bootloaders/MatekF405-TE-bdshot_bl.hex | 998 +++++++++++++++++++ 2 files changed, 998 insertions(+) create mode 100644 Tools/bootloaders/MatekF405-TE-bdshot_bl.bin create mode 100644 Tools/bootloaders/MatekF405-TE-bdshot_bl.hex diff --git a/Tools/bootloaders/MatekF405-TE-bdshot_bl.bin b/Tools/bootloaders/MatekF405-TE-bdshot_bl.bin new file mode 100644 index 0000000000000000000000000000000000000000..38f871f537475c0b486a286b8637af5a7bbaea8e GIT binary patch literal 15932 zcmch83w%>mw)Z}dG^Yx6oFsJZFNHC!(DE_;{^+d(oWgyqYKN zD+1*TpB@e8SLa@pGgKRD@|+#^n*+C^){dZriE(Ci&Q&n1d=j|)k(_K@Hw^1~DRM~vKh`}%UBPwOwgkj1ek=K0?!d=Zf!pWqJNrSKD_ zeq(%OGpqWg^lnCeD0Xd4b``PIj(z(9MlOye#+|j=BI&y=5>sYzH6qoBRHJL!8tb-_ z-bU#=y{wVQ>n4jWjV|jp&Z-SHO4fK;)gk{%UstK?BLM=jHzKHN zLMBKlYookxJM^NHv>MH-Ded{EB_gX6zpBx1>+1bw6=UjmWqK3TPS83q^=!@lE3|%e zDnV<~sqcQ;NjeO!pVg3`=|Rug0b~B zlx)bIGx}^8GU0{%MzyntPt!Ippv`ANW~Jr^a^cjD56@|3E^V4lf0M?dY2!_r=ZRbt zoq6WAD&906UXSmk_;)m1E9VO~$bVf_7~us?YXa5~eQjjnj0+*mKdOyXo=;EzR&?(K zXqQUl-4pY>)8%w7-6{mgTs5*awjnG6I@g;~cVgTcX3(}JHcy-jNqxz# zJxNz=bet)&$@lKyZyXID+_1ppMW#cq;_5iu=HPH)Ny>8DrIp>DV!L&}MWP0#And7ov)K}Cg z#ub`2o5-6rFA#ar1i#cLhQp=6zjj>HdLjHLCEJ&fgKNiA!o;%C#6Qos5m^K5+s9rx zK>K_k-sgb>d^?fvMXS%Qf*VmN-2OP+U2(XMI9%iS`S^J2;$^KE@0Rh8;w3fllE)8d zUdRTIn#XyQR^(fGNbP{KOzaI)&h;qT+3KZ-4!jPoZ8=a1u4#u;<6PSm?+JT3=6?49 z%u-uh(YtEp*b4`$FsIKH%%zpCfP+fv2%kCrzzsP&*>Sob?7S_LF*?LR%A@m zMzrJyind6N98rzkPb*rIIO}RZ&D-Os!wLfksg~}=qq|f>r4}Kx1~7i z6qC&&ec;hJ8S&SmQ7n4HRY?N0AKC|FQk+}s@Ny{#~aFUUkDXYX+ zFeR^C^sThIE*$sboOl)Owjwa{;XX1#T;!s!h)CW_ntqDV93wC5BShmgNE&BeOQ&I% zojs|mVB}M85Tmz}wxu{q{lXevT+m%087unEmD(8j{2MgQ$bX(B1*5@I^hIHHSSM+r zLl^n&nq%l=?f#28TTmgTIU@SBOoYEI)1{$=q*Ont%q=SECKjP-2U3C=bO|u%nFO}c zaXWM9XamH^pOO9fPFBp3@|;IT(>45Dk}g$&)yVrKbR*g#8+?FL<+PMi#LA}asF|Sr83*E7=MTb7zCtb@QTO zZza})W6qjv@yE(sqgHGY*S-Fs;%)ue%g7g5d+D035^rcwBWG2VkRu}k`>eenU>4u& zDHoq2nqePNBL`_+(Q|pTD=zg2i)L1|R(#U)m@?OOI;2Kss-)mAA>oX*i5uR@?Xv%S zP>oDO*&jmCzs@PU7~@2k@|ATOwjp>aZ>en4HB{=)U7fqeh?Ol&E`a3Y+?~8$y0)sR z`Iy3&I%JkRikOklDg|O@HIc8IYHHT4p>+k)jA~1=e!snT?4y!&7ZW6M#e^j7xAQ?N zv0AiP@j8{$!Rv_eTp1B;_8CM*9A8%$gV&$o%vdvfTZZ#?Wxlb)&WqE6X-;CwHs^?H zq+aD+jEEZ2cg|}g^0lwi^+m@{+f$tTktY7mLtl)h?vTt9+8ER?Mm4(_XXmCE zjNn%zpR0s?6)q(Sx8VvL;7O4`bxm5ullE!BOob_1ZxbxGQNlB23vGH?<#wN6OD=`J z2p9DkcfIyGTXS4;$Va&2&|8U)vGLA&N$2R0*1OWWb7tu(DV<-#_@E<}uejws<<50q zNLJ~T=4U+_0|}k5c8qu_-#3r>9<;g=x?rN_L*L-{&oo_357Gr(I zX`{iNo6@e-U$~lklq|>zWQdGaBOXyU+I6A%&UX8>&^%}TeRf&L)^Du8KOWzcZklJ@ za6genWk9*pJiFQ=?XlOMuOnQLx#)B6u@{C6)l9`J<2>n}7#$@AZw4$fP6S!YInLX- zXIk1^XImVyjnlg=PdH?Tt8|LNFCAEWX8)yI+%mxH_LcBC@D>%sY@XUsUOxel8nwUcnkx_-rH zGC*Dw|25)HDaG@mJzd=4DGfX({gc5D=}$kFBNjr6|8=U%W3A|NcS#%ax?BaK(wA{E zM=VCoi&F>lK9ZJ;MHOn~xv8^KS;a8+QQGEdZ=5#Z-ViZ?jKyKVyR^kWoe z?^Gl3HUe*fNHKGVvyYz3IGJ#+8ZEpy9k;B^mS0G}=W#GP7uW^sJC>cTzZ<5Q2JwYTs3p-3&oHB)RCgGzpDt!zx&gBqL_>DP#N zcNdDZjT$LeInmWy9&f)3?MH$MtlRRqxUSTTI}9YL)hPb9lIh$F44)fjS5QpvhZA$| zcV||R&Yf{8Fql8(Cw4CJS~0QeekJ`1GokZn^wj4!xMz7!B&l##YW#98uzh5xg*4TF z)W~OjOCi70YgiXC+d*a4%$RwR-I^|vRx)xYQ#U^(i2O)4+IN5=DW{CH zfYnXUFg5a6ptSGn^Va(-Hl0xREip)$+xP|7giMdJ3$jAFk7PZ;SoYfV_KXno0za~v zF!FpAa1~6a=@C{mN<{wiID1Ifmkk~8g*PwLjgh;MUX8NvB(+?p{;T}%Ffo_ca zKoYJpNjC~to}`=3AG|UmUYr?XFsAI#9gnO_j%j*`Vn~azVpTUC6K43J`w^qmcTR_$ z+uKX&V%wxfP6Hq1?RI~blfxZ9Ssw%TDl%j-}MkZRbUOcdK$+(M!F?Sr`qp`6Vjl*}R80%M3&0-pSp{ zZEI<-G*5YlJJcJceON^%UgRM!`6{tk9tKoVLI!w|%%h{${m3XevGSRjGMdp;AqV>?gxJxW^9t zOI&(m-HH8%AAU?*G)uskUy4mg8$5YZ3g(m7&9pM|*c8*wy}-yHPf@;eoe3>(uacmx z2K)bnRPV`>Na4j`-X5k*ZyO2mBNgoVaO&bx|60Xldq3F=Ml@G1t)pDyPD`DhyQEd! zyvdb=^C6a4J-91Q(jE42(uP>tM|sD{&%ef4I4`jr8DdKM-MbpNhW-Xe1J~%SEXBT= zm;;%2WQe;R`|IuHE=K;jg7xa9`#NyM=d2OedQQ2fi`imMH#Aqw)fwIIxtv}VT`U%W zTV5L@J9`P)DX}t>wG;ctks;o^)6K|#?3G^u?fA+kK9QJt&v|}e`v=FW9Tv#t`)w9xrlUtP6~ozx|z!kGXxylC@aVN~4q~S-L5e z>1eP^_Ho;M%Gx3gDBwVy4l_;%-RN1?<)U)fs;o6SB-Wb;Elgud?5kdXtFoksN<6Uu za}ni;5puD2yiw|uUhdrodDP1;&5c0_6 zOHPINLGn3yJG3a)V!OcNyeINIKGWdKutHS@rwuaJl|dGE$u=Lc_CShOv(GlN=8qdK z8{Z1Qd~wHiB6s>;zG&P2Txg#n7BSZSp;wgEMf8?YeCFkgWb>NfOyJtTd2z7o;*mzi z+B(=M0n+%7_*Uv(QL2iJ;-N}Xusi6Gx*9p@Y@-3~benGq+Agv7Hv9ImZ3pjkb~Un= zvyH^kkMYu8wvRO*r2Wv_%G*QJZ+{Nyc^kKdUjYqiZ`0$W*{$3H?2K%Tb5P&S#3{%@ z3W)`+N`4mRM{2pQMh18-+jy%kl#p9Wq2I=+q;jT4X}40l))eO?r8(`NSpOPCX%P=h zlsClsUXYFBK8EpC70pWFJC zCddrtb?f?4%UJ8gV4~gPWP8ik+UK6R#yS*AkFU+EN25mmnzZSk3io4=+yH(Lgf5SY zuEsxysjs7dh?I1=yp_iJ#7J=3?WC3<>8H|@_K9Ql66dnJbguQudI5S2U4Pu89LC67 zrv&EpD)Kw?)7LzHh!=H1t0%37fjx5GIF*!7R36?6n!jV*>RIp6;#^WACsid( z+cnRkGLW&R+->#jkUB6Q?306uQ*>{D-sxXa8OuU9BU-j5PS;rETZc)2w&h_D%k#8i ze`~kz!_AYPpR`=(7vPIBdJK};b(@PZTik}NYNS~B{bDrJXT(>tE1|#8vrXqOq9wcE9u@fPZmQ4gK#jxdZltK)k*m2C zcgPKfcKgI2-~&WQ&g^utW_G8ya+lOK@+j+2G8VEPhq7X!9pBQ0+8T$FzwoH!P;?7f zGp7g(3BKBeT_ZWfTR9K@G^*E9{zKMO0?kH^h{+wA-UVP0bLM&0yJr~H$n-c}FGG() zuM_;BTDb_ci34PVwDNZ}6p99I!yBsbawNr1>TUvq#9C(rvG)Sy#t?Ldq<>Pa2 z()rW#dm8lG-F6Zx?c*ei>rU4y$l{MIGa-n|5BUO z1)Hgm%gF1a4|+PJefA8<_pe=6SCi`+SBG?$D=V)fzA{GL-o8BPIm3U%<+IeEx4O{- zt3vSdIw9sA(owWXt4P3~b(i*;MNYCS*(-^u&0g<%%f*GL1T%8};SOnsG_Q%mGV+{g zBYG~++hhOqE|=8)le3y!2VFJgZVw}KQA^W{(p!c- z_GfI09{`XyC<)(`MknpFvW8C%KlZQMjnZhg!CnCf(gBP4$BlK^y>6NE=2Xj z=_S{kN$A@`=nzgkYi~m9rW!Xts796^HWv;Dqv5Y=+azGY__cn`f|)pR7&-S^E;rYh zpr5V=+Ay@n!6?&?npCmTaJKT=3Z4Z@_Uva(UH_@HR4h=7k|Hn$BIpjREG z2tP*fV*LnML9xjDlkfIG|5(CpOYeo{zONW3b1c$FE&cFo!cGmpid;$8ODyv4q_z6p zo&v1G4^^RCd()+!f@+!@L{5iXeZ_%QV)?5zFITmS|^!DaDA^9U2OkMI-#a?*b^IG&i?Tyoyd=M7Q)p5uNC)@E} z;o1D$ZK{iEv|o7&5SlxiJvF4>CpPy9@DF1l_mQ zIr#|mWeBySp5`V`P#GjESexKab>?k*uvd-9s@7@nkitM9rKaA+jOEV$V<+^+E75f$Ew`w;BD%PZj3fc|!?VkB}OF;0eyZb07%`!E*<{v#t+ z5>01dC8ZZo9iKUglM83TpH=E#np>1panz9B%NWPPS+I`DA-;_I9%!5N0=kP9K&t;d z3A>xBM*fGIRWoWi?mA0O_c+GLgH%J-yY(K&n6E_d*2Hz52EgsdT!C9h>Fu+j;9QnZU zjY(pBKTKPdxJ%-#O5Eu!Wxhn4aBOAEVudXW^t^6=BUln|S>pZ(7SN;NxILE2Pc@`r zTS0doq~TOuOgrHP(IT4MrV4) zz?-!N#5TiOzcm)D-i-&`?9w&vd(k1O);O@mGXemrP#u@yoROHmvP=D5M37}v(J zP#dwA*eEWopD{D=)~b=CD(>X*w>WxmUX5H(_uHX;#%q~<)TU2uM05}5pc5H-xte3j z)&gobUP9%rh^`SeGNQ8Z)EybMVScn6K9F6S>Y7bvnPF=hrIKBEv6a}{fawcz#u&FZ zHoThQoK|yEGL4;ar}C*8X^vB__-1;Bzr;!-J;8_>(e+V z!c=d8UKIDs&@nBAKC>Kw&Xt~9Y0mVj^qN+C`tfw%gYaWfITw)XGLGEU{JxTH6!VWM zawcca$Xp*2Ath6rJtBFvE4huV)blm7MD5 zdR`vhJwqPcCp`xr{~ZdyeW~lY;Z*IM3jT)3V17k<#XjidC&H!R>k~}5Y-C_(_H?F9 zp2&jyoH$H+HH4x?h08pTk=B`nhe?kFqvY=&WdNhsSn-vwlX^Q>z&JT;^gw_kN~P7HXta-6XxO=%my5W+UWF&fYZ00(etGeGt_5 z(&h5@r8wz&qhqIQ*p^Lf95J$FMbQxfLGf2KYea%OGxP`bg=V}|gKg(Wz_+9nd-XlQ zTR?Rke%O)4l>FR&R3RROO-B_W6(Rk?v2>}adHC+e2AxIkzSeWCtV@{)Q92eyPhf_Y zu~;LWX&3fao5dmPxGr}pX00p5s7uqF!_Xs-IFK(BC`HPU@*rL|+{}&WSnL7%^LKYO zD1C2(?lvFM*_&IHTXc|(IA+IrMvu{yCj7wEdbg_ilyt3>B6BGZ&StHe;c|V3=o4o| zcZ}DbFV|s4OuwSb!yFmt6I^@XRi24*qfdH%7$~_VWyJT5l#4_p3zi4JxrZNF&r~x@ z9h=t-o_p0ch^-d*~rXxEV>oAOXpDB+o(5LGh99MFAB*s zjgj(yLri-%o#(hCu#c?d@XCiv!&zM*n!v4RV}RD-Ey6O(7;zjyOmSJxYqhw42MB0I zc*5>%&XSJatwv0+ZLeSKXs%{9tjE4$9{Mm*Jj-vu)(vpX-~FfZ_dXXg;yp<#~K}6i3Kkx*x_=WV^k0f+2^zmU{nPGzXc0=LT?GVcJV%ZjjH z&~tX~n){nmhHZKt?^}fLU{Co@sWxrkJ;+q9Hf2CFyqhzLr>P%KYOjoH=frDHYxCkY zC#663?)6mdsh4^tI(kw77#*Cf69~;ssqC&G&icOP{%Fm~XspfH!~`k1D#>!xYa#!ssG;-5p32)WZ|tc{1iJSzBaEY8S(4-J z1I-tK=0>B-C@tEvJC{=Y(wOc1+ct{BQ1Nb<`psrnt!mZ`SLo532UPNmXlD)#VD+8S z>IVp@bW(D9=3wssY|lA%ERS4gaDB^_m_40)yGrj#B`LJck^;uk1@B8{km^8+O^sOk z5)|R$6ybL41x3z*BJGu*hT&(6?>W?O*1r0l=7&5lduG|L8S|}w$gKs2SR`#K?h%Am z^w=BZ`m9s$VJG}y)z7uF12jdY=3T_^;WY%+VBSR>i{wldXfy-6acAhA+*K9BJFFM@ z4DePc)ypX}MkULbw=N^#7}M1`#`f2Zx(c=YKqGd@^zMhN+AD|IttSq$*A1LdZfpHe z`C~V^4*Nh_>TqRT!Z_?tu(jTh35g_S#5(O%!xL#y?Wh^+uW<)I{5b6Lr(ykFCa%W} zyPBD$os!z~bNgRUo&$aEZC>7VbTm!J$}>22OwQ^7CcG#0^<1>wAcT0VTw*>g;TnTejMvUioR`ZjophBeOI?PHXkVtsqe*_x$PJ4J$Oc& zfX-5%L5f08QyY+?(1L2wZohc@K?={RYr~DrA1db#!J8DHWmj{j^sVUQ<3C-s^3r$d zyT##Z$OKuyj@is~tY*j~SwISBpQ5o{ZpB$m79`3hPP>|`Aq}2MGboZ8r-%g zK#}S=MXCT{m}HjzF8ric2w)fUX$#u}c&D?M9bwq^K<)XQf*oPD1hil&71l||l$;~) zD}wR;A(H>ha7G3(wb;`rt$5hsar7M@Dm*TCn?FI5H&Ij|`<{IvVM|RNfT#h-9L~eAKlWXG|5Zt&=5Wl3EP`iip+ zxPPCqe7mHV-ZNv7EkBcHaB!N;EmOBsuK((tyo_GKYe?6`3(R(8>vsA z6`A*8Q)zMEOVgm1a(Gs_ISf z3H?$&nPDYZtMFy%^sEE7lC&-PJG2G2=HP7ol3x~&Vb-$^AA<*9=hp;YnO@DWqzo+o zJ2G$;$Ee)Xj=!scKmL)&DDunHNKl0}1T_0R zoZ#Cuu~q!3c=_E1ng6o*tESrC>Nv;tgJX23FS^Vz?Q+BO!ztQ-hE6?GwB3+*QZr)X zaBsKbc3^!v$u02erUb9P?DfYg<-EA+wH&=WLD>|j~ z%n)q&-MgChcJpPOhUr1Qs~@jA`d$4VL&Yu+>!vR;;_CslU@WlO!1Dkpms?)LJ;*`K z>l+Pj)_e*aO5|yZ+U0zX_3(Yh<0fyVQ*yZWO1oTtkosNe9*5iM;TraO91ZF415kLu zKi@gO%HXkGP&3mU@qa9gsaxnRkERWqP}XQ@#`o^oHF?dMknZr}&J2zo%W6*u+ z|4+2hSfm;jgf4|b#3Gv@cXSRq{4ayvDh(SAc*BMGo@q6C_qWAw0Bz8(@iNog(Eu&J z_*4Ticev{tPr(w+nCsmF-b>{hry^_n;(g(5D4^|vKhuL(Yqpa;zjJhIGu_&OghmjH z6ecbC0^TIyt{)$%8u`U*gv^0mX!H4_>o%W17XRPJ(NO^uq&EkHrydq_VygGtfq#e? zni^zSjT#J1Y%;EITHjFLbO!>R1?u9nKzxtk{`4B1L|?<{TsfP`n9Y0WBH2DWP&?); z%DFf9-a4H3*eR$C+GL2ZbE-6;pfGQ{3c0{bt&({@yvx`pvCqIR|<-#pT;#aOKt1Nq6v* z139oCJjF~7tUmJgcN8@`o-0!VK%Pk*KJw9pU5N@++$-b6S`hGWaBkppr#nAVc zD2k_J^50$jUU^# zrQY3@!VloJcWgu?l~HSU~&);#9uni45Z^r|sx>f6{%U90>97`MH z_sC2le2QQrHsXc)}hDA~{7jI%Ua~Z<$b6Hk1H-#`-%}x$Zl2o1{Y#JJBH4JN`(GD7s zEQH&DD~r*gCt^#@D*q;svK$7%bE$lChGdO<>)o5gB}F%0|Bc&fSCgW}#U)E_ylH9a zvU0nlVwH%NKy-D8&w|eOzY2u7bBU0fkN?IY*wDBg^QD2#|9Qkd#5QE&v|^sW7FqHl zet4NjzW6!K;e7iQCdDU6mZ&4lhiamZenFXR8q+$OR